ROS 2 configurations
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 |
Which module provides sensor data: Rosbag2Dataset vs BridgeROS2. |
2. Namespace |
Plain |
Whether the launch uses |
3. State estimator |
StateEstimationSimple (default) vs StateEstimationSmoother |
Which module publishes the final fused pose. |
4. REP-105 |
Publish |
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
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 |
|
|
Map frame |
|
|
Odom frame (REP-105 only) |
|
|
LiDAR topic |
|
|
IMU topic |
|
|
GNSS topic (NavSatFix) |
|
|
External odom ( |
(off) |
|
External odom (topic) |
|
|
|
|
|
|
|
|
LiDAR/IMU subscription QoS |
|
|
Note
Subscription QoS for sensor topics defaults to REP-2003 (best_effort,
volatile) with a queue depth of 50. For high-rate sensors consumed
together with a heavy SLAM pipeline (e.g. a 640 Hz IMU), set
imu_qos_reliability:=reliable and increase imu_qos_depth (e.g.
1000) so the bridge subscription matches the publisher and can
absorb executor stalls. See the launch arguments documented in
mola_lo_ros_node and the per-topic qos: block accepted by
BridgeROS2’s subscribe list.
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.
# 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.
# 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.
# 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.
# 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.
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
/tf ↔ tf 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).
Important
With the Smoother, external odometry must be consumed via a
nav_msgs/Odometry topic (odom_topic_name:=...).
forward_ros_tf_odom_to_mola:=True (the /tf pathway) is only valid
with the Simple estimator + REP-105 (§4.1), where the bridge splits
its output into map → odom. The Smoother instead publishes
map → base_link directly, so an external odom → base_link on
/tf would give base_link two parents and break the tf2 tree.
The launch file enforces this and fails fast if both
forward_ros_tf_odom_to_mola:=True and use_state_estimator:=True
are set.
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.
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.
Why not the /tf pathway here?
forward_ros_tf_odom_to_mola:=True makes BridgeROS2 query
odom → base_link from /tf at its execution rate and inject a 2D
CObservationOdometry. That pathway relies on an external
publisher (wheel driver, robot_state_publisher) putting
odom → base_link on /tf. With the Simple estimator in REP-105
mode, the bridge publishes map → odom and the tree is well
formed: map → odom → base_link.
With the Smoother, the bridge publishes map → base_link directly.
Adding an external odom → base_link on top means two edges
pointing at base_link (from map and from odom), which
violates the tf2 tree invariant. For Smoother fusion the only
viable pathway is the /odom topic, whose observations do not
participate in /tf.
Via |
Via |
|
|---|---|---|
Launch arg |
|
|
Upstream must publish |
|
|
Observation type fed to MOLA |
|
|
Sensor label |
Hardcoded |
|
Multiple sources |
No (single TF chain) |
Yes (multiple subscribe entries / labels) |
Rate |
BridgeROS2 |
Publisher rate |
Compatible with |
Simple SE + REP-105 only (§4.1). Incompatible with Smoother — rejected by the launch file. |
Simple SE (no REP-105) and Smoother SE (recommended). |
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.
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.
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.
MOLA_LIDAR_TOPIC=__LIDAR_TOPIC__ \
MOLA_TF_BASE_LINK=__BASE_LINK__ \
mola-lo-gui-rosbag2 __BAG_PATH__
MOLA_DESKEW_METHOD=MotionCompensationMethod::IMU \ MOLA_LO_INITIAL_LOCALIZATION_METHOD=InitLocalization::PitchAndRollFromIMU \ 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.
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 |
|---|---|
|
The bag/driver is not publishing a |
LO starts but |
Forgot to set |
Smoother set, but |
REP-105 is incompatible with the smoother. Set
|
Namespaced bag silently ignored on |
Before |
Smoother converges slowly to geo-reference |
The vehicle must move non-trivially for GNSS factors to constrain
|