Open3D (C++ API)  0.18.0+252c867
Data Structures | Typedefs | Enumerations | Functions
open3d::pipelines::registration Namespace Reference

Data Structures

class  TransformationEstimationForColoredICP
 
class  CorrespondenceChecker
 Base class that checks if two (small) point clouds can be aligned. More...
 
class  CorrespondenceCheckerBasedOnEdgeLength
 Check if two point clouds build the polygons with similar edge lengths. More...
 
class  CorrespondenceCheckerBasedOnDistance
 Check if two aligned point clouds are close. More...
 
class  CorrespondenceCheckerBasedOnNormal
 Class to check if two aligned point clouds have similar normals. More...
 
class  FastGlobalRegistrationOption
 Options for FastGlobalRegistration. More...
 
class  Feature
 Class to store featrues for registration. More...
 
class  TransformationEstimationForGeneralizedICP
 
class  GlobalOptimizationOption
 Option for GlobalOptimization. More...
 
class  GlobalOptimizationConvergenceCriteria
 Convergence criteria of GlobalOptimization. More...
 
class  GlobalOptimizationMethod
 Base class for global optimization method. More...
 
class  GlobalOptimizationGaussNewton
 Global optimization with Gauss-Newton algorithm. More...
 
class  GlobalOptimizationLevenbergMarquardt
 Global optimization with Levenberg-Marquardt algorithm. More...
 
class  PoseGraphNode
 Node of PoseGraph. More...
 
class  PoseGraphEdge
 Edge of PoseGraph. More...
 
class  PoseGraph
 Data structure defining the pose graph. More...
 
class  ICPConvergenceCriteria
 Class that defines the convergence criteria of ICP. More...
 
class  RANSACConvergenceCriteria
 Class that defines the convergence criteria of RANSAC. More...
 
class  RegistrationResult
 
class  RobustKernel
 
class  L2Loss
 
class  L1Loss
 
class  HuberLoss
 
class  CauchyLoss
 
class  GMLoss
 
class  TukeyLoss
 
class  TransformationEstimation
 
class  TransformationEstimationPointToPoint
 
class  TransformationEstimationPointToPlane
 

Typedefs

typedef std::vector< Eigen::Vector2i > CorrespondenceSet
 

Enumerations

enum class  TransformationEstimationType {
  Unspecified = 0 , PointToPoint = 1 , PointToPlane = 2 , ColoredICP = 3 ,
  GeneralizedICP = 4
}
 

Functions

RegistrationResult RegistrationColoredICP (const geometry::PointCloud &source, const geometry::PointCloud &target, double max_distance, const Eigen::Matrix4d &init=Eigen::Matrix4d::Identity(), const TransformationEstimationForColoredICP &estimation=TransformationEstimationForColoredICP(), const ICPConvergenceCriteria &criteria=ICPConvergenceCriteria())
 Function for Colored ICP registration. More...
 
RegistrationResult FastGlobalRegistrationBasedOnCorrespondence (const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres, const FastGlobalRegistrationOption &option=FastGlobalRegistrationOption())
 Fast Global Registration based on a given set of correspondences. More...
 
RegistrationResult FastGlobalRegistrationBasedOnFeatureMatching (const geometry::PointCloud &source, const geometry::PointCloud &target, const Feature &source_feature, const Feature &target_feature, const FastGlobalRegistrationOption &option=FastGlobalRegistrationOption())
 Fast Global Registration based on a given set of FPFH features. More...
 
std::shared_ptr< FeatureComputeFPFHFeature (const geometry::PointCloud &input, const geometry::KDTreeSearchParam &search_param)
 
CorrespondenceSet CorrespondencesFromFeatures (const Feature &source_features, const Feature &target_features, bool mutual_filter=false, float mutual_consistency_ratio=0.1)
 Function to find correspondences via 1-nearest neighbor feature matching. Target is used to construct a nearest neighbor search object, in order to query source. More...
 
