Hi Janosch, hi Paul,
thanks for your answer! Assuming a conservative noise model reduces the errors to a reasonable value. I am using an XSens Mti-G 700 (400Hz) together with a Bumblebee2 stereo camera (20Hz). According to other threads in this forum, the results from the calibration should be ok:
Calibration results
===================
Reprojection error squarred (cam0): mean 0.0391469662938, median 0.0212802778721, std: 0.0698499823634
Reprojection error squarred (cam1): mean 0.0397683752791, median 0.0244933967691, std: 0.0596360389564
Gyro error squarred (imu0): mean 0.171323444722, median 0.082274108564, std: 0.205328937958
Accelerometer error squarred (imu0): mean 0.357950788613, median 0.242382793176, std: 0.737434428464
Transformation (cam0):
-----------------------
T_ci: (imu to cam0): [m]
[[-0.99949509 -0.01183534 -0.02948715 -0.02826914]
[ 0.02948785 0.00011519 -0.99956513 -0.01627083]
[ 0.01183359 -0.99992995 0.00023387 -0.01153722]
[ 0. 0. 0. 1. ]]
T_ic: (cam0 to imu): [m]
[[-0.99949509 0.02948785 0.01183359 -0.02763854]
[-0.01183534 0.00011519 -0.99992995 -0.01186911]
[-0.02948715 -0.99956513 0.00023387 -0.01709463]
[ 0. 0. 0. 1. ]]
timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
0.0396549938643
Transformation (cam1):
-----------------------
T_ci: (imu to cam1): [m]
[[-0.99949509 -0.01183534 -0.02948715 -0.14795114]
[ 0.02948785 0.00011519 -0.99956513 -0.01627083]
[ 0.01183359 -0.99992995 0.00023387 -0.01153722]
[ 0. 0. 0. 1. ]]
T_ic: (cam1 to imu): [m]
[[-0.99949509 0.02948785 0.01183359 -0.14726012]
[-0.01183534 0.00011519 -0.99992995 -0.01328558]
[-0.02948715 -0.99956513 0.00023387 -0.02062371]
[ 0. 0. 0. 1. ]]
timeshift cam1 to imu0: [s] (t_imu = t_cam + shift)
0.0396322637769
Baselines:
----------
Baseline (cam0 to cam1): [m]
[[ 1. 0. 0. -0.119682]
[ 0. 1. 0. 0. ]
[ 0. 0. 1. 0. ]
[ 0. 0. 0. 1. ]]
baseline norm: 0.119682 [m]
Gravity vector in target coords: : [m/s^2]
[ 9.79741866 -0.42528333 -0.2565573 ]
Calibration configuration
=========================
cam0
-----
Camera model: pinhole
Focal length: [290.77888, 290.77872]
Principal point: [324.56128, 249.41136]
Distortion model: radtan
Distortion coefficients: [0, 0, 0, 0]
Type: checkerboard
Rows
Count: 6
Distance: 0.0407 [m]
Cols
Count: 8
Distance: 0.0407 [m]
cam1
-----
Camera model: pinhole
Focal length: [290.77888, 290.77872]
Principal point: [324.56128, 249.41136]
Distortion model: radtan
Distortion coefficients: [0, 0, 0, 0]
Type: checkerboard
Rows
Count: 6
Distance: 0.0407 [m]
Cols
Count: 8
Distance: 0.0407 [m]
IMU configuration
=================
Update rate: 400.0
Accelerometer:
Noise density: 0.006056
Noise density (discrete): 0.12112
Random walk: 0.0011056
Gyroscope:
Noise density: 0.0013248
Noise density (discrete): 0.026496
Random walk: 6.2176e-05
However, I don't see how the found translation between the IMU and the cameras can be
correct (the rotation seems fine), since the IMU is between the cameras with the imu-x-axis aligned with the cam-x-axes but in the opposite direction. The result should therefore be something around +-6cm (at least less than the baseline) for both cameras in the first value of the T_ci/T_ic. Trying with other datasets, the translation is always different, so how do I know if I found a good estimate, if the error values are as good as the ones above? Do I need to consider anything special when exciting the system besides rotation around at least two axes? (I attached the calibration protocol to the post)
I am also trying with the --time-calibration option because there is a small time-difference of a few ms between the sensors. I receive better results with the time-calibration option, but I have the feeling that with this parameter the calibration is very sensitive to abrupt movement, is that correct? For me, it only works sometimes and if it does not, I get the error output below.
From the output I see, that the optimization is not initialized with the T_cam_imu from the camchain.yaml file but with the baseline of the camera, could this pose a problem?
Before Optimization
===================
Reprojection error squarred (cam0): mean 0.384721468439, median 0.0638888864722, std:
1.3472417695Reprojection error squarred (cam1): mean 0.413390906049, median 0.107302183586, std: 1.14918075707
Gyro error squarred (imu0): mean 92.3289277877, median 30.6993818637, std: 186.046937566
Accelerometer error squarred (imu0): mean 13248.4207943, median 13193.633743, std: 1063.90094598
Transformation T_cam0_imu0 (imu0 to cam0, T_ci): [m]
[[-0.99912566 -0.03779982 -0.01786283 0. ]
[ 0.01768259 0.00509722 -0.99983066 0. ]
[ 0.03788447 -0.99927233 -0.00442436 0. ]
[ 0. 0. 0. 1. ]]
cam0 to imu0 time: [s] (t_imu = t_cam + shift)
0.142917489186
Transformation T_cam1_imu0 (imu0 to cam1, T_ci): [m]
[[-0.99912566 -0.03779982 -0.01786283 -0.119682 ]
[ 0.01768259 0.00509722 -0.99983066 0. ]
[ 0.03788447 -0.99927233 -0.00442436 0. ]
[ 0. 0. 0. 1. ]]
cam1 to imu0 time: [s] (t_imu = t_cam + shift)
0.142917489186
Optimizing...
No linear system solver set in the options. Defaulting to the sparse_cholesky solver
Using the sparse_cholesky linear system solver
Using the levenberg_marquardt trust region policy
No linear system solver set in the options. Defaulting to the sparse_cholesky solver
Using the sparse_cholesky linear system solver
Using the levenberg_marquardt trust region policy
Initializing
Optimization problem initialized with 10625 design variables and 148239 error terms
The Jacobian matrix is 423690 x 47794
[0.0]: J: 2.82731e+08
Exception in thread block: [aslam::Exception] /var/kalibr-build/src/kalibr/aslam_nonparametric_estimation/aslam_splines/src/BSplineExpressions.cpp:447: toTransformationMatrixImplementation() assert(_bufferTmin <= _time.toScalar() < _bufferTmax) failed [2301.9 <= 2301.84 < 2301.95]: Spline Coefficient Buffer Exceeded. Set larger buffer margins!
Exception in thread block: [aslam::Exception] /var/kalibr-build/src/kalibr/aslam_nonparametric_estimation/aslam_splines/src/BSplineExpressions.cpp:447: toTransformationMatrixImplementation() assert(_bufferTmin <= _time.toScalar() < _bufferTmax) failed [2302.85 <= 2302.79 < 2302.9]: Spline Coefficient Buffer Exceeded. Set larger buffer margins!
Exception in thread block: [aslam::Exception] /var/kalibr-build/src/kalibr/aslam_nonparametric_estimation/aslam_splines/src/BSplineExpressions.cpp:447: toTransformationMatrixImplementation() assert(_bufferTmin <= _time.toScalar() < _bufferTmax) failed [2250.75 <= 2250.69 < 2250.8]: Spline Coefficient Buffer Exceeded. Set larger buffer margins!
[ERROR] [1425995348.595741]: Optimization failed!Traceback (most recent call last):
File "/var/kalibr-build/devel/bin/kalibr_calibrate_imu_camera", line 5, in <module>
exec(fh.read())
File "<string>", line 206, in <module>
File "<string>", line 182, in main
File "/var/kalibr-build/src/kalibr/aslam_offline_calibration/kalibr/python/kalibr_imu_camera_calibration/IccCalibrator.py", line 181, in optimize
raise RuntimeError("Optimization failed!")
RuntimeError: Optimization failed!Error in sys.excepthook:
Traceback (most recent call last):
File "/usr/lib/python2.7/dist-packages/apport_python_hook.py", line 64, in apport_excepthook
from apport.fileutils import likely_packaged, get_recent_crashes
ImportError: No module named apport.fileutils
Original exception was:
Traceback (most recent call last):
File "/var/kalibr-build/devel/bin/kalibr_calibrate_imu_camera", line 5, in <module>
exec(fh.read())
File "<string>", line 206, in <module>
File "<string>", line 182, in main
File "/var/kalibr-build/src/kalibr/aslam_offline_calibration/kalibr/python/kalibr_imu_camera_calibration/IccCalibrator.py", line 181, in optimize
raise RuntimeError("Optimization failed!")
RuntimeError: Optimization failed!