the lever arm estimated by Kalibr between IMU and camera changes between different calibration datasets

678 views
Skip to first unread message

jianzhu...@gmail.com

unread,
Nov 26, 2014, 2:46:10 PM11/26/14
to kalibr...@googlegroups.com
I was using your Kalibr program to calibrate the camera on Kinect and a Steval MKi062v2 iNEMO MEMS IMU assembly. According to your instructions on Kalibr-Wiki, Kalibr-CDE package successfully processed my camera and IMU data, but using different calibration datasets the lever arm between IMU and camera may differ as large as 5 cm.

The following was my test procedure.
First, kalibr_calibrate_cameras was used to calibrate this camera, although there is only one camera. The calibrated camera intrinsic parameters are close to expected values, and using different datasets the change in parameters are not so much, Two typical camera calibration results are listed below. As I believe the camera calibration was good enough and in the following imu_camera calibration step, the first set of camera intrinsics was used. One pdf report on the camera calibration was attached.

From one camera calibration dataset,

cam0:
cam_overlaps: []
camera_model: pinhole
distortion_coeffs: [0.36025836474169376, 0.027011336613730973, 0.6289218924137748,
-1.467816814894584]
distortion_model: equidistant
intrinsics: [531.748357566183, 531.1784387993816, 326.90754924804975, 246.95747759324985]
resolution: [640, 480]
rostopic: /cam0/image_raw
From another camera calirbation dataset

cam0:
cam_overlaps: []
camera_model: pinhole
distortion_coeffs: [0.33038141232253154, 0.30194425076431575, -0.3902440632914327,
-0.11174482055148192]
distortion_model: equidistant
intrinsics: [531.8119087478724, 531.5077088739464, 326.8136384813593, 247.5597011285021]
resolution: [640, 480]
rostopic: /cam0/image_raw
Then, I collected image data of 15Hz and IMU data of 100 Hz, spanning about 80 seconds. Given such a dataset to kalibr_calibrate_camera_imu, most of the times, it produced converged results which were close to what we expected. The only problem was the lever arm changed much over different datasets. In particular,

One IMU camera calibration dataset gave

Calibration results
===================
Reprojection error squarred (cam0): mean 0.967124831538, median 0.438482957918, std: 1.49212524186
Gyro error squarred (imu0): mean 4.70335739178, median 2.06811505441, std: 7.77011812634
Accelerometer error squarred (imu0): mean 11.6008745717, median 11.1775889733, std: 4.74254682123

Transformation (cam0):
-----------------------
T_ci: (imu to cam0): [m]
[[ 0.00690077 -0.99997455 0.00180841 -0.01651289]
[-0.00130581 -0.00181746 -0.9999975 0.00273948]
[ 0.99997534 0.00689839 -0.00131832 -0.01366752]
[ 0. 0. 0. 1. ]]

T_ic: (cam0 to imu): [m]
[[ 0.00690077 -0.00130581 0.99997534 0.01378471]
[-0.99997455 -0.00181746 0.00689839 -0.01641321]
[ 0.00180841 -0.9999975 -0.00131832 0.00275131]
[ 0. 0. 0. 1. ]]

timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
0.164991994431


Gravity vector in target coords: : [m/s^2]
[-0.11348225 -9.69825613 -1.47209028]

Using another dataset, kalibr_calibrate_camera_imu gave

Calibration results
===================
Reprojection error squarred (cam0): mean 1.14421248677, median 0.46128479855, std: 2.13366609753
Gyro error squarred (imu0): mean 8.14218435925, median 1.99445870114, std: 16.4039685153
Accelerometer error squarred (imu0): mean 1.83472643863, median 1.06673809144, std: 2.55616453574

Transformation (cam0):
-----------------------
T_ci: (imu to cam0): [m]
[[-0.00323024 -0.99998677 -0.00400194 -0.07260569]
[ 0.00265847 0.00399336 -0.99998849 -0.02914802]
[ 0.99999125 -0.00324084 0.00264553 -0.10633775]
[ 0. 0. 0. 1. ]]

T_ic: (cam0 to imu): [m]
[[-0.00323024 0.00265847 0.99999125 0.10617977]
[-0.99998677 0.00399336 -0.00324084 -0.07283296]
[-0.00400194 -0.99998849 0.00264553 -0.02915693]
[ 0. 0. 0. 1. ]]

timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
0.197395716479


Gravity vector in target coords: : [m/s^2]
[-0.03798543 -9.70436744 -1.43523855]

