map_merging.h
Go to the documentation of this file.
1 #ifndef MAP_MERGE_MAP_MERGING_H_
2 #define MAP_MERGE_MAP_MERGING_H_
3 
4 #include <ostream>
5 
9 
10 #include <ros/ros.h>
11 
12 namespace map_merge_3d
13 {
29  double resolution = 0.1;
30  double descriptor_radius = resolution * 8.0;
32  double normal_radius = resolution * 6.0;
33  Keypoint keypoint_type = Keypoint::SIFT;
34  double keypoint_threshold = 5.0;
35  Descriptor descriptor_type = Descriptor::PFH;
36  EstimationMethod estimation_method = EstimationMethod::MATCHING;
37  bool refine_transform = true;
38  double inlier_threshold = resolution * 5.0;
39  double max_correspondence_distance = inlier_threshold * 2.0;
40  int max_iterations = 500;
41  size_t matching_k = 5;
42  double transform_epsilon = 1e-2;
43  double confidence_threshold = 0.0;
44  double output_resolution = 0.05;
45 
58  static MapMergingParams fromCommandLine(int argc, char **argv);
59 
69  static MapMergingParams fromROSNode(const ros::NodeHandle &node);
70 };
71 std::ostream &operator<<(std::ostream &stream, const MapMergingParams &params);
72 
85 std::vector<Eigen::Matrix4f>
86 estimateMapsTransforms(const std::vector<PointCloudConstPtr> &clouds,
87  const MapMergingParams &params);
88 
99 PointCloudPtr composeMaps(const std::vector<PointCloudConstPtr> &clouds,
100  const std::vector<Eigen::Matrix4f> &transforms,
101  double resolution);
102 
104 
105 } // namespace map_merge_3d
106 
107 #endif // MAP_MERGE_MAP_MERGING_H_
std::ostream & operator<<(std::ostream &stream, const MapMergingParams &params)
std::vector< Eigen::Matrix4f > estimateMapsTransforms(const std::vector< PointCloudConstPtr > &clouds, const MapMergingParams &params)
Estimate transformations between n pointclouds.
static MapMergingParams fromCommandLine(int argc, char **argv)
Sources parameters from command line arguments.
static MapMergingParams fromROSNode(const ros::NodeHandle &node)
Sources parameters from ROS node parameters.
EstimationMethod estimation_method
Definition: map_merging.h:36
Parameters for map merging high-level interface.
Definition: map_merging.h:28
pcl::PointCloud< PointT >::Ptr PointCloudPtr
Definition: typedefs.h:17
PointCloudPtr composeMaps(const std::vector< PointCloudConstPtr > &clouds, const std::vector< Eigen::Matrix4f > &transforms, double resolution)
Composes the global map.


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