File: Registration.cpp

package info (click to toggle)
open3d 0.19.0-3
  • links: PTS, VCS
  • area: main
  • in suites: trixie
  • size: 83,236 kB
  • sloc: cpp: 206,501; python: 27,254; ansic: 8,356; javascript: 1,883; sh: 1,527; makefile: 259; xml: 69
file content (280 lines) | stat: -rw-r--r-- 11,635 bytes parent folder | download | duplicates (2)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
// ----------------------------------------------------------------------------
// -                        Open3D: www.open3d.org                            -
// ----------------------------------------------------------------------------
// Copyright (c) 2018-2024 www.open3d.org
// SPDX-License-Identifier: MIT
// ----------------------------------------------------------------------------

#include "open3d/t/pipelines/registration/Registration.h"

#include <benchmark/benchmark.h>

#include "open3d/core/CUDAUtils.h"
#include "open3d/core/EigenConverter.h"
#include "open3d/core/nns/NearestNeighborSearch.h"
#include "open3d/data/Dataset.h"
#include "open3d/t/io/PointCloudIO.h"
#include "open3d/t/pipelines/registration/TransformationEstimation.h"

namespace open3d {
namespace t {
namespace pipelines {
namespace registration {

// Testing parameters:
// ICP ConvergenceCriteria.
static const double relative_fitness = 1e-6;
static const double relative_rmse = 1e-6;
static const int max_iterations = 10;

static const double voxel_downsampling_factor = 0.02;

// NNS parameter.
static const double max_correspondence_distance = 0.05;

// Normal estimation parameters.
static const double normals_search_radius = 10.0;
static const int normals_max_neighbors = 30;

// Initial transformation guess for registration.
static const std::vector<float> initial_transform_flat{
        0.862, 0.011, -0.507, 0.5,  -0.139, 0.967, -0.215, 0.7,
        0.487, 0.255, 0.835,  -1.4, 0.0,    0.0,   0.0,    1.0};

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) {
    geometry::PointCloud source, target;

    io::ReadPointCloud(source_pointcloud_filename, source,
                       {"auto", false, false, true});
    io::ReadPointCloud(target_pointcloud_filename, target,
                       {"auto", false, false, true});

    source = source.To(device);
    target = target.To(device);

    // Eliminates the case of impractical values (including negative).
    if (voxel_downsample_factor > 0.001) {
        source = source.VoxelDownSample(voxel_downsample_factor);
        target = target.VoxelDownSample(voxel_downsample_factor);
    } else {
        utility::LogWarning(
                "VoxelDownsample: Impractical voxel size [< 0.001], skipping "
                "downsampling.");
    }

    source.SetPointPositions(source.GetPointPositions().To(dtype));
    source.SetPointNormals(source.GetPointNormals().To(dtype));
    if (source.HasPointColors()) {
        source.SetPointColors(source.GetPointColors().To(dtype).Div(255.0));
    }

    target.SetPointPositions(target.GetPointPositions().To(dtype));
    target.SetPointNormals(target.GetPointNormals().To(dtype));
    if (target.HasPointColors()) {
        target.SetPointColors(target.GetPointColors().To(dtype).Div(255.0));
    }

    return std::make_tuple(source, target);
}

static void BenchmarkICP(benchmark::State& state,
                         const core::Device& device,
                         const core::Dtype& dtype,
                         const TransformationEstimationType& type) {
    utility::SetVerbosityLevel(utility::VerbosityLevel::Error);
    data::DemoICPPointClouds demo_icp_pointclouds;
    geometry::PointCloud source, target;
    std::tie(source, target) = LoadTensorPointCloudFromFile(
            demo_icp_pointclouds.GetPaths(0), demo_icp_pointclouds.GetPaths(1),
            voxel_downsampling_factor, dtype, device);

    std::shared_ptr<TransformationEstimation> estimation;
    if (type == TransformationEstimationType::PointToPlane) {
        estimation = std::make_shared<TransformationEstimationPointToPlane>();
    } else if (type == TransformationEstimationType::PointToPoint) {
        estimation = std::make_shared<TransformationEstimationPointToPoint>();
    } else if (type == TransformationEstimationType::ColoredICP) {
        estimation = std::make_shared<TransformationEstimationForColoredICP>();
    }

    core::Tensor init_trans =
            core::Tensor(initial_transform_flat, {4, 4}, core::Float32, device)
                    .To(dtype);

    RegistrationResult reg_result(init_trans);

    // Warm up.
    reg_result = ICP(source, target, max_correspondence_distance, init_trans,
                     *estimation,
                     ICPConvergenceCriteria(relative_fitness, relative_rmse,
                                            max_iterations));

    for (auto _ : state) {
        reg_result = ICP(source, target, max_correspondence_distance,
                         init_trans, *estimation,
                         ICPConvergenceCriteria(relative_fitness, relative_rmse,
                                                max_iterations));
        core::cuda::Synchronize(device);
    }
}

core::Tensor ComputeDirectionVectors(const core::Tensor& positions) {
    core::Tensor directions = core::Tensor::Empty(
            positions.GetShape(), positions.GetDtype(), positions.GetDevice());
    for (int64_t i = 0; i < positions.GetLength(); ++i) {
        // Compute the norm of the position vector.
        core::Tensor norm = (positions[i][0] * positions[i][0] +
                             positions[i][1] * positions[i][1] +
                             positions[i][2] * positions[i][2])
                                    .Sqrt();

        // If the norm is zero, set the direction vector to zero.
        if (norm.Item<float>() == 0.0) {
            directions[i].Fill(0.0);
        } else {
            // Otherwise, compute the direction vector by dividing the position
            // vector by its norm.
            directions[i] = positions[i] / norm;
        }
    }
    return directions;
}

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) {
    geometry::PointCloud source, target;

    io::ReadPointCloud(source_pointcloud_filename, source,
                       {"auto", false, false, true});
    io::ReadPointCloud(target_pointcloud_filename, target,
                       {"auto", false, false, true});

    source.SetPointAttr("directions",
                        ComputeDirectionVectors(source.GetPointPositions()));

    source = source.To(device);
    target = target.To(device);

    // Eliminates the case of impractical values (including negative).
    if (voxel_downsample_factor > 0.001) {
        source = source.VoxelDownSample(voxel_downsample_factor);
        target = target.VoxelDownSample(voxel_downsample_factor);
    } else {
        utility::LogWarning(
                "VoxelDownsample: Impractical voxel size [< 0.001], skipping "
                "downsampling.");
    }

    source.SetPointPositions(source.GetPointPositions().To(dtype));
    source.SetPointAttr("dopplers", source.GetPointAttr("dopplers").To(dtype));
    source.SetPointAttr("directions",
                        source.GetPointAttr("directions").To(dtype));

    target.SetPointPositions(target.GetPointPositions().To(dtype));
    target.EstimateNormals(normals_search_radius, normals_max_neighbors);

    return std::make_tuple(source, target);
}

static void BenchmarkDopplerICP(benchmark::State& state,
                                const core::Device& device,
                                const core::Dtype& dtype,
                                const TransformationEstimationType& type) {
    utility::SetVerbosityLevel(utility::VerbosityLevel::Error);
    data::DemoDopplerICPSequence demo_sequence;
    geometry::PointCloud source, target;
    std::tie(source, target) = LoadTensorDopplerPointCloudFromFile(
            demo_sequence.GetPath(0), demo_sequence.GetPath(1),
            voxel_downsampling_factor, dtype, device);

    Eigen::Matrix4d calibration{Eigen::Matrix4d::Identity()};
    double period{0.0};
    demo_sequence.GetCalibration(calibration, period);

    const core::Tensor calibration_t =
            core::eigen_converter::EigenMatrixToTensor(calibration)
                    .To(device, dtype);

    TransformationEstimationForDopplerICP estimation_dicp;
    estimation_dicp.period_ = period;
    estimation_dicp.transform_vehicle_to_sensor_ = calibration_t;

    core::Tensor init_trans = core::Tensor::Eye(4, dtype, device);
    RegistrationResult reg_result(init_trans);

    // Warm up.
    reg_result = ICP(source, target, max_correspondence_distance, init_trans,
                     estimation_dicp,
                     ICPConvergenceCriteria(relative_fitness, relative_rmse,
                                            max_iterations));

    for (auto _ : state) {
        reg_result = ICP(source, target, max_correspondence_distance,
                         init_trans, estimation_dicp,
                         ICPConvergenceCriteria(relative_fitness, relative_rmse,
                                                max_iterations));
        core::cuda::Synchronize(device);
    }
}

#define ENUM_ICP_METHOD_DEVICE(BENCHMARK_FUNCTION, METHOD_NAME,         \
                               TRANSFORMATION_TYPE, DEVICE)             \
    BENCHMARK_CAPTURE(BENCHMARK_FUNCTION, DEVICE METHOD_NAME##_Float32, \
                      core::Device(DEVICE), core::Float32,              \
                      TRANSFORMATION_TYPE)                              \
            ->Unit(benchmark::kMillisecond);                            \
    BENCHMARK_CAPTURE(BENCHMARK_FUNCTION, DEVICE METHOD_NAME##_Float64, \
                      core::Device(DEVICE), core::Float64,              \
                      TRANSFORMATION_TYPE)                              \
            ->Unit(benchmark::kMillisecond);

ENUM_ICP_METHOD_DEVICE(BenchmarkICP,
                       PointToPoint,
                       TransformationEstimationType::PointToPoint,
                       "CPU:0")
ENUM_ICP_METHOD_DEVICE(BenchmarkICP,
                       PointToPlane,
                       TransformationEstimationType::PointToPlane,
                       "CPU:0")
ENUM_ICP_METHOD_DEVICE(BenchmarkICP,
                       ColoredICP,
                       TransformationEstimationType::ColoredICP,
                       "CPU:0")
ENUM_ICP_METHOD_DEVICE(BenchmarkDopplerICP,
                       DopplerICP,
                       TransformationEstimationType::DopplerICP,
                       "CPU:0")

#ifdef BUILD_CUDA_MODULE
ENUM_ICP_METHOD_DEVICE(BenchmarkICP,
                       PointToPoint,
                       TransformationEstimationType::PointToPoint,
                       "CUDA:0")
ENUM_ICP_METHOD_DEVICE(BenchmarkICP,
                       PointToPlane,
                       TransformationEstimationType::PointToPlane,
                       "CUDA:0")
ENUM_ICP_METHOD_DEVICE(BenchmarkICP,
                       ColoredICP,
                       TransformationEstimationType::ColoredICP,
                       "CUDA:0")
ENUM_ICP_METHOD_DEVICE(BenchmarkDopplerICP,
                       DopplerICP,
                       TransformationEstimationType::DopplerICP,
                       "CUDA:0")
#endif

}  // namespace registration
}  // namespace pipelines
}  // namespace t
}  // namespace open3d