cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP#

class cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP#

Class to estimate a transformation between two point clouds using color information

__init__(*args, **kwargs)#

Overloaded function.

  1. __init__(self: cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP) -> None

Default constructor

  1. __init__(self: cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP, arg0: cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP) -> None

Copy constructor

  1. __init__(self: cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP, period: typing.SupportsFloat, lambda_doppler: typing.SupportsFloat, reject_dynamic_outliers: bool, doppler_outlier_threshold: typing.SupportsFloat, outlier_rejection_min_iteration: typing.SupportsInt, geometric_robust_loss_min_iteration: typing.SupportsInt, doppler_robust_loss_min_iteration: typing.SupportsInt, goemetric_kernel: cloudViewer::t::pipelines::registration::RobustKernel, doppler_kernel: cloudViewer::t::pipelines::registration::RobustKernel, transform_vehicle_to_sensor: cloudViewer.core.Tensor) -> None

  2. __init__(self: cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP, lambda_doppler: typing.SupportsFloat) -> None

compute_rmse(self, source, target, correspondences)#

Compute RMSE between source and target points cloud given correspondences.

Parameters:
  • source (cloudViewer::t::geometry::PointCloud) – Source point cloud.

  • target (cloudViewer::t::geometry::PointCloud) – Target point cloud.

  • correspondences (cloudViewer.core.Tensor) – 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.

Returns:

float

compute_transformation(self: cloudViewer.t.pipelines.registration.TransformationEstimationForDopplerICP, arg0: cloudViewer::t::geometry::PointCloud, arg1: cloudViewer::t::geometry::PointCloud, arg2: cloudViewer.core.Tensor, arg3: cloudViewer.core.Tensor, arg4: typing.SupportsInt) cloudViewer.core.Tensor#

Compute transformation from source to target point cloud given correspondences

property doppler_kernel#

Robust Kernel used in the Doppler Error Optimization

property doppler_outlier_threshold#

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

property doppler_robust_loss_min_iteration#

Minimum iterations after which Robust Kernel is used for the Doppler error

property geometric_kernel#

Robust Kernel used in the Geometric Error Optimization

property geometric_robust_loss_min_iteration#

Minimum iterations after which Robust Kernel is used for the Geometric error

property lambda_doppler#

λ ∈ [0, 1] in the overall energy (1−λ)EG + λED. Refer the documentation of DopplerICP for more information.

property outlier_rejection_min_iteration#

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

property period#

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

property reject_dynamic_outliers#

Whether or not to reject dynamic point outlier correspondences.

property transform_vehicle_to_sensor#

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