MIT-SPARK / Kimera-VIO

Visual Inertial Odometry with SLAM capabilities and 3D Mesh generation.
BSD 2-Clause "Simplified" License
1.56k stars 418 forks source link

A question about using Kalibr calibration #221

Open roee-lulav opened 10 months ago

roee-lulav commented 10 months ago

Hi,

I'm trying to use Kimera with my own stereo-inertial system. I use Kalibr to calibrate the system, but seems to have trouble using this calibration as Kimera params. I'll be gratefull if you can make sense of this, or instruct me about the correct process (Sorry if this is a naive question).

I use Kalibr for calibration. First I let Kalibr calibrate the stereo cameras, and then I run the camera-IMU calibration. It seem calibration quality is reasonable. here are the camchain results (and the report is attached):

cam0:
  T_cam_imu:
  - [0.9999716025968234, 0.007536083730242084, 3.7973012641616903e-05, 0.0108651519009325]
  - [0.0075359432646419965, -0.9999674638941768, 0.002877622657443581, -6.921269167160957e-06]
  - [5.965778243819578e-05, -0.0028772547779639356, -0.9999958589143706, -0.009233353628607393]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [1]
  camera_model: pinhole
  distortion_coeffs: [0.016505831035777817, -0.012776480969926762, 0.0031973773556680535, 0.0004363594811094286]
  distortion_model: radtan
  intrinsics: [454.0197736242923, 453.8473536093487, 328.79611945947175, 248.33311077152317]
  resolution: [640, 480]
  rostopic: /camera/left/image_raw
  timeshift_cam_imu: 0.01028381753919678
cam1:
  T_cam_imu:
  - [0.9997744537833064, 0.0021638842783179724, 0.02112721389869831, -0.06397922951452535]
  - [0.0023130913812779395, -0.9999725405523516, -0.007040436743354743, -0.00021012881305586695]
  - [0.02111139906669287, 0.007087717975862903, -0.9997520057911069, -0.009287187714801477]
  - [0.0, 0.0, 0.0, 1.0]
  T_cn_cnm1:
  - [0.9997631722621214, 0.005431225836602889, -0.02107370812862414, -0.07503635165455318]
  - [-0.005223118444649479, 0.9999371769450766, 0.0099177213523427, -5.4884174970129624e-05]
  - [0.02112624959835002, -0.009805302087206142, 0.9997287320212848, -0.00028594657548777313]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0]
  camera_model: pinhole
  distortion_coeffs: [0.01791825434224609, -0.016760459290022168, 0.0014904938887851868, 0.001512018426513471]
  distortion_model: radtan
  intrinsics: [454.6029343586522, 454.60467575923786, 328.77040966412136, 244.93434878902355]
  resolution: [640, 480]
  rostopic: /camera/right/image_raw
  timeshift_cam_imu: 0.010157301849536133

I use the calibration results in the Kimera params (ImuParams.yaml, LeftCameraParams.yaml, RightCameraParams.yaml), but when I run Kimera, I get this error:

I1218 10:41:55.482234  8169 EurocDataProvider.cpp:89] Parsing Euroc dataset...
W1218 10:41:55.622618  8169 EurocDataProvider.cpp:741] Value for final_k, 10000 is larger than total number of frames in dataset 1341
W1218 10:41:55.622642  8169 EurocDataProvider.cpp:744] Using final_k = 1341
F1218 10:41:55.629426  8169 StereoCamera.cpp:76] Check failed: stereo_baseline_ > 0.0 (-0.0748447 vs. 0)

This also happens if I try to switch left and right cameras in the calibration. Am I doing something wrong? Do I need to convert Kalibr results in a specific way?

Here are my Kimera left camera parameters:

%YAML:1.0
# General sensor definitions.
camera_id: left_cam

# Sensor extrinsics wrt. the body-frame.
T_BS:
  cols: 4
  rows: 4
  data: [0.9999714666013159, 0.00755413386325996, -3.232320192801165e-05, 0.010406890812832878,
         0.007554191847297251, -0.9999681920570268, 0.0025591130759338473, -0.00013071217933279441,
         -1.2990291046624778e-05, -0.0025592842314086568, -0.9999967249423746, -0.009487547844787392,
         0.0, 0.0, 0.0, 1.0]

# Camera specific definitions.
rate_hz: 30
resolution: [640, 480]
camera_model: pinhole
intrinsics: [453.95543933447914, 453.77049354846196, 328.88751255525864, 248.2109867107653] #fu, fv, cu, cv
distortion_model: radial-tangential
distortion_coefficients: [0.01718375101348283, -0.013927588644694358, 0.0031311798734795135, 0.0004805675336608899]

And Kimera right camera parameters:

%YAML:1.0
# General sensor definitions.
camera_id: right_cam

# Sensor extrinsics wrt. the body-frame.
T_BS:
  cols: 4
  rows: 4
  data: [0.999777590845132, 0.0022025160458964826, 0.020974216718905415, -0.06442508066887512,
         0.0023542291155824267, -0.9999712264584765, -0.007211370216678955, -0.00034324707498098705,
         0.020957730057794593, 0.007259144453599805, -0.99975400893051, -0.009723957625997903,
         0.0, 0.0, 0.0, 1.0]

# Camera specific definitions.
rate_hz: 30
resolution: [640, 480]
camera_model: pinhole
intrinsics: [454.49128575319435, 454.45921712411433, 328.82003686929625, 244.87789267282753] #fu, fv, cu, cv
distortion_model: radial-tangential
distortion_coefficients: [0.018301316416890166, -0.017595730482422675, 0.0014356719201293936, 0.0015261238673996466]

2023-12-05-10-04-42-results-imucam.txt 2023-12-05-10-04-42-report-imucam.pdf

neliudochka commented 3 months ago

Hello! I have the same issue: Check failed: stereobaseline > 0.0 (-0.0949439 vs. 0) Did you find a way to solve it?

neliudochka commented 2 months ago

Go to the Kimera-VIO/src/frontend/StereoCamera.cpp On line 67, there is a comment: // Calc baseline (see L.2700 and L.2616 in // https://github.com/opencv/opencv/blob/master/modules/calib3d/src/calibration.cpp // NOTE: OpenCV pose convention is the opposite, therefore the missing -1.0

Therefore, on line 71, change 1 for -1: stereo_baseline_ = -1.0 / Q_.at<double>(3, 2); Then catkin build