M3DSS-dataset

Camera_and_IMU_Extrinsic

Kang Xu

Abstract

In the extrinsic calibration of cameras and IMU, there is no significant difference between event cameras and traditional cameras, mainly in the process of obtaining calibration packages, Taking dvxplorer and FLIR BFLY-U3-23S3C cameras as examples, this paper introduces the external calibration process and results of event cameras and traditional cameras with imu using kalibr.

Procession

1、Record rosbag package

When recording, be sure to move as smoothly as possible, not too fast or too slow, and fully motivate the IMU

(1)Event cameras

i.Record topics

Record the topic corresponding to the IMU and event camera, as shown in Figure 1:

Image description
Fig. 1. dvx event and imu
ii.rosbag package process

Using the rosbag editor (please refer to:Link) Separate the recorded package above into rosbag packages that only contain IMU messages and event messages. The latter is used for image reconstruction, and the specific method can be found in the Event Reconstruction Image in the webpage tools (Link). After obtaining the reconstructed image, run Python code to convert the image into ROSBAG. The conversion code link is: https://github.com/ERGlab/M3DSS/blob/main/html/Calibration/Event_Camera_Intrinsics/dvs346/event/kalibr/images_to_rosbag.py.

iii.Merge rosbag package

Merge the separated rosbag package containing only IMU messages with the ROSBAG package of the reconstructed image. For specific methods, please refer to the Data pre process in the webpage tools (Link). By following the above steps, the rosbag package for event camera and IMU external parameter calibration can be obtained

Image description
Fig. 2. dvx reconstruction images 与 imu

(2)Traditional cameras

Traditional cameras can directly record to obtain rosbag packages for calibration.

Image description
Fig. 3. traditional camera and imu

2、Kalibr Calitration

Enter the Kalibr workspace and run the following instructions (You may need to first source dev/setup. bash)

rosrun kalibr kalibr_calibrate_imu_camera --target checkerboard.yaml --bag image_imu.bag --cam camera.yaml --imu imu.yaml --imu-models scale-misalignment

--target Some parameters of the calibration board should be noted that there are differences between horizontal and vertical parameters
--bag rosbag package containing IMU messages and image messages
--cam Camera intrinsics file (see Event_Camera_Intrinsics and Standard_Camera_Intrinsics for obtaining methods)
--imu IMU intrinsics file (see IMU_Intrinsic_Calibration for the method of obtaining)
--imu-models imu model

Results:

Event Camera:
cam0:
T_cam_imu:
- [0.9997422588222811, -0.02001746287604113, 0.01071060712234844, -0.06221593621272268]
- [0.01029935593289703, -0.02053601067811628, -0.9997360629350108, -0.051090683104806286]
- [0.020232132667874752, 0.9995887021397524, -0.020324550727504498, -0.39893710199304666]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: []
camera_model: pinhole
distortion_coeffs: [-0.392284303511741, 0.197170640598008, 0, 0]
distortion_model: radtan
intrinsics: [564.876270222055, 562.715380641741, 346.856114369583, 265.341885433265]
resolution: [640, 480]
rostopic: /ex2_dvx_left_reconstruction_image
timeshift_cam_imu: 0.9604708226887384
Traditional camera:
cam0:
T_cam_imu:
- [0.9998698145365037, -0.006122574459816224, 0.014928766215645779, 0.04356622890941122]
- [0.014809180352380559, -0.0191330654913891, -0.9997072641439556, -0.02204373277280234]
- [0.006406415224450121, 0.9997981995817385, -0.01903990433499364, -0.14281966654391087]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: []
camera_model: pinhole
distortion_coeffs: [-0.146017223858946, 0.082234840924577, 0, 0]
distortion_model: radtan
intrinsics: [1068.42870237679, 1064.36748532345, 953.624929519216, 607.201198303378]
resolution: [1920, 1200]
rostopic: /camera_left/image_raw
timeshift_cam_imu: -0.021772368032966484
Image description
Fig. 4. Dvx reconstruction images and imu calibration of reprojection error
Image description
Fig. 5. Images and imu calibration of reprojection error

Conclusion

To verify the effectiveness of the event based camera reconstruction image and imu external parameter calibration scheme, we selected a dvs346 camera with both images and events, and used the same camera to participate in imu internal parameter acquisition and calibration After the package is packaged, the images and event reconstruction images are externally calibrated with IMU in Kalibr. The results are as follows:

dvs346 reconstruction image:
T_cam_imu:
- [-0.99944484 -0.02962565 -0.01524232 -0.00201907]
- [-0.02977555 0.99950951 0.00970351 0.00829386]
- [0.01494737 0.01015197 -0.99983674 -0.07010229]
- [0.0, 0.0, 0.0, 1.0]
dvs346 image:
T_cam_imu:
- [-0.99950297, -0.02744539, -0.01551036, -0.00220836]
- [-0.0275675, 0.99959018, 0.00771412, 0.00733739]
- [0.01529229, 0.00813787, -0.99984995, -0.0678873]
- [0.0, 0.0, 0.0, 1.0]
Image description
Fig. 6. Reconstructed images from dvs346 and reprojection errors calibrated with imu
Image description
Fig. 7.Images from dvs346 and reprojection errors calibrated with imu
From the above results, it can be seen that the Rotation matrix calibrated by the two images is basically identical, and the translation error is millimeter level, which is within the acceptable range of error, indicating that the result of external parameter calibration using the reconstructed image is reliable