MOLA in ROS 2: configuration cookbook

This page walks through every supported way of launching MOLA-LO / MOLA-SLAM in a ROS 2 workflow. Each configuration shows a block diagram, the exact command line, and the expected /tf tree.

Live parameter editor

The form at §3 lets you set your own robot frame, topic names, bag path, and namespace; the command blocks below will be rewritten automatically and persisted in your browser.




1. The five axes of configuration

A MOLA ROS 2 deployment is defined by five independent choices:

Axis

Choices

What it affects

1. Input

Offline rosbag2 (mola-lidar-odometry-cli or mola-lo-gui-rosbag2) vs live ROS 2 node

Which module provides sensor data: Rosbag2Dataset vs BridgeROS2.

2. Namespace

Plain /tf/topics vs namespaced (/robot1/tf, /robot1/scan, …)

Whether the launch uses use_namespace:=True (online) or sets MOLA_TF_TOPIC / MOLA_TF_STATIC_TOPIC (offline).

3. State estimator

StateEstimationSimple (default) vs StateEstimationSmoother

Which module publishes the final fused pose.

4. REP-105

Publish map odom (REP-105) vs direct map base_link

Whether an external wheel / visual odometry source is expected. REP-105 is only compatible with the Simple estimator.

5. Extra sensors

IMU (for LIO / gravity), GNSS (logging, live geo-ref, relocalization), multiple odometry sources (Smoother only)

Topics subscribed, factors added, output TFs.

Hint

The most common pitfall is REP-105 + Smoother: the smoother publishes map base_link directly and cannot split the transform.


2. Decision flowchart

flowchart TD Start([Where does your data come from?]) --> Q1{Live ROS 2<br/>or rosbag file?} Q1 -- rosbag --> QO1{GUI or fastest<br/>offline run?} Q1 -- Live --> Q2{Namespaced<br/>topics/tf?} QO1 -- GUI --> QO2[§5.1 mola-lo-gui-rosbag2] QO1 -- fastest --> QO3[§5.3 mola-lidar-odometry-cli] Q2 -- yes --> Q3ns[§4.3 namespaced online] Q2 -- no --> Q3{Need sensor fusion<br/>GNSS / multi-odom?} Q3 -- no --> Q4{Wheel / external<br/>odometry available?} Q3 -- yes --> Q5[§4.4 … §4.6] Q4 -- yes --> Q4a[§4.1 Simple + REP-105] Q4 -- no --> Q4b[§4.2 Simple, no REP-105]

3. Parameter editor

Loading editor… if this message stays, JavaScript is disabled and the commands below show default placeholder values.

Concept

Typical value

Where it is set

Robot base frame

base_link

mola_tf_base_link:= (online) / MOLA_TF_BASE_LINK (offline)

Map frame

map

mola_state_estimator_reference_frame:= / MOLA_TF_MAP

Odom frame (REP-105 only)

odom

mola_lo_reference_frame:= / MOLA_TF_ESTIMATED_ODOMETRY

LiDAR topic

/ouster/points

lidar_topic_name:= / MOLA_LIDAR_TOPIC

IMU topic

/imu

imu_topic_name:= / MOLA_IMU_TOPIC

GNSS topic (NavSatFix)

/gps

gnss_topic_name:= / MOLA_GNSS_TOPIC

External odom (/tf)

(off)

forward_ros_tf_odom_to_mola:=True / MOLA_FORWARD_ROS_TF_ODOM_TO_MOLA

External odom (topic)

/wheel_odom

odom_topic_name:= / MOLA_ODOM_TOPIC (+ odom_sensor_label:= / MOLA_ODOM_SENSOR_LABEL)

/tf topic in bag

/tf

MOLA_TF_TOPIC (rosbag2 YAML tf_topic)

/tf_static topic in bag

/tf_static

MOLA_TF_STATIC_TOPIC (rosbag2 YAML tf_static_topic)


4. Live ROS 2 node

All sections in this group use ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py. See all launch arguments for the full list.

4.1. Simple SE, LO or LIO, REP-105 (wheel / external odometry available)

