Published in IEEE RA-L --- pdf.
1) Install prerequisities (mrs_lib
, PCL
):
curl https://ctu-mrs.github.io/ppa-stable/add_ppa.sh | bash
apt-get install ros-noetic-mrs-lib ros-noetic-pcl-ros
2) Clone and build via catkin
cd <ROS1_WORKSPACE>/src
git clone git@github.com:ctu-mrs/RMS.git
catkin build
1) Launch as nodelet:
roslaunch rms rms_nodelet.launch NS:=<NAMESPACE> points_in:=<POINTS IN TOPIC> points_out:=<POINTS OUT TOPIC>
2) Use as library in your code:
rms
among dependencies in CMakeLists.txt
and package.xml
and include the <rms/rms.h>
header file#include <rms/rms.h>
...
// Initialize
ros::NodeHandle nh;
mrs_lib::ParamLoader param_loader(nh, "RMS");
RMS rms = RMS(param_loader);
...
// Use
sensor_msgs::PointCloud2::Ptr msg = ...;
rms->sample(msg); // 'msg' now contains sampled data
RMSNodelet
implemented in src/rms_nodelet.cppTo complement the in-paper experiments, we offer comparison on the MulRan dataset by plugging its 3D LiDAR (Ouster OS1-64) data to the KISS-ICP odometry. For ROS Noetic, you may follow this workflow:
1) Click here to download the Sejong01
sequence rosbag (beware: 56 GB).
2) Install RMS (see Installation
above).
3) Clone, compile, and source our KISS-ICP fork (minor changes made for ROS Noetic and launching).
cd ~/ROS1_WORKSPACE/src
git clone git@github.com:petrapa6/kiss-icp.git
cd kiss_icp
git checkout noetic
catkin build --this
source ~/ROS1_WORKSPACE/devel/setup.sh
4) Launch as:
roslaunch kiss_icp odometry.launch bagfile:=<PATH TO ROSBAG> topic:=/mulran/velo/pointclouds use_RMS:=[true | false]
Results for the Sejong01
experiment here.
APE of the experiment (voxelization in blue, RMS in orange):
@article{petracek2024rms,
author = {Petracek, Pavel and Alexis, Kostas and Saska, Martin},
title = {{RMS: Redundancy-Minimizing Point Cloud Sampling for Real-Time Pose Estimation}},
journal = {IEEE Robotics and Automation Letters},
year = {2024},
volume = {9},
number = {6},
pages = {5230--5237},
doi = {10.1109/LRA.2024.3389820}
}
This work was supported