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:

https://mrpt.github.io/imgs/mola-lo-ros2-launch-demo-kitti.png


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 and RViz2 (or use FoxGlove if preferred).

  • How MOLA mola_lidar_odometry publishes the local map, the estimated trajectory, and /tf for the estimated odometry.

https://mrpt.github.io/imgs/mola-lo-ros2-launch-demo-live-forest.png
# 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 \
   publish_localization_following_rep105:=False

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')

   'start_mapping_enabled':
      Whether MOLA-LO should start with map update enabled (true), or in localization-only mode (false)
      (default: 'True')

   'start_active':
      Whether MOLA-LO should start active, that is, processing incoming sensor data (true), or ignoring them (false)
      (default: 'True')

   'mola_lo_reference_frame':
      The /tf frame name to be used for MOLA-LO localization updates
      (default: 'map')

   'mola_lo_pipeline':
      The LiDAR-Odometry pipeline configuration YAML file defining the LO system. Absolute path, or relative to 'mola-cli-launchs/lidar_odometry_ros2.yaml'. Default is the 'lidar3d-default.yaml' system described in the IJRR 2025 paper.
      (default: '../pipelines/lidar3d-default.yaml')

   'generate_simplemap':
      Whether to create a '.simplemap', useful for map post-processing. Refer to online tutorials.
      (default: 'False')

   'mola_initial_map_mm_file':
      Can be used to provide a metric map '.mm' file to be loaded as initial map. Refer to online tutorials.
      (default: '""')

   'mola_initial_map_sm_file':
      Can be used to provide a keyframes map '.simplemap' file to be loaded as initial map. Refer to online tutorials.
      (default: '""')

   'mola_footprint_to_base_link_tf':
      Can be used to define a custom transformation between base_footprint and base_link. The coordinates are [x, y, z, yaw_deg, pitch_deg, roll_deg].
      (default: '[0, 0, 0, 0, 0, 0]')

   'enforce_planar_motion':
      Whether to enforce z, pitch, and roll to be zero.
      (default: 'False')

   'use_state_estimator':
      If false, the basic state estimator 'mola::state_estimation_simple::StateEstimationSimple' will be used. If true, 'mola::state_estimation_smoother::StateEstimationSmoother' is used instead.
      (default: 'False')

   'state_estimator_config_yaml':
      A YAML file with settings for the state estimator. Absolute path or relative to 'mola-cli-launchs/lidar_odometry_ros2.yaml'
      (default: PythonExpr(''../state-estimator-params/state-estimation-smoother.yaml' if ' + LaunchConfig('use_state_estimator') + ' else '../state-estimator-params/state-estimation-simple.yaml''))

   '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_LINK (Default: "base_link"): The robot reference frame id in /tf. Used to get sensor poses with respect to the vehicle.

  • MOLA_TF_FOOTPRINT_LINK (Default: base_footprint): If not empty, the node will broadcast a static /tf from base_footprint to base_link with the TF base_footprint_to_base_link_tf at start up.

  • MOLA_TF_FOOTPRINT_TO_BASE_LINK (Default: '[0, 0, 0, 0, 0, 0]'): [x, y, z, yaw_deg, pitch_deg, roll_deg].

  • MOLA_LIDAR_TOPIC (Default: '/ouster/points'): The sensor_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'): The sensor_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'): The sensor_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:

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):

imgs/gui_parts.png


3. Re-localization

Write me!



4. Published /tf frames

The frames of reference (`frame_id`s) at work when using MOLA depend on your system configuration:

  • Using just mola_lidar_odometry: Two situations here depending on the ROS launch argument publish_localization_following_rep105:

      1. Strictly following ROS REP-105 in systems with wheels (encoders-based) high-frequency odometry, or

      1. Not following REP-105 (e.g. if you do not have wheels odometry).

    1. Using state estimation data fusion (this case does not follow REP-105), and

And orthogonal to both above, whether the map is geo-referenced or not.

The diagrams below show the cases of following or not following ROS REP-105 for the different situations listed above:

For cases with ground robots with wheel-based odometry:

https://mrpt.github.io/imgs/mola_mrpt_ros_geo_referenced_utm_frames.png

This is who is responsible of publishing each transformation:

  • odom base_link: Wheel odometry module. High-frequency, relatively accurate in the short term, but drifts in the long term.

  • map odom: Localization module, which corrects the odometry drift.

  • enu {map, utm}: Published by mrpt_map_server (github) or mola_lidar_odometry map loading service if fed with a geo-referenced metric map (.mm) file.

When using just a LiDAR as single sensor.

https://mrpt.github.io/imgs/mola_mrpt_ros_frames_no_rep105.png

This is who is responsible of publishing each transformation:

  • map base_link: Localization module.

  • enu {map, utm}: Published by mrpt_map_server (github) or mola_lidar_odometry map loading service if fed with a geo-referenced metric map (.mm) file.

When using state estimation data fusion: applicable if having just one LiDAR sensor, or LiDAR + wheel odometry, or several odometry sources, optionally GNNS (GPS) and IMU, etc.

https://mrpt.github.io/imgs/mola_mrpt_ros_frames_fusion.png

This is who is responsible of publishing each transformation:

  • odom_{i} base_link: One or more odometry sources.

  • map base_link: Published by state estimation data fusion.

  • enu {map, utm}: Published by mrpt_map_server (github) or mola_lidar_odometry map loading service if fed with a geo-referenced metric map (.mm) file.

Note

For non geo-referenced maps, all frames remain the same but utm and enu will not exist.

Definition of the frames above:

  • base_link: The robot reference frame. For ground vehicles, normally placed at the center of the rear axle.

  • base_footprint (optional): The projection of base_link on the ground plane. In MOLA, this frame is published by BridgeROS2 as a child of base_link.

  • odom, odom_1,… odom_n: The arbitrary origin for odometry measurements. There may be different odometry sources: wheels, LiDAR odometry, visual odometry, etc.

  • 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 different enu frames, since it is defined by collected GNSS measurements.

  • utm: The origin of the UTM zone in which enu falls. Unlike enu, it is independent of the trajectory followed while building the map.




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\"}"