|
Open3D (C++ API)
0.19.0
|
#include <TransformationEstimation.h>
Public Member Functions | |
| ~TransformationEstimationForDopplerICP () override | |
| 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. | |
| TransformationEstimationType | GetTransformationEstimationType () const override |
| 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. | |
| core::Tensor | ComputeTransformation (const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences, const core::Tensor ¤t_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}, and dtype Float64 on CPU device. | |
| Public Member Functions inherited from open3d::t::pipelines::registration::TransformationEstimation | |
| TransformationEstimation () | |
| Default Constructor. | |
| virtual | ~TransformationEstimation () |
Data Fields | |
| double | period_ {0.1} |
| Time period (in seconds) between the source and the target point clouds. | |
| double | lambda_doppler_ {0.01} |
| Factor that weighs the Doppler residual term in DICP objective. | |
| bool | reject_dynamic_outliers_ {false} |
| Whether or not to prune dynamic point outlier correspondences. | |
| double | doppler_outlier_threshold_ {2.0} |
| std::size_t | outlier_rejection_min_iteration_ {2} |
| Number of iterations of ICP after which outlier rejection is enabled. | |
| std::size_t | geometric_robust_loss_min_iteration_ {0} |
| Number of iterations of ICP after which robust loss kicks in. | |
| std::size_t | doppler_robust_loss_min_iteration_ {2} |
| RobustKernel | geometric_kernel_ |
| RobustKernel for outlier rejection. | |
| RobustKernel | doppler_kernel_ |
| core::Tensor | transform_vehicle_to_sensor_ |
This is the implementation of the following paper: B. Hexsel, H. Vhavle, Y. Chen, DICP: Doppler Iterative Closest Point Algorithm, RSS 2022.
Class to estimate a transformation matrix tensor of shape {4, 4}, dtype Float64, on CPU device for DopplerICP method.
|
inlineoverride |
|
inlineexplicit |
Constructor.
| period | Time period (in seconds) between the source and the target point clouds. Default value: 0.1. |
| lambda_doppler | λ ∈ [0, 1] in the overall energy (1−λ)EG + λED. Refer the documentation of DopplerICP for more information. |
| reject_dynamic_outliers | Whether or not to reject dynamic point outlier correspondences. |
| doppler_outlier_threshold | Correspondences with Doppler error greater than this threshold are rejected from optimization. |
| outlier_rejection_min_iteration | Number of iterations of ICP after which outlier rejection is enabled. |
| geometric_robust_loss_min_iteration | Number of iterations of ICP after which robust loss for geometric term kicks in. |
| doppler_robust_loss_min_iteration | Number of iterations of ICP after which robust loss for Doppler term kicks in. |
| geometric_kernel | (optional) Any of the implemented statistical robust kernel for outlier rejection for the geometric term. |
| doppler_kernel | (optional) Any of the implemented statistical robust kernel for outlier rejection for the Doppler term. |
| transform_vehicle_to_sensor | The 4x4 extrinsic transformation matrix between the vehicle and the sensor frames. Defaults to identity transform. |
|
overridevirtual |
Computes RMSE (double) for DopplerICP method, between two pointclouds, given correspondences.
| source | Source pointcloud. (Float32 or Float64 type). |
| target | Target pointcloud. (Float32 or Float64 type). It must contain normals, directions, and Doppler of the same shape and dtype as the positions. |
| correspondences | Tensor of type Int64 containing indices of corresponding target points, where the value is the target index and the index of the value itself is the source index. It contains -1 as value at index with no correspondence. |
Implements open3d::t::pipelines::registration::TransformationEstimation.
|
overridevirtual |
Estimates the transformation matrix for DopplerICP method, a tensor of shape {4, 4}, and dtype Float64 on CPU device.
| source | Source pointcloud. (Float32 or Float64 type). |
| target | Target pointcloud. (Float32 or Float64 type). It must contain normals, directions, and Doppler of the same shape and dtype as the positions. |
| correspondences | Tensor of type Int64 containing indices of corresponding target points, where the value is the target index and the index of the value itself is the source index. It contains -1 as value at index with no correspondence. |
| current_transform | The current pose estimate of ICP. |
| iteration | The current iteration number of the ICP algorithm. |
Implements open3d::t::pipelines::registration::TransformationEstimation.
|
inlineoverridevirtual |
| RobustKernel open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::doppler_kernel_ |
| double open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::doppler_outlier_threshold_ {2.0} |
Correspondences with Doppler error greater than this threshold are rejected from optimization.
| std::size_t open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::doppler_robust_loss_min_iteration_ {2} |
| RobustKernel open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::geometric_kernel_ |
RobustKernel for outlier rejection.
| std::size_t open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::geometric_robust_loss_min_iteration_ {0} |
Number of iterations of ICP after which robust loss kicks in.
| double open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::lambda_doppler_ {0.01} |
Factor that weighs the Doppler residual term in DICP objective.
| std::size_t open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::outlier_rejection_min_iteration_ {2} |
Number of iterations of ICP after which outlier rejection is enabled.
| double open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::period_ {0.1} |
Time period (in seconds) between the source and the target point clouds.
| bool open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::reject_dynamic_outliers_ {false} |
Whether or not to prune dynamic point outlier correspondences.
| core::Tensor open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::transform_vehicle_to_sensor_ |
The 4x4 extrinsic transformation matrix between the vehicle and the sensor frames.