The pdf reprots for the two datasets are attached.
Our expected T_ci measured with ruler is
T_ci: (imu to cam0): [m]
[[ 0 -1 0 -0.062]
[ 0 0 -1 -0.041]
[ 1 0 0 -0.030]
[ 0. 0. 0. 1. ]]

Our MEMS IMU had accelerometer noise density 2.18e-3 m/s^2/sqrt(Hz), and gyro noise density 3.14e-4 rad/s/sqrt(Hz). In setting the gyro and accelerometer noise magnitude, I referred to your sample dataset for ADIS 16448 which had similar specifications in the datasheet as Mkio62v2 iNEMO IMU.

Do you have any idea why the lever arm between MEMS IMU and camera change so much in different calibration experiments?

Thanks for your time in advance.

Jianzhu Huai

unread,
Nov 26, 2014, 3:00:05 PM11/26/14
to kalibr...@googlegroups.com
Here are one pdf report for the single camera calibration, and two reports for IMU and camera calibration.


report-cam-wacky.pdf
report-imucam-gutsy1.pdf
report-imucam-rusty1.pdf

Paul Furgale

unread,
Nov 27, 2014, 7:15:49 AM11/27/14
to kalibr...@googlegroups.com
Thanks for taking the time to send us these reports. I think the big problem is that the cameras that are integrated into the Kinect are rolling shutter cameras. Unfortunately, Kalibr doesn't currently support rolling shutter cameras.

Just briefly, calibration based on maximum likelihood (as we use in Kalibr) only works well if all the models are correct. In practice, our models are not exact, but they end up being just good enough for the procedures to work. Something like a rolling shutter camera (where each row of the image has its own timestamp) ends up being enough of a violation of the model that you see the effects---in this case, unstable calibration.

Sorry! 


Jianzhu Huai

unread,
Dec 1, 2014, 11:33:19 AM12/1/14
to kalibr...@googlegroups.com
Thanks a lot for your reply. I learned another way to fail in calibration.

yih...@gmail.com

unread,
Apr 4, 2016, 12:48:12 PM4/4/16
to kalibr-users
Hi,

After reading your comment, I have to say we have the same problem here. However, we are using a global shutter camera Xicam USB version and 3DM-GX4-25 IMU. We are using a hardware trigger to sync camera and IMU, which has a constant 3ms time-shift (being perfectly handled by the time-calibration feature in Kalibr). Also, we hack the kalibr by adding an outliers rejection procedure into system. It helps, but we still get inconsistent results.

Maybe we can share some information, if you had any progress?

Thanks in advance.

Jianzhu Huai

unread,
Apr 4, 2016, 3:00:03 PM4/4/16
to kalibr-users
Inconsistent results are common for rolling shutter CMOS cameras, c.f Luc Léonce Humair master thesis page 74 http://e-collection.library.ethz.ch/eserv/eth:48046/eth-48046-01.pdf. I believe different results in each run are also common for global shutter cameras, although maybe more stable than that of the rolling shutter(RS) cameras. There are many factors involved. If we have
1. almost perfect flat calibration pattern,
2. almost perfect motion during data collection (slow, not abrupt, not pure rotation, and has motion in 3 axes),
3. no auto focus, no auto exposure, no white balancing,
4. stable data communication (i.e., images are saved onboard with good timestamps, and constantly use one USB cable, and the same computer with the same settings when collecting the data), 
5. also balanced image frequency (too high frequency not only generates redundant data but also unstable timestamps because hard drive is not infinitely fast in saving data, too low frequency of images cannot handle well high frequency motion), 
6. make sure the camera lens (e.g. wide angle, fish eye, narrow FOV) is handled well by the toolbox (kalibr, matlab camera calibration toolbox etc)
then I believe, even using a rolling shutter camera can get stable results between different calibration tests.


yih...@gmail.com

unread,
Apr 4, 2016, 8:28:56 PM4/4/16
to kalibr-users
Thanks for the prompt reply!
Checking against the list, I think the only thing different we are doing is that we are trying to use fast motion to make the acceleration measurements large in the imu. We'll try to check each of those items on the list and see if we can obtain more consistent result. But thanks!

Jianzhu Huai

unread,
Aug 16, 2021, 10:38:56 PM8/16/21
to kalibr-users
Finally, I added [the rolling shutter camera - IMU calibration feature](https://github.com/JzHuai0108/kalibr) to the powerful Kalibr.
Reply all
Reply to author
Forward
0 new messages