Localization

Localization differs from SLAM in that the map or world model is not updated while it is being used to keep a robot or vehicle accurately localized within a pre-mapped environment [BC24].

Once a map is built, the result is a simple-map and/or a metric map (*.mm), optionally georeferenced. This map can then be used to enable autonomous navigation (“Go from A to B”), for which localization is a fundamental requirement (“Where is B?”).

At present, this framework provides two fundamentally different algorithms for localization:

  • Based on optimization, by using the LiDAR odometry module, without map updates.

  • Based on particle filtering, by using any combination of metric maps (grid maps, point clouds, etc.) and wheels odometry.




1. Common aspects

Independently of the localization algorithm, the problem of finding the rough localization of the vehicle at start up is quite special due to the large initial uncertainty.

MOLA provides a specific module for this task (mola-relocalization) which can be used by all position tracking algorithms to solve the initial relocalization problem.

Also, implementations below offer two ways to specify the initial guess about the robot pose in the environment:

  • From a pose with a covariance, which needs to be given manually either from a ROS topic, RViz/FoxGlove, or a parameter; and

  • From GNSS readings (“Automatic re-localization via GPS”). This version requires georeferenced metric maps, naturally.



2. Localization with LiDAR odometry

Write me!



3. Localization with particle filtering

To localize with a particle filter (PF) you will need:

  1. A metric map (the .mm file) of the environment. Built as described in: Tutorial: build a map.

  2. To publish that map using mrpt_map_server.

  3. Launch mrpt_pf_localization and configure it to read from wheels odometry (if they exist), the input sensors (e.g. LiDAR), GPS (GNSS) if present. This node will subscribe to the published metric map and use the sensors to publish updates on the robot pose in the map frame.

Note

Do NOT set the raw LiDAR pointcloud as input for the PF. It is just too large and it must be subsampled first. We can use mrpt_pointcloud_pipeline for such task, as can be seen in the tutorial below.

3.1. Tutorial

A complete demonstration has been put together on: https://github.com/MOLAorg/mola_warehouse_pf_tutorial

Key points of this tutorial:

How to run the tutorial

Clone the tutorial package (which already includes a prebuilt .mm), make sure of having all dependencies, build and run it:

cd ~/ros2_ws/src
git clone https://github.com/MOLAorg/mola_warehouse_pf_tutorial.git

cd ~/ros2_ws
rosdep install --from-paths src --ignore-src -r -y

colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo
. install/setup.bash

ros2 launch mola_warehouse_pf_tutorial tutorial_launch.py