ROS 2 package providing a C++ bridge between MRPT (Mobile Robot Programming Toolkit) and the ROS 2 ecosystem.
It enables seamless conversion between MRPT and ROS message types for maps, sensor data, poses, images, and more.
| Distro | Build dev | Stable sync | 
|---|---|---|
| ROS 2 Humble (u22.04) | ||
| ROS 2 Jazzy (u24.04) | ||
| ROS 2 Kilted (u24.04) | ||
| ROS 2 Rolling (u24.04) | 
| Package | ROS 2 Humble BinBuild | ROS 2 Jazzy BinBuild | ROS 2 Kilted BinBuild | ROS 2 Rolling BinBuild | 
|---|---|---|---|---|
| mrpt_libros_bridge | ||||
| rosbag2rawlog | 
The mrpt_libros_bridge library provides bidirectional converters between MRPT data structures and ROS 2 message types.
It simplifies integrating MRPT-based algorithms (e.g. SLAM, perception, mapping) with ROS 2 nodes.
| Package | Description | 
|---|---|
| mrpt_libros_bridge | Core C++ library bridging MRPT data types with ROS 2 messages (poses, maps, sensor data, etc.). | 
| rosbag2rawlog | Command-line tool to convert ROS 2 .bagfiles into MRPT.rawlogdatasets. | 
- Convert between MRPT and ROS 2 types:
- geometry_msgs::Pose⇄- mrpt::poses::CPose3D
- sensor_msgs::LaserScan⇄- mrpt::obs::CObservation2DRangeScan
- sensor_msgs::Image⇄- mrpt::img::CImage
- sensor_msgs::Imu,- NavSatFix,- PointCloud2, etc.
 
- Compatible with ROS 2 distros: Humble, Jazzy, Kilted, and Rolling.
- Written in C++17, using ament_cmake.
- Includes unit tests for conversions and message integrity.
Install from ROS build servers with:
sudo apt install ros-${ROS_DISTRO}-rosbag2rawlog ros-${ROS_DISTRO}-mrpt-ros-bridgeIf needed to build from source code, do this:
# Source your ROS 2 environment
source /opt/ros/jazzy/setup.bash
# Clone dependencies
mkdir -p ~/ros2_ws/src
cd ~/ros2_ws/src
git clone https://github.com/MRPT/mrpt_ros_bridge.git
# Install dependencies
rosdep install --from-paths . --ignore-src -r -y
# Build
cd ~/ros2_ws
colcon build --symlink-install#include <mrpt_libros_bridge/pose.h>
#include <geometry_msgs/msg/pose.hpp>
#include <mrpt/poses/CPose3D.h>
geometry_msgs::msg::Pose ros_pose;
mrpt::poses::CPose3D mrpt_pose(1.0, 2.0, 0.0, 0.0, 0.0, 1.57);
mrpt::ros2bridge::toROS(mrpt_pose, ros_pose);Refer to the dataset conversions page on the MOLA project website.
Run unit tests with:
colcon test --packages-select mrpt_libros_bridge
colcon test-result --verboseAuto-generated API docs (Doxygen):
cd mrpt_ros_bridge
doxygen doc/rosdoc.yamlFurther information about MRPT: 👉 https://www.mrpt.org
This package is distributed under the BSD License.
José-Luis Blanco-Claraco 📧 [email protected] 🔗 https://github.com/MRPT