Show EOL distros: 

Package Summary

Merging multiple 3D maps, represented as pointclouds, without knowledge of initial positions of robots.

  • Maintainer status: developed
  • Maintainer: Jiri Horner <laeqten AT gmail DOT com>
  • Author: Jiri Horner <laeqten AT gmail DOT com>
  • License: BSD
  • Source: git https://github.com/hrnr/map-merge.git (branch: lunar-devel)

Package Summary

Merging multiple 3D maps, represented as pointclouds, without knowledge of initial positions of robots.

  • Maintainer status: developed
  • Maintainer: Jiri Horner <laeqten AT gmail DOT com>
  • Author: Jiri Horner <laeqten AT gmail DOT com>
  • License: BSD
  • Source: git https://github.com/hrnr/map-merge.git (branch: melodic-devel)

Use GitHub to report bugs or submit feature requests. [View active issues]

Overview

This package provides a 3D global map for multiple robots and the respective transformations between robots. It merges robots' individual maps based on the overlapping space in the maps and requires no dependencies on a particular SLAM or communication between the robots.

screenshot.jpg

The ROS node can merge maps from the arbitrary number of robots. It expects maps from individual robots as ROS topics and does not impose any particular messaging between robots. If your run multiple robots under the same ROS master then map_merge_3d may work for you out-of-the-box, this makes it easy to setup a simulation experiment.

In the multi-robot exploration scenario your robots probably run multiple ROS masters and you need to setup a communication link between robots. Common solution might be multimaster_fkie. You need to provide maps from your robots on local topics (under the same master). Also if you want to distribute merged map and tf transformations back to robots your communication must take care of it.

Architecture

map_merge_3d finds robot maps automatically and new robots can be added to the system at any time. 3D maps are expected as sensor_msgs/PointCloud2, other map messages are not supported.

architecture.svg

Recommended topics names for robot maps are /robot1/map, /robot2/map etc. However the names are configurable. All robots are expected to publish map under <robot_namespace>/map, where topic name (map) is configurable, but must be the same for all robots. For each robot <robot_namespace> is of cause different, but it does not need to follow any pattern. Further, you can exclude some topics using robot_namespace parameter, to avoid merging unrelated point clouds.

Estimation

Transformations between maps are estimated by feature-matching algorithm and therefore it is required to have sufficient amount of overlapping space between maps to make a high-probability match. If maps don't have enough overlapping space to make a solid match, merger might reject those matches.

Estimating transforms between maps is cpu-intesive so you might want to tune estimation_rate parameter to run the re-estimation less often.

ROS API

map_merge_node

Provides map merging services offered by this package. Dynamically looks for new robots in the system and merges their maps. Provides tf transforms.

Subscribed Topics

<robot_namespace>/map (sensor_msgs/PointCloud2)
  • Local map for a specific robot.

Published Topics

map (sensor_msgs/PointCloud2)
  • Merged map from all robots in the system.

Parameters

NODE PARAMETERS
Parameters affecting general setup of the node.
~robot_map_topic (string, default: map)
  • Name of robot map topic without namespaces (last component of the topic name). Only topics with this name are considered when looking for new maps to merge. This topics may be subject to further filtering (see below).
~robot_namespace (string, default: <empty string>)
  • Fixed part of the robot map topic. You can employ this parameter to further limit which topics are considered during dynamic lookup for robots. Only topics which contain (anywhere) this string are considered for lookup. Unlike robot_map_topic you are not limited by namespace logic. Topics are filtered using text-based search. Therefore robot_namespace does not need to be a ROS namespace, but it can contain slashes etc. This string must be a common part of all maps topic name (all robots for which you want to merge map).
~merged_map_topic (string, default: map)
  • Topic name where merged map is published.
~world_frame (string, default: world)
  • Frame id (in tf tree) which is assigned to published merged map and used as reference frame for tf transforms.
~compositing_rate (double, default: 0.3)
  • Rate in Hz. Basic frequency on which the node merges maps and publishes merged map. Increase this value if you want faster updates.
~discovery_rate (double, default: 0.05)
  • Rate in Hz. Frequency on which this node discovers new robots (maps). Increase this value if you need more agile behaviour when adding new robots.
