Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Issue about calibrating IMU (VN100) with a RS Camera (Intel R200) #111

Closed
rising-turtle opened this issue Jun 30, 2017 · 8 comments
Closed
Labels
user-platform User has trouble running on their own dataset

Comments

@rising-turtle
Copy link

Hi all:
I am a rookie in calibrating a cam imu system. Now I can successfully run the kalibr_calibrate_imu_camera program using the sample data (https://github.com/ethz-asl/kalibr/wiki/downloads).
However, when I run the program using my dataset, the result seems very odd, especially for the large gyro error. Before showing the results, some details needs to be clarified:

  1. timing: IMU and Camera timestamps come with their data, and they are based on the same UTC clock. So they are auto synchronized.
  2. Camera images are recorded at 60 Hz with 320x240, while IMU measurements are recorded at 200Hz.
  3. The Apriltag pattern we use is the Aprilgrid 6x6 0.8x0.8 m (A0 page)
  4. We run kalibr_calibrate_imu_camera with parameters --perform-synchronization --time-calibration
    as #64 suggests.

The output is shown below:

Initializing IMUs:
  Update rate: 200.0
  Accelerometer:
    Noise density: 0.0137 
    Noise density (discrete): 0.193747258045 
    Random walk: 0.00039
  Gyroscope:
    Noise density: 6e-05
    Noise density (discrete): 0.000848528137424 
    Random walk: 4.8e-05
Initializing imu rosbag dataset reader:
	Dataset:          /media/davidz/work/work/data/rosbagForCal/320/myImage01.bag
	Topic:            /imu0
bagstart 1498852695.03
baglength 40.8659617901
[ WARN] [1498861635.132183]: BagImuDatasetReader: truncated 2174 / 8171 messages.
	Number of messages: 8171
Reading IMU data (/imu0)
  Read 5997 imu readings over 30.0 seconds                       
Initializing calibration target:
  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.088 [m]
    Spacing 0.0264 [m]
Initializing camera chain:
Camera chain - cam0:
  Camera model: pinhole
  Focal length: [313.497102, 316.596985]
  Principal point: [159.2211455, 120.558304]
  Distortion model: equidistant
  Distortion coefficients: [-0.077133, 0.053167, -0.000144, 0.001798]
  baseline: no data available
Initializing camera rosbag dataset reader:
	Dataset:          /media/davidz/work/work/data/rosbagForCal/320/myImage01.bag
	Topic:            /cam0/image_raw
[ WARN] [1498861636.843761]: BagImageDatasetReader: truncated 650 / 2451 images.
	Number of images: 2451
Extracting calibration target corners
  Extracted corners for 501 images (of 1801 images)                              

Building the problem
	Spline order: 6
	Pose knots per second: 100
	Do pose motion regularization: False
		xddot translation variance: 1000000.000000
		xddot rotation variance: 100000.000000
	Bias knots per second: 50
	Do bias motion regularization: True
	Blake-Zisserman on reprojection errors -1
	Acceleration Huber width (sigma): -1.000000
	Gyroscope Huber width (sigma): -1.000000
	Do time calibration: True
	Max iterations: 30
	Time offset padding: 0.010000
Estimating time shift camera to imu:

Initializing a pose spline with 2988 knots (100.000000 knots per second over 29.883333 seconds)
  Time shift camera to imu (t_imu = t_cam + shift):
0.475257548831

Estimating imu-camera rotation prior

Initializing a pose spline with 2988 knots (100.000000 knots per second over 29.883333 seconds)
Gravity was intialized to [-0.14368229 -9.75212383 -1.02169423] [m/s^2]
  Orientation prior camera-imu found as: (T_i_c)
[[ 0.99739153  0.01562711 -0.0704694 ]
 [-0.01987285  0.99800315 -0.05995657]
 [ 0.06939174  0.0612006   0.99571044]]
  Gyro bias prior found as: (b_gyro)
[ 0.00208277  0.01721677  0.01574063]

Initializing a pose spline with 2992 knots (100.000000 knots per second over 29.923333 seconds)

Initializing the bias splines with 1496 knots

Adding camera error terms (/cam0/image_raw)
  Added 501 camera error terms                                

Adding accelerometer error terms (/imu0)
  Added 5972 of 5997 accelerometer error terms (skipped 25 out-of-bounds measurements)

Adding gyroscope error terms (/imu0)
  Added 5972 of 5997 gyroscope error terms (skipped 25 out-of-bounds measurements)

Before Optimization
===================
Normalized Residuals
----------------------------
Reprojection error (cam0):     mean 2.73770086953, median 1.99469368493, std: 2.37824047041
Gyroscope error (imu0):        mean 944.913357819, median 825.054325211, std: 592.004675423
Accelerometer error (imu0):    mean 35.9483865343, median 29.563896721, std: 25.6275162902

Residuals
----------------------------
Reprojection error (cam0) [px]:     mean 2.73770086953, median 1.99469368493, std: 2.37824047041
Gyroscope error (imu0) [rad/s]:     mean 0.801785571537, median 0.700081809845, std: 0.502332624583
Accelerometer error (imu0) [m/s^2]: mean 6.96490132217, median 5.72792392683, std: 4.96526101173

Optimizing...
Using the block_cholesky linear system solver
Using the levenberg_marquardt trust region policy
Using the block_cholesky linear system solver
Using the levenberg_marquardt trust region policy
Initializing
Optimization problem initialized with 6003 design variables and 52134 error terms
The Jacobian matrix is 116210 x 26997
[0.0]: J: 7.43734e+09
[1]: J: 9.18448e+07, dJ: 7.34549e+09, deltaX: 1.95033, LM - lambda:10 mu:2
[2]: J: 4.89244e+07, dJ: 4.29204e+07, deltaX: 4.29776, LM - lambda:3.33333 mu:2
[3]: J: 4.88955e+07, dJ: 28890, deltaX: 1.37402, LM - lambda:1.11111 mu:2
[4]: J: 4.88955e+07, dJ: 11.4047, deltaX: 0.123134, LM - lambda:0.37037 mu:2
[5]: J: 4.88955e+07, dJ: 0.396745, deltaX: 0.0204856, LM - lambda:0.184018 mu:2
[6]: J: 4.88955e+07, dJ: 0.0107514, deltaX: 0.00181452, LM - lambda:0.0613393 mu:2
[7]: J: 4.88955e+07, dJ: 0.000579372, deltaX: 0.000445212, LM - lambda:0.0204464 mu:2

After Optimization (Results)
==================
Normalized Residuals
----------------------------
Reprojection error (cam0):     mean 1.25092499662, median 1.08839629497, std: 0.850419115889
Gyroscope error (imu0):        mean 64.9848992691, median 45.8271822112, std: 62.8292263354
Accelerometer error (imu0):    mean 0.991050203492, median 0.823059396661, std: 0.697544903804

Residuals
----------------------------
Reprojection error (cam0) [px]:     mean 1.25092499662, median 1.08839629497, std: 0.850419115889
Gyroscope error (imu0) [rad/s]:     mean 0.0551415155375, median 0.0388856535651, std: 0.0533123663981
Accelerometer error (imu0) [m/s^2]: mean 0.192013259512, median 0.159465501311, std: 0.135147412475

Transformation T_cam0_imu0 (imu0 to cam0, T_ci): 
[[ 0.99998822  0.00483851 -0.00039609 -0.06229347]
 [-0.00484429  0.99985742 -0.01617637  0.00073187]
 [ 0.00031776  0.0161781   0.99986908 -0.05993304]
 [ 0.          0.          0.          1.        ]]

cam0 to imu0 time: [s] (t_imu = t_cam + shift)
0.475340042466

This is not an acceptable result since the absolute distance between cam and imu is < 0.05m. Also the gyroscope error is extremely large and reprojection error as well as the accelerometer error are not small either.
Any suggestion will be greatly appreciated! Thanks!

@rising-turtle
Copy link
Author

BTW,
I set the IMU parameters as:

rostopic: /imu0
update_rate: 200.0 #Hz

accelerometer_noise_density: 0.0137 # 0.14 mg/√Hz * 10
accelerometer_random_walk: 0.00039 # < 0.04 mg
gyroscope_noise_density: 0.6e-4 # 0.0035 °/s √Hz 
gyroscope_random_walk: 0.48e-4 #< 10 °/hr

These are set according to the specification of IMU VN100, please correct me if any of them has been computed with mistake.
VN100_Specification.pdf

@rising-turtle
Copy link
Author

The calibration report is shown in the file below, if you have some ideas about how to improve, please tell me, thanks in advance.
report-Cal320.pdf

@DapperFactory
Copy link

Could you please clarify how you computed the IMU yaml parameters from the the VN100 datasheet.

@vik748
Copy link

vik748 commented Nov 29, 2017

@rising-turtle We are trying to calibrate a system with 2 Blackfly S cameras and a VN-100 IMU. We are experiencing similar issues where the calibration results put the imu very close to the first camera instead of the center of the baseline of the 2 cameras.
Were you able to resolve your issues?

@rising-turtle
Copy link
Author

@DapperFactory @vik748 sorry to reply late, this issue fall out of my radar recently. I set the IMU yaml parameters according to this wiki page https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model and VN100's datasheet https://github.com/rising-turtle/imu_vn100/blob/master/VN100_Specification.pdf
In the datasheet, the Noise Density and In-Run Bias Stability for Gyro are 0.0035 degree/s/√Hz, <10 degree/hr and for Accelerometer are 0.14mg/√Hz, < 0.04mg. The frequency is 200 fps, meaning Hz = 200. Then, a little different to the previous post, the parameters I calculate as follows:

accelerometer_noise_density = 0.14 mg/√Hz * = 0.14 * 10-3 * 9.8 m/s^2 /√Hz = 0.001372 m/s^2 /√Hz (usually augment this parameter by 10 or 100)
accelerometer_random_walk = 0.04 mg = 0.04 * 10-3 * 9.8 m/s^2/s/Hz = 0.000392 m/s^3/√Hz/√Hz = 0.000392/√200 m/s^3/√Hz = 0.000027719 m/s^3/√Hz
gyroscope_noise_density = 0.0035 °/s /√Hz = 0.0035 * 3.1416 / 180 rad/s/√Hz = 0.000061087 rad/s/√Hz
gyroscope_random_walk = 10 °/hr = 10 * 3.1416 / 180 / 3600 rad/s /s/Hz = 0.000048481 rad/s^2/√Hz/√Hz = 0.000048481/√200 rad/s^2/√Hz = 0.000003428 rad/s^2/√Hz

@rising-turtle
Copy link
Author

@vik748 For me, lately I figure out two issues that damage the calibration process. First is time synchronization, result from different system clock. After debug this, and enable time sync in kalibr during calibration, I got much better result below. But the translation part is still not good. The second issue is that the camera I used is a rolling-shutter camera, which bring in large error. So finally, I manually measure the tic as initial value. Then optimize Tic = [Ric, tic] in the VIO backend, which works well.
In your case, use global shutter camera could generate much accurate calibration result. There must be some improper configurations.

Normalized Residuals

Reprojection error (cam0): mean 1.16525262707, median 1.01856825194, std: 0.786876790991
Gyroscope error (imu0):
mean 0.696252519623, median 0.53304336824, std: 0.573797989019
Accelerometer error (imu0): mean 0.607325978671, median 0.536172087399, std: 0.34442369664
Residuals

Reprojection error (cam0) [px]: mean 1.16525262707, median 1.01856825194, std: 0.786876790991
Gyroscope error (imu0) [rad/s]: mean 0.0196929951217, median 0.015076743214, std: 0.0162294579627
Accelerometer error (imu0) [m/s^2]: mean 0.117667743107, median 0.103881871774, std: 0.0667311468298
Transformation (cam0):

T_ci: (imu0 to cam0):
[[ 0.99998278 0.00492281 0.00319431 -0.07110804]
[-0.00486584 0.9998332 -0.01760385 0.009218 ]
[-0.00328044 0.017588 0.99983994 -0.05973258]
[ 0.0.0.1.]]
T_ic: (cam0 to imu0):
[[ 0.99998278 -0.00486584 -0.00328044 0.07095572]
[ 0.00492281 0.9998332 0.017588 -0.00781583]
[ 0.00319431 -0.01760385 0.99983994 0.06011244]
[ 0.0.0.1.]]
timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
0.467116630307

@vik748
Copy link

vik748 commented Nov 30, 2017

@rising-turtle Thanks for the response, I will try out these tips and provide feedback.

@goldbattle
Copy link
Collaborator

Closing due to age, please reopen if still an issue.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
user-platform User has trouble running on their own dataset
Projects
None yet
Development

No branches or pull requests

4 participants