MOLA-LO: Build a map and then localize
This tutorial will show you how to build a map using MOLA-LO, then save the map to disk, and how to load that map to use the LO localization mode.
This video shows the steps in the tutorial:
Prerequisites: MOLA installation
This tutorial requires the installation of these packages: mola_lidar_odometry
, mola_viz
, mvsim
.
The MVSim simulator is used as an example, but a live robot or LiDAR sensor can be used instead.
Following the default installation instructions is enough.
1. Create a map and save it
Open three terminals, and run these commands in each one:
Launch the simulator or, if you are on a real robot, make sure to have the system up and LiDAR data coming out:
ros2 launch mvsim demo_warehouse.launch.py \
do_fake_localization:=False \
use_rviz:=False
In terminal #2, launch MOLA-LO, enabling saving the map in simple-map format:
MOLA_GENERATE_SIMPLEMAP=true \
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
lidar_topic_name:=/lidar1_points
Note
Remember replacing /lidar1_points
with your actual PointCloud2 topic with raw LiDAR data.
Next, move the robot around.
In the simulator, you can click on the MVSim GUI and use keys a/d``+ ``s/w
to drive around,
or use a gamepad to teleoperate it.
Once the map looks OK in the mola_viz GUI, let’s save it. In terminal #3, run:
ros2 service call /map_save mola_msgs/srv/MapSave "map_path: '/tmp/my_map'"
Watch the response to check that success
is true
. Your map is now
stored as file(s) named /tmp/my_map*
.
2. Optional: Build down-sampled, globally consistent map
The map saved in the former step comprises two files:
A key-frame (view-based) map (
*.simplemap
): a set of SE(3) poses annotated with metadata and raw sensor observations.The metric local map used by the specific LO pipeline; e.g. for the
lidar3d-default
pipeline, it is a voxel-based point cloud of the current area, which may include an area of more than 100 meters around the latest robot pose, but if you mapped a larger area, it would be an incomplete representation of the whole map.
The key-frame map is the more versatile one since it allows for running further map filtering, loop closure, downsampling, etc. while the metric local map is just what LO needs for local alignment of incoming scans.
If your map is “small” in comparison to the sensor range (e.g. a few hundreds of meters length for 3D LiDARs outdoors), the local map would contain the whole scenario and you are good to go with it as is, so you can skip to next section.
Visually inspect the generated *.mm
file
You can check how the final metric map looks like using:
mm-viewer -l libmola_metric_maps.so /path/to/your/map.mm
Where the -l
flag is used to load the additional metric map classes defined in mola_metric_maps
, and
used in the lidar3d-default
pipeline.
However, if the map is much larger, you need to generate a new local metric map that includes the whole area where the robot needs to operate so it can localize correctly.
How to generate a new local metric map
Discard the local metric map file (*.mm
) and let’s start processing the key-frame map (*.simplemap
).
First, if your map is so large that it needs to close loops (e.g. several building blocks, a large part of a campus, etc.)
the loop closure module would be needed to post-process the *.simplemap
file.
Next, either if you already have closed loops or you do not need them, follow these instructions, taking into account that there must exist an output metric map layer named as expected by the LO pipeline (e.g. lidar3d-default).
TO-DO: Write complete example files and commands!
3. Load a prebuilt map in localization-only mode
Note
Make sure of closing the former instance of MOLA-LO in terminal #2 used to build the map before going on with this part.
Again, we will use three terminals:
You can keep the former instance of the MVSim simulator running from the former step, or launch it again and move to a different pose, it is up to you!
Let’s launch MOLA-LO in non-mapping (localization only) mode with:
MOLA_MAPPING_ENABLED=false \
MOLA_START_ACTIVE=false \
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
lidar_topic_name:=/lidar1_points
Note
Remember replacing /lidar1_points
with your actual PointCloud2 topic with raw LiDAR data.
Explanation:
MOLA_MAPPING_ENABLED=false
disables map updates, so the loaded map will remain static.MOLA_START_ACTIVE=false
is recommended so LO does not attempt to match incoming sensor data until a relocalization method or rough initial localization is set (see next section below).
Next, in terminal #3, let’s order MOLA-LO to load our former map from disk:
ros2 service call /map_load mola_msgs/srv/MapLoad "map_path: '/tmp/my_map'"
If you want to load a post-processed metric map (just the *.mm
file), use the full
path to the map file, without the extension. Read more on how to generate metric maps
from key-frame maps (*.simplemap
) here.
Note that it is also possible to directly launch MOLA-LO with a map loaded from disk
from the beginning, but it implies passing one or both maps (*.mm
and *.simplemap
)
by command line as environment variables.
Directly loading the map from MOLA-LO start up
Instead of first invoking MOLA-LO and then requesting to load the map via a ROS 2 service, it is possible to instruct MOLA-LO to start loading the map straightaway as it starts up by specifying the path to both map files, instead of the map prefix used in the ROS 2 service:
MOLA_MAPPING_ENABLED=false \
MOLA_START_ACTIVE=false \
MOLA_LOAD_MM=/tmp/my_map.mm \
MOLA_LOAD_SM=/tmp/my_map.simplemap \
ros2 launch mola_lidar_odometry ros2-lidar-odometry.launch.py \
lidar_topic_name:=/lidar1_points
Of course, the ROS 2 service offers a greater flexibility to switch
between maps at run-time. You can drop MOLA_LOAD_SM
if you do not need
to extend the map (multi-session mapping).
4. Invoke relocalization
As explained here, initial localization is a hard problem on its own and can be handled in different ways.
Here we will show the common situation of wanting to re-localize the robot in a prebuilt map, given we already know a rough estimation of its actual pose, including the orientation. Check out all the details about requesting relocalization via ROS 2 API.
Just use the RViz2’s button 2D pose estimate
or FoxGlove’s “Pose Estimate”
to pick a pose and MOLA-LO will try to re-localize the vehicle in the given area.
There is also a ROS 2 service for programmatically request a relocalization, and obtaining feedback about whether the request was received or not by a running MOLA module:
Service default name:
/relocalize_near_pose
Service interface: mola_msgs::srv::RelocalizeNearPose
Once MOLA-LO knows how to handle initialization, we can activate it, either from the GUI (click the “active” checkbox) or via this command (see all other similar commands):
# active: true ros2 service call /mola_runtime_param_set mola_msgs/srv/MolaRuntimeParamSet \ "{parameters: \"mola::LidarOdometry:lidar_odom:\n active: true\n\"}"
Then, the module will start to produce localization estimates via /tf
, Odometry
messages,
together with a localization quality metric (see all published topics).