Use this when the robot already publishes a high-frequency odom base_link transform from wheel encoders (or any other odometry source). MOLA-LO only corrects long-term drift by publishing map odom.

flowchart LR subgraph ROS2[ROS 2 topics / tf] lidar[/"__LIDAR_TOPIC__"/] odomtf[/'tf: odom → base_link'/] mapodom[/'tf: map → odom'/] end wheel[Wheel odometry driver] -->|'tf'| odomtf lidar --> bridge[BridgeROS2] bridge --> lo[mola::LidarOdometry] lo --> bridge se --> lo lo --> se[StateEstimationSimple] bridge -->|odom| se bridge -->|map → odom| mapodom
# LiDAR only odometry (LO): No IMU
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  forward_ros_tf_odom_to_mola:=True \
  publish_localization_following_rep105:=True

Resulting /tf tree:

map --→ odom --→ base_link --→ (sensor frames)
     ^        ^
     |        └── wheel odometry (external)
     └── MOLA-LO (corrects drift)
Variant: LIO (LiDAR + IMU), REP-105

Adds IMU-based scan deskew. Gravity alignment is on by default.

flowchart LR lidar[/"__LIDAR_TOPIC__"/] --> bridge[BridgeROS2] imu[/"__IMU_TOPIC__"/] --> bridge bridge --> lo[mola::LidarOdometry] lo --> bridge lo --> se[StateEstimationSimple] se --> lo bridge -->|map → odom| tfout[/'tf'/] bridge -->|odom| se
# LiDAR inertial odometry (LIO): with IMU
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  imu_topic_name:=__IMU_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  use_imu_for_lio:=True \
  forward_ros_tf_odom_to_mola:=True \
  publish_localization_following_rep105:=True

4.2. Simple SE, no REP-105: LO or LIO, no external wheels odometry

When no external odometry exists (e.g. handheld mapping, drone), MOLA-LO publishes map base_link directly.

flowchart LR lidar[/"__LIDAR_TOPIC__"/] --> bridge[BridgeROS2] bridge --> lo[mola::LidarOdometry] lo --> se[StateEstimationSimple] lo --> bridge se --> lo bridge -->|map → base_link| tfout[/'tf'/]
# LiDAR only odometry (LO): No IMU
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  publish_localization_following_rep105:=False

Resulting /tf tree:

map --→ base_link --→ (sensor frames)
Variant: LIO (LiDAR + IMU), no REP-105

Adds IMU-based scan deskew. Gravity alignment is on by default.

flowchart LR lidar[/"__LIDAR_TOPIC__"/] --> bridge[BridgeROS2] imu[/"__IMU_TOPIC__"/] --> bridge bridge --> lo[mola::LidarOdometry] bridge -->|imu| se[StateEstimationSimple] lo --> se lo --> bridge se --> lo bridge -->|map → base_link| tfout[/'tf'/]
# LiDAR inertial odometry (LIO): with IMU
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  imu_topic_name:=__IMU_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  use_imu_for_lio:=True \
  publish_localization_following_rep105:=False
Variant: no sensor /tf available

If the driver does not publish base_link lidar on /tf, either configure it via a robot_state_publisher or force an identity sensor pose:

ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  ignore_lidar_pose_from_tf:=True \
  publish_localization_following_rep105:=False

4.3. Namespaced robot (/robot1/tf, /robot1/scan, …)

When your robot publishes everything under a ROS 2 namespace, the launch file pushes the whole MOLA system into that namespace and remaps /tf / /tf_static so tf2 inside the namespace is transparent to MOLA.

flowchart LR subgraph NS["namespace: __NS__"] lidar[/"__LIDAR_TOPIC__"/] tfns["/tf (namespaced)/"] bridge[BridgeROS2] lo[mola::LidarOdometry] se[StateEstimationSimple] end lidar --> bridge bridge --> lo --> se --> bridge bridge --> tfns
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  use_namespace:=True \
  namespace:=__NS__

Note

The lidar_topic_name should be given relative (no leading /). It gets prefixed by the namespace automatically. The launch file remaps /tftf internally so tf2 subscribes to /__NS__/tf without any extra configuration.


