LiDAR odometry

MOLA LiDAR odometry (MOLA-LO) is the main MOLA component for 3D and 2D LiDAR odometry and localization. It is designed to provide accurate and robust motion tracking, with a default configuration provided to work out of the box for you without parameter tuning: it works for 16 to 128 ring LiDARs, indoors or outdoors, with motion profiles ranging from hand-held, slow wheeled or quadruped robots, to fast vehicles on highways.

This page explains the role of this component in the MOLA ecosystem, how to deal with generated maps, and gives a glimpse into its internal theoretical design.

Note

After installing and getting familiar with the core ideas, you can jump into running some demos with the provided GUI applications, the CLI interface, or learn how to build a map from your own ROS 2 bag dataset.


Role within the MOLA ecosystem

At a conceptual level, an odometry module takes raw sensory data as input and outputs an estimated trajectory of the sensor or vehicle.

By picking a subset of the input raw data and pairing them with the corresponding pose at which it was sensed, we can build a sparse “graph” of tuples “(Observation, pose)”. We dub such data structure view-based map or simple-map.

_images/odometry_inputs_outputs.png

Role of an “odometry” module (Figure adapted from [BC24]).

Simple-maps can then be used as input to mp2p_icp applications for analysis, filtering, or creation of arbitrarily-complex metric maps of different kinds, like point clouds, voxel maps, 2D grid maps, etc. Refer to Basics. Most often, users might be interested in analyzing generated simple-maps with sm-cli, in generating metric maps using sm2mm, and in visualizing those maps with mm-viewer.

MOLA-LO is provided as the C++ class mola::LidarOdometry, which implements the mola::ExecutableBase interface so it is able to communicate with other input and output MOLA modules:

imgs/mola_system_scheme.png

Scheme of MOLA launcher with input, output, and a LO module (modified from [BC19a]).

As shown in the figure above, once encapsulated within a MOLA application container, the LO module can take input sensory data from other MOLA input modules, and the live LO output can optionally be either visualized in the mola_viz GUI, and/or published to an external ROS 2 system.

Therefore, the most flexible way to use MOLA LO is by means of different combinations of input and output modules, depending on what are the desired input data sources, and that is defined by means of mola-cli launch files.

mola-cli is a standalone command line interface (CLI) program provided by the mola_launcher package. Predefined launch files are provided for common tasks like running MOLA-LO on well-known public datasets or from rosbags. However, to make thinks simpler, a set of executable scripts are provided to make launching them easier: MOLA GUI apps.

Apart of this way to run MOLA-LO, two additional ways are provided for convenience:

  • mola-lidar-odometry-cli: this standalone program is provided as a way to process a given dataset as fast as possible, without any interaction with GUIs, message subscription or reception, etc. It is also great for scripting and automating SLAM pipelines from raw datasets or rosbags.

  • ROS 2 integration: ROS 2 launch files are also provided for easier integration for real-time odometry and mapping.


Internal architecture

Internally, MOLA LO is based on mp2p_icp filtering and ICP pipelines:

imgs/mola_lidar_odometry_architecture.png

Block diagram of the MOLA-LO module (Figure adapted from [BC24]).

Most blocks in the diagram above can be redefined without coding, just changing the MOLA-LO pipeline configuration YAML file. Refer to the MOLA LO paper for further details.

Note

You cannot debug what you cannot see. A powerful GUI named icp-log-viewer is provided to carefully inspect the internals of ICP optimization iterations.

How to cite it

The mola_lidar_odometry system was presented in [BC24]: