ACloudViewer  3.9.4
A Modern Library for 3D Data Processing
Registration.cpp
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 
9 
10 #include <benchmark/benchmark.h>
11 
18 
19 namespace cloudViewer {
20 namespace t {
21 namespace pipelines {
22 namespace registration {
23 
24 // Testing parameters:
25 // ICP ConvergenceCriteria.
26 static const double relative_fitness = 1e-6;
27 static const double relative_rmse = 1e-6;
28 static const int max_iterations = 10;
29 
30 static const double voxel_downsampling_factor = 0.02;
31 
32 // NNS parameter.
33 static const double max_correspondence_distance = 0.05;
34 
35 // Normal estimation parameters.
36 static const double normals_search_radius = 10.0;
37 static const int normals_max_neighbors = 30;
38 
39 // Initial transformation guess for registration.
40 static const std::vector<float> initial_transform_flat{
41  0.862, 0.011, -0.507, 0.5, -0.139, 0.967, -0.215, 0.7,
42  0.487, 0.255, 0.835, -1.4, 0.0, 0.0, 0.0, 1.0};
43 
44 static std::tuple<geometry::PointCloud, geometry::PointCloud>
45 LoadTensorPointCloudFromFile(const std::string& source_pointcloud_filename,
46  const std::string& target_pointcloud_filename,
47  const double voxel_downsample_factor,
48  const core::Dtype& dtype,
49  const core::Device& device) {
50  geometry::PointCloud source, target;
51 
52  io::ReadPointCloud(source_pointcloud_filename, source,
53  {"auto", false, false, true});
54  io::ReadPointCloud(target_pointcloud_filename, target,
55  {"auto", false, false, true});
56 
57  source = source.To(device);
58  target = target.To(device);
59 
60  // Eliminates the case of impractical values (including negative).
61  if (voxel_downsample_factor > 0.001) {
62  source = source.VoxelDownSample(voxel_downsample_factor);
63  target = target.VoxelDownSample(voxel_downsample_factor);
64  } else {
66  "VoxelDownsample: Impractical voxel size [< 0.001], skipping "
67  "downsampling.");
68  }
69 
70  source.SetPointPositions(source.GetPointPositions().To(dtype));
71  source.SetPointNormals(source.GetPointNormals().To(dtype));
72  if (source.HasPointColors()) {
73  source.SetPointColors(source.GetPointColors().To(dtype).Div(255.0));
74  }
75 
76  target.SetPointPositions(target.GetPointPositions().To(dtype));
77  target.SetPointNormals(target.GetPointNormals().To(dtype));
78  if (target.HasPointColors()) {
79  target.SetPointColors(target.GetPointColors().To(dtype).Div(255.0));
80  }
81 
82  return std::make_tuple(source, target);
83 }
84 
85 static void BenchmarkICP(benchmark::State& state,
86  const core::Device& device,
87  const core::Dtype& dtype,
90  data::DemoICPPointClouds demo_icp_pointclouds;
91  geometry::PointCloud source, target;
92  std::tie(source, target) = LoadTensorPointCloudFromFile(
93  demo_icp_pointclouds.GetPaths(0), demo_icp_pointclouds.GetPaths(1),
94  voxel_downsampling_factor, dtype, device);
95 
96  std::shared_ptr<TransformationEstimation> estimation;
98  estimation = std::make_shared<TransformationEstimationPointToPlane>();
100  estimation = std::make_shared<TransformationEstimationPointToPoint>();
102  estimation = std::make_shared<TransformationEstimationForColoredICP>();
103  }
104 
105  core::Tensor init_trans =
107  .To(dtype);
108 
109  RegistrationResult reg_result(init_trans);
110 
111  // Warm up.
112  reg_result = ICP(source, target, max_correspondence_distance, init_trans,
113  *estimation,
115  max_iterations));
116 
117  for (auto _ : state) {
118  reg_result = ICP(source, target, max_correspondence_distance,
119  init_trans, *estimation,
121  max_iterations));
122  core::cuda::Synchronize(device);
123  }
124 }
125 
127  core::Tensor directions = core::Tensor::Empty(
128  positions.GetShape(), positions.GetDtype(), positions.GetDevice());
129  for (int64_t i = 0; i < positions.GetLength(); ++i) {
130  // Compute the norm of the position vector.
131  core::Tensor norm = (positions[i][0] * positions[i][0] +
132  positions[i][1] * positions[i][1] +
133  positions[i][2] * positions[i][2])
134  .Sqrt();
135 
136  // If the norm is zero, set the direction vector to zero.
137  if (norm.Item<float>() == 0.0) {
138  directions[i].Fill(0.0);
139  } else {
140  // Otherwise, compute the direction vector by dividing the position
141  // vector by its norm.
142  directions[i] = positions[i] / norm;
143  }
144  }
145  return directions;
146 }
147 
148 static std::tuple<geometry::PointCloud, geometry::PointCloud>
150  const std::string& source_pointcloud_filename,
151  const std::string& target_pointcloud_filename,
152  const double voxel_downsample_factor,
153  const core::Dtype& dtype,
154  const core::Device& device) {
155  geometry::PointCloud source, target;
156 
157  io::ReadPointCloud(source_pointcloud_filename, source,
158  {"auto", false, false, true});
159  io::ReadPointCloud(target_pointcloud_filename, target,
160  {"auto", false, false, true});
161 
162  source.SetPointAttr("directions",
164 
165  source = source.To(device);
166  target = target.To(device);
167 
168  // Eliminates the case of impractical values (including negative).
169  if (voxel_downsample_factor > 0.001) {
170  source = source.VoxelDownSample(voxel_downsample_factor);
171  target = target.VoxelDownSample(voxel_downsample_factor);
172  } else {
174  "VoxelDownsample: Impractical voxel size [< 0.001], skipping "
175  "downsampling.");
176  }
177 
178  source.SetPointPositions(source.GetPointPositions().To(dtype));
179  source.SetPointAttr("dopplers", source.GetPointAttr("dopplers").To(dtype));
180  source.SetPointAttr("directions",
181  source.GetPointAttr("directions").To(dtype));
182 
183  target.SetPointPositions(target.GetPointPositions().To(dtype));
185 
186  return std::make_tuple(source, target);
187 }
188 
189 static void BenchmarkDopplerICP(benchmark::State& state,
190  const core::Device& device,
191  const core::Dtype& dtype,
194  data::DemoDopplerICPSequence demo_sequence;
195  geometry::PointCloud source, target;
196  std::tie(source, target) = LoadTensorDopplerPointCloudFromFile(
197  demo_sequence.GetPath(0), demo_sequence.GetPath(1),
198  voxel_downsampling_factor, dtype, device);
199 
200  Eigen::Matrix4d calibration{Eigen::Matrix4d::Identity()};
201  double period{0.0};
202  demo_sequence.GetCalibration(calibration, period);
203 
204  const core::Tensor calibration_t =
206  .To(device, dtype);
207 
209  estimation_dicp.period_ = period;
210  estimation_dicp.transform_vehicle_to_sensor_ = calibration_t;
211 
212  core::Tensor init_trans = core::Tensor::Eye(4, dtype, device);
213  RegistrationResult reg_result(init_trans);
214 
215  // Warm up.
216  reg_result = ICP(source, target, max_correspondence_distance, init_trans,
217  estimation_dicp,
219  max_iterations));
220 
221  for (auto _ : state) {
222  reg_result = ICP(source, target, max_correspondence_distance,
223  init_trans, estimation_dicp,
225  max_iterations));
226  core::cuda::Synchronize(device);
227  }
228 }
229 
230 #define ENUM_ICP_METHOD_DEVICE(BENCHMARK_FUNCTION, METHOD_NAME, \
231  TRANSFORMATION_TYPE, DEVICE) \
232  BENCHMARK_CAPTURE(BENCHMARK_FUNCTION, DEVICE METHOD_NAME##_Float32, \
233  core::Device(DEVICE), core::Float32, \
234  TRANSFORMATION_TYPE) \
235  ->Unit(benchmark::kMillisecond); \
236  BENCHMARK_CAPTURE(BENCHMARK_FUNCTION, DEVICE METHOD_NAME##_Float64, \
237  core::Device(DEVICE), core::Float64, \
238  TRANSFORMATION_TYPE) \
239  ->Unit(benchmark::kMillisecond);
240 
242  PointToPoint,
244  "CPU:0")
246  PointToPlane,
247  TransformationEstimationType::PointToPlane,
248  "CPU:0")
250  ColoredICP,
251  TransformationEstimationType::ColoredICP,
252  "CPU:0")
254  DopplerICP,
255  TransformationEstimationType::DopplerICP,
256  "CPU:0")
257 
258 #ifdef BUILD_CUDA_MODULE
260  PointToPoint,
262  "CUDA:0")
264  PointToPlane,
265  TransformationEstimationType::PointToPlane,
266  "CUDA:0")
268  ColoredICP,
269  TransformationEstimationType::ColoredICP,
270  "CUDA:0")
272  DopplerICP,
273  TransformationEstimationType::DopplerICP,
274  "CUDA:0")
275 #endif
276 
277 } // namespace registration
278 } // namespace pipelines
279 } // namespace t
280 } // namespace cloudViewer
Common CUDA utilities.
#define ENUM_ICP_METHOD_DEVICE(BENCHMARK_FUNCTION, METHOD_NAME, TRANSFORMATION_TYPE, DEVICE)
void Sqrt(const double in[2], double out[2])
Definition: Factor.cpp:124
char type
int64_t GetLength() const
Definition: Tensor.h:1125
Dtype GetDtype() const
Definition: Tensor.h:1164
static Tensor Eye(int64_t n, Dtype dtype, const Device &device)
Create an identity matrix of size n x n.
Definition: Tensor.cpp:418
Device GetDevice() const override
Definition: Tensor.cpp:1435
static Tensor Empty(const SizeVector &shape, Dtype dtype, const Device &device=Device("CPU:0"))
Create a tensor with uninitialized values.
Definition: Tensor.cpp:400
SizeVector GetShape() const
Definition: Tensor.h:1127
void Fill(S v)
Fill the whole Tensor with a scalar value, the scalar will be casted to the Tensor's Dtype.
Definition: Tensor.h:1400
Tensor Div(const Tensor &value) const
Divides a tensor and returns the resulting tensor.
Definition: Tensor.cpp:1205
Tensor To(Dtype dtype, bool copy=false) const
Definition: Tensor.cpp:739
Data class for DemoDopplerICPSequence contains an example sequence of 100 point clouds with Doppler v...
Definition: Dataset.h:355
std::string GetPath(std::size_t index) const
Path to the point cloud at index.
bool GetCalibration(Eigen::Matrix4d &calibration, double &period) const
Returns the vehicle to sensor calibration transformation and the time period (in secs) between sequen...
Data class for DemoICPPointClouds contains 3 point clouds of binary PCD format. This data is used in ...
Definition: Dataset.h:423
std::vector< std::string > GetPaths() const
Returns list of 3 point cloud paths.
Definition: Dataset.h:428
A point cloud contains a list of 3D points.
Definition: PointCloud.h:82
void SetPointNormals(const core::Tensor &value)
Set the value of the "normals" attribute. Convenience function.
Definition: PointCloud.h:198
core::Tensor & GetPointNormals()
Get the value of the "normals" attribute. Convenience function.
Definition: PointCloud.h:130
PointCloud VoxelDownSample(double voxel_size, const std::string &reduction="mean") const
Downsamples a point cloud with a specified voxel size.
Definition: PointCloud.cpp:280
void SetPointColors(const core::Tensor &value)
Set the value of the "colors" attribute. Convenience function.
Definition: PointCloud.h:192
void EstimateNormals(const utility::optional< int > max_nn=30, const utility::optional< double > radius=utility::nullopt)
Function to estimate point normals. If the point cloud normals exist, the estimated normals are orien...
Definition: PointCloud.cpp:619
void SetPointPositions(const core::Tensor &value)
Set the value of the "positions" attribute. Convenience function.
Definition: PointCloud.h:186
core::Tensor & GetPointPositions()
Get the value of the "positions" attribute. Convenience function.
Definition: PointCloud.h:124
PointCloud To(const core::Device &device, bool copy=false) const
Definition: PointCloud.cpp:112
const TensorMap & GetPointAttr() const
Getter for point_attr_ TensorMap. Used in Pybind.
Definition: PointCloud.h:111
void SetPointAttr(const std::string &key, const core::Tensor &value)
Definition: PointCloud.h:177
core::Tensor & GetPointColors()
Get the value of the "colors" attribute. Convenience function.
Definition: PointCloud.h:127
Class that defines the convergence criteria of ICP.
Definition: Registration.h:31
double period_
Time period (in seconds) between the source and the target point clouds.
#define LogWarning(...)
Definition: Logging.h:72
core::Tensor EigenMatrixToTensor(const Eigen::MatrixBase< Derived > &matrix)
Converts a eigen matrix of shape (M, N) with alignment A and type T to a tensor.
const Dtype Float32
Definition: Dtype.cpp:42
void To(const core::Tensor &src, core::Tensor &dst, double scale, double offset)
Definition: Image.cpp:17
bool ReadPointCloud(const std::string &filename, geometry::PointCloud &pointcloud, const cloudViewer::io::ReadPointCloudOption &params)
static void BenchmarkICP(benchmark::State &state, const core::Device &device, const core::Dtype &dtype, const TransformationEstimationType &type)
static const double max_correspondence_distance
static const std::vector< float > initial_transform_flat
static std::tuple< geometry::PointCloud, geometry::PointCloud > LoadTensorDopplerPointCloudFromFile(const std::string &source_pointcloud_filename, const std::string &target_pointcloud_filename, const double voxel_downsample_factor, const core::Dtype &dtype, const core::Device &device)
RegistrationResult ICP(const geometry::PointCloud &source, const geometry::PointCloud &target, const double max_correspondence_distance, const core::Tensor &init_source_to_target, const TransformationEstimation &estimation, const ICPConvergenceCriteria &criteria, const double voxel_size, const std::function< void(const std::unordered_map< std::string, core::Tensor > &)> &callback_after_iteration)
Functions for ICP registration.
core::Tensor ComputeDirectionVectors(const core::Tensor &positions)
static void BenchmarkDopplerICP(benchmark::State &state, const core::Device &device, const core::Dtype &dtype, const TransformationEstimationType &type)
static std::tuple< geometry::PointCloud, geometry::PointCloud > LoadTensorPointCloudFromFile(const std::string &source_pointcloud_filename, const std::string &target_pointcloud_filename, const double voxel_downsample_factor, const core::Dtype &dtype, const core::Device &device)
static const double voxel_downsampling_factor
void SetVerbosityLevel(VerbosityLevel level)
Definition: Logging.cpp:89
Generic file read and write utility for python interface.