matching.h
Go to the documentation of this file.
1 #ifndef MAP_MERGE_MATCHING_H_
2 #define MAP_MERGE_MATCHING_H_
3 
4 #include <map_merge_3d/enum.h>
6 
7 namespace map_merge_3d
8 {
26 CorrespondencesPtr findFeatureCorrespondences(
27  const LocalDescriptorsPtr &source_descriptors,
28  const LocalDescriptorsPtr &target_descriptors, size_t k = 5);
29 
45  const PointCloudPtr &source_keypoints,
46  const PointCloudPtr &target_keypoints,
47  const CorrespondencesPtr &correspondences, CorrespondencesPtr &inliers,
48  double inlier_threshold);
49 
69  const PointCloudPtr &source_keypoints,
70  const LocalDescriptorsPtr &source_descriptors,
71  const PointCloudPtr &target_keypoints,
72  const LocalDescriptorsPtr &target_descriptors, double min_sample_distance,
73  double max_correspondence_distance, int max_iterations);
74 
94 Eigen::Matrix4f estimateTransformICP(const PointCloudPtr &source_points,
95  const PointCloudPtr &target_points,
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);
101 
102 // defines enum class EstimationMethod + string conversions
103 ENUM_CLASS(EstimationMethod, MATCHING, SAC_IA);
104 
129 Eigen::Matrix4f estimateTransform(
130  const PointCloudPtr &source_points, const PointCloudPtr &source_keypoints,
131  const LocalDescriptorsPtr &source_descriptors,
132  const PointCloudPtr &target_points, const PointCloudPtr &target_keypoints,
133  const LocalDescriptorsPtr &target_descriptors, EstimationMethod method,
134  bool refine, double inlier_threshold, double max_correspondence_distance,
135  int max_iterations, size_t matching_k, double transform_epsilon);
136 
150 double transformScore(const PointCloudPtr &source_points,
151  const PointCloudPtr &target_points,
152  const Eigen::Matrix4f &transform, double max_distance);
153 
155 
156 } // namespace map_merge_3d
157 
158 #endif // MAP_MERGE_MATCHING_H_
pcl::PCLPointCloud2::Ptr LocalDescriptorsPtr
Definition: typedefs.h:28
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_)


map_merge_3d
Author(s): Jiri Horner
autogenerated on Mon Feb 28 2022 22:47:17