10 #include <benchmark/benchmark.h>
22 namespace registration {
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};
44 static std::tuple<geometry::PointCloud, geometry::PointCloud>
46 const std::string& target_pointcloud_filename,
47 const double voxel_downsample_factor,
53 {
"auto",
false,
false,
true});
55 {
"auto",
false,
false,
true});
57 source = source.
To(device);
58 target = target.
To(device);
61 if (voxel_downsample_factor > 0.001) {
66 "VoxelDownsample: Impractical voxel size [< 0.001], skipping "
82 return std::make_tuple(source, target);
96 std::shared_ptr<TransformationEstimation> estimation;
98 estimation = std::make_shared<TransformationEstimationPointToPlane>();
100 estimation = std::make_shared<TransformationEstimationPointToPoint>();
102 estimation = std::make_shared<TransformationEstimationForColoredICP>();
117 for (
auto _ : state) {
119 init_trans, *estimation,
129 for (int64_t i = 0; i < positions.
GetLength(); ++i) {
131 core::Tensor norm = (positions[i][0] * positions[i][0] +
132 positions[i][1] * positions[i][1] +
133 positions[i][2] * positions[i][2])
137 if (norm.
Item<
float>() == 0.0) {
138 directions[i].
Fill(0.0);
142 directions[i] = positions[i] / norm;
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,
158 {
"auto",
false,
false,
true});
160 {
"auto",
false,
false,
true});
165 source = source.
To(device);
166 target = target.
To(device);
169 if (voxel_downsample_factor > 0.001) {
174 "VoxelDownsample: Impractical voxel size [< 0.001], skipping "
186 return std::make_tuple(source, target);
200 Eigen::Matrix4d calibration{Eigen::Matrix4d::Identity()};
209 estimation_dicp.
period_ = period;
221 for (
auto _ : state) {
223 init_trans, estimation_dicp,
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);
258 #ifdef BUILD_CUDA_MODULE
#define ENUM_ICP_METHOD_DEVICE(BENCHMARK_FUNCTION, METHOD_NAME, TRANSFORMATION_TYPE, DEVICE)
void Sqrt(const double in[2], double out[2])
int64_t GetLength() const
static Tensor Eye(int64_t n, Dtype dtype, const Device &device)
Create an identity matrix of size n x n.
Device GetDevice() const override
static Tensor Empty(const SizeVector &shape, Dtype dtype, const Device &device=Device("CPU:0"))
Create a tensor with uninitialized values.
SizeVector GetShape() const
void Fill(S v)
Fill the whole Tensor with a scalar value, the scalar will be casted to the Tensor's Dtype.
Tensor Div(const Tensor &value) const
Divides a tensor and returns the resulting tensor.
Tensor To(Dtype dtype, bool copy=false) const
Data class for DemoDopplerICPSequence contains an example sequence of 100 point clouds with Doppler v...
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 ...
std::vector< std::string > GetPaths() const
Returns list of 3 point cloud paths.
A point cloud contains a list of 3D points.
void SetPointNormals(const core::Tensor &value)
Set the value of the "normals" attribute. Convenience function.
core::Tensor & GetPointNormals()
Get the value of the "normals" attribute. Convenience function.
PointCloud VoxelDownSample(double voxel_size, const std::string &reduction="mean") const
Downsamples a point cloud with a specified voxel size.
void SetPointColors(const core::Tensor &value)
Set the value of the "colors" attribute. Convenience function.
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...
void SetPointPositions(const core::Tensor &value)
Set the value of the "positions" attribute. Convenience function.
core::Tensor & GetPointPositions()
Get the value of the "positions" attribute. Convenience function.
PointCloud To(const core::Device &device, bool copy=false) const
const TensorMap & GetPointAttr() const
Getter for point_attr_ TensorMap. Used in Pybind.
void SetPointAttr(const std::string &key, const core::Tensor &value)
core::Tensor & GetPointColors()
Get the value of the "colors" attribute. Convenience function.
bool HasPointColors() const
Class that defines the convergence criteria of ICP.
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.
void To(const core::Tensor &src, core::Tensor &dst, double scale, double offset)
bool ReadPointCloud(const std::string &filename, geometry::PointCloud &pointcloud, const cloudViewer::io::ReadPointCloudOption ¶ms)
static const double relative_fitness
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)
static const int normals_max_neighbors
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)
TransformationEstimationType
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 normals_search_radius
static const int max_iterations
static const double relative_rmse
static const double voxel_downsampling_factor
void SetVerbosityLevel(VerbosityLevel level)
Generic file read and write utility for python interface.