Open3D (C++ API)  0.18.0+5c982c7
Public Member Functions
open3d::t::pipelines::registration::TransformationEstimation Class Referenceabstract

#include <TransformationEstimation.h>

Inheritance diagram for open3d::t::pipelines::registration::TransformationEstimation:
open3d::t::pipelines::registration::TransformationEstimationForColoredICP open3d::t::pipelines::registration::TransformationEstimationForDopplerICP open3d::t::pipelines::registration::TransformationEstimationPointToPlane open3d::t::pipelines::registration::TransformationEstimationPointToPoint

Public Member Functions

 TransformationEstimation ()
 Default Constructor. More...
 
virtual ~TransformationEstimation ()
 
virtual TransformationEstimationType GetTransformationEstimationType () const =0
 
virtual double ComputeRMSE (const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences) const =0
 
virtual 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 =0
 

Detailed Description

Base class that estimates a transformation between two point clouds The virtual function ComputeTransformation() must be implemented in subclasses.

Constructor & Destructor Documentation

◆ TransformationEstimation()

open3d::t::pipelines::registration::TransformationEstimation::TransformationEstimation ( )
inline

Default Constructor.

◆ ~TransformationEstimation()

virtual open3d::t::pipelines::registration::TransformationEstimation::~TransformationEstimation ( )
inlinevirtual

Member Function Documentation

◆ ComputeRMSE()

virtual double open3d::t::pipelines::registration::TransformationEstimation::ComputeRMSE ( const geometry::PointCloud source,
const geometry::PointCloud target,
const core::Tensor correspondences 
) const
pure virtual

Compute RMSE between source and target points cloud given correspondences.

Parameters
sourceSource point cloud. (Float32 or Float64 type).
targetTarget point cloud. (Float32 or Float64 type).
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.

Implemented in open3d::t::pipelines::registration::TransformationEstimationForDopplerICP, open3d::t::pipelines::registration::TransformationEstimationForColoredICP, open3d::t::pipelines::registration::TransformationEstimationPointToPlane, and open3d::t::pipelines::registration::TransformationEstimationPointToPoint.

◆ ComputeTransformation()

virtual core::Tensor open3d::t::pipelines::registration::TransformationEstimation::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
pure virtual

Compute transformation from source to target point cloud given correspondences.

Parameters
sourceSource point cloud. (Float32 or Float64 type).
targetTarget point cloud. (Float32 or Float64 type).
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.

Implemented in open3d::t::pipelines::registration::TransformationEstimationForDopplerICP, open3d::t::pipelines::registration::TransformationEstimationForColoredICP, open3d::t::pipelines::registration::TransformationEstimationPointToPlane, and open3d::t::pipelines::registration::TransformationEstimationPointToPoint.

◆ GetTransformationEstimationType()

virtual TransformationEstimationType open3d::t::pipelines::registration::TransformationEstimation::GetTransformationEstimationType ( ) const
pure virtual

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