Open3D (C++ API)  0.18.0+5c982c7
Public Member Functions | Data Fields
open3d::t::pipelines::registration::TransformationEstimationForDopplerICP Class Reference

#include <TransformationEstimation.h>

Inheritance diagram for open3d::t::pipelines::registration::TransformationEstimationForDopplerICP:
open3d::t::pipelines::registration::TransformationEstimation

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. More...
 
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. More...
 
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}, and dtype Float64 on CPU device. More...
 
- Public Member Functions inherited from open3d::t::pipelines::registration::TransformationEstimation
 TransformationEstimation ()
 Default Constructor. More...
 
virtual ~TransformationEstimation ()
 

Data Fields

double period_ {0.1}
 Time period (in seconds) between the source and the target point clouds. More...
 
double lambda_doppler_ {0.01}
 Factor that weighs the Doppler residual term in DICP objective. More...
 
bool reject_dynamic_outliers_ {false}
 Whether or not to prune dynamic point outlier correspondences. More...
 
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. More...
 
std::size_t geometric_robust_loss_min_iteration_ {0}
 Number of iterations of ICP after which robust loss kicks in. More...
 
std::size_t doppler_robust_loss_min_iteration_ {2}
 
RobustKernel geometric_kernel_
 RobustKernel for outlier rejection. More...
 
RobustKernel doppler_kernel_
 
core::Tensor transform_vehicle_to_sensor_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ~TransformationEstimationForDopplerICP()

open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::~TransformationEstimationForDopplerICP ( )
inlineoverride

◆ TransformationEstimationForDopplerICP()

open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::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::Float64core::Device("CPU:0")) 
)
inlineexplicit

Constructor.

Parameters
periodTime 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_outliersWhether or not to reject dynamic point outlier correspondences.
doppler_outlier_thresholdCorrespondences with Doppler error greater than this threshold are rejected from optimization.
outlier_rejection_min_iterationNumber of iterations of ICP after which outlier rejection is enabled.
geometric_robust_loss_min_iterationNumber of iterations of ICP after which robust loss for geometric term kicks in.
doppler_robust_loss_min_iterationNumber 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_sensorThe 4x4 extrinsic transformation matrix between the vehicle and the sensor frames. Defaults to identity transform.

Member Function Documentation

◆ ComputeRMSE()

double open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::ComputeRMSE ( const geometry::PointCloud source,
const geometry::PointCloud target,
const core::Tensor correspondences 
) const
overridevirtual

Computes RMSE (double) for DopplerICP method, between two pointclouds, given correspondences.

Parameters
sourceSource pointcloud. (Float32 or Float64 type).
targetTarget pointcloud. (Float32 or Float64 type). It must contain normals, directions, and Doppler of the same shape and dtype as the positions.
correspondencesTensor 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.

◆ ComputeTransformation()

core::Tensor open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::ComputeTransformation ( const geometry::PointCloud source,
const geometry::PointCloud target,
const core::Tensor correspondences,
const core::Tensor current_transform = core::Tensor::Eye(4, core::Float64core::Device("CPU:0")),
const std::size_t  iteration = 0 
) const
overridevirtual

Estimates the transformation matrix for DopplerICP method, a tensor of shape {4, 4}, and dtype Float64 on CPU device.

Parameters
sourceSource pointcloud. (Float32 or Float64 type).
targetTarget pointcloud. (Float32 or Float64 type). It must contain normals, directions, and Doppler of the same shape and dtype as the positions.
correspondencesTensor 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_transformThe current pose estimate of ICP.
iterationThe current iteration number of the ICP algorithm.
Returns
transformation between source to target, a tensor of shape {4, 4}, type Float64 on CPU device.

Implements open3d::t::pipelines::registration::TransformationEstimation.

◆ GetTransformationEstimationType()

TransformationEstimationType open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::GetTransformationEstimationType ( ) const
inlineoverridevirtual

Field Documentation

◆ doppler_kernel_

RobustKernel open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::doppler_kernel_

◆ doppler_outlier_threshold_

double open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::doppler_outlier_threshold_ {2.0}

Correspondences with Doppler error greater than this threshold are rejected from optimization.

◆ doppler_robust_loss_min_iteration_

std::size_t open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::doppler_robust_loss_min_iteration_ {2}

◆ geometric_kernel_

RobustKernel open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::geometric_kernel_
Initial value:
=
RobustKernel(RobustKernelMethod::L2Loss, 1.0, 1.0)

RobustKernel for outlier rejection.

◆ geometric_robust_loss_min_iteration_

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.

◆ lambda_doppler_

double open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::lambda_doppler_ {0.01}

Factor that weighs the Doppler residual term in DICP objective.

◆ outlier_rejection_min_iteration_

std::size_t open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::outlier_rejection_min_iteration_ {2}

Number of iterations of ICP after which outlier rejection is enabled.

◆ period_

double open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::period_ {0.1}

Time period (in seconds) between the source and the target point clouds.

◆ reject_dynamic_outliers_

bool open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::reject_dynamic_outliers_ {false}

Whether or not to prune dynamic point outlier correspondences.

◆ transform_vehicle_to_sensor_

core::Tensor open3d::t::pipelines::registration::TransformationEstimationForDopplerICP::transform_vehicle_to_sensor_
Initial value:
=
core::Tensor::Eye(4, core::Float64, core::Device("CPU:0"))
static Tensor Eye(int64_t n, Dtype dtype, const Device &device)
Create an identity matrix of size n x n.
Definition: Tensor.cpp:386
const Dtype Float64
Definition: Dtype.cpp:43

The 4x4 extrinsic transformation matrix between the vehicle and the sensor frames.


The documentation for this class was generated from the following files: