โโโโโโ โโโโโโ โโโโโโโ โโโโโโ โโโโโโ โโโโโ โโ โโ โโโโโโ
โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ
โโโโโโ โโ โโ โโโโโโโ โโโโโ โโ โโโโโโโ โโ โโ โโโโโโ
โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ โโ
โโ โโ โโโโโโ โโโโโโโ โโโโโโโ โโโโโโ โโ โโ โโโโโโโ โโ โโโโโโ
โโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโ
Multi-Sensor Calibration Tool for ROS 2
๐ฏ Precise โข ๐ Fast โข ๐ง Interactive
>>> pip install ros2-calib <<<
โโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโโ
ros2_calib is a multi-sensor calibration tool for ROS 2 that provides intuitive graphical interfaces for performing precise extrinsic calibration between different sensor types. The tool supports both LiDAR-to-Camera and LiDAR-to-LiDAR calibration workflows. Built with PySide6, it operates on recorded rosbag data without requiring a live ROS 2 environment. It supports reading /tf_static
transforms from rosbags and allows users to quickly calibrate and export the resulting transformation directly into URDF format. Although it is a manual calibration tool, we made the expierence that it is faster to use than a target-based calibration method and is more accurate than automatic methods.
- ๐ฏ Interactive Calibration: Point-and-click interface for 2D-3D correspondences
- ๐ Real-time Visualization: Live point cloud projection with adjustable parameters
- ๐ง Smart Algorithms: RANSAC-based PnP solver with Scipy least-squares refinement
- ๐งน Point Cloud Cleaning: Advanced occlusion removal using the RePLAy algorithm
- โจ๏ธ Keyboard Shortcuts: ESC to cancel, Backspace to delete, Enter to confirm
- ๐ฎ 3D Interactive Interface: Open3D-based point cloud visualization
- ๐ง Manual Adjustment: Precise transformation controls with step-size configuration
- ๐ค Automatic Registration: Point-to-point and point-to-plane ICP algorithms
- ๐๏ธ Dual Visualization: Independent control over source and target point cloud visibility
- ๐ Calibration View: Live transformation matrix updates and registration metrics
- ๐ณ TF Tree Integration: Visual transform chain management and URDF export
- ๐พ Offline Processing: Works with .mcap rosbag files - no live ROS 2 required
- ๐จ Easy-to-Use UI: Organized sections with responsive design
- ๐ฑ Multi-Calibration Types: Seamless switching between different calibration workflows
- Tested with Python 3.12.3 and Ubuntu 24.04
- Compatible rosbag files in
.mcap
format
Your rosbag file (.mcap
format, tested with Jazzy and Humble) should contain the following topics:
For LiDAR-to-Camera Calibration:
- Camera topics:
/camera/image_raw
or/camera/image_rect
sensor_msgs/Image
sensor_msgs/CompressedImage
- Camera info:
/camera/camera_info
(sensor_msgs/CameraInfo) - LiDAR topics:
/lidar/points
or similar (sensor_msgs/PointCloud2)
For LiDAR-to-LiDAR Calibration:
- Source LiDAR topic:
/lidar1/points
(sensor_msgs/PointCloud2) - Target LiDAR topic:
/lidar2/points
(sensor_msgs/PointCloud2)
Optional but Recommended:
- Transform topics:
/tf_static
(tf2_msgs/TFMessage)- Contains static transformations between sensor frames
- If not available, you'll need to manually specify initial transforms
Furthermore, the metadata file (metadata.yaml) must be present in the same
directory as the .mcap
file (usually automatically created by ROS 2 when recording).
pip install ros2-calib
# Clone the repository
git clone https://github.com/ika-rwth-aachen/ros2_calib.git
cd ros2_calib
# Create a virtual environment
python -m venv .venv
source ./venv/bin/activate
# Install in development mode
python -m pip install .
-
Launch the application:
ros2_calib
-
Select calibration type: Choose between LiDAR-to-Camera or LiDAR-to-LiDAR calibration
-
Load your rosbag: Click "Load Rosbag" and select your .mcap file
-
Select topics: Choose your sensor topics based on calibration type
-
Set initial transform: Configure the transformation between sensor frames
-
Perform calibration:
- LiDAR-to-Camera: Select frame, create 2D-3D correspondences, run calibration
- LiDAR-to-LiDAR: Use interactive 3D interface with manual adjustment and/or ICP
-
Export results: View transformation chains and export URDF-ready transforms
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ
โ Select Calib โ -> โ Load Rosbag โ -> โ Select Topics โ -> โ Set Initial TF โ
โ Type (L2C/L2L) โ โ (.mcap file) โ โ (sensors) โ โ (manual/auto) โ
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ
โ
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โ
โ Frame Selection โ -> โ LiDAR2Camera โ <----------โ
โ (L2C only) โ โ Calibration โ
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ
โ
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โ
โ Export URDF โ <- โ Transform Chain โ <- โ View Results & โ <----------โ
โ Transform โ โ Visualization โ โ TF Integration โ โ
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โ
โฒ โ
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ โ
โ LiDAR2LiDAR โ -> โ โ <----------โ
โ Calibration O3D โ โ โ
โโโโโโโโโโโโโโโโโโโ โโโโโโโโโโโโโโโโโโโ
- main.py: Application entry point with PySide6 QApplication setup
- main_window.py: Multi-view interface with stacked widget navigation and calibration type selection
- calibration_widget.py: Interactive LiDAR-to-Camera calibration view with 2D/3D visualization
- lidar2lidar_o3d_widget.py: Open3D-based LiDAR-to-LiDAR calibration interface
- frame_selection_widget.py: Frame selection interface for synchronized sensor data
- calibration.py: Core mathematical algorithms using OpenCV and Scipy
- bag_handler.py: Rosbag processing and message extraction utilities
- ros_utils.py: Mock ROS 2 message types for offline operation
- tf_graph_widget.py: Interactive TF tree visualization using NodeGraphQt
- lidar_cleaner.py: Point cloud cleaning based on RePLAy Algorithm (ECCV 2024)
Two-Stage Calibration Process:
- Initial Estimation: OpenCV's
solvePnPRansac
for robust pose estimation - Refinement: Scipy's
least_squares
optimization minimizing reprojection error - Quality Assessment: Automatic outlier detection and correspondence validation
Point Cloud Processing:
- Occlusion Removal: RePLAy algorithm removes projective artifacts
- Intensity-based Coloring: Configurable colormap visualization
- Real-time Projection: Live updates during manual adjustments
Interactive 3D Calibration:
- Manual Adjustment: Precise translation and rotation controls with configurable step sizes
- Automatic Registration: Point-to-point and point-to-plane ICP algorithms
- Real-time Visualization: Open3D-based 3D rendering with dual point cloud display
- Quality Metrics: Live fitness and RMSE feedback during ICP registration
The tool automatically handles:
- Message Format Detection: Supports Image and CompressedImage types
- Coordinate Frame Resolution: TF tree parsing and path finding
- Camera Model Integration: Full camera info and distortion support
# Run linter
ruff check
# Format code
ruff format
We welcome contributions! Please see our Contributing Guidelines for details.
- Fork the repository
- Create your feature branch (
git checkout -b feature/AmazingFeature
) - Commit your changes (
git commit -m 'Add some AmazingFeature'
) - Push to the branch (
git push origin feature/AmazingFeature
) - Open a Pull Request
- "No topics found": Ensure your .mcap file contains the required sensor topics
- "TF tree empty": Check that your rosbag includes transform messages
- Calibration fails: Verify you have at least 4 correspondence points
- Open an issue for bug reports
This project is licensed under the MIT License - see the LICENSE file for details.
If you use this tool in your research, please cite:
@software{ros2_calib,
title={ros2\_calib: Multi-Sensor Calibration Tool for ROS 2},
author={Till Beemelmanns},
year={2025},
url={https://github.com/ika-rwth-aachen/ros2_calib}
}
We integrate the RePLAy algorithm for removing projective LiDAR artifacts:
@inproceedings{zhu2024replay,
title={RePLAy: Remove Projective LiDAR Depthmap Artifacts via Exploiting Epipolar Geometry},
author={Zhu, Shengjie and Ganesan, Girish Chandar and Kumar, Abhinav and Liu, Xiaoming},
booktitle={ECCV},
year={2024},
}
- PySide6 - Cross-platform GUI toolkit
- OpenCV - Computer vision algorithms
- NumPy - Numerical computing
- SciPy - Scientific computing
- Open3D - 3D visualization and point cloud processing
- NodeGraphQt - Node graph visualization
- rosbags - Pure Python rosbag processing
Important
This repository is open-sourced and maintained by the Institute for Automotive Engineering (ika) at RWTH Aachen University.
We cover a wide variety of research topics within our Vehicle Intelligence & Automated Driving domain.
If you would like to learn more about how we can support your automated driving or robotics efforts, feel free to reach out to us!
๐ง [email protected]