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

how to use scale-misalignment result? #189

Closed
Neil-Oyoung opened this issue May 24, 2018 · 8 comments
Closed

how to use scale-misalignment result? #189

Neil-Oyoung opened this issue May 24, 2018 · 8 comments
Labels
question Theory or implementation question

Comments

@Neil-Oyoung
Copy link

Hello, after I used kalibr_calibrate_imu_camera with scale-misalignment option, I got following result.
Do anyone know how to use M, A or C_gyro_i to correct IMU raw measurements ?

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

IMU0:
----------------------------
  Model: scale-misalignment
  Update rate: 500
  Accelerometer:
    Noise density: 0.039813853765 
    Noise density (discrete): 0.890264834649 
    Random walk: 0.00347566152835
  Gyroscope:
    Noise density: 0.00861190257109
    Noise density (discrete): 0.192567995646 
    Random walk: 0.000577879736374
  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]
  Gyroscope: 
    M:
      [[ 0.99732203  0.          0.        ]
       [ 0.00373207  0.99372249  0.        ]
       [-0.00218998 -0.00186741  0.99919668]]
    A [(rad/s)/(m/s^2)]:
      [[-0.00075474  0.00162226  0.00019704]
       [-0.00346093 -0.00023962 -0.00694434]
       [-0.00216607  0.00254173  0.00037087]]
    C_gyro_i:
      [[ 0.99999949  0.00071135  0.00071417]
       [-0.00071004  0.99999806 -0.00183835]
       [-0.00071547  0.00183784  0.99999806]]
  Accelerometer: 
    M:
      [[ 0.98064672  0.          0.        ]
       [-0.01260154  1.01224075  0.        ]
       [-0.01087295  0.00237432  1.00600802]]
@QingfengLi-hit
Copy link

reference paper Extending kalibr: Calibrating the Extrinsics of Multiple IMUs and of Individual Axes

@AmosLewis
Copy link

reference paper Extending kalibr: Calibrating the Extrinsics of Multiple IMUs and of Individual Axes

The paper doesnot explain it well. If the M here is M or S*M, weather it contains scale in it or not?

@arenas7307979
Copy link

same question, How to correct misalignment and scale through these parameters

@mhyoosefian
Copy link

mhyoosefian commented Nov 25, 2021

Although this issue is for a long time ago, I put the answer here, for future reference:

Say you have a set of raw measurements:
, .
From the Kalibr you have gyroscope misalignment and g-sensitivity matrices:
,
, accelerometer misalignment matrix:

, and the rotation matrix from accelerometer frame to gyroscope frame:
.
Firstly, you have to transfer gyroscope reading to the accelerometer coordinate frame (i.e., the body frame):
.
Next, you apply the matrices using the following formulas:


These are the new (i.e., the corrected) measurements.
Although these formulas are obtainable from the reference paper, to be over-sure (!), after calibrating my setup, I have corrected the calibration measurements and reran the Kalibr using the corrected measurements. The new matrices were so close to their ideal values (Identity for misalignments and Zero for g-sensitivity). However, I recommend you doing the same and report any issues!

Regards,
Mohammad

@goldbattle
Copy link
Collaborator

This paper has details of the different models:
https://timohinzmann.com/publications/icra_2016_rehder.pdf

For example you can see the following:
image

Additionally one can inspect the code to compare:
https://github.com/ethz-asl/kalibr/blob/master/aslam_offline_calibration/kalibr/src/GyroscopeError.cpp#L70-L73

This paper also has some background details if you want to further research:
https://roboticsconference.org/2020/program/papers/26.html

@sgraybi
Copy link

sgraybi commented Apr 4, 2023

After working through the paper, the code, and the output yaml files I'm still not certain that I have the correct formulation to correct raw accelerometer and raw gyro measurements. It's not trivial to reconcile the three as they use different notations. A small error in applying the calibration may not be easily detectable in the calibrated result. The text below aims to reconcile the notation between the paper and the Kalibr output yaml files. The notation below should match the paper. @goldbattle please verify for correctness.

Coordinate frames

$B$: body frame
$W$: world/calibration board frame
$A$: IMU frame
$C$: Camera frame

Coordinate frame transformation

$C_{XY}$ denotes the direction cosine matrix, rotation matrix, that rotates a vector from frame $Y$ to frame $X$, i.e., $x_X = C_{XY} x_Y$

