ACloudViewer  3.9.4
A Modern Library for 3D Data Processing
TransformationEstimation.h
Go to the documentation of this file.
1 // ----------------------------------------------------------------------------
2 // - CloudViewer: www.cloudViewer.org -
3 // ----------------------------------------------------------------------------
4 // Copyright (c) 2018-2024 www.cloudViewer.org
5 // SPDX-License-Identifier: MIT
6 // ----------------------------------------------------------------------------
7 
8 #pragma once
9 
10 #include <Logging.h>
11 
12 #include <cmath>
13 #include <memory>
14 #include <string>
15 #include <utility>
16 #include <vector>
17 
22 
23 namespace cloudViewer {
24 
25 namespace t {
26 namespace geometry {
27 class PointCloud;
28 }
29 
30 namespace pipelines {
31 namespace registration {
32 
33 namespace {
34 
35 // Minimum time period (sec) between two sequential scans for Doppler ICP.
36 constexpr double kMinTimePeriod{1e-3};
37 
38 } // namespace
39 
41  Unspecified = 0,
42  PointToPoint = 1,
43  PointToPlane = 2,
44  ColoredICP = 3,
45  DopplerICP = 4,
46 };
47 
54 public:
58 
59 public:
61  const = 0;
62 
72  virtual double ComputeRMSE(const geometry::PointCloud &source,
73  const geometry::PointCloud &target,
74  const core::Tensor &correspondences) const = 0;
89  const geometry::PointCloud &source,
90  const geometry::PointCloud &target,
91  const core::Tensor &correspondences,
92  const core::Tensor &current_transform =
94  const std::size_t iteration = 0) const = 0;
95 };
96 
102 public:
103  // TODO: support with_scaling.
106 
107 public:
109  const override {
110  return type_;
111  };
121  double ComputeRMSE(const geometry::PointCloud &source,
122  const geometry::PointCloud &target,
123  const core::Tensor &correspondences) const override;
124 
139  const geometry::PointCloud &source,
140  const geometry::PointCloud &target,
141  const core::Tensor &correspondences,
142  const core::Tensor &current_transform =
144  const std::size_t iteration = 0) const override;
145 
146 private:
147  const TransformationEstimationType type_ =
149 };
150 
156 public:
160 
166  : kernel_(kernel) {}
167 
168 public:
170  const override {
171  return type_;
172  };
173 
184  double ComputeRMSE(const geometry::PointCloud &source,
185  const geometry::PointCloud &target,
186  const core::Tensor &correspondences) const override;
187 
203  const geometry::PointCloud &source,
204  const geometry::PointCloud &target,
205  const core::Tensor &correspondences,
206  const core::Tensor &current_transform =
208  const std::size_t iteration = 0) const override;
209 
210 public:
213 
214 private:
215  const TransformationEstimationType type_ =
217 };
218 
228 public:
230 
238  double lambda_geometric = 0.968,
239  const RobustKernel &kernel =
241  : lambda_geometric_(lambda_geometric), kernel_(kernel) {
242  if (lambda_geometric_ < 0 || lambda_geometric_ > 1.0) {
243  lambda_geometric_ = 0.968;
244  }
245  }
246 
248  const override {
249  return type_;
250  };
251 
252 public:
264  double ComputeRMSE(const geometry::PointCloud &source,
265  const geometry::PointCloud &target,
266  const core::Tensor &correspondences) const override;
267 
284  const geometry::PointCloud &source,
285  const geometry::PointCloud &target,
286  const core::Tensor &correspondences,
287  const core::Tensor &current_transform =
289  const std::size_t iteration = 0) const override;
290 
291 public:
292  double lambda_geometric_ = 0.968;
295 
296 private:
297  const TransformationEstimationType type_ =
299 };
300 
310 public:
312 
337  const double period = 0.1,
338  const double lambda_doppler = 0.01,
339  const bool reject_dynamic_outliers = false,
340  const double doppler_outlier_threshold = 2.0,
341  const std::size_t outlier_rejection_min_iteration = 2,
342  const std::size_t geometric_robust_loss_min_iteration = 0,
343  const std::size_t doppler_robust_loss_min_iteration = 2,
344  const RobustKernel &geometric_kernel =
346  const RobustKernel &doppler_kernel =
348  const core::Tensor &transform_vehicle_to_sensor =
350  : period_(period),
351  lambda_doppler_(lambda_doppler),
352  reject_dynamic_outliers_(reject_dynamic_outliers),
353  doppler_outlier_threshold_(doppler_outlier_threshold),
354  outlier_rejection_min_iteration_(outlier_rejection_min_iteration),
356  geometric_robust_loss_min_iteration),
357  doppler_robust_loss_min_iteration_(doppler_robust_loss_min_iteration),
358  geometric_kernel_(geometric_kernel),
359  doppler_kernel_(doppler_kernel),
360  transform_vehicle_to_sensor_(transform_vehicle_to_sensor) {
361  core::AssertTensorShape(transform_vehicle_to_sensor, {4, 4});
362 
363  if (std::abs(period) < kMinTimePeriod) {
364  utility::LogError("Time period too small.");
365  }
366 
367  if (lambda_doppler_ < 0 || lambda_doppler_ > 1.0) {
368  lambda_doppler_ = 0.01;
369  }
370  }
371 
373  const override {
374  return type_;
375  };
376 
377 public:
389  double ComputeRMSE(const geometry::PointCloud &source,
390  const geometry::PointCloud &target,
391  const core::Tensor &correspondences) const override;
392 
409  const geometry::PointCloud &source,
410  const geometry::PointCloud &target,
411  const core::Tensor &correspondences,
412  const core::Tensor &current_transform =
414  const std::size_t iteration = 0) const override;
415 
416 public:
418  double period_{0.1};
420  double lambda_doppler_{0.01};
440 
441 private:
442  const TransformationEstimationType type_ =
444 };
445 
446 } // namespace registration
447 } // namespace pipelines
448 } // namespace t
449 } // namespace cloudViewer
#define AssertTensorShape(tensor,...)
Definition: TensorCheck.h:61
static Tensor Eye(int64_t n, Dtype dtype, const Device &device)
Create an identity matrix of size n x n.
Definition: Tensor.cpp:418
A point cloud contains a list of 3D points.
Definition: PointCloud.h:82
core::Tensor ComputeTransformation(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences, const core::Tensor &current_transform=core::Tensor::Eye(4, core::Float64, core::Device("CPU:0")), const std::size_t iteration=0) const override
Estimates the transformation matrix for ColoredICP method, a tensor of shape {4, 4},...
double ComputeRMSE(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences) const override
Computes RMSE (double) for ColoredICP method, between two pointclouds, given correspondences.
TransformationEstimationForColoredICP(double lambda_geometric=0.968, const RobustKernel &kernel=RobustKernel(RobustKernelMethod::L2Loss, 1.0, 1.0))
Constructor.
std::size_t geometric_robust_loss_min_iteration_
Number of iterations of ICP after which robust loss kicks in.
std::size_t outlier_rejection_min_iteration_
Number of iterations of ICP after which outlier rejection is enabled.
core::Tensor ComputeTransformation(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences, const core::Tensor &current_transform=core::Tensor::Eye(4, core::Float64, core::Device("CPU:0")), const std::size_t iteration=0) const override
Estimates the transformation matrix for DopplerICP method, a tensor of shape {4, 4},...
double period_
Time period (in seconds) between the source and the target point clouds.
bool reject_dynamic_outliers_
Whether or not to prune dynamic point outlier correspondences.
double lambda_doppler_
Factor that weighs the Doppler residual term in DICP objective.
double ComputeRMSE(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences) const override
Computes RMSE (double) for DopplerICP method, between two pointclouds, given correspondences.
TransformationEstimationForDopplerICP(const double period=0.1, const double lambda_doppler=0.01, const bool reject_dynamic_outliers=false, const double doppler_outlier_threshold=2.0, const std::size_t outlier_rejection_min_iteration=2, const std::size_t geometric_robust_loss_min_iteration=0, const std::size_t doppler_robust_loss_min_iteration=2, const RobustKernel &geometric_kernel=RobustKernel(RobustKernelMethod::L2Loss, 1.0, 1.0), const RobustKernel &doppler_kernel=RobustKernel(RobustKernelMethod::L2Loss, 1.0, 1.0), const core::Tensor &transform_vehicle_to_sensor=core::Tensor::Eye(4, core::Float64, core::Device("CPU:0")))
Constructor.
double ComputeRMSE(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences) const override
Computes RMSE (double) for PointToPlane method, between two pointclouds, given correspondences.
TransformationEstimationPointToPlane(const RobustKernel &kernel)
Constructor that takes as input a RobustKernel.
core::Tensor ComputeTransformation(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences, const core::Tensor &current_transform=core::Tensor::Eye(4, core::Float64, core::Device("CPU:0")), const std::size_t iteration=0) const override
Estimates the transformation matrix for PointToPlane method, a tensor of shape {4,...
double ComputeRMSE(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences) const override
Computes RMSE (double) for PointToPoint method, between two pointclouds, given correspondences.
core::Tensor ComputeTransformation(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences, const core::Tensor &current_transform=core::Tensor::Eye(4, core::Float64, core::Device("CPU:0")), const std::size_t iteration=0) const override
Estimates the transformation matrix for PointToPoint method, a tensor of shape {4,...
virtual double ComputeRMSE(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences) const =0
virtual core::Tensor ComputeTransformation(const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences, const core::Tensor &current_transform=core::Tensor::Eye(4, core::Float64, core::Device("CPU:0")), const std::size_t iteration=0) const =0
virtual TransformationEstimationType GetTransformationEstimationType() const =0
#define LogError(...)
Definition: Logging.h:60
__host__ __device__ int2 abs(int2 v)
Definition: cutil_math.h:1267
const Dtype Float64
Definition: Dtype.cpp:43
::ccPointCloud PointCloud
Definition: PointCloud.h:19
Generic file read and write utility for python interface.