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

#include <TransformationEstimation.h>

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

Public Member Functions

 TransformationEstimationPointToPoint ()
 
 ~TransformationEstimationPointToPoint () override
 
TransformationEstimationType GetTransformationEstimationType () const override
 
double ComputeRMSE (const geometry::PointCloud &source, const geometry::PointCloud &target, const core::Tensor &correspondences) const override
 Computes RMSE (double) for PointToPoint 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 PointToPoint 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 ()
 

Detailed Description

Class to estimate a transformation matrix tensor of shape {4, 4}, dtype Float64, on CPU device for point to point distance.

Constructor & Destructor Documentation

◆ TransformationEstimationPointToPoint()

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

◆ ~TransformationEstimationPointToPoint()

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

Member Function Documentation

◆ ComputeRMSE()

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

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

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

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

◆ ComputeTransformation()

core::Tensor open3d::t::pipelines::registration::TransformationEstimationPointToPoint::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 PointToPoint 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).
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::TransformationEstimationPointToPoint::GetTransformationEstimationType ( ) const
inlineoverridevirtual

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