4.4. Smoother SE + external (wheel / VIO) odometry fusion

Adds an external odometry source to the smoother. The smoother estimates a distinct T_map_to_odom per source and fuses their deltas with LO (and IMU, if enabled).

BridgeROS2 offers two complementary pathways for consuming external odometry; pick one according to what the upstream driver publishes.

Warning

The two pathways below are mutually exclusive. Enabling both (forward_ros_tf_odom_to_mola:=True and a non-empty odom_topic_name:=) feeds duplicate observations to the state estimator under different labels and degrades the fusion.

Pathway comparison

Variant A: via /tf

Variant B: via /odom topic

Launch arg

forward_ros_tf_odom_to_mola:=True

odom_topic_name:=/your_odom

Upstream must publish

odom base_link TF

nav_msgs/Odometry message

Observation type fed to MOLA

CObservationOdometry (2D, no covariance)

CObservationRobotPose (3D, 6×6 covariance)

Sensor label

Hardcoded odom

odom_sensor_label:=... (per source)

Multiple sources

No (single TF chain)

Yes (multiple subscribe entries / labels)

Rate

BridgeROS2 execution_rate (20 Hz)

Publisher rate

Recommended for

Simple SE, or 2D robots where only TF is available

Smoother SE fusion (3D pose + covariance)

The upstream wheel driver (or robot_state_publisher) publishes odom base_link to /tf. BridgeROS2 queries that TF at its own execution_rate and injects a 2D CObservationOdometry.

flowchart LR lidar[/"__LIDAR_TOPIC__"/] --> bridge[BridgeROS2] imu[/"__IMU_TOPIC__"/] --> bridge wheel[Wheel driver] -->|'/tf: odom → base_link'| bridge bridge --> lo[mola::LidarOdometry] bridge --> smoother[StateEstimationSmoother] lo --> smoother smoother --> bridge bridge -->|map → base_link| tfout[/'tf'/]
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  imu_topic_name:=__IMU_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  use_state_estimator:=True \
  use_imu_for_lio:=True \
  forward_ros_tf_odom_to_mola:=True

If your odom frame has a non-default name, also set mola_bridge_odometry_frame:=<name>.

The upstream driver publishes a nav_msgs/Odometry message on a topic. BridgeROS2 subscribes directly, converts each message to a 3D CObservationRobotPose (6×6 covariance) and forwards it under odom_sensor_label. This preserves Z / pitch / roll and allows fusing multiple labeled sources.

flowchart LR lidar[/"__LIDAR_TOPIC__"/] --> bridge[BridgeROS2] imu[/"__IMU_TOPIC__"/] --> bridge wheel[/wheel odom topic/] --> bridge bridge --> lo[mola::LidarOdometry] bridge --> smoother[StateEstimationSmoother] lo --> smoother smoother --> bridge bridge -->|map → base_link| tfout[/'tf'/]
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  imu_topic_name:=__IMU_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  use_state_estimator:=True \
  use_imu_for_lio:=True \
  odom_topic_name:=__ODOM_TOPIC__ \
  odom_sensor_label:=odom_wheels

For multiple external sources (e.g. wheels + VIO), add extra subscribe entries to lidar_odometry_ros2.yaml with distinct output_sensor_label values.

See the “Fusing two Odometry sources” tutorial for a full worked example with fake publishers.


4.5. Smoother SE + live geo-referencing (GNSS)

The smoother estimates the enu map transform online from incoming GNSS fixes. It publishes enu and utm TFs once convergence is reached.

flowchart LR lidar[/"__LIDAR_TOPIC__"/] --> bridge[BridgeROS2] imu[/"__IMU_TOPIC__"/] --> bridge gnss[/"__GNSS_TOPIC__"/] --> bridge bridge --> lo[mola::LidarOdometry] bridge --> smoother[StateEstimationSmoother] lo --> smoother smoother --> bridge bridge -->|'map → base_link, enu → map'| tfout[/'tf'/]
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  imu_topic_name:=__IMU_TOPIC__ \
  gnss_topic_name:=__GNSS_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  use_state_estimator:=True \
  use_imu_for_lio:=True \
  gnss_mode:=live_georef