RegistrationResult RegistrationGeneralizedICP (const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &init=Eigen::Matrix4d::Identity(), const TransformationEstimationForGeneralizedICP &estimation=TransformationEstimationForGeneralizedICP(), const ICPConvergenceCriteria &criteria=ICPConvergenceCriteria())
 Function for Generalized ICP registration. More...
 
std::shared_ptr< PoseGraphCreatePoseGraphWithoutInvalidEdges (const PoseGraph &pose_graph, const GlobalOptimizationOption &option)
 
void GlobalOptimization (PoseGraph &pose_graph, const GlobalOptimizationMethod &method, const GlobalOptimizationConvergenceCriteria &criteria, const GlobalOptimizationOption &option)
 
RegistrationResult EvaluateRegistration (const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation=Eigen::Matrix4d::Identity())
 Function for evaluating registration between point clouds. More...
 
RegistrationResult RegistrationICP (const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &init=Eigen::Matrix4d::Identity(), const TransformationEstimation &estimation=TransformationEstimationPointToPoint(false), const ICPConvergenceCriteria &criteria=ICPConvergenceCriteria())
 Functions for ICP registration. More...
 
RegistrationResult RegistrationRANSACBasedOnCorrespondence (const geometry::PointCloud &source, const geometry::PointCloud &target, const CorrespondenceSet &corres, double max_correspondence_distance, const TransformationEstimation &estimation=TransformationEstimationPointToPoint(false), int ransac_n=3, const std::vector< std::reference_wrapper< const CorrespondenceChecker >> &checkers={}, const RANSACConvergenceCriteria &criteria=RANSACConvergenceCriteria())
 Function for global RANSAC registration based on a given set of correspondences. More...
 
RegistrationResult RegistrationRANSACBasedOnFeatureMatching (const geometry::PointCloud &source, const geometry::PointCloud &target, const Feature &source_features, const Feature &target_features, bool mutual_filter, double max_correspondence_distance, const TransformationEstimation &estimation=TransformationEstimationPointToPoint(false), int ransac_n=3, const std::vector< std::reference_wrapper< const CorrespondenceChecker >> &checkers={}, const RANSACConvergenceCriteria &criteria=RANSACConvergenceCriteria())
 Function for global RANSAC registration based on feature matching. More...
 
Eigen::Matrix6d GetInformationMatrixFromPointClouds (const geometry::PointCloud &source, const geometry::PointCloud &target, double max_correspondence_distance, const Eigen::Matrix4d &transformation)
 

Typedef Documentation

◆ CorrespondenceSet

typedef std::vector< Eigen::Vector2i > open3d::pipelines::registration::CorrespondenceSet

Enumeration Type Documentation

◆ TransformationEstimationType

Enumerator
Unspecified 
PointToPoint 
PointToPlane 
ColoredICP 
GeneralizedICP 

Function Documentation

◆ ComputeFPFHFeature()

std::shared_ptr< Feature > open3d::pipelines::registration::ComputeFPFHFeature ( const geometry::PointCloud input,
const geometry::KDTreeSearchParam search_param = geometry::KDTreeSearchParamKNN() 
)

Function to compute FPFH feature for a point cloud.

Parameters
inputThe Input point cloud.
search_paramKDTree KNN search parameter.

◆ CorrespondencesFromFeatures()

CorrespondenceSet open3d::pipelines::registration::CorrespondencesFromFeatures ( const Feature source_features,
const Feature target_features,
bool  mutual_filter = false,
float  mutual_consistency_ratio = 0.1 
)

Function to find correspondences via 1-nearest neighbor feature matching. Target is used to construct a nearest neighbor search object, in order to query source.

Parameters
source_features(D, N) feature
target_features(D, M) feature
mutual_filterBoolean flag, only return correspondences (i, j) s.t. source_features[i] and target_features[j] are mutually the nearest neighbor.
mutual_consistency_ratioFloat threshold to decide whether the number of correspondences is sufficient. Only used when mutual_filter is set to True.
Returns
A CorrespondenceSet. When mutual_filter is disabled: the first column is arange(0, N) of source, and the second column is the corresponding index of target. When mutual_filter is enabled, return the filtering subset of the aforementioned correspondence set where source[i] and target[j] are mutually the nearest neighbor. If the subset size is smaller than mutual_consistency_ratio * N, return the unfiltered set.

