Low-level functions for matching the map pair. More...
Functions | |
| map_merge_3d::ENUM_CLASS (EstimationMethod, MATCHING, SAC_IA) | |
| Eigen::Matrix4f | map_merge_3d::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. More... | |
| Eigen::Matrix4f | map_merge_3d::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. More... | |
| Eigen::Matrix4f | map_merge_3d::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. More... | |
| Eigen::Matrix4f | map_merge_3d::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. More... | |
| CorrespondencesPtr | map_merge_3d::findFeatureCorrespondences (const LocalDescriptorsPtr &source_descriptors, const LocalDescriptorsPtr &target_descriptors, size_t k=5) |
| Finds correspondences between two sets of feature descriptors. More... | |
| double | map_merge_3d::transformScore (const PointCloudPtr &source_points, const PointCloudPtr &target_points, const Eigen::Matrix4f &transform, double max_distance) |
| Computes euclidean distance between two pointclouds. More... | |
Low-level functions for matching the map pair.
Low-level functions to find correspondences between two pointclouds and match them together. These functions operate on two pointclouds.
| map_merge_3d::ENUM_CLASS | ( | EstimationMethod | , |
| MATCHING | , | ||
| SAC_IA | |||
| ) |
| Eigen::Matrix4f map_merge_3d::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.
Uses extracted features to estimate rigid transformation. First the initial transformation is estimated using selected method, then the transformation may be selectively refined using ICP.
| source_points | Source pointcloud |
| source_keypoints | Keypoints of source pointcloud |
| source_descriptors | Descriptors for keypoints of source pointcloud |
| target_points | Target pointcloud |
| target_keypoints | Keypoints of target pointcloud |
| target_descriptors | Descriptors for keypoints of target pointcloud |
| method | Method for estimating initial transformation |
| refine | Whether to refine initial transformation with ICP. |
| inlier_threshold | Threshold for inliers in RANSAC during initial estimation. |
| max_correspondence_distance | Maximum distance for a matched points to be considered the same point |
| max_iterations | maximum iterations for RANSAC |
| matching_k | number of nearest descriptors to consider for matching |
| transform_epsilon | the smallest change allowed until ICP convergence. |
| Eigen::Matrix4f map_merge_3d::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.
Uses RANSAC to find inliers fitting a rigid transformation model. Final transformation is found using SVD on inliers set.
| source_keypoints | Keypoints of source pointcloud | |
| target_keypoints | Keypoints of target pointcloud | |
| correspondences | Correspondences between keypoints | |
| [out] | inliers | Estimated inliers from RANSAC |
| inlier_threshold | threshold for considering a point as inlier in RANSAC |
| Eigen::Matrix4f map_merge_3d::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.
Use SampleConsensusInitialAlignment to find a rough alignment from the source to the target
| source_keypoints | Keypoints of source pointcloud |
| source_descriptors | descriptors for source_keypoints |
| target_keypoints | Keypoints of target pointcloud |
| target_descriptors | descriptors for target_keypoints |
| min_sample_distance | The minimum distance between any two random samples |
| max_correspondence_distance | Maximum distance for a matched points to be considered the same point |
| max_iterations | The number of RANSAC iterations to perform |
| Eigen::Matrix4f map_merge_3d::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.
| source_points | source point cloud |
| target_points | target point cloud. |
| initial_guess | Initial transformation to start with |
| max_correspondence_distance | A threshold on the distance between any two corresponding points. Any corresponding points that are further apart than this threshold will be ignored when computing the source-to-target transformation |
| outlier_rejection_threshold | A threshold used to define outliers during RANSAC |
| max_iterations | maximum iterations for RANSAC |
| transformation_epsilon | The smallest iterative transformation allowed before the algorithm is considered to have converged |
| CorrespondencesPtr map_merge_3d::findFeatureCorrespondences | ( | const LocalDescriptorsPtr & | source_descriptors, |
| const LocalDescriptorsPtr & | target_descriptors, | ||
| size_t | k = 5 |
||
| ) |
Finds correspondences between two sets of feature descriptors.
Uses cross-matching algorithm with first-k selection
| source_descriptors | Feature descriptors of source pointcloud |
| target_descriptors | Feature descriptors of target pointcloud |
| k | number of nearest descriptors to consider for matching |
| double map_merge_3d::transformScore | ( | const PointCloudPtr & | source_points, |
| const PointCloudPtr & | target_points, | ||
| const Eigen::Matrix4f & | transform, | ||
| double | max_distance | ||
| ) |
Computes euclidean distance between two pointclouds.
Computes a euclidean score for an estimated transformation. Because we expect only some parts of the maps overlapping, only points closer than max_distance will be include in the score.
| source_points | Source pointcloud |
| target_points | Target pointcloud |
| transform | estimated transformation between source and target |
| max_distance | Maximum distance between two points to be included in the score. |