VDB Mapping ROS2 Package¶
DISCLAIMER: This library is still under development. Be warned that some interfaces will be changed and/or extended in the future.
The VDB Mapping ROS2 Package is a ROS2 wrapper around VDB Mapping
Getting Started¶
Requirements¶
This library requires OpenVDB as it is build around it. This library was initially developed using Version 5.0 and should work with all versions above.
Either use the apt package which will be automatically installed via rosdep or compile the package from source using the provided build instructions
Build instructions¶
Since the required VDB Mapping library is a plain C++ package, you cannot use catkin_make directly. Instead you have to use colcon build to build the workspace.
# source global ros
source /opt/ros/<your_ros_version>/setup.bash
# create a catkin workspace
mkdir -p ~/colcon_ws/src && cd ~/colcon_ws/src
# clone packages
git clone https://github.com/fzi-forschungszentrum-informatik/vdb_mapping
git clone https://github.com/fzi-forschungszentrum-informatik/vdb_mapping_ros2
# install dependencies
sudo apt update
rosdep update
rosdep install --from-paths src --ignore-src -y
# build the workspace.
colcon build
# source the workspace
source install/setup.bash
Remote Mapping¶
The remote mapping module is at the moment mainly designed to provide an external access to the map, without saving and loading it in a different node. In our case we use it to visualize the map data on a remote base station which is then used to control the robots from far away and give the user an overview of the area the robot operates in. Basically it is a full additional mapping node which can access the data chunks generated by the main mapping on the robot. These can the be integrated into the remote mapping instance to generate the same or a similar map depending on the chosen parameter settings. Diving deeper into the remote mapping functionality you might stumble over the term of updates, overwrites and sections. These are different mechanics to update a remote mapping instance. The first two are just a byproduct of the normal mapping process. Therefore there is no additional computation needed to generate the data for a remote mapping instance. However all three mechanics use OpenVDB grids which are compressed and serialized as a bitstream before sending them out over the network.
Updates¶
Updates are grids generated during the raycasting process and are also used for the internal map update. Here all sensor data is previously accumulated into an update grid which specifies whether the occupancy probability in the map should be updated as occupied or free. This two step process helps to prevent discretization issues due to the larger resolution of the grid compared to the raw sensor data. It is also possible to accumulate multiple sensor sources and measurements into one update grid (see accumulation parameters). The update grid can then be applied to the local or remote instance to generate the same map on both sides.
Overwrites¶
Overwrite grids are similar to the update grid but only contain the voxel that have changed their occupancy state in the last iteration. Therefore they are more lightweight in terms of necessary bandwith. This can be useful in cases where the network is rather limited but has the downside, that the probabilistic framework is lost on the remote side.
Sections¶
In contrast to updates and overwrites, sections are not bound to the sensor data rate but are generated with a defined rate and create additional processing load. Here the binary occupancy state of a section around a specified frame is copied out of the map and transformed into an update grid that can be applied to a remote instance. Although this created additional overhead it is still highly useful in certain scenarios. In our case we had to handle transmission delay and package loss where both the update and overwrites would result in incomplete maps since grids were lost. Sections on the other hand contain the complete chunk of the map while still being small with respect to the bandwidth.
ROS API¶
ROS Parameters¶
VDB Mapping is highly configurable using ROS parameters. Below is a complete list of all available parameters. Internally we store them in a yaml configuration file. An example can be found here.
Basic Parameters¶
Listed below are the general parameters to configure the basic behavior of vdb_mapping
Parameter Name | Type | Default | Information |
---|---|---|---|
map_frame | string | ' ' | Coordinate frame of the map |
robot_frame | string | ' ' | Coordinate frame of the robot |
max_range | double | 15.0 | Global maximum raycasting range (can also be set for each sensor source individually) |
resolution | double | 0.07 | Map resolution |
prob_hit | double | 0.7 | Probability update if a beam hits a voxel |
prob_miss | double | 0.4 | Probability update if a beam misses a voxel |
prob_thres_min | double | 0.12 | Lower occupancy threshold of a voxel |
prob_thres_max | double | 0.97 | Upper occupancy threshold of a voxel |
map_save_dir | string | ' ' | Storage location for saved maps |
accumulate_updates | boolean | false | Specifies whether the data of multiple sensor measurement should be accumulated before integrating it into the map. |
accumulation_period | double | 1 | Specifies how long updates should be accumulated before integration |
visualization_rate | double | 1 | Specifies in which rate the visualization is published |
publish_pointcloud | boolean | true | Specifies whether the map should be published as pointcloud |
publish_vis_marker | boolean | true | Specifies whether the map should be published as visual marker |
apply_raw_sensor_data | boolean | true | Specify whether raw sensor data (e.g. Pointclouds) should be integrated into the map. This flag becomes relevant when the user wants to use a pure remote instance. If set to true all sensor sources will be periodically integrated into the map. |
sources | string[] | [] | List of sensor sources |
remote_sources | string[] | [] | List of remote sources |
Sensor Sources¶
VDB Mapping is able to integrate an arbitrary amount of different sensor sources (given they are available as PointCloud2 msg). To add a new sensor source the user has to add it to the list of sources in the basic parameters. Below are listed the parameters that can be used to configure the individual sensor source. These have to be put into the corresponding namespace in the yaml file. For an example see this configuration file.
Parameter Name | Type | Default | Information |
---|---|---|---|
topic | string | ' ' | Topic name of the sensor msg |
sensor_origin_frame | string | ' ' | Sensor frame of the measurement. This parameter is optional and in general the frame id of the msg is used. However in some cases like already frame aligned point clouds this info is no longer the origin of the sensor. For this purpose the user can specify here from which frame the raycasting should be performed. |
max_range | double | 0 | Individual per sensor max raycasting range. This parameter is optional and per default the global max range is used. |
Remote Sources¶
VDB Mapping provides a remote operation mode. Here the map data is shared between multiple instances to generate the same or similar maps (depending on the chosen parameter settings). For this remote sources can be specified over the parameter server.
Local side¶
Parameter Name | Type | Default | Information |
---|---|---|---|
publish_updates | boolean | false | Specifies whether updates are published |
publish_overwrites | boolean | false | Specifies whether overwrites are published |
publish_sections | boolean | false | Specifies whether sections are published |
section_update/rate | double | 1 | Rate in which the section update is published |
section_update/frame | string | robot_frame | Center of the update section |
section_update/min_coord/{x,y,z} | double | -10 | Min coordinate of the section bounding box centered around the section frame |
section_update/max_coord/{x,y,z} | double | 10 | Max coordinate of the section bounding box centered around the section frame |
Remote side¶
Below are listed the parameters that can be used to configure the individual remote source. These have to be put into the corresponding namespace in the yaml file. An example config file can be found here.
Parameter Name | Type | Default | Information |
---|---|---|---|
namespace | string | ' ' | Namespace of the remote mapping instance |
apply_remote_updates | boolean | false | Specifies whether remote updates should be applied to the map |
apply_remote_overwrites | boolean | false | Specifies whether remote overwrites should be applied to the map |
apply_remote_sections | boolean | false | Specifies whether remote sections should be applied to the map |
Advertised ROS Topics¶
Topic Name | Type | Information |
---|---|---|
~/vdb_map_visualization | visualization_msgs/Marker | Map visualization topic as voxel marker |
~/vdb_map_pointcloud | sensor_msgs/PointCloud2 | Map visualization topic as pointcloud |
~/vdb_map_updates | vdb_mapping_msgs/UpdateGrid | Map updates topic |
~/vdb_map_overwrites | vdb_mapping_msgs/UpdateGrid | Map overwrites topic |
~/vdb_map_sections | vdb_mapping_msgs/UpdateGrid | Map sections topic |
Subscribed ROS Topics¶
Topic Name | Type | Information |
---|---|---|
{Parameter:sensor_source}/{Parameter:topic} | sensor_msgs/PointCloud2 | Pointcloud sensor message |
{Parameter:remote_source}/vdb_map_updates | vdb_mapping_msgs/UpdateGrid | Map updates topic |
{Parameter:remote_source}/vdb_map_overwrites | vdb_mapping_msgs/UpdateGrid | Map overwrites topic |
{Parameter:remote_source}/vdb_map_sections | vdb_mapping_msgs/UpdateGrid | Map sections topic |
ROS Services¶
Service Name | Type | Information |
---|---|---|
~/load_map | vdb_mapping_msgs/LoadMap | Loads the map specified in the msg |
~/save_map | std_srvs/Trigger | Saves the current map in the destination specified in the map_save_dir parameter |
~/reset_map | std_srvs/Trigger | Resets the current map |
~/raytrace | vdb_mapping_msgs/Raytrace | Raytraces a point and returns coordinate where the ray first intersected the map |
~/trigger_map_section_update | vdb_mapping_msgs/TriggerMapSectionUpdate | Triggers a map section update on a remote instance |
Citation¶
Thanks that you read until here and please let us know if you run into any issues or have suggestions for improvements. If you use our work in your publications please feel free to cite our manuscript:
@inproceedings{besselmann2021vdb,
title={VDB-Mapping: a high resolution and real-time capable 3D mapping framework for versatile mobile robots},
author={Besselmann, M Grosse and Puck, Lennart and Steffen, Lea and Roennau, Arne and Dillmann, R{\"u}diger},
booktitle={2021 IEEE 17th International Conference on Automation Science and Engineering (CASE)},
pages={448--454},
year={2021},
organization={IEEE}
doi={10.1109/CASE49439.2021.9551430}}
}
@incollection{besselmann2022remote,
title={Remote VDB-Mapping: A Level-Based Data Reduction Framework for Distributed Mapping},
author={Besselmann, Marvin Grosse and R{\"o}nnau, Arne and Dillmann, R{\"u}diger},
booktitle={Robotics in Natural Settings: CLAWAR 2022},
pages={448--459},
year={2022},
publisher={Springer}
doi={10.1007/978-3-031-15226-9_42}
}