◆ CreatePoseGraphWithoutInvalidEdges()

std::shared_ptr< PoseGraph > open3d::pipelines::registration::CreatePoseGraphWithoutInvalidEdges ( const PoseGraph pose_graph,
const GlobalOptimizationOption option 
)

Function to prune out uncertain edges having confidence_ < .edge_prune_threshold_

◆ EvaluateRegistration()

RegistrationResult open3d::pipelines::registration::EvaluateRegistration ( const geometry::PointCloud source,
const geometry::PointCloud target,
double  max_correspondence_distance,
const Eigen::Matrix4d &  transformation = Eigen::Matrix4d::Identity() 
)

Function for evaluating registration between point clouds.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
max_correspondence_distanceMaximum correspondence points-pair distance.
transformationThe 4x4 transformation matrix to transform source to target. Default value: array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]).

◆ FastGlobalRegistrationBasedOnCorrespondence()

RegistrationResult open3d::pipelines::registration::FastGlobalRegistrationBasedOnCorrespondence ( const geometry::PointCloud source,
const geometry::PointCloud target,
const CorrespondenceSet corres,
const FastGlobalRegistrationOption option = FastGlobalRegistrationOption() 
)

Fast Global Registration based on a given set of correspondences.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
corresCorrespondence indices between source and target point clouds.
optionFGR options

◆ FastGlobalRegistrationBasedOnFeatureMatching()

RegistrationResult open3d::pipelines::registration::FastGlobalRegistrationBasedOnFeatureMatching ( const geometry::PointCloud source,
const geometry::PointCloud target,
const Feature source_feature,
const Feature target_feature,
const FastGlobalRegistrationOption option = FastGlobalRegistrationOption() 
)

Fast Global Registration based on a given set of FPFH features.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
corresCorrespondence indices between source and target point clouds.
optionFGR options

◆ GetInformationMatrixFromPointClouds()

Eigen::Matrix6d open3d::pipelines::registration::GetInformationMatrixFromPointClouds ( const geometry::PointCloud source,
const geometry::PointCloud target,
double  max_correspondence_distance,
const Eigen::Matrix4d &  transformation 
)
Parameters
sourceThe source point cloud.
targetThe target point cloud.
max_correspondence_distanceMaximum correspondence points-pair distance.
transformationThe 4x4 transformation matrix to transform source to target.

◆ GlobalOptimization()

void open3d::pipelines::registration::GlobalOptimization ( PoseGraph pose_graph,
const GlobalOptimizationMethod method = GlobalOptimizationLevenbergMarquardt(),
const GlobalOptimizationConvergenceCriteria criteria = GlobalOptimizationConvergenceCriteria(),
const GlobalOptimizationOption option = GlobalOptimizationOption() 
)

Function to optimize a PoseGraph Reference: [Kümmerle et al 2011] R Kümmerle, G. Grisetti, H. Strasdat, K. Konolige, W. Burgard g2o: A General Framework for Graph Optimization, ICRA 2011 [Choi et al 2015] S. Choi, Q.-Y. Zhou, V. Koltun, Robust Reconstruction of Indoor Scenes, CVPR 2015 [M. Lourakis 2009] M. Lourakis, SBA: A Software Package for Generic Sparse Bundle Adjustment, Transactions on Mathematical Software, 2009

◆ RegistrationColoredICP()

RegistrationResult open3d::pipelines::registration::RegistrationColoredICP ( const geometry::PointCloud source,
const geometry::PointCloud target,
double  max_distance,
const Eigen::Matrix4d &  init = Eigen::Matrix4d::Identity(),
const TransformationEstimationForColoredICP estimation = TransformationEstimationForColoredICP(),
const ICPConvergenceCriteria criteria = ICPConvergenceCriteria() 
)

