Skip to content

Commit 39cfb3b

Browse files
committed
Updated README and added documentation
1 parent 3dcdf0f commit 39cfb3b

30 files changed

+1860
-1
lines changed

.gitignore

+3
Original file line numberDiff line numberDiff line change
@@ -117,7 +117,10 @@ CATKIN_IGNORE
117117
Doxyfile
118118
/doc/*
119119
!/doc/assets
120+
!/doc/user_docs
120121
!/doc/*.md
122+
!/doc/*.yml
123+
121124

122125
# thirdparty
123126
thirdparty/*

CHANGELOG.rst

+1
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@ Forthcoming
66
------------------
77

88
Features:
9+
910
* Added Documentation.
1011
* Added Node multisensor_calibration with Calibration Configurator
1112
* Added Node extrinsic_camera_lidar_calibration

README.md

+12-1
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,17 @@ It provides a variety of methods and applications to calibrate complex multi-sen
99
- <b>Extrinsic LiDAR-Reference Calibration</b>, and
1010
- <b>Extrinsic LiDAR-Vehicle Calibration</b> (prototype).
1111

12+
The software is licensed under the new [BSD 3-Clause license](license.md). If you use this project for your research, please cite:
13+
14+
```text
15+
TODO: add bibtex
16+
```
17+
18+
The latest source code is available on [GitHub](https://github.com/FraunhoferIOSB/multisensor_calibration).
19+
Furthermore, the `multisensor_calibration` is also released as an official package for ROS 2 and can be installed with apt-get.
20+
Since ROS 1 is soon end-of-life, there will be no official release for ROS 1.
21+
However, there is a version of the source code available for ROS 1 under the branch [noetic](https://github.com/FraunhoferIOSB/camera_aravis2/tree/noetic).
22+
1223

1324
**Acknowledgement**: This software was developed as part of the projects [AKIT-PRO](https://a-kit.de) (grant no. 13N15673) and [ROBDEKON – Robotic Systems for Decontamination in Hazardous Environments](https://robdekon.de/) (grant nos. 13N14674 and 13N16538), funded by the Federal Ministry of Education and Research (BMBF) under the German Federal Government’s Research for Civil Security program.
1425

@@ -27,7 +38,7 @@ It provides a variety of methods and applications to calibrate complex multi-sen
2738
- [Getting Started](#getting-started)
2839
- [Requirements](#requirements)
2940
- [Build](#build)
30-
- [Changlog](CHANGELOG.md)
41+
- [Changelog](CHANGELOG.md)
3142
- [Contributing](CONTRIBUTING.md)
3243
- [License](LICENSE)
3344

doc/mkdocs.yml

+32
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
site_name: Multi-Sensor Calibration
2+
3+
copyright: Copyright 2024 - 2025 Fraunhofer IOSB and contributors
4+
theme:
5+
name: readthedocs
6+
7+
site_dir: html
8+
docs_dir: user_docs
9+
10+
markdown_extensions:
11+
- admonition
12+
- attr_list
13+
- toc:
14+
toc_depth: 3
15+
permalink: true
16+
17+
repo_url: https://github.com/FraunhoferIOSB/multisensor_calibration
18+
repo_name: 'GitHub'
19+
edit_uri: https://github.com/FraunhoferIOSB/multisensor_calibration/docs/user_docs
20+
21+
extra_javascript:
22+
- js/tables.js
23+
- js/mathjax.js
24+
- js/tex-mml-chtml.js
25+
26+
plugins:
27+
- git-revision-date-localized
28+
- search
29+
- literate-nav:
30+
nav_file: SUMMARY.md
31+
extra:
32+
generator: false

doc/user_docs/SUMMARY.md

+11
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,11 @@
1+
2+
- [Installation](installation.md)
3+
- [Tutorial](tutorial.md)
4+
- [Calibration Target](calibration_target.md)
5+
- [Data Processing](data_processing.md)
6+
- [Workspace Handling](workspaces.md)
7+
- [Nodes and Nodelets](nodes_and_nodelets.md)
8+
- [Troubleshooting](troubleshooting.md)
9+
- [License](license.md)
10+
- [Changelog](https://github.com/FraunhoferIOSB/multisensor_calibration/blob/main/CHANGELOG.rst)
11+
- [Contributing](https://github.com/FraunhoferIOSB/multisensor_calibration/blob/main/CONTRIBUTING.md)
Loading
Loading
Binary file not shown.
Loading
Loading
Binary file not shown.
Loading
Loading
Binary file not shown.
Loading
Binary file not shown.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
[calibration]
2+
base_frame_id= ## (Optional) Enter base frame ID string with respect to which the calibration is to be calculated ##
3+
save_observations=true
4+
target_config_file=TargetWithCirclesAndAruco.yaml
5+
use_initial_guess=true
6+
7+
[camera]
8+
image_state= ## Enter integer representing image state. 0 = DISTORTED, 1 = UNDISTORTED, 2 = STEREO_RECTIFIED ##
9+
image_topic= ## Enter image topic string ##
10+
info_topic= ## Enter info topic string ##
11+
is_stereo_camera=true
12+
rect_suffix=_rect
13+
right_info_topic= ## Enter info topic string of right camera (if stereo camera) ##
14+
right_sensor_name= ## Enter name of right camera (if stereo camera) ##
15+
sensor_name= ## Enter name of camera which is to be calibrated ##
16+
17+
[lidar]
18+
cloud_topic= ## Enter cloud topic string ##
19+
sensor_name= ## Enter name of lidar ##
20+
21+
[misc]
22+
sync_queue_size=100
23+
use_exact_sync=false
24+
25+
[workspace]
26+
type=extrinsic-camera-lidar-calibration
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
[calibration]
2+
base_frame_id= ## (Optional) Enter base frame ID string with respect to which the calibration is to be calculated ##
3+
save_observations=true
4+
target_config_file=TargetWithCirclesAndAruco.yaml
5+
use_initial_guess=false
6+
7+
[camera]
8+
image_state= ## Enter integer representing image state. 0 = DISTORTED, 1 = UNDISTORTED, 2 = STEREO_RECTIFIED ##
9+
image_topic= ## Enter image topic string ##
10+
info_topic= ## Enter info topic string ##
11+
is_stereo_camera=true
12+
rect_suffix=_rect
13+
right_info_topic= ## Enter info topic string of right camera (if stereo camera) ##
14+
right_sensor_name= ## Enter name of right camera (if stereo camera) ##
15+
sensor_name= ## Enter name of camera which is to be calibrated ##
16+
17+
[reference]
18+
frame_id= ## Enter string of frame ID in which the reference data is provided ##
19+
name= ## Enter name of reference, e.g. 'reference' ##
20+
21+
[workspace]
22+
type=extrinsic-camera-reference-calibration
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,22 @@
1+
[calibration]
2+
align_ground_planes= ## Set to true, if ground planes are additionally to be aligned ##
3+
base_frame_id= ## (Optional) Enter base frame ID string with respect to which the calibration is to be calculated ##
4+
save_observations=true
5+
target_config_file=TargetWithCirclesAndAruco.yaml
6+
upright_frame_id= ## (Optional) Enter frame ID string of upright frame used to find ground plane ##
7+
use_initial_guess=true
8+
9+
[misc]
10+
sync_queue_size=100
11+
use_exact_sync=false
12+
13+
[reference_lidar]
14+
cloud_topic= ## Enter cloud topic string of reference lidar ##
15+
sensor_name= ## Enter name of reference lidar ##
16+
17+
[source_lidar]
18+
cloud_topic= ## Enter cloud topic string of source lidar ##
19+
sensor_name= ## Enter name of source lidar ##
20+
21+
[workspace]
22+
type=extrinsic-lidar-lidar-calibration
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
[calibration]
2+
base_frame_id= ## (Optional) Enter base frame ID string with respect to which the calibration is to be calculated ##
3+
save_observations=false
4+
target_config_file=TargetWithCirclesAndAruco.yaml
5+
use_initial_guess=false
6+
7+
[reference]
8+
frame_id= ## Enter string of frame ID in which the reference data is provided ##
9+
name= ## Enter name of reference, e.g. 'reference' ##
10+
11+
[source_lidar]
12+
cloud_topic= ## Enter cloud topic string of source lidar ##
13+
sensor_name= ## Enter name of source lidar ##
14+
15+
[workspace]
16+
type=extrinsic-lidar-reference-calibration
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
[robot]
2+
name= ## Enter robot name ##
3+
urdf_model_path= ## (OPTIONAL) Provide relative or absolute path to URDF file ###
4+
5+
[workspace]
6+
type=robot

doc/user_docs/calibration_target.md

+57
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,57 @@
1+
# Calibration Target
2+
3+
For extrinsic Multi-Sensor Calibration the toolbox was developed to use an asymmetric calibration target as depicted below.
4+
The asymmetry allows to detect a full 6-DOF pose of the target within the sensor data, reducing possible ambiguities in the correspondence search and making the calibration process more robust.
5+
6+
![](assets/images/extrinsic_calibration_target.png)
7+
*Figure 1: Picture of the asymmetric calibration target used for extrinsic calibration.*
8+
9+
The default calibration target used by 'multisensor_calibration' has the following properties:
10+
11+
- **Width:** 1.2m
12+
- **Height:** 0.8m
13+
14+
- Three **Circular Cutouts**
15+
- with a **Radius:** 0.12m
16+
- **located** plus-minus 0.15m in X-Y direction around the center.
17+
18+
- Four **ArUco Markers** from ```DICT_6X6_250```
19+
- with the **IDs:** 1, 2, 3, 4 (arranged clockwise, starting from top-left)
20+
- with an **Edge Length:** 0.18m
21+
- **located** plus-minus 0.05m in X-Y direction from the respective corner of the board
22+
23+
## Using a Custom Calibration Target
24+
25+
The Multi-Sensor Calibration the toolbox, however, allows to adjust the parameters of the calibration target by editing them within a yaml file: `<repository>/mutlisensor_calibration/cfg/TargetWithCirclesAndAruco.yaml`
26+
27+
```yaml
28+
%YAML:1.0
29+
board_width: 1.2 # width of board in meters
30+
board_height: 0.8 # height of board in meters
31+
marker_size: 0.18 # side length of aruco markers in meters
32+
marker_ids: # ids of marker used as a single column matrix
33+
rows: 4
34+
cols: 1
35+
dt: i
36+
data: [1, 2, 3, 4] # marker order goes clockwise, starting from top left of board
37+
marker_positions: # x,y marker positions (top-left) on board relative to center, stored row-by-row in meters. x: rightwards, y: upwards
38+
rows: 4
39+
cols: 2
40+
dt: f
41+
data: [-0.55, 0.35,
42+
0.37, 0.35,
43+
0.37, -0.17,
44+
-0.55, -0.17]
45+
cutouts: # Cutouts (id + parameters) stored as a single row matrix. x: rightwards, y: upwards
46+
rows: 1
47+
cols: 12
48+
dt: f
49+
data: [1, -0.15, 0.15, 0.12, # Circular cutout: (id: 1, parameters: {X,Y,Radius})
50+
1, 0.15, -0.15, 0.12,
51+
1, -0.15, -0.15, 0.12]
52+
min_marker_detection: 2 # minimum number of markers that need to be detected in the camera image
53+
cad_model_mesh: "calibration_target_3holes_cad_mesh.ply" # relative file path to CAD model of the calibration target as mesh
54+
cad_model_cloud: "calibration_target_3holes_cad_cloud.ply" # relative file path to CAD model of the calibration target as cloud
55+
```
56+
57+
*The CAD model mesh/cloud is used for the optimization of the detected target pose by aligning the model data to the segmented point cloud by means of GICP.*

doc/user_docs/data_processing.md

+113
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,113 @@
1+
# Data Processing
2+
3+
## Calibration Target Detection in the Camera Data
4+
5+
The calibration target is detected in the image data by means of the ArUco markers.
6+
In this, the [functionalities provided by OpenCV](https://docs.opencv.org/4.x/d5/dae/tutorial_aruco_detection.html) are utilized to detect markers and compute the pose of the calibration target with respect to the camera.
7+
To deduce the pose of the target from the marker detection, the algorithm requires the intrinsic parameters of the camera, which is why a good intrinsic calibration is vital.
8+
The image points of the detected markers are stored to be later used as 2D correspondences as part of the PnP algorithm.
9+
Furthermore, with the image positions of the detected markers and the a priori knowledge about the calibration board geometry, a 3D point cloud of the calibration target is also created.
10+
The detections, as well as the 6-DOF Pose of the target and the reconstructed 3D point cloud are published after the detection was successful.
11+
In this, the marker ID to which the detected corner belongs is stored in the intensity value of the point.
12+
13+
## Calibration Target Detection in the LiDAR Data
14+
15+
The detection and pose estimation of the calibration target within the LiDAR cloud data is realized in a number of consecutive steps.
16+
In this numerous algorithms from the [Point Cloud Library (PCL)](https://pointclouds.org/) are used.
17+
18+
1. First, the input point cloud is segmented into planer regions using a region growing algorithm.
19+
This algorithm requires the point cloud to have normal vectors which are computed prior to the region growing.
20+
21+
2. After that each segmented cluster whether its size and aspect ratio fits to the geometry of the calibration target.
22+
If so, the cluster is considered as region of interest (which are also published as preview) in which a detailed detection and pose estimation of the target is performed.
23+
In this, the algorithm fits a rotating bounding box to the cluster and checks its dimension.
24+
25+
3. When the actual target detection and pose estimation is to be performed, the orientation of the bounding box is first aligned to the actual orientation of the calibration target using the arrangement of the cutouts.
26+
In this, all possible orientations are tested by counting the points in the point cloud at the assumed location of the cutouts.
27+
The orientation for which the smallest number of points have been accumulated is taken as the orientation of the target.
28+
29+
4. This pose is used as an initialization to a RANSAC algorithm which tries to fit a custom sample consensus (SAC) model of the calibration target to the segmented region of interest.
30+
In this it computes the normal vector of the board based on a random set of points from the cluster and varies position and rotation of the target pose with each RANSAC iteration.
31+
Finally the pose with the most inliers is chosen as the winner-takes-it-all solution.
32+
As inliers all point that lie on the calibration target are chosen.
33+
With each point that falls into the circular cutout, the current estimation is penalized by reducing the number of inliers by a certain factor.
34+
35+
5. When RANSAC has found a pose, the coefficients are optimized by fitting a CAD model into the point cloud using GICP.
36+
In this only the points forming the convex hull of the cloud segmented from the input cloud are used.
37+
38+
6. Finally, the 3D coordinates of the marker corners are deduced based on the estimated board pose and stored as 3D correspondences.
39+
40+
The detections, as well as the 6-DOF Pose of the target and the segmented 3D point cloud are published after the detection was successful.
41+
In this, the marker ID to which the detected corner belongs is stored in the intensity value of the point.
42+
43+
The parameters for the algorithm outlined above are exposed as dynamic parameters and can be adjusted by calling `rqt_reconfigure` or opening the preferences from the UI (*Edit->Preferences*).
44+
An overview of these parameters is given blow:
45+
46+
**Input Filter:**
47+
48+
- `max_range`: Maximum range at which to filter the incoming point cloud prior to any processing. Any point with a range (absolute distance from sensor) larger than max_range will be discarded. Turn to 0 to switch off.
49+
50+
**Normal Estimation:**
51+
52+
- `normal_estimation_search_method`: Select method to use for neighbor search. (0 = RadiusSearch, 1 = NearestNeighborSearch)
53+
- `normal_estimation_search_radius`: Radius in which to search for neighbors. In case of 'RadiusSearch', this is a spatial extend. In case of 'NearestNeighborSearch', this represents the number of nearest neighbors (truncated to int).
54+
55+
**Region Growing:**
56+
57+
- `region_growing_cluster_size_min`: Minimum number of points a cluster needs to contain in order to be considered as valid inside the region growing.
58+
- `region_growing_cluster_size_max`: Maximum number of points a cluster needs to contain in order to be considered as valid inside the region growing.
59+
- `region_growing_number_neighbors`: Number of neighbor points to consider during region growing.
60+
- `region_growing_angle_thresh`: Angle in degrees used as the allowable range for the normals deviation. If the deviation between points normals is less than the smoothness threshold then they are suggested to be in the same cluster.
61+
- `region_growing_curvature_thresh`: Second criteria for the region growing. If two points have a small normals deviation then the disparity between their curvatures is tested.
62+
63+
**Size Filter:**
64+
65+
- `size_filter_width_min_tolerance`: Tolerance (in m) of the minimum board width when filtering the clusters based on their size.
66+
- `size_filter_width_max_tolerance`: Tolerance (in m) of the maximum board width when filtering the clusters based on their size.
67+
- `size_filter_height_min_tolerance`: Tolerance (in m) of the minimum board height when filtering the clusters based on their size.
68+
- `size_filter_height_max_tolerance`: Tolerance (in m) of the maximum board height when filtering the clusters based on their size.
69+
70+
**RANSAC:**
71+
72+
- `ransac_distance_thresh`: Distance threshold (in m) from model for points to count as inliers during RANSAC.
73+
- `ransac_rotation_variance`: Maximum angle in rotation (in degrees) to be sampled when computing the new coefficients within RANSAC.
74+
- `ransac_translation_variance`: Maximum distance in translation (in m) to be sampled when computing the new coefficients within RANSAC.
75+
- `ransac_optimize_coefficients`: Option to activate the optimization of the coefficients by means of ICP.
76+
- `target_icp_variant`: Select ICP variant to use to optimize coefficients. (0 = ICP, 1 = PlaneICP, 2 = GICP)
77+
- `target_icp_max_correspondence_distance`: Maximum distance for ICP to search for point correspondences. Given as ratio with respect to shorter side of calibration target.
78+
- `target_icp_rotation_tolerance`: Rotation tolerance for convergence check. Given in degrees.
79+
- `target_icp_translation_tolerance`: Translation tolerance for convergence check. Given in unit of the LiDAR point cloud, typically meters.
80+
81+
## Perspective-n-Point for 2D-3D Pose Estimation
82+
83+
In the extrinsic pose estimation using sets of 2D-3D correspondences (e.g. Camera-LiDAR calibration) the [Perspective-n-Point (PnP) algorithm from OpenCV](https://docs.opencv.org/4.x/d5/d1f/calib3d_solvePnP.html) is used.
84+
The parameters to configure the PnP algorithm are exposed as dynamic parameters and can be adjusted by calling `rqt_reconfigure` or opening the preferences from the UI (*Edit->Preferences*).
85+
An overview of these parameters is given blow:
86+
87+
- `limit_single_board_rpj_error`: Use max maximum reprojection error to accept during calibration of a single target pose. If false, 'board_max_rpj_error' is ignored.
88+
- `single_board_max_rpj_error`: Limit for maximum reprojection error to accept during calibration of a single target pose. All calibrated poses, that exceed this limit are rejected.
89+
- `single_board_min_inliers`: Threshold for minimum number of inliers to accept during calibration of a single target pose. All calibrated poses, that do not reach this threshold are rejected.
90+
- `pnp_inlier_rpj_error_limit`: Limit for maximum reprojection error for which points are considered as RANSAC inliers during PnP.
91+
92+
## GICP for 3D-3D Alignment
93+
94+
In the alignment of 3D point clouds of two LiDAR sensors (e.g. LiDAR-LiDAR calibration) the [Generalized-ICP (GICP) of 'small_gicp'](https://github.com/koide3/small_gicp) is used.
95+
The parameters to configure the GICP algorithm are exposed as dynamic parameters and can be adjusted by calling `rqt_reconfigure` or opening the preferences from the UI (*Edit->Preferences*).
96+
An overview of these parameters is given blow:
97+
98+
- `registration_icp_variant`: Select ICP variant to use for registration. (0 = ICP, 1 = PlaneICP, 2 = GICP)
99+
- `registration_icp_max_correspondence_distance`: Maximum distance for ICP to search for point correspondences. Given as ratio with respect to shorter side of calibration target.
100+
- `registration_icp_rotation_tolerance`: Rotation tolerance for convergence check. Given in degrees.
101+
- `registration_icp_translation_tolerance`: Translation tolerance for convergence check. Given in unit of the LiDAR point cloud, typically meters.
102+
103+
## Error Computation and Estimation of Calibration Certainty
104+
105+
In the calibration using the PnP algorithm to align two sensors by means of 2D-3D correspondences, the quality of the calibration is measured by the [mean reprojection error](https://docs.opencv.org/3.4/dc/dbb/tutorial_py_calibration).html).
106+
For a good calibration a typical reprojection error lies between 2-4 Pixels.
107+
108+
In the calibration of two 3D sensors in which the sensor data gets aligned by means of GIPC, the quality of the calibration is measured using the [root mean squared error (RMSE)](https://en.wikipedia.org/wiki/Root_mean_square_deviation).
109+
For a good calibration a typical RMSE lies in the range of view centimeters.
110+
111+
To quantify the certainty of the result, the standard deviation of the individual target poses is also calculated.
112+
In this, for a given extrinsic calibration the poses of the detected calibration target are projected from the coordinate frame of the source sensor into the coordinate frame of the reference sensor.
113+
The standard deviation in the translational and rotational difference should give us a good indication on the consistency of the calibration.

0 commit comments

Comments
 (0)