Skip to content

Commit e3a7eb4

Browse files
committed
feat: kalibrated
0 parents  commit e3a7eb4

16 files changed

+504
-0
lines changed

.gitignore

+1
Original file line numberDiff line numberDiff line change
@@ -0,0 +1 @@
1+
*/*.bag

README.md

+23
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
# ZED2i Camera Calibration
2+
3+
## Dependencies
4+
5+
[ZED SDK](https://www.stereolabs.com/developers/release)
6+
[Kalibr](https://github.com/ethz-asl/kalibr)
7+
8+
## Calibration
9+
10+
- Generate aprilgrid and target.yaml
11+
- Bump zed_wrapper resolution to 1080p
12+
- Run `kalibr_record.sh`
13+
- Run `kalibr_calibrate_mcc.sh zed2i.bag`
14+
- Run `kalibr_calibrate_imu.sh zed2i.bag camchain.yaml`
15+
16+
## Errors
17+
18+
- [kalibr_calibrate_imu_camera : Optimization failed](https://github.com/ethz-asl/kalibr/issues/41)
19+
20+
## References
21+
22+
- [Kalibr Wiki](https://github.com/ethz-asl/kalibr/wiki/)
23+
- [ZED2i datasheet](https://www.stereolabs.com/assets/datasheets/zed-2i-datasheet-feb2022.pdf)

aprilgrid.pdf

18.6 KB
Binary file not shown.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
cam0:
2+
T_cam_imu:
3+
- [0.20491451916597242, -0.9383621898209672, -0.27836386358394105, -0.1871957524572456]
4+
- [0.17218276494676943, 0.3145228428207421, -0.9335033351837827, -0.202849959743378]
5+
- [0.9635160275212163, 0.14335892737586797, 0.22602009346820634, 0.30889113677880975]
6+
- [0.0, 0.0, 0.0, 1.0]
7+
cam_overlaps: [1]
8+
camera_model: pinhole
9+
distortion_coeffs: [0.39966946154803484, 0.463531463471755, 144.48847522150243, -2417.061665773314]
10+
distortion_model: equidistant
11+
intrinsics: [1713.9143864069194, 1731.0495429117157, 307.32895208006624, 250.9605778429886]
12+
resolution: [960, 540]
13+
rostopic: /zed2i/zed_node/right_raw/image_raw_color
14+
timeshift_cam_imu: 0.013429007190913361
15+
cam1:
16+
T_cam_imu:
17+
- [0.1805735337435404, -0.9412174966060454, -0.2854869926879675, -0.061896519862077226]
18+
- [0.17643334344952205, 0.3165474125408502, -0.9320241471833849, -0.2011406036960496]
19+
- [0.9676076034377745, 0.11792946915992608, 0.22322223471926933, 0.309902044845798]
20+
- [0.0, 0.0, 0.0, 1.0]
21+
T_cn_cnm1:
22+
- [0.9996743123417962, 0.0015603073968219153, -0.025472233604089525, 0.13342292073582038]
23+
- [-0.001440526912694867, 0.9999878228513484, 0.004720066867218399, -2.0761426428970212e-05]
24+
- [0.025479288180160896, -0.004681836161660715, 0.9996643868238902, 0.004934480248516449]
25+
- [0.0, 0.0, 0.0, 1.0]
26+
cam_overlaps: [0]
27+
camera_model: pinhole
28+
distortion_coeffs: [0.20651699541056007, 0.2957692962102138, 44.9944228499361, -359.4542014801639]
29+
distortion_model: equidistant
30+
intrinsics: [1738.7909891212125, 1747.9754745146804, 366.02468479684694, 238.9106672375295]
31+
resolution: [960, 540]
32+
rostopic: /zed2i/zed_node/left_raw/image_raw_color
33+
timeshift_cam_imu: 0.012782112373362825
+21
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
cam0:
2+
cam_overlaps: [1]
3+
camera_model: pinhole
4+
distortion_coeffs: [0.39966946154803484, 0.463531463471755, 144.48847522150243, -2417.061665773314]
5+
distortion_model: equidistant
6+
intrinsics: [1713.9143864069194, 1731.0495429117157, 307.32895208006624, 250.9605778429886]
7+
resolution: [960, 540]
8+
rostopic: /zed2i/zed_node/right_raw/image_raw_color
9+
cam1:
10+
T_cn_cnm1:
11+
- [0.999674312341795, 0.001560307396821915, -0.02547223360408952, 0.13342292073582038]
12+
- [-0.0014405269126948669, 0.9999878228513472, 0.004720066867218397, -2.0761426428970212e-05]
13+
- [0.02547928818016089, -0.0046818361616607134, 0.9996643868238891, 0.004934480248516449]
14+
- [0.0, 0.0, 0.0, 1.0]
15+
cam_overlaps: [0]
16+
camera_model: pinhole
17+
distortion_coeffs: [0.20651699541056007, 0.2957692962102138, 44.9944228499361, -359.4542014801639]
18+
distortion_model: equidistant
19+
intrinsics: [1738.7909891212125, 1747.9754745146804, 366.02468479684694, 238.9106672375295]
20+
resolution: [960, 540]
21+
rostopic: /zed2i/zed_node/left_raw/image_raw_color

assets/2022-10-08-00-57-54-imu.yaml

+14
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
imu0:
2+
T_i_b:
3+
- [1.0, 0.0, 0.0, 0.0]
4+
- [0.0, 1.0, 0.0, 0.0]
5+
- [0.0, 0.0, 1.0, 0.0]
6+
- [0.0, 0.0, 0.0, 1.0]
7+
accelerometer_noise_density: 0.0016
8+
accelerometer_random_walk: 0.0002509
9+
gyroscope_noise_density: 0.00012217304763960306
10+
gyroscope_random_walk: 3.398854185333757e-05
11+
model: calibrated
12+
rostopic: /zed2i/zed_node/imu/data_raw
13+
time_offset: 0.0
14+
update_rate: 400.0
566 KB
Binary file not shown.
1.56 MB
Binary file not shown.
+30
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
Calibration results
2+
====================
3+
Camera-system parameters:
4+
cam0 (/zed2i/zed_node/right_raw/image_raw_color):
5+
type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
6+
distortion: [ 0.39966946 0.46353146 144.48847522 -2417.06166577] +- [0.03477123 0.60426411 0.09470205 0.01042813]
7+
projection: [1713.91438641 1731.04954291 307.32895208 250.96057784] +- [0.50091219 0.87957026 3.25426851 2.06066098]
8+
reprojection error: [-0.000341, -0.000213] +- [1.013732, 0.956983]
9+
10+
cam1 (/zed2i/zed_node/left_raw/image_raw_color):
11+
type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
12+
distortion: [ 0.206517 0.2957693 44.99442285 -359.45420148] +- [0.01936849 0.17706955 0.49900956 0.08315889]
13+
projection: [1738.79098912 1747.97547451 366.0246848 238.91066724] +- [1.02632685 0.78708899 0.72086017 2.67523907]
14+
reprojection error: [-0.000100, -0.000261] +- [0.945557, 0.858031]
15+
16+
baseline T_1_0:
17+
q: [0.00235067 0.01273895 0.00075027 0.99991581] +- [0.00157382 0.0022139 0.00017778]
18+
t: [ 0.13342292 -0.00002076 0.00493448] +- [0.00030146 0.00023496 0.00090939]
19+
20+
21+
22+
Target configuration
23+
====================
24+
25+
Type: aprilgrid
26+
Tags:
27+
Rows: 4
28+
Cols: 3
29+
Size: 0.055 [m]
30+
Spacing 0.012485000000000001 [m]
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,120 @@
1+
Calibration results
2+
===================
3+
Normalized Residuals
4+
----------------------------
5+
Reprojection error (cam0): mean 2.1080386866599587, median 1.707054700247669, std: 4.397413420058306
6+
Reprojection error (cam1): mean 2.0178707999763503, median 1.6358700065926572, std: 1.587350090015915
7+
Gyroscope error (imu0): mean 2.2024128676638366, median 1.8006662074163826, std: 1.5134376836795942
8+
Accelerometer error (imu0): mean 3.184769154578532, median 2.268581467209623, std: 2.769548699057428
9+
10+
Residuals
11+
----------------------------
12+
Reprojection error (cam0) [px]: mean 2.1080386866599587, median 1.707054700247669, std: 4.397413420058306
13+
Reprojection error (cam1) [px]: mean 2.0178707999763503, median 1.6358700065926572, std: 1.587350090015915
14+
Gyroscope error (imu0) [rad/s]: mean 0.005381509844063374, median 0.004399857566834101, std: 0.003698025884555151
15+
Accelerometer error (imu0) [m/s^2]: mean 0.10191261294651303, median 0.07259460695070794, std: 0.08862555836983768
16+
17+
Transformation (cam0):
18+
-----------------------
19+
T_ci: (imu0 to cam0):
20+
[[ 0.20491452 -0.93836219 -0.27836386 -0.18719575]
21+
[ 0.17218276 0.31452284 -0.93350334 -0.20284996]
22+
[ 0.96351603 0.14335893 0.22602009 0.30889114]
23+
[ 0. 0. 0. 1. ]]
24+
25+
T_ic: (cam0 to imu0):
26+
[[ 0.20491452 0.17218276 0.96351603 -0.22433517]
27+
[-0.93836219 0.31452284 0.14335893 -0.15613877]
28+
[-0.27836386 -0.93350334 0.22602009 -0.31128525]
29+
[ 0. 0. 0. 1. ]]
30+
31+
timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
32+
0.013429007190913361
33+
34+
35+
Transformation (cam1):
36+
-----------------------
37+
T_ci: (imu0 to cam1):
38+
[[ 0.18057353 -0.9412175 -0.28548699 -0.06189652]
39+
[ 0.17643334 0.31654741 -0.93202415 -0.2011406 ]
40+
[ 0.9676076 0.11792947 0.22322223 0.30990204]
41+
[ 0. 0. 0. 1. ]]
42+
43+
T_ic: (cam1 to imu0):
44+
[[ 0.18057353 0.17643334 0.9676076 -0.25319879]
45+
[-0.9412175 0.31654741 0.11792947 -0.03113413]
46+
[-0.28548699 -0.93202415 0.22322223 -0.27431558]
47+
[ 0. 0. 0. 1. ]]
48+
49+
timeshift cam1 to imu0: [s] (t_imu = t_cam + shift)
50+
0.012782112373362825
51+
52+
Baselines:
53+
----------
54+
Baseline (cam0 to cam1):
55+
[[ 0.99967431 0.00156031 -0.02547223 0.13342292]
56+
[-0.00144053 0.99998782 0.00472007 -0.00002076]
57+
[ 0.02547929 -0.00468184 0.99966439 0.00493448]
58+
[ 0. 0. 0. 1. ]]
59+
baseline norm: 0.13351413896676573 [m]
60+
61+
62+
Gravity vector in target coords: [m/s^2]
63+
[ 2.65506463 -9.28080635 1.72791444]
64+
65+
66+
Calibration configuration
67+
=========================
68+
69+
cam0
70+
-----
71+
Camera model: pinhole
72+
Focal length: [1713.9143864069194, 1731.0495429117157]
73+
Principal point: [307.32895208006624, 250.9605778429886]
74+
Distortion model: equidistant
75+
Distortion coefficients: [0.39966946154803484, 0.463531463471755, 144.48847522150243, -2417.061665773314]
76+
Type: aprilgrid
77+
Tags:
78+
Rows: 4
79+
Cols: 3
80+
Size: 0.055 [m]
81+
Spacing 0.012485000000000001 [m]
82+
83+
cam1
84+
-----
85+
Camera model: pinhole
86+
Focal length: [1738.7909891212125, 1747.9754745146804]
87+
Principal point: [366.02468479684694, 238.9106672375295]
88+
Distortion model: equidistant
89+
Distortion coefficients: [0.20651699541056007, 0.2957692962102138, 44.9944228499361, -359.4542014801639]
90+
Type: aprilgrid
91+
Tags:
92+
Rows: 4
93+
Cols: 3
94+
Size: 0.055 [m]
95+
Spacing 0.012485000000000001 [m]
96+
97+
98+
99+
IMU configuration
100+
=================
101+
102+
IMU0:
103+
----------------------------
104+
Model: calibrated
105+
Update rate: 400.0
106+
Accelerometer:
107+
Noise density: 0.0016
108+
Noise density (discrete): 0.032
109+
Random walk: 0.0002509
110+
Gyroscope:
111+
Noise density: 0.00012217304763960306
112+
Noise density (discrete): 0.002443460952792061
113+
Random walk: 3.398854185333757e-05
114+
T_ib (imu0 to imu0)
115+
[[1. 0. 0. 0.]
116+
[0. 1. 0. 0.]
117+
[0. 0. 1. 0.]
118+
[0. 0. 0. 1.]]
119+
time offset with respect to IMU0: 0.0 [s]
120+

imu.yaml

+12
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,12 @@
1+
# imu.yaml for ZED2i
2+
3+
#Accelerometers
4+
accelerometer_noise_density: 1.6e-03 #Noise density (continuous-time)
5+
accelerometer_random_walk: 2.509e-4 #Bias random walk
6+
7+
#Gyroscopes
8+
gyroscope_noise_density: 1.2217304763960306e-4 #Noise density (continuous-time)
9+
gyroscope_random_walk: 3.398854185333757e-05 #Bias random walk
10+
11+
rostopic: /zed2i/zed_node/imu/data_raw #IMU ROS topic
12+
update_rate: 400.0 #Hz (for discretization of the values above)

kalibr_calibrate_imu.sh

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
#! /bin/bash
2+
3+
rosrun kalibr kalibr_calibrate_imu_camera --bag $1 --cam $2 --imu imu.yaml --target target.yaml --timeoffset-padding 0.01
4+

kalibr_calibrate_mcc.sh

+4
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
#! /bin/bash
2+
3+
rosrun kalibr kalibr_calibrate_cameras --bag $1 --topics /zed2i/zed_node/right_raw/image_raw_color /zed2i/zed_node/left_raw/image_raw_color --models pinhole-equi pinhole-equi --target target.yaml
4+

kalibr_record.sh

+6
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
#! /bin/bash
2+
3+
terminator --new-tab --title=roscore --execute roscore &
4+
terminator --new-tab --title=zed_wrapper --execute roslaunch zed_wrapper zed2i.launch &
5+
terminator --new-tab --title=rviz --execute rviz -d zed2i.rviz &
6+
terminator --new-tab --title=record --execute rosbag record /zed2i/zed_node/right_raw/image_raw_color /zed2i/zed_node/left_raw/image_raw_color /zed2i/zed_node/imu/data_raw

target.yaml

+5
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
target_type: 'aprilgrid'
2+
tagCols: 3
3+
tagRows: 4
4+
tagSize: 0.055
5+
tagSpacing: 0.227

0 commit comments

Comments
 (0)