Paper • Contact Us
Kinematic-ICP is a LiDAR odometry approach that explicitly incorporates the kinematic constraints of mobile robots into the classic point-to-point ICP algorithm.
Our system operates on ROS2, supporting ROS Humble, Iron, and Jazzy. To build and run Kinematic-ICP, follow these steps:
-
Clone the Repository:
cd <your_ros_workspace>/src git clone https://github.com/PRBonn/kinematic-icp cd ..
-
Ensure all Dependencies are Installed:
rosdep install --from-paths src --ignore-src -r -y
-
Build the Workspace:
colcon build
-
Source the Setup Script:
source ./install/setup.bash
Kinematic ICP can enhance existing odometry using a 3D LiDAR. However, there are specific requirements regarding motion and transformations since we use a kinematic motion model for the pose correction. Below are the key requirements:
-
Planar Movement: The robot is expected to move primarily on a planar surface.
-
Existing Odometry: An existing odometry source must be provided, such as the platform's wheel odometry. In the ROS ecosystem, this means that another node must publish the
tf
transformation betweenbase_link
andodom
. (Note: The names may vary and can be adjusted in the pipeline parameters.) -
Static Transform for LiDAR: To utilize the platform's motion model effectively, the system needs to compute the pose in
base_link
. Therefore, a statictf
transform betweenbase_link
and the LiDAR frame (extrinsic calibration) is required. If this calibration is significantly inaccurate, it may compromise system performance.
Finally, Kinematic ICP will publish a new tf
transformation between base_link
and odom_lidar
.
This system offers two entry points for deployment, depending on your use case: one for real-time operation and one for offline processing.
Use the online_node
to run the system on a robotics platform. The only required parameter is the lidar_topic. You can start the system using the following command:
ros2 launch kinematic_icp online_node.launch.py lidar_topic:=<TOPIC>
To enable simultaneous visualization through RViz, use the visualize
flag set to true
:
ros2 launch kinematic_icp online_node.launch.py lidar_topic:=<TOPIC> visualize:=true
For post-processing and analysis, the offline_node
processes a ROS bag file at CPU speed, ensuring no frames are dropped. This mode is ideal for reviewing trajectory results, debugging, and speeding up bag file processing. You can launch the offline node with the following command:
ros2 launch kinematic_icp offline_node.launch.py lidar_topic:=<TOPIC> bag_filename:=<ROSBAG>
RViz can also be used in this mode by setting the visualize
flag to true
. Additionally, the system will output a file in TUM format containing the estimated poses, named <ROSBAG>_kinematic_poses_tum.txt. This file is saved in the same directory as the ROS bag file by default.
To specify a custom directory for the output file, use the output_dir
parameter:
ros2 launch kinematic_icp offline_node.launch.py lidar_topic:=<TOPIC> bag_filename:=<ROSBAG> output_dir:=<OUTPUT_DIRECTORY>
If you use this library for any academic work, please cite our original paper.
@article{kissteam2024arxiv,
author = {Guadagnino ,Tiziano and Mersch, Benedikt and Vizzo, Ignacio and Gupta, Saurabh and Malladi, Meher V.R. and Lobefaro, Luca and Doisy, Guillaume and Stachniss, Cyrill},
title = {{Kinematic-ICP: Enhancing LiDAR Odometry with Kinematic Constraints for Wheeled Mobile Robots Moving on Planar Surfaces}},
journal = arXiv Preprint,
year = {2024},
volume = {arXiv:2410.10277},
url = {https://arxiv.org/pdf/2410.10277},
}