ROS 2 API
This page reflects the topics and services that a MOLA system will expose when running a SLAM or LiDAR-odometry module. At present, this applies to:
Any MOLA system including the BridgeROS2 module: This module acts as a wrapper of
mola-kernel
virtual interfaces implemented in other MOLA modules and the ROS 2 system.
1. Nodes and launch files
1.1. ROS 2 node for Lidar Odometry (LO)
Note
It is recommended to start with the tutorial on how to build a map.
This launch file (view sources) runs MOLA-LO live on point clouds received from a ROS 2 topic, demonstrating a few features:
Launching and visualizing LO in both,
mola_viz
andRViz2
(or use FoxGlove if preferred).How MOLA
mola_lidar_odometry
publishes the local map, the estimated trajectory, and /tf for the estimated odometry.
# Minimal use case (requires correct LiDAR sensor /tf):
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
lidar_topic_name:=ouster/points
# Usage without sensor /tf:
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
lidar_topic_name:=ouster/points \
ignore_lidar_pose_from_tf:=True
If your robot uses a ROS 2 namespace ROBOT_NS
for all its sensor and tf topics, use:
# Minimal use case:
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
lidar_topic_name:=ouster/points \
use_namespace:=True \
namespace:=ROBOT_NS
$ ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py --show-args
Arguments (pass arguments as '<name>:=<value>'):
'namespace':
Top-level namespace
(default: '')
'use_namespace':
Whether to apply a namespace to the navigation stack
(default: 'false')
'lidar_topic_name':
Topic name to listen for PointCloud2 input from the LiDAR (for example '/ouster/points')
'ignore_lidar_pose_from_tf':
If true, the LiDAR pose will be assumed to be at the origin (base_link). Set to false (default) if you want to read the actual sensor pose from /tf
(default: 'false')
'gnss_topic_name':
Topic name to listen for NavSatFix input from a GNSS (for example '/gps')
(default: 'gps')
'imu_topic_name':
Topic name to listen for Imu input (for example '/imu')
(default: 'imu')
'use_mola_gui':
Whether to open MolaViz GUI interface for watching live mapping and control UI
(default: 'True')
'publish_localization_following_rep105':
Whether to publish localization TFs in between map->odom (true) or directly map->base_link (false)
(default: 'True')
'use_rviz':
Whether to launch RViz2 with default lidar-odometry.rviz configuration
(default: 'True')
Configure sensor inputs for ROS 2 node and rosbag2 input
The following environment variables can be set to change the behavior of how BridgeROS2
handles input ROS 2 messages on sensor inputs.
Please, refer to the actual mola-cli launch files where these variables are defined:
Environment variables:
MOLA_TF_BASE_FOOTPRINT
(Default:"base_link"
): The robot reference frame id in/tf
. Used to get sensor poses with respect to the vehicle.MOLA_LIDAR_TOPIC
(Default:'/ouster/points'
): Thesensor_msgs/PointCloud2
topic with raw LiDAR data (mandatory).MOLA_USE_FIXED_LIDAR_POSE
(Default:false
): If false, sensor pose will be retrieved from/tf
. You can also set it to true and then the sensor pose will be given by these env. variables:LIDAR_POSE_X
,LIDAR_POSE_Y
,LIDAR_POSE_Z
(in meters).LIDAR_POSE_YAW
,LIDAR_POSE_PITCH
,LIDAR_POSE_ROLL
(in degrees).
MOLA_GNSS_TOPIC
(Default:'/gps'
): Thesensor_msgs/NavSatFix
topic with GNSS data (optional).MOLA_USE_FIXED_GNSS_POSE
(Default:true
): If false, sensor pose will be retrieved from/tf
. You can also set it to true and then the sensor pose will be given by these env. variables:GNSS_POSE_X
,GNSS_POSE_Y
,GNSS_POSE_Z
(in meters).GNSS_POSE_YAW
,GNSS_POSE_PITCH
,GNSS_POSE_ROLL
(in degrees).
MOLA_IMU_TOPIC
(Default:'/imu'
): Thesensor_msgs/Imu
topic with IMU data (optional).MOLA_USE_FIXED_IMU_POSE
(Default:true
): If false, sensor pose will be retrieved from/tf
. You can also set it to true and then the sensor pose will be given by these env. variables:IMU_POSE_X
,IMU_POSE_Y
,IMU_POSE_Z
(in meters).IMU_POSE_YAW
,IMU_POSE_PITCH
,IMU_POSE_ROLL
(in degrees).
More LO parameters
The lidar3d-default.yaml
pipeline file defines plenty of additional parameters and options that you can explore.
See also the docs for the ROS 2 API and this tutorial on how to save and load a map using ROS 2 MOLA-LO nodes.
2. Map loading / saving
During a live SLAM run, BridgeROS2
will look for modules implementing
MapServer and will expose
these ROS 2 services to load or save the current map:
/map_load
: See ROS docs for mola_msgs/MapLoad/map_save
: See ROS docs for mola_msgs/MapSave
Example ROS 2 cli service calls
To save the current map:
ros2 service call /map_save mola_msgs/srv/MapSave "map_path: '/tmp/my_map_file_prefix'"
To load a map from disk:
ros2 service call /map_load mola_msgs/srv/MapLoad "map_path: '/tmp/my_map_file_prefix'"
Note that filename extension should not be given, since each service implementation may add a different extension, or even save several files that should all, together, be later on loaded as one to load the map again.
Alternatively, you can enable saving the map when mapping is ended by checking the corresponding checkbox in the MOLA-LO GUI (block “6” below):
3. Re-localization
Write me!
4. Published /tf
frames
These frames of reference exist when using MOLA geo-referenced maps:
Note
For non geo-referenced maps, all frames remain the same but utm
and enu
will not exist.
These are the existing frames:
base_link
: The robot reference frame. For ground vehicles, normally placed at the center of the rear axle.odom
: The arbitrary origin for odometry measurements.map
: The origin of the reference metric map used for localization.enu
: For geo-referenced maps, the North (y
axis), East (x
axis), Up (z
axis) frame for which we have reference geodetic coordinates (latitude and longitude). Different maps built in the same zone will surely have differentenu
frames, since it is defined by collected GNSS measurements.utm
: The origin of the UTM zone in whichenu
falls. Unlikeenu
, it is independent of the trajectory followed while building the map.
And this is who is responsible of publishing each transformation:
odom → base_link
: Odometry module. High-frequency, accurate in the short term, but drifts in the long term.map → odom
: Localization module, which corrects the odometry drift.enu → {map, utm}
: Published bymrpt_map_server
(github), if fed with a geo-referenced metric map (.mm
) file.
5. Published topics
Write me!
6. Map publishing
There are two ways of publishing maps to ROS:
Using
mrpt_map_server
(github): the recommended way for static, previously-built maps. In this case, one ROS topic will be published for each map layer, as described in the package documentation. See also this tutorial.During a live map building process (e.g. MOLA-LO).
In this latter case, BridgeROS2 will look for modules implementing
MapSourceBase and will publish
one topic named <METHOD>/<LAYER_NAME>
for each map layer.
The metric map layer C++ class will determine the ROS topic type to use.
Note
Using the default MOLA LiDAR odometry pipeline, only one map topic will be generated during mapping:
Name:
/lidar_odometry/localmap_points
Type:
sensor_msgs/PointCloud2
7. Runtime dynamic reconfiguration
MOLA modules may expose a subset of their parameters through an interface that allows runtime reconfiguration via ROS 2 service requests:
7.1. Runtime parameters for mola_lidar_odometry
List all existing parameters:
ros2 service call /mola_runtime_param_get mola_msgs/srv/MolaRuntimeParamGet
Example output
requester: making request: mola_msgs.srv.MolaRuntimeParamGet_Request() response: mola_msgs.srv.MolaRuntimeParamGet_Response(parameters='mola::LidarOdometry:lidar_odom:\n active: true\n generate_simplemap: false\n mapping_enabled: true\n')Returned
parameters
as YAML:mola::LidarOdometry:lidar_odom: active: true generate_simplemap: false mapping_enabled: true
Documented parameters:
active
: Whether MOLA-LO should process incoming sensor data (active: true
) or ignore them (active: false
).
Copy & paste commands for active
# active: true
ros2 service call /mola_runtime_param_set mola_msgs/srv/MolaRuntimeParamSet \
"{parameters: \"mola::LidarOdometry:lidar_odom:\n active: true\n\"}"
# active: false
ros2 service call /mola_runtime_param_set mola_msgs/srv/MolaRuntimeParamSet \
"{parameters: \"mola::LidarOdometry:lidar_odom:\n active: false\n\"}"
mapping_enabled
: Whether MOLA-LO should update the localmap (true
) or just use it in localization-only mode (false
).
Copy & paste commands for mapping_enabled
# mapping_enabled: true
ros2 service call /mola_runtime_param_set mola_msgs/srv/MolaRuntimeParamSet \
"{parameters: \"mola::LidarOdometry:lidar_odom:\n mapping_enabled: true\n\"}"
# mapping_enabled: false
ros2 service call /mola_runtime_param_set mola_msgs/srv/MolaRuntimeParamSet \
"{parameters: \"mola::LidarOdometry:lidar_odom:\n mapping_enabled: false\n\"}"
generate_simplemap
: Whether MOLA-LO should build the keyframes-based map (apart of the local metric map), so you end up with a*.simplemap
file.
Copy & paste commands for generate_simplemap
# generate_simplemap: true
ros2 service call /mola_runtime_param_set mola_msgs/srv/MolaRuntimeParamSet \
"{parameters: \"mola::LidarOdometry:lidar_odom:\n generate_simplemap: true\n\"}"
# generate_simplemap: false
ros2 service call /mola_runtime_param_set mola_msgs/srv/MolaRuntimeParamSet \
"{parameters: \"mola::LidarOdometry:lidar_odom:\n generate_simplemap: false\n\"}"