Open3D (C++ API)
0.18.0
|
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< Feature > | ComputeFPFHFeature (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< PoseGraph > | CreatePoseGraphWithoutInvalidEdges (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 std::vector< Eigen::Vector2i > open3d::pipelines::registration::CorrespondenceSet |
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.
input | The Input point cloud. |
search_param | KDTree KNN search parameter. |
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.
source_features | (D, N) feature |
target_features | (D, M) feature |
mutual_filter | Boolean flag, only return correspondences (i, j) s.t. source_features[i] and target_features[j] are mutually the nearest neighbor. |
mutual_consistency_ratio | Float threshold to decide whether the number of correspondences is sufficient. Only used when mutual_filter is set to True. |
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_
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.
source | The source point cloud. |
target | The target point cloud. |
max_correspondence_distance | Maximum correspondence points-pair distance. |
transformation | The 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.]]). |
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.
source | The source point cloud. |
target | The target point cloud. |
corres | Correspondence indices between source and target point clouds. |
option | FGR options |
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.
source | The source point cloud. |
target | The target point cloud. |
corres | Correspondence indices between source and target point clouds. |
option | FGR options |
Eigen::Matrix6d open3d::pipelines::registration::GetInformationMatrixFromPointClouds | ( | const geometry::PointCloud & | source, |
const geometry::PointCloud & | target, | ||
double | max_correspondence_distance, | ||
const Eigen::Matrix4d & | transformation | ||
) |
source | The source point cloud. |
target | The target point cloud. |
max_correspondence_distance | Maximum correspondence points-pair distance. |
transformation | The 4x4 transformation matrix to transform source to target . |
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
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.
source | The source point cloud. |
target | The target point cloud. |
max_distance | Maximum correspondence points-pair distance. |
init | Initial transformation estimation. Default value: array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]). |
estimation | TransformationEstimationForColoredICP method. Can only change the lambda_geometric value and the robust kernel used in the optimization |
criteria | Convergence criteria. |
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.
source | The source point cloud. |
target | The target point cloud. |
max_distance | Maximum correspondence points-pair distance. |
init | Initial transformation estimation. Default value: array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]). |
criteria | Convergence criteria. |
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.
source | The source point cloud. |
target | The target point cloud. |
max_correspondence_distance | Maximum correspondence points-pair distance. |
init | Initial transformation estimation. Default value: array([[1., 0., 0., 0.], [0., 1., 0., 0.], [0., 0., 1., 0.], [0., 0., 0., 1.]]) |
estimation | Estimation method. |
criteria | Convergence criteria. |
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.
source | The source point cloud. |
target | The target point cloud. |
corres | Correspondence indices between source and target point clouds. |
max_correspondence_distance | Maximum correspondence points-pair distance. |
estimation | Estimation method. |
ransac_n | Fit ransac with ransac_n correspondences. |
checkers | Correspondence checker. |
criteria | Convergence criteria. |
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.
source | The source point cloud. |
target | The target point cloud. |
source_features | Source point cloud feature. |
target_features | Target point cloud feature. |
mutual_filter | Enables mutual filter such that the correspondence of the source point's correspondence is itself. |
max_correspondence_distance | Maximum correspondence points-pair distance. |
ransac_n | Fit ransac with ransac_n correspondences. |
checkers | Correspondence checker. |
criteria | Convergence criteria. |