Building a Mesh Map With GLIM
This guide will teach you how to use the GLIM SLAM software to build mesh maps for use with MeshNav (the mesh can of course also be used for other applications).
Recording Data
The first step is to record data in your environment. Since GLIM is a range-based mapping framework your robot needs to feature some sort of range sensor, for example a 3D LiDAR or an RGB-D camera. You can reference GLIM's Sensor-setup-guide for more information on recommended sensors. GLIM expects to receive your data either via ROS2 topics or to read directly from a ROS2 bag file.
I recommend to first record data to a bag file for better reproducibility and then run GLIM afterwards.
Use the following command to start the recording and make sure to replace the <> parameters with the paths to your topics.
ros2 bag record -s mcap --topics </pointcloud2/topic> </imu/topic>
CTRL-C.
Great! 🎉
Now copy the recorded bag file to the device you want to continue on.
Environment Setup
The next step is to setup your environment with the tools necessary to continue. First install GLIM by following their installation instructions. The easiest and fastest way is to install using the PPA method. Then install GLIM for ROS (I recommend the CUDA version if you have a compatible system).
Next create a new colcon workspace to build the necessary glim_scan_saver extension and the slam_to_mesh mesh generation tool:
mkdir -p mesh_ws/src
cd mesh_ws/src
# slam_to_mesh tool
git clone https://github.com/JustusBraun/slam_to_mesh.git
# Plugin to export undeskewed point clouds from GLIM
git clone https://github.com/JustusBraun/glim_scan_saver_ext.git
slam_to_mesh tool uses the LVR2 C++ library in the background.
If you are using Ubuntu 24 you can download a prebuild .deb archive from the releases page and install using apt:
apt install ./path/to/archive
git clone https://github.com/uos/lvr2.git
Now you can build your workspace:
cd ..
colcon build --cmake-args " -DCMAKE_BUILD_TYPE=Release"
Running GLIM SLAM
Configure GLIM
Before you can run GLIM with your dataset you need to adjust the configuration to reflect your setup.
First go to the root of your workspace and create a copy of GLIM's config directory:
cp -r /opt/ros/$ROS_DISTRO/share/glim/config/ .
Then follow the steps outlined in the Getting Started section of GLIM's documentation to adjust your configuration files.
The imu_topic and points_topic in the config_ros.json file tell GLIM which topics to read the IMU and LiDAR data from.
Set them to the topics you recorded in the first section.
You also need to add the glim_scan_saver_ext.so extension model to the extension_modules list to ensure that GLIM exports the individual pointclouds for us to use later.
Enabling the glim_scan_saver extension module
"glim_ros": {
...
"keep_raw_points": true // SET THIS TO TRUE IF YOU WANT FULL RESOLUTION LIDAR SCANS
...
// Extension modules
"extension_modules": [
"libmemory_monitor.so",
"libstandard_viewer.so",
"librviz_viewer.so",
"libglim_scan_saver_ext.so" // THIS IS THE IMPORTANT LINE
],
...
}
To fuse the IMU and pointcloud data GLIM needs to know the transformation between the IMU and range sensor coordinate systems.
The transform must be written to the T_lidar_imu parameter in the config_sensors.json file.
You should read GLIM's documentation page on parameters
to tune the configuration to get the best mapping results with your sensor setup.
Run the SLAM
Now that configuration is complete you can run GLIM on your dataset.
I will use the downsampled example bag file provided on GLIM's Getting Started page.
Run GLIM with your custom configuration, make sure to replace the <> parameter with the path to your bag file.
ros2 run glim_ros glim_rosbag <path/to/your/bagfile> --ros-args -p config_path:=$(realpath config/)
After GLIM is done processing your bag file you can close the window and the resulting map will be saved to /tmp/dump.
You can now optionally use the offline_viewer provided in the glim_ros package to manually add loop-closures and optimize the map.
When you are done editing your map, use the File menu to save your map to a folder of your choice.
If you do this you need to manually copy the deskewed_scans/ directory from /tmp/dump/ to the new map directory.
Generating the Mesh Map
Now we can use our exported scans and the trajectory generated by GLIM to create a triangle mesh map.
For this now use the slam_to_mesh tool with the following command and replace the paths to the traj_lidar.txt file and deskewed_scans directory with the paths to your results:
slam_to_mesh --poses /tmp/dump/traj_lidar.txt --poses-filetype-hint tum --scans /tmp/dump/deskewed_scans/ --displacement 0.3 1.0
The --displacement 0.3 1.0 flag reduces the number of scans processed by only adding a scan when the robot moved 0.3 meters or changed orientation by 1.0 radian.
This reduces the necessary computation workload and can lead to reduced artifacts in the mesh from moving objects in the point clouds.
The mesh generated from the example dataset looks as follows:

The mesh can then be further processed with tools like MeshLab to remove artifacts and reduce the number of faces. For more information on mesh post-processing take a look at the Tutorials page.