1 #ifndef MAP_MERGE_MAP_MERGING_H_ 2 #define MAP_MERGE_MAP_MERGING_H_ 85 std::vector<Eigen::Matrix4f>
100 const std::vector<Eigen::Matrix4f> &transforms,
107 #endif // MAP_MERGE_MAP_MERGING_H_
std::ostream & operator<<(std::ostream &stream, const MapMergingParams ¶ms)
double max_correspondence_distance
std::vector< Eigen::Matrix4f > estimateMapsTransforms(const std::vector< PointCloudConstPtr > &clouds, const MapMergingParams ¶ms)
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
Parameters for map merging high-level interface.
Descriptor descriptor_type
double confidence_threshold
int outliers_min_neighbours
pcl::PointCloud< PointT >::Ptr PointCloudPtr
PointCloudPtr composeMaps(const std::vector< PointCloudConstPtr > &clouds, const std::vector< Eigen::Matrix4f > &transforms, double resolution)
Composes the global map.
double keypoint_threshold