Kimera-VIO-ROS
Kimera-VIO-ROS copied to clipboard
RealSense calibration with Kalibr
Hello - I'm working on getting Kimera running with a RealSense D435i, following the hardware setup instructions. I've run Kalibr calibration for the left and right cameras on the RealSense, and gotten a camchain.yaml file which I'll paste below.
I'm not sure how to convert this into the Kimera format (e.g. Kimera-VIO/params/RealSenseIR/LeftCameraParams.yaml and RightCameraParams.yaml). I've looked at config2kimeravio.py as suggested by the instructions, but this script seems to require an IMU calibration file as well. Is it required to also calibrate the IMU using Kalibr, or is there something else I'm missing?
Thanks for your work releasing and supporting this code! Brian
Here are the contents of the camchain.yaml file outputted by Kalibr:
cam0:
cam_overlaps: [1]
camera_model: pinhole
distortion_coeffs: [0.3209965194308784, 0.8070591908434555, -2.9447705598973335,
3.8238784975539826]
distortion_model: equidistant
intrinsics: [393.992543431021, 392.8544350474975, 319.018468455671, 243.3671252772004]
resolution: [640, 480]
rostopic: /camera/infra1/image_rect_raw
cam1:
T_cn_cnm1:
- [0.9999851461535377, 0.00023630422730915455, 0.005445331264508205, -0.048195085165018095]
- [-0.00023563891196742644, 0.9999999646945043, -0.0001228221224057136, -1.470629712559274e-05]
- [-0.00544536009564487, 0.00012153716609029549, 0.9999851665310473, -0.0005490088828873391]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0]
camera_model: pinhole
distortion_coeffs: [0.46531388970311016, -1.2269602724399762, 7.172420924475765,
-12.274713687690216]
distortion_model: equidistant
intrinsics: [392.55726805499006, 391.3853067072748, 317.03442389767497, 242.9937460456073]
resolution: [640, 480]
rostopic: /camera/infra2/image_rect_raw
Hi Brian,
Glad to hear! A brief reminder that the existing params should work reasonably well for any d435i. That said, calibration with your specific camera may give you accuracy gains. You do need the IMU calibration, as Kimera uses both stereo images and IMU data. The second half of the video on the Kalibr github page walks you through how to feed the camchain into Kalibr to generate the IMU camchain. If you follow the video all the way through, you will have all the parameters you need.
config2kimeravio.py
is, unfortunately, a legacy script as the Kimera parameter format changed pretty significantly since it was written. Camera/IMU calibration parameters are in LeftCameraParams.yaml, RightCameraParams.yaml, and ImuParams.yaml in the Kimera-VIO/params/RealSenseIR folder. They match nearly one-to-one with the parameters generated by the kalibr_calibrate_imu_camera
script. You will need some IMU noise parameters to do the second half of the calibration; estimates for these can be found in the ImuParams.yaml above.
When you replace the existing calibration parameters, I recommend you start by copying the existing RealSenseIR folder into another RealSenseIR2 folder to maintain the expected param folder layout. Note that these parameter folders are in Kimera-VIO, not Kimera-VIO-ROS. You tell Kimera where to find your parameters by setting the dataset_name to the name of your parameter folder, which in turn sets the params_folder arg. You can move the parameters to an arbitrary folder by setting params_folder
yourself, but this is not recommended.
Hi Brian,
Glad to hear! You do need the IMU calibration, as Kimera uses both stereo images and IMU data. The second half of the video on the Kalibr github page walks you through how to feed the camchain into Kalibr to generate the IMU camchain. If you follow the video all the way through, you will have all the parameters you need.
config2kimeravio.py
is, unfortunately, a legacy script as the Kimera parameter format changed pretty significantly since it was written. Camera/IMU calibration parameters are in LeftCameraParams.yaml, RightCameraParams.yaml, and ImuParams.yaml in the Kimera-VIO/params/RealSenseIR folder. They match nearly one-to-one with the parameters generated by thekalibr_calibrate_imu_camera
script. You will need some IMU noise parameters to do the second half of the calibration; estimates for these can be found in the ImuParams.yaml above.When you replace the existing calibration parameters, I recommend you start by copying the existing RealSenseIR folder into another RealSenseIR2 folder to maintain the expected param folder layout. Note that these parameter folders are in Kimera-VIO, not Kimera-VIO-ROS. You tell Kimera where to find your parameters by setting the dataset_name to the name of your parameter folder, which in turn sets the params_folder arg. You can move the parameters to an arbitrary folder by setting
params_folder
yourself, but this is not recommended.
Hi @violetteavi, In the hardware setup: https://github.com/MIT-SPARK/Kimera-VIO-ROS/blob/master/docs/hardware_setup.md you said that you already collected the calibration parameters for the D435i, why we need to do it again? is it needed for every new D435i?
I'm talking about this section:
- Collect calibration parameters for the RealSense. This is already done for the D435i in VIO's params/RealSenseIR.
Collect calibration bagfiles for camera intrinsics and extrinsics (see instructions). Calibrate camera intrinsics and extrinsics using Kalibr Convert the intrinsics and extrinsics to configuration files for Kimera-VIO-ROS wrapper using Kalibr2KimeraVIO-pinhole-radtan.
Correct! The calibration parameters given should work reasonably well with any d435i. That said, each camera is a little different— you may see an accuracy boost if you recalibrate to your specific camera.
If there is a lot of interest in this, I can add a more detailed guide for transferring the results of the Kalibr calibration into the Kimera parameters. Would that be useful to you?
Correct! The calibration parameters given should work reasonably well with any d435i. That said, each camera is a little different— you may see an accuracy boost if you recalibrate to your specific camera.
If there is a lot of interest in this, I can add a more detailed guide for transferring the results of the Kalibr calibration into the Kimera parameters. Would that be useful to you?
Yes I would be happy to get something like this! thanks!
If there is a lot of interest in this, I can add a more detailed guide for transferring the results of the Kalibr calibration into the Kimera parameters. Would that be useful to you?
+1 :rocket: :smile:
Thanks for the very helpful response and sorry for the slow reply! I ran the Kalibr IMU-camera calibration, using the IMU parameters from the included ImuParams.yaml fil. I then converted the Kalibr camchain file (with IMU-camera calibration results) to get LeftCameraParams.yaml and RightCameraParams.yaml, using a script I wrote which you can find here. I'll attach my camera parameters files below.
I'm able to start up Kimera VIO and Semantics (for metric mapping only) in ROS, using these camera parameters, but when using Kimera on a ~60 second rosbag I recorded outdoors using a RealSense D435i, VIO crashes with an error in undistortRectifyPoints. This happens consistently 20-25 seconds into playing the bag. I don't get a crash using the provided default parameters. I'm not sure if I might have converted the Kalibr params to Kimera format incorrectly, or if there was something wrong with my calibration - can you help with this? Let me know if it would also be helpful to have the bag file. Thanks very much!
Here's the error message I get:
----------- # Hz (avg +- std ) [min,max]
Data Provider [ms] 0
IMU Preintegration Timing [us] 690 29.7702 (40.8522 +- 11.4069) [20,247]
Mesher [ms] 107 4.64836 (17.3084 +- 10.4737) [6,49]
VioBackEnd [ms] 108 4.65512 (26.2407 +- 13.561) [0,80]
VioFrontEnd [ms] 689 29.5923 (22.5617 +- 33.5856) [3,164]
Visualizer [ms] 107 4.64603 (13.0561 +- 3.97338) [7,29]
F0518 21:09:48.494928 24125 StereoFrame.cpp:369] undistortRectifyPoints: versor with zero depth
*** Check failure stack trace: ***
@ 0x7f9acfb89b0d google::LogMessage::Fail()
@ 0x7f9acfb8b9b1 google::LogMessage::SendToLog()
@ 0x7f9acfb8963d google::LogMessage::Flush()
@ 0x7f9acfb8c389 google::LogMessageFatal::~LogMessageFatal()
@ 0x7f9ac84434c9 VIO::StereoFrame::undistortRectifyPoints()
@ 0x7f9ac8444e6f VIO::StereoFrame::sparseStereoMatching()
@ 0x7f9ac8451748 VIO::StereoVisionFrontEnd::processStereoFrame()
@ 0x7f9ac8452bfd VIO::StereoVisionFrontEnd::spinOnce()
@ 0x7f9ac845b25d VIO::PipelineModule<>::spin()
@ 0x7f9ace7c36df (unknown)
@ 0x7f9acdee56db start_thread
@ 0x7f9ace21e88f clone
[kimera_vio_ros/kimera_vio_ros_node-1] process has died [pid 24055, exit code -6, cmd /home/brian/kimera_ws/devel/lib/kimera_vio_ros/kimera_vio_ros_node --use_lcd=false --vocabulary_path=/home/brian/kimera_ws/src/Kimera-VIO/vocabulary/ORBvoc.yml --flagfile=/home/brian/kimera_ws/src/Kimera-VIO/params/RealSenseIR/flags/Mesher.flags --flagfile=/home/brian/kimera_ws/src/Kimera-VIO/params/RealSenseIR/flags/VioBackEnd.flags --flagfile=/home/brian/kimera_ws/src/Kimera-VIO/params/RealSenseIR/flags/RegularVioBackEnd.flags --flagfile=/home/brian/kimera_ws/src/Kimera-VIO/params/RealSenseIR/flags/Visualizer3D.flags --logtostderr=1 --colorlogtostderr=1 --log_prefix=1 --v=0 --log_output=false --log_euroc_gt_data=false --output_path=/home/brian/kimera_ws/src/Kimera-VIO-ROS/output_logs/ --viz_type=0 --visualize=true left_cam/image_raw:=/camera/infra1/image_rect_raw right_cam/image_raw:=/camera/infra2/image_rect_raw imu:=/camera/imu left_cam/camera_info:=/cam0/camera_info right_cam/camera_info:=/cam1/camera_info reinit_flag:=reinit_flag reinit_pose:=reinit_pose odometry:=odometry resiliency:=resiliency imu_bias:=imu_bias optimized_trajectory:=optimized_trajectory pose_graph:=pose_graph mesh:=mesh frontend_stats:=frontend_stats debug_mesh_img/image_raw:=debug_mesh_img/image_raw feature_tracks/image_raw:=feature_tracks/image_raw time_horizon_pointcloud:=time_horizon_pointcloud __name:=kimera_vio_ros_node __log:=/home/brian/.ros/log/74e7d8fc-994d-11ea-9ce4-c8f750384bc6/kimera_vio_ros-kimera_vio_ros_node-1.log].
log file: /home/brian/.ros/log/74e7d8fc-994d-11ea-9ce4-c8f750384bc6/kimera_vio_ros-kimera_vio_ros_node-1*.log
^C[velo_link_broadcaster-3] killing on exit
[kimera_vio_ros/posegraph_viewer-2] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done
Here is my LeftCameraParams.yaml file:
%YAML:1.0
# Converted from Kalibr format by kalibr2kimera.py
# General sensor definitions.
camera_id: left_cam
# Sensor extrinsics wrt. the body-frame.
T_BS:
cols: 4
rows: 4
data: [0.9605716727207227, -0.018375782904855604, -0.2774245702333278, -0.0784215131187792,
0.02563926013322598, 0.9994162934698905, 0.02257655170141823, 0.02561235334080471,
0.2768477738872642, -0.028799356755657896, 0.9604821222407666, 0.021345820593799098,
0.0, 0.0, 0.0, 1.0]
# Camera specific definitions.
rate_hz: 30
resolution: [640, 480]
camera_model: pinhole
intrinsics: [392.55726805499006, 391.3853067072748, 317.03442389767497, 242.9937460456073]
distortion_model: equidistant
distortion_coefficients: [0.46531388970311016, -1.2269602724399762, 7.172420924475765,
-12.274713687690216]
Here is my RightCameraParams.yaml file:
%YAML:1.0
# Converted from Kalibr format by kalibr2kimera.py
# General sensor definitions.
camera_id: right_cam
# Sensor extrinsics wrt. the body-frame.
T_BS:
cols: 4
rows: 4
data: [0.9590438271087344, -0.018454188453736156, -0.28265594034646857, -0.030351242938224773,
0.025899893668793444, 0.9994084157176268, 0.02262772858085408, 0.025622577135979204,
0.282071149167329, -0.029021742216786342, 0.9589544333732053, 0.021726764217406616,
0.0, 0.0, 0.0, 1.0]
# Camera specific definitions.
rate_hz: 30
resolution: [640, 480]
camera_model: pinhole
intrinsics: [393.992543431021, 392.8544350474975, 319.018468455671, 243.3671252772004]
distortion_model: equidistant
distortion_coefficients: [0.3209965194308784, 0.8070591908434555, -2.9447705598973335,
3.8238784975539826]
Also - agree that a guide on calibration would be very useful. Thanks!
Any update regarding the guide?