Function for Colored ICP registration.

This is implementation of following paper J. Park, Q.-Y. Zhou, V. Koltun, Colored Point Cloud Registration Revisited, ICCV 2017.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
max_distanceMaximum correspondence points-pair distance.
initInitial transformation estimation. Default value: array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]).
estimationTransformationEstimationForColoredICP method. Can only change the lambda_geometric value and the robust kernel used in the optimization
criteriaConvergence criteria.

◆ RegistrationGeneralizedICP()

RegistrationResult open3d::pipelines::registration::RegistrationGeneralizedICP ( const geometry::PointCloud source,
const geometry::PointCloud target,
double  max_correspondence_distance,
const Eigen::Matrix4d &  init = Eigen::Matrix4d::Identity(),
const TransformationEstimationForGeneralizedICP estimation = TransformationEstimationForGeneralizedICP(),
const ICPConvergenceCriteria criteria = ICPConvergenceCriteria() 
)

Function for Generalized ICP registration.

This is implementation of following paper Generalized-ICP, RSS 2009.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
max_distanceMaximum correspondence points-pair distance.
initInitial transformation estimation. Default value: array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]).
criteriaConvergence criteria.

◆ RegistrationICP()

RegistrationResult open3d::pipelines::registration::RegistrationICP ( const geometry::PointCloud source,
const geometry::PointCloud target,
double  max_correspondence_distance,
const Eigen::Matrix4d &  init = Eigen::Matrix4d::Identity(),
const TransformationEstimation estimation = TransformationEstimationPointToPoint(false),
const ICPConvergenceCriteria criteria = ICPConvergenceCriteria() 
)

Functions for ICP registration.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
max_correspondence_distanceMaximum correspondence points-pair distance.
initInitial transformation estimation. Default value: array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]])
estimationEstimation method.
criteriaConvergence criteria.

◆ RegistrationRANSACBasedOnCorrespondence()

RegistrationResult open3d::pipelines::registration::RegistrationRANSACBasedOnCorrespondence ( const geometry::PointCloud source,
const geometry::PointCloud target,
const CorrespondenceSet corres,
double  max_correspondence_distance,
const TransformationEstimation estimation = TransformationEstimationPointToPoint(false),
int  ransac_n = 3,
const std::vector< std::reference_wrapper< const CorrespondenceChecker >> &  checkers = {},
const RANSACConvergenceCriteria criteria = RANSACConvergenceCriteria() 
)

Function for global RANSAC registration based on a given set of correspondences.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
corresCorrespondence indices between source and target point clouds.
max_correspondence_distanceMaximum correspondence points-pair distance.
estimationEstimation method.
ransac_nFit ransac with ransac_n correspondences.
checkersCorrespondence checker.
criteriaConvergence criteria.

◆ RegistrationRANSACBasedOnFeatureMatching()

RegistrationResult open3d::pipelines::registration::RegistrationRANSACBasedOnFeatureMatching ( const geometry::PointCloud source,
const geometry::PointCloud target,
const Feature source_features,
const Feature target_features,
bool  mutual_filter,
double  max_correspondence_distance,
const TransformationEstimation estimation = TransformationEstimationPointToPoint(false),
int  ransac_n = 3,
const std::vector< std::reference_wrapper< const CorrespondenceChecker >> &  checkers = {},
const RANSACConvergenceCriteria criteria = RANSACConvergenceCriteria() 
)

Function for global RANSAC registration based on feature matching.

Parameters
sourceThe source point cloud.
targetThe target point cloud.
source_featuresSource point cloud feature.
target_featuresTarget point cloud feature.
mutual_filterEnables mutual filter such that the correspondence of the source point's correspondence is itself.
max_correspondence_distanceMaximum correspondence points-pair distance.
ransac_nFit ransac with ransac_n correspondences.
checkersCorrespondence checker.
criteriaConvergence criteria.