Parameter definition from Kalibr IMU calibration file

Let's define the parameters in the XXX-imu.yaml files as follows:

$C^\alpha_{AB}\equiv$ T_i_b (4x4 double matrix) [Pose matrix that transforms an accelerometer measurement in the body frame, $B$, to the IMU frame, $A$.]

$S_{\alpha}M_{\alpha} \equiv$ accelerometers.M [1] (3x3 lower triangular double matrix) [Applies the accelerometer scale factor and misalignment correction.]

$A_{\omega} \equiv$ gyroscopes.A [rad.s^-1 / (m.s^{-2})] (3x3 double matrix) [Effect of linear accelerations on gyroscopes.]

$C^{\omega}_{AB} \equiv$ gyroscopes.C_gyro_i [1] (3x3 double matrix) [Rotation matrix that rotates a gyroscope measurement in the body frame, $B$, to the IMU frame, $A$.]

$S_{\omega}M_{\omega} \equiv$ gyroscopes.M [1] (3x3 lower triangular double matrix) [Applies the gyroscope scale factor and misalignment correction.]

Parameter definition from Kalibr camera calibration file

Let's define the parameter in the XXX-camchain-imucam.yaml files as follows:

$C_{CA} \equiv$ cam0.T_cam_imu (4x4 double matrix) [Pose matrix that transforms a vector in the IMU frame, $A$, to the camera frame, $C$.]

How to apply intrinsic calibration

Let's denote the uncalibrated, raw, accelerometer and gyroscope measurements as $\alpha$ and $\omega$, respectively. The calibrated accelerometer and gyroscope measurements in the body frame, $B$, are then given by:

$$ \alpha_A= (S_\alpha M_\alpha)^{-1} (\alpha - b_\alpha)$$

$$ \omega_A= (S_\omega M_\omega)^{-1} (\omega -A_\omega \alpha_A - b_\omega)$$

$$ \alpha_B = (C^{\alpha}_{AB})^{T} \alpha_A$$

$$ \omega_B = (C^{\omega}_{AB})^{T} \omega_A$$

Note well, $b_\alpha$ and $b_\omega$ are the accelerometer and gyroscope biases. These parameters are NOT stored in the IMU or camera yaml files but are included here for completeness.

Using the same notation and parameters as the yaml files

$\alpha_A = ($ accelerometers.M $)^{-1} \alpha$

$\omega_A = ($ gyroscopes.M $)^{-1}(\omega -$ gyroscopes.A $\alpha_A)$

$\alpha_B = ($ T_i_b $)^{T} \alpha_A$

$\omega_B = ($ gyroscopes.C_gyro_i $)^{T} \omega_A$

The accelerometer and gyro biases are not applied here as they are not stored in the yaml files.

How to apply extrinsic calibration

For some applications the IMU measurement needs to be rotated into the camera frame, $C$. This can be done using:

$\alpha_C = C_{CA}\alpha_A =$ cam0.T_cam_imu $\alpha_A$

$\omega_C = C_{CA}\omega_A =$ cam0.T_cam_imu $\omega_A$

Note well that this is only true in the static case for the accelerometer. See equations (1), (2), and (5) from paper for the dynamic case.

KalibrHowToApplyCalibration.md

@cai199626
Copy link

cai199626 commented Apr 7, 2023

Using the same notation and parameters as the yaml files

αA=(accelerometers.M)−1α

ωA=(gyroscopes.M)−1(ω−gyroscopes.AαA)

αB=(T_i_b)TαA

ωB=(gyroscopes.C_gyro_i)TωA

@sgraybi thanks for your answer, but your formulas are not equal to @mhyoosefian above, I do not know who is right...

@sgraybi
Copy link

sgraybi commented Apr 7, 2023

@cai199626 yes. We need @goldbattle, or another expert to review. Intuitively, you would apply the intrinsics before the extrinsics, like in my correction equations. Intuitively, you would also correct the accelerometer measurement before it's used to correct the effect of linear accelerations on gyroscopes. I believe the mathematical formulation supports these intuitions also.

I'm don't quite understand how other people know how to apply the model. Kalibr seems to be quite widely used.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
question Theory or implementation question
Projects
None yet
Development

No branches or pull requests

8 participants