Requirements:
- PCL e.g. via
sudo apt install libpcl-dev ros-${ROS_DISTRO}-pcl-ros
- OpenCV e.g. via
sudo apt install libopencv-dev
- Eigen3 e.g. via
sudo apt install libeigen3-dev
- Octomap
- python3 modules: cv2, numpy, scipy, yaml
colcon build --packages-select ros2_map_tools --cmake-args -DCMAKE_BUILD_TYPE=Release
Squashes 3D data files into 2D binary occupancy maps compatible with the ROS2 map_server.
Supported input formats: .pcd, .ply, .obj, .ot, .xyz
- file: input filepath
- occupancy_likelihood_threshold: probability threshold for occupancy (applicable formats: .ot). Default: 0.5
- resolution: occupancy map resolution. Default: 0.05
- z_min: minimum point z-value for inclusion. Default: 0.0
- z_max: maximum point z-value for inclusion. Default: 1.8
- voxel_min_points: minimum point count per occupancy grid cell for occupancy. Default: 1
- transform: optional comma-separated floating point initial transform as a 6-tuple (tx,ty,tz,rx,ry,rz) or 7-tuple (tx,ty,tz,qx,qy,qz,qw)
- yaw: yaw value for map origin in metadata. Default: 0.0
- tf_ext: optional extension override for transform metadata. Default: follows extension of "cloud" param
- In one terminal, load config/pcl_to_map.rviz in RViz, e.g.:
rviz2 -d config/pcl_to_map.rviz
- In a second terminal:
ros2 run ros2_map_tools pcl_to_map --ros-args ...
- In a third terminal, iteratively transform the cloud until the occupancy map looks OK:
- translate:
ros2 topic pub --once /pcl_to_map/translate geometry_msgs/msg/Vector3 "{x: 0.0, y: 0.0, z: 0.0 }"
- rotate:
ros2 topic pub --once /pcl_to_map/rotate geometry_msgs/msg/Vector3 "{x: 0.0, y: 0.0, z: 0.0 }"
- translate:
- To save (suggested to call from third terminal):
This saves a .png and .yaml pair that can be loaded with map_server (see below). The .yaml also contains the final cumulative transform from map frame to the raw input.
ros2 service call /pcl_to_map/save std_srvs/srv/Trigger
- To verify (optional):
- Enable the "Map" display in RViz
- From some other terminal not running RViz:
Note: you may need to also run
ros2 run nav2_map_server map_server --ros-args -p yaml_filename:=/path/to/map.yaml
ros2 run nav2_util lifecycle_bringup map_server
Builds dense maps from timestamp-synchronized nav_msgs/msg/Odometry and sensor_msgs/msg/PointCloud2.
ros2 run ros2_map_tools dense_map_builder --ros-args ...
Params:
- cloud_hz: optional cloud cache throttling frequency if > 0.0 . Default: -1.0
- trajectory: optional trajectory file in TUM format
- odom_topic: optional odometry topic. If omitted, incoming cloud msgs with stamps beyond the range in the trajectory file will be rejected
- voxel_size: voxel grid size. Default: 0.05
- voxel_min_points: minimum points per voxel for downsampling inbound point clouds. Default: 1
- occupancy_likelihood_threshold: probability threshold for occupancy. Default: 0.5
- out_path: outbound binary .ply path. Default: "cloud"
To save the dense cloud from another terminal once all your data has been published:
ros2 service call /dense_map_builder/save std_srvs/srv/Trigger
Note: This will clear the message buffers, unless there are no point clouds available.
An alternative trigger is publishing the optional path to a trajectory file after cloud accumulation:
ros2 topic pub /dense_map_builder/load_trajectory_and_save std_msgs/msg/String "data: /path/to/trajectory/file" --once
A "UI" to align >=2 2D maps together, to generate new map metadatas and a final combined map. Future work may be towards automating this, given the assumption of maps that fit together cleanly and are suitable for alignment via feature matching.
ros2 run ros2_map_tools map_aligner_ui.py