~estimation_rate (double, default: 0.01)
  • Rate in Hz. Frequency on which this node re-estimates transformations between maps. Estimation is cpu-intensive, so you may wish to lower this value.
~publish_tf (bool, default: true)
  • Whether to publish estimated transforms in the tf tree. See below.
REGISTRATION PARAMETERS
Parameters affecting only registration algorithm used for estimating transformations between maps. These parameters should be defined in the same namespace as normal node parameters.
~resolution (double, default: 0.1)
  • Resolution used for the registration. Small value increases registration time.
~descriptor_radius (double, default: resolution * 8.0)
  • Radius for descriptors computation.
~outliers_min_neighbours (int, default: 50)
  • Minimum number of neighbours for a point to be kept in the map during outliers pruning.
~normal_radius (double, default: resolution * 6.0)
  • Radius used for estimating normals.
~keypoint_type (string, default: SIFT)
  • Type of keypoints used. Possible values are SIFT, HARRIS.
~keypoint_threshold (double, default: 5.0)
  • Keypoints with lower response that this value are pruned. Lower this threshold when using Harris keypoints (you can set 0.0).
~descriptor_type (string, default: PFH)
  • Type of descriptors used. Possible values are PFH, PFHRGB, FPFH, RSD, SHOT, SC3D.
~estimation_method (string, default: MATCHING)
  • Type of descriptors matching algorithm used. This algorithm is used for initial global match. Possible values are MATCHING, SAC_IA.
~refine_transform (bool, default: true)
  • Whether to refine estimated transformation with ICP or not.
~inlier_threshold (double, default: resolution * 5.0)
  • Inlier threshold used in RANSAC during estimation.
~max_correspondence_distance (double, default: inlier_threshold * 2.0)
  • Maximum distance for matched points to be considered the same point.
~max_iterations (int, default: 500)
  • Maximum iterations for RANSAC.
~matching_k (int, default: 5)
  • Number of the nearest descriptors to consider for matching.
~transform_epsilon (double, default: 1e-2)
  • The smallest change allowed until ICP convergence.
~confidence_threshold (double, default: 0.0)
  • Minimum confidence in the pair-wise transform estimate to be included in the map-merging graph. Pair-wise transformations with lower confidence are not considered when computing global transforms. Increase this value if you are having problems with invalid transforms being estimated. The confidence value is computed as a reciprocal of Euclidean distance between transformed maps.
~output_resolution (double, default: 0.05)
  • Resolution of the merged global map.

Provided tf Transforms

worldmapX_frame
  • Transformation from the world frame (which name can be configured using world_frame parameter) to each of the maps. Each map must have a correct frame_id set (instead mapX_frame) in the sensor_msgs/PointCloud2 message. If the transformation could not be estimated, null transformation is published.

Tools

Alongside ROS node map_merge_3d provides command-line tools to work with point cloud maps saved in pcd files. Both tools accept any of the #REGISTRATION PARAMETERS.

The tools use PCL command-line parsing module. PCL command-line parsing has some limits (PCL users won't be surprised): it supports only --param value format, --param=value is not accepted. Unknown options are ignored. Options may be arbitrarily mixed with filenames. There are no short versions for parameters.

map_merge_tool

Tool for merging maps offline. Produces output.pcd with merged global map. This tool can merge arbitrary number of maps.

Usage

rosrun map_merge_3d map_merge_tool [--param value] map1.pcd map2.pcd [map3.pcd...]

For example to use SHOT descriptors with 3 maps:

rosrun map_merge_3d map_merge_tool --descriptor_type SHOT map1.pcd map2.pcd map3.pcd

registration_visualisation

Visualises pair-wise transform estimation between 2 maps. Uses PCL visualiser for the visualisation.

Usage

rosrun map_merge_3d registration_visualisation [--param value] map1.pcd map2.pcd

After one step of the estimation a visualisation window appears. You can freely navigate the point cloud, save a screenshot or camera parameters (press h to see all shortcuts). After the window is closed, estimation continues with the next phase and the next visualisation window appears. Details about estimation progress are printed to stdout.

Acknowledgements

This package was developed as part of my master thesis at Charles University in Prague.

Wiki: map_merge_3d (last edited 2018-06-20 12:37:50 by hrnr)