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

Kalibr Extrinsic parameters between IMU and Camera #436

Open
alperodabasi opened this issue Sep 6, 2023 · 3 comments
Open

Kalibr Extrinsic parameters between IMU and Camera #436

alperodabasi opened this issue Sep 6, 2023 · 3 comments

Comments

@alperodabasi
Copy link

Hi,

I am using D435i for camera and IMU.
I used Kalibr for calculate extrinsic parameters between IMU and Camera.

Kalibr Results are belew:
Calibration results

Normalized Residuals

Reprojection error (cam0): mean 0.228997030901, median 0.191416620057, std: 0.16113606739
Gyroscope error (imu0): mean 1.80273207259, median 1.41933925519, std: 1.41959071786
Accelerometer error (imu0): mean 1.9661515366, median 1.47889525633, std: 1.81360494159
Residuals

Reprojection error (cam0) [px]: mean 0.228997030901, median 0.191416620057, std: 0.16113606739
Gyroscope error (imu0) [rad/s]: mean 0.00444238022651, median 0.00349760496186, std: 0.00349822462841
Accelerometer error (imu0) [m/s^2]: mean 0.0313104143646, median 0.02355099412, std: 0.0288811524228
Transformation (cam0):

T_ci: (imu0 to cam0):
[[ 0.99994418 -0.00621841 0.00854216 0.00722463]
[ 0.00616542 0.99996168 0.00621569 -0.0021275 ]
[-0.00858049 -0.00616268 0.9999442 -0.0188065 ]
[ 0. 0. 0. 1. ]]
T_ic: (cam0 to imu0):
[[ 0.99994418 0.00616542 -0.00858049 -0.00737248]
[-0.00621841 0.99996168 -0.00616268 0.00205644]
[ 0.00854216 0.00621569 0.9999442 0.01875696]
[ 0. 0. 0. 1. ]]

timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
0.000504146910849
Gravity vector in target coords: [m/s^2]
[-0.04110426 -9.80612558 0.08145265]

Now i have some questions how to update parameters in "euroc_config.yaml"
Kalibr results are T_ci(imu0 to cam0) and T_ic(cam0 to imu0) and these tables are [4x4]

At euroc_config.yaml there are 2 matrix
1-extrinsicRotation 3x3
2-extrinsicTranslation 3x1

i will be very pleased if anybody tell me how to fill the euroc_config.yaml tables according Kalibr results.
Thanks all.
Alper.
@xuhao1
@shaojie
@qintonguav

@omeredemen
Copy link

omeredemen commented Mar 22, 2024

T_ic and T_ci matrices involve your extrinsic rotation and translation matrices. I think the cam0 to imu0 matrix should be written on the yaml file
image

in this matrices, the first three column represent rotation matrix (extrinsicRotation 3x3) and the last column represents transtlation matrix(extrinsicTranslation 3x1)

@SerpentWindy
Copy link

T_ic and T_ci matrices involve your extrinsic rotation and translation matrices. I think the cam0 to imu0 matrix should be written on the yaml file image

in this matrices, the first three column represent rotation matrix (extrinsicRotation 3x3) and the last column represents transtlation matrix(extrinsicTranslation 3x1)

I have doubts about this. Taking the Euroc dataset as an example. Using the conversion tool in https://www.andre-gaschler.com/rotationconverter/, we can calculate the pose angle of the rotation matrix corresponding to the ZYX order in the Euroc dataset as (x: 0.2 °, y: 1.5 °, z: 89.1 °). The camera and IMU coordinate axis in Euroc can be viewed in the official website images, as shown below.
image
In the figure, it can be seen that cam0 to imu0 represents a Z-axis rotation of -90 °, while imu0 to cam0 represents a Z-axis rotation of+90 °. This is inconsistent with the description of "# Rotation from camera frame to imu frame, imu ^ R_cam" in VINS yaml, so I would like to ask for your opinion.

@SerpentWindy
Copy link

T_ic and T_ci matrices involve your extrinsic rotation and translation matrices. I think the cam0 to imu0 matrix should be written on the yaml file image
in this matrices, the first three column represent rotation matrix (extrinsicRotation 3x3) and the last column represents transtlation matrix(extrinsicTranslation 3x1)

I have doubts about this. Taking the Euroc dataset as an example. Using the conversion tool in https://www.andre-gaschler.com/rotationconverter/, we can calculate the pose angle of the rotation matrix corresponding to the ZYX order in the Euroc dataset as (x: 0.2 °, y: 1.5 °, z: 89.1 °). The camera and IMU coordinate axis in Euroc can be viewed in the official website images, as shown below. image In the figure, it can be seen that cam0 to imu0 represents a Z-axis rotation of -90 °, while imu0 to cam0 represents a Z-axis rotation of+90 °. This is inconsistent with the description of "# Rotation from camera frame to imu frame, imu ^ R_cam" in VINS yaml, so I would like to ask for your opinion.

Okay, I understand now.In the figure, cam0 to imu0 represents a Z-axis rotation of +90 °, while imu0 to cam0 represents a Z-axis rotation of-90 °.

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

No branches or pull requests

3 participants