1 #ifndef MAP_MERGE_MATCHING_H_ 2 #define MAP_MERGE_MATCHING_H_ 47 const CorrespondencesPtr &correspondences, CorrespondencesPtr &inliers,
48 double inlier_threshold);
73 double max_correspondence_distance,
int max_iterations);
96 const Eigen::Matrix4f &initial_guess,
97 double max_correspondence_distance,
98 double outlier_rejection_threshold,
99 int max_iterations = 100,
100 double transformation_epsilon = 0.0);
103 ENUM_CLASS(EstimationMethod, MATCHING, SAC_IA);
134 bool refine,
double inlier_threshold,
double max_correspondence_distance,
135 int max_iterations,
size_t matching_k,
double transform_epsilon);
152 const Eigen::Matrix4f &transform,
double max_distance);
158 #endif // MAP_MERGE_MATCHING_H_ pcl::PCLPointCloud2::Ptr LocalDescriptorsPtr
Eigen::Matrix4f estimateTransformFromDescriptorsSets(const PointCloudPtr &source_keypoints, const LocalDescriptorsPtr &source_descriptors, const PointCloudPtr &target_keypoints, const LocalDescriptorsPtr &target_descriptors, double min_sample_distance, double max_correspondence_distance, int max_iterations)
Estimates transformation between source and target pointcloud based on descriptors.
Eigen::Matrix4f estimateTransformICP(const PointCloudPtr &source_points, const PointCloudPtr &target_points, const Eigen::Matrix4f &initial_guess, double max_correspondence_distance, double outlier_rejection_threshold, int max_iterations=100, double transformation_epsilon=0.0)
Use ICP to estimate transform between grids.
Eigen::Matrix4f estimateTransform(const PointCloudPtr &source_points, const PointCloudPtr &source_keypoints, const LocalDescriptorsPtr &source_descriptors, const PointCloudPtr &target_points, const PointCloudPtr &target_keypoints, const LocalDescriptorsPtr &target_descriptors, EstimationMethod method, bool refine, double inlier_threshold, double max_correspondence_distance, int max_iterations, size_t matching_k, double transform_epsilon)
Estimate transformation between two pointclouds.
PointCloud::Ptr PointCloudPtr
Eigen::Matrix4f estimateTransformFromCorrespondences(const PointCloudPtr &source_keypoints, const PointCloudPtr &target_keypoints, const CorrespondencesPtr &correspondences, CorrespondencesPtr &inliers, double inlier_threshold)
Estimates transformation between source and target pointcloud based on correspondences.
CorrespondencesPtr findFeatureCorrespondences(const LocalDescriptorsPtr &source_descriptors, const LocalDescriptorsPtr &target_descriptors, size_t k=5)
Finds correspondences between two sets of feature descriptors.
double transformScore(const PointCloudPtr &source_points, const PointCloudPtr &target_points, const Eigen::Matrix4f &transform, double max_distance)
Computes euclidean distance between two pointclouds.
DOXYGEN_SKIP ENUM_CLASS(Descriptor, DESCRIPTORS_NAMES_)