ethz-asl / kalibr

The Kalibr visual-inertial calibration toolbox
Other
4.37k stars 1.4k forks source link

Wrong transformation between IMU and camera #228

Closed ghost closed 6 years ago

ghost commented 6 years ago

Hi all,

I am using a drone setup with a 30FPS rolling shutter camera and an IMU sampling at 500hz. While I am confident that the camera intrinsic calibration gives a good result, I am not that happy with the result form the camera-imu calibration. These are my results

Calibration results
===================
Normalized Residuals
----------------------------
Reprojection error (cam0):     mean 3.91713530728, median 2.22753269008, std: 4.56603194399
Gyroscope error (imu0):        mean 3.12146269366, median 1.77668006139, std: 3.77334998179
Accelerometer error (imu0):    mean 3.99558146194, median 2.98216281851, std: 3.43522643883

Residuals
----------------------------
Reprojection error (cam0) [px]:     mean 3.91713530728, median 2.22753269008, std: 4.56603194399
Gyroscope error (imu0) [rad/s]:     mean 0.0104697041584, median 0.0059591660873, std: 0.0126562005933
Accelerometer error (imu0) [m/s^2]: mean 0.0178687835171, median 0.0133366375643, std: 0.0153627996707

Transformation (cam0):
-----------------------
T_ci:  (imu0 to cam0): 
[[-0.08524694 -0.99617388 -0.01924994 -0.07873375]
 [ 0.26428721 -0.00397957 -0.96443581 -0.15836483]
 [ 0.96066916 -0.08730272  0.26361526  0.32828055]
 [ 0.          0.          0.          1.        ]]

T_ic:  (cam0 to imu0): 
[[-0.08524694  0.26428721  0.96066916 -0.28022701]
 [-0.99617388 -0.00397957 -0.08730272 -0.05040294]
 [-0.01924994 -0.96443581  0.26361526 -0.2407881 ]
 [ 0.          0.          0.          1.        ]]

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

Gravity vector in target coords: [m/s^2]
[ 0.3750241  -9.27447998  3.16414301]

Calibration configuration
=========================

cam0
-----
  Camera model: pinhole
  Focal length: [221.07687575440082, 201.00370259460317]
  Principal point: [353.05038155848024, 243.34238110535617]
  Distortion model: equidistant
  Distortion coefficients: [0.4608488890407063, 0.5578837467481197, -1.0824505677105334, 0.4908256226446969]
  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.021 [m]
    Spacing 0.00651 [m]

IMU configuration
=================

IMU0:
----------------------------
  Model: calibrated
  Update rate: 500.0
  Accelerometer:
    Noise density: 0.0002 
    Noise density (discrete): 0.004472135955 
    Random walk: 8.5e-05
  Gyroscope:
    Noise density: 0.00015
    Noise density (discrete): 0.00335410196625 
    Random walk: 5e-06
  T_i_b
    [[1. 0. 0. 0.]
     [0. 1. 0. 0.]
     [0. 0. 1. 0.]
     [0. 0. 0. 1.]]
  time offset with respect to IMU0: 0.0 [s]

And the generated plots: report-imucam-imu_camera_cal_deinterlaced_sync_20180926.pdf

I have tried to reduce shocks and motion blur as much as possible. I found the noise model using the Allan deviation.

I think that the rotation part of the transformation could be correct, however, the translation part doesn't make any sense to me. The distance between camera and IMU is in the magnitude of several centimeters instead of meters.

Does anybody know what might be going wrong and how I can improve the results?

ZacharyTaylor commented 6 years ago

There are two common possibilities when the translation is off 1) There is some time offset between the sensors, try recalibrating with the --time-calibration flag set 2) The system did not undergo a sufficient range of movements to observe the offset. I couldn't get the pdf to open so I am not sure how much the sensor moved. If repeforming the calibration ensure you have large changes in rotation and translation about all 3 axes.

ghost commented 6 years ago

Thanks you for the tips.

I tried running the calibration with the --time-calibration flag and using movements that should excite the sensors more. However, Kalibr give we the following error:

Exception in thread block: [aslam::Exception] /home/evlamaa/kalibr_workspace/src/Kalibr/aslam_nonparametric_estimation/aslam_splines/src/BSplineExpressions.cpp:447: toTransformationMatrixImplementation() assert(_bufferTmin <= _time.toScalar() < _bufferTmax) failed [225.292 <= 225.288 < 225.322]: Spline Coefficient Buffer Exceeded. Set larger buffer margins!
[ERROR] [1538120362.562590]: Optimization failed!

Do you have an idea what might cause this error and how I can fix this?

I manually synchronize the IMU and image stream based on a visual cue. Here, I assume that the offset is constant over time. This already reduces the offset to be, at maximum, the time between two frames. If I understand it correctly, the --time-calibration flag should be able to detect the remaining delay and correct this?

ZacharyTaylor commented 6 years ago

By default the timing calibration assumes that the imu timestamps are within 10ms of correct. If this assumption is violated the calibration fails. As the error says this can be fixed by setting larger buffer margins. This is done with the --timeoffset-padding option, try setting it to something like 100ms ie --timeoffset-padding 0.1

Out of curiosity what application are you needing the IMU-camera calibration for, as if you are wanting to fuse readings from the two sensors this method of synchronization will likely be insufficient to obtain accurate results.

ghost commented 6 years ago

The --show-extraction flag showed me the real problem of the calibration not working, the tag was most of the time not detected. Moving my setup closer to the aprilgrid already improved the transformation into a range that seems reasonable. Now I am trying to get a bigger aprilgrid to make it possible to make larger enough movements. I still want to thank you for your help.

I am working on a project to use VIO (ROVIOLI) on a micro drone (Crazyflie) such that it does not need any external measurement methods (GPS or Ultrawideband positioning). Since the Crazyflies cannot transfer the video feed to my PC I am using an external system to do that. I am also working on a system that removes the need of manual synchronization, but that is not yet finished. I do agree that transmitting the video through the drone would make this allot easier, but sadly bigger drones will probably destroy our lab.

ZacharyTaylor commented 6 years ago

In my experience for reliable operation on a dynamic platform like a drone, ROVIO / ROVIOLI need timestamps that are correct to within 5ms, this could be quite difficult to achieve with your described configuration.

mohamedelomari commented 5 years ago

@maartenvlaswinkel Hi I'm trying to use the Kalibr with my crazyflie and I need help with that? Can I text you if you succeeded to run it and get output calibration results?

ghost commented 5 years ago

Hi @mohamedelomari ,

As @ZacharyTaylor already mentioned Kalibr needs a proper synchronization between the video and IMU data streams. Without this, Kalibr will not work. I was able to gets a proper synchronization and got Kalibr to work. Sadly I am not able to share my solution to synchronize the two stream since it was partof a confidential project.