|
| 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...
|
|