4.6. Smoother SE + relocalization in a geo-referenced map

Load a previously built geo-referenced .mm map. MOLA-LO stays idle until the smoother has converged on an initial pose from GNSS, then switches to localization-only mapping.

flowchart LR mm[(__MM_PATH__ .mm map)] --> lo lidar[/"__LIDAR_TOPIC__"/] --> bridge[BridgeROS2] imu[/"__IMU_TOPIC__"/] --> bridge gnss[/"__GNSS_TOPIC__"/] --> bridge bridge --> lo[mola::LidarOdometry] bridge --> smoother[StateEstimationSmoother] lo --> smoother smoother --> bridge bridge -->|'map → base_link, enu → map'| tfout[/'tf'/]
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
  lidar_topic_name:=__LIDAR_TOPIC__ \
  imu_topic_name:=__IMU_TOPIC__ \
  gnss_topic_name:=__GNSS_TOPIC__ \
  mola_tf_base_link:=__BASE_LINK__ \
  mola_initial_map_mm_file:=__MM_PATH__ \
  use_state_estimator:=True \
  use_imu_for_lio:=True \
  start_mapping_enabled:=False \
  gnss_mode:=relocalize

5. Offline rosbag2

5.1. mola-lo-gui-rosbag2 (Simple SE, the default)

GUI replay of a bag. All configuration is via environment variables.

flowchart LR bag[(__BAG_PATH__)] --> ds[Rosbag2Dataset] ds --> lo[mola::LidarOdometry] lo --> se[StateEstimationSimple] se --> gui[MolaViz GUI]
MOLA_LIDAR_TOPIC=__LIDAR_TOPIC__ \
MOLA_IMU_TOPIC=__IMU_TOPIC__ \
MOLA_TF_BASE_LINK=__BASE_LINK__ \
  mola-lo-gui-rosbag2 __BAG_PATH__
Variant: bag recorded with a ROS 2 namespace

When the bag was recorded from a namespaced robot, both the sensor topics and the /tf topics are prefixed with the namespace. Unlike the live ROS 2 node (§4.3), there is no tf2 remap at play here: Rosbag2Dataset looks up topics by literal name, so you must set them explicitly.

Requires mola_input_rosbag2 1.12 (exposes tf_topic / tf_static_topic params). Edit the live form above so LiDAR topic (and IMU topic / GNSS topic if used) already carry the namespace prefix, e.g. /__NS__/ouster/points:

MOLA_LIDAR_TOPIC=__LIDAR_TOPIC__ \
MOLA_IMU_TOPIC=__IMU_TOPIC__ \
MOLA_TF_BASE_LINK=__BASE_LINK__ \
MOLA_TF_TOPIC=/__NS__/tf \
MOLA_TF_STATIC_TOPIC=/__NS__/tf_static \
  mola-lo-gui-rosbag2 __BAG_PATH__

Note

MOLA_TF_BASE_LINK is the frame id inside the TF messages (e.g. base_link); it is not namespaced. Only the bag topic names carry the namespace.


5.2. mola-lo-gui-rosbag2 (Smoother SE)

Same as §5.1 but force the smoother and LIO-style deskew:

MOLA_LIDAR_TOPIC=__LIDAR_TOPIC__ \
MOLA_IMU_TOPIC=__IMU_TOPIC__ \
MOLA_TF_BASE_LINK=__BASE_LINK__ \
MOLA_DESKEW_METHOD=MotionCompensationMethod::IMU \
MOLA_STATE_ESTIMATOR=mola::state_estimation_smoother::StateEstimationSmoother \
MOLA_STATE_ESTIMATOR_YAML="$(ros2 pkg prefix mola_state_estimation_smoother)/share/mola_state_estimation_smoother/params/state-estimation-smoother.yaml" \
  mola-lo-gui-rosbag2 __BAG_PATH__
Variant: bag recorded with a ROS 2 namespace

Same caveat as §5.1: Rosbag2Dataset resolves topics by literal name, so namespaced bags need explicit MOLA_TF_TOPIC / MOLA_TF_STATIC_TOPIC, and the sensor topics in the form above must already carry the namespace prefix (e.g. /__NS__/ouster/points, /__NS__/imu):

MOLA_LIDAR_TOPIC=__LIDAR_TOPIC__ \
MOLA_IMU_TOPIC=__IMU_TOPIC__ \
MOLA_TF_BASE_LINK=__BASE_LINK__ \
MOLA_TF_TOPIC=/__NS__/tf \
MOLA_TF_STATIC_TOPIC=/__NS__/tf_static \
MOLA_DESKEW_METHOD=MotionCompensationMethod::IMU \
MOLA_STATE_ESTIMATOR=mola::state_estimation_smoother::StateEstimationSmoother \
MOLA_STATE_ESTIMATOR_YAML="$(ros2 pkg prefix mola_state_estimation_smoother)/share/mola_state_estimation_smoother/params/state-estimation-smoother.yaml" \
  mola-lo-gui-rosbag2 __BAG_PATH__

5.3. mola-lidar-odometry-cli (fastest, no GUI)

Best option for large batch runs and reproducible benchmarks.

flowchart LR bag[(__BAG_PATH__)] --> ds[Rosbag2Dataset] ds --> lo[mola::LidarOdometry] lo --> se[StateEstimationSimple / Smoother] se --> trj[[trajectory.tum]] se --> sm[[map.simplemap]]
mola-lidar-odometry-cli \
  -c $(ros2 pkg prefix mola_lidar_odometry)/share/mola_lidar_odometry/pipelines/lidar3d-default.yaml \
  --input-rosbag2 __BAG_PATH__ \
  --lidar-sensor-label __LIDAR_TOPIC__ \
  --base-link-frame-id __BASE_LINK__ \
  --output-tum-path trajectory.tum \
  --output-simplemap map.simplemap
Variant: bag with a ROS 2 namespace
mola-lidar-odometry-cli \
  -c $(ros2 pkg prefix mola_lidar_odometry)/share/mola_lidar_odometry/pipelines/lidar3d-default.yaml \
  --input-rosbag2 __BAG_PATH__ \
  --lidar-sensor-label __LIDAR_TOPIC__ \
  --base-link-frame-id __BASE_LINK__ \
  --tf-topic /__NS__/tf \
  --tf-static-topic /__NS__/tf_static \
  --output-tum-path trajectory.tum
Variant: use the Smoother
mola-lidar-odometry-cli \
  -c $(ros2 pkg prefix mola_lidar_odometry)/share/mola_lidar_odometry/pipelines/lidar3d-default.yaml \
  --state-estimator "mola::state_estimation_smoother::StateEstimationSmoother" \
  --state-estimator-param-file $(ros2 pkg prefix mola_state_estimation_smoother)/share/mola_state_estimation_smoother/params/state-estimation-smoother.yaml \
  --load-plugins libmola_state_estimation_smoother.so \
  --input-rosbag2 __BAG_PATH__ \
  --lidar-sensor-label __LIDAR_TOPIC__ \
  --base-link-frame-id __BASE_LINK__ \
  --output-tum-path trajectory.tum

6. Troubleshooting

Symptom

Most common cause

"base_link" passed to lookupTransform ... does not exist

The bag/driver is not publishing a base_link frame, or the launch mola_tf_base_link does not match the one in /tf.

LO starts but /tf is empty / map not visible in RViz2

Forgot to set publish_localization_following_rep105:=False when no external odometry is running. The launch waits for odom base_link that never arrives.

Smoother set, but map odom appears (and not map base_link)

REP-105 is incompatible with the smoother. Set publish_localization_following_rep105:=False or simply do not set it (the launch default already matches when use_state_estimator:=True).

Namespaced bag silently ignored on /tf

Before mola_input_rosbag2 gained tf_topic / tf_static_topic params, /tf was hardcoded. Update the package and set MOLA_TF_TOPIC / MOLA_TF_STATIC_TOPIC (see §5.1).

Smoother converges slowly to geo-reference

The vehicle must move non-trivially for GNSS factors to constrain enu map. Drive at least a few meters.