The article adapt the method of reconstructing images through E2vid for intrinsic calibration of event camera. Here, we used dvs346 as an example to demonstrate the results of the event camera calibration process, and verified the effectiveness of the method by comparing the image and event calibration results
rosbag record /capture_node/camera/image /capture_node/events /capture_node/imu -O out.bag
--/capture_node/camera/image image topic
--/capture_node/events events topic
--/capture_node/imu imu topic
--out.bag file name
Using Kalibr or MATLAB (requires exporting images from rosbag)
Go to Kalibr's official website to install according to the tutorial, link: https://github.com/ethz-asl/kalibr
Enter the Kalibr workspace and run the following instructions (You may need to first source dev/setup. bash)
rosrun kalibr kalibr_calibrate_cameras --bag out.bag --topics /capture_node/camera/image --models pinhole-radtan --target checkerboard.yaml
--bag rosbag package
--topics image topic
--models image model
--target checkerboard parameters
result:
cam0:
cam_overlaps: []
camera_model: pinhole
distortion_coeffs: [-0.38176694245439546, 0.14885485907996424, 3.70127391038794e-05, -0.00017056761391653452]
distortion_model: radtan
intrinsics: [252.37893909717883, 252.40414164107983, 173.4386346201833, 120.19819514545445]
resolution: [346, 260]
rostopic: /capture_node/camera/image
First, start a terminal to run the roscore node
roscore
The instructions for the three terminals are (run in sequence):
Reduce frequency:
rosrun topic_tools throttle messages /capture_node/camera/image 4.0 /image_raw
--/capture_node/camera/image topic that need to be reduced in frequency
--/image_raw topic name after reducing frequency
Record the image and imu after reducing the frequency:
rosbag record /image_raw /capture_node/imu -O sample.bag
--/image_raw record the image topic with IMU after reducing the frequency
Play rosbag package containing topics that require frequency reduction:
rosbag play out.bag
This will result in a rosbag containing a 4Hz frequency image and IMU data
refer to:Link
Export images as shown in Figure 4:
Import the exported image into the Matlab Camera Calibrator toolbox and click on Calibrate above for calibration:
Identify the images that cause significant reprojection errors and delete them
Export Camera Parameters
The calibrated camera internal parameters are located in the work area, and the calibration results of intrinsics are shown in the following figure:
For event camera Intrinsics we use the e2vid reconstruction method to reconstruct image frames for calibration
For specific methods, please refer to the Event Reconstruction Image in the webpage tools: (Link).
Through e2vid, reconstructed images can be generated, and Python code can be run to convert the images into rosbag for calibration. The conversion code link is: https://github.com/ERGlab/M3DSS/blob/main/html/Calibration/Event_Camera_Intrinsics/dvs346/event/kalibr/images_to_rosbag.py.
python images_to_rosbag.py --rosbag_folder /img_out --image_folder /e2calib --image_topic /dvs/image_reconstructed
--rosbag_folder rosbag output folder
--image_topic the topic of reconstruction images
At this point, a rosbag package for event reconstruction images can be obtained,
which can be calibrated using the Kalibr calibration method mentioned above. The results are shown in Figure 9:
Note: Using reconstructed images for Kalibr calibration may result in abnormal distortion. The above calibration is normal, but during multiple calibrations, abnormal distortion may occur as shown in Figure 11
According to the reconstructed image, calibrate it in the Matlab toolbox, following the same steps as the image intrinsic calibration using Matlab. The results are shown in Figure 12:
The calibration results are as follows:
(1)kalibr results
Intrinsics based on images
k : [ 252.3789391 252.40414164 173.43863462 120.19819515]
d : [-0.38176694 0.14885486 0.00003701 -0.00017057]
Intrinsics based on events
k : [ 253.84773123 253.88799685 174.01053551 123.19547128]
d : [-0.38261608 0.14698837 -0.00143755 -0.00033804]
(2)Matlab results
Intrinsics based on images:
k : [ 254.0247 253.9952 173.8491 121.3679]
d : [-0.3912 0.1596 0 0]
Intrinsics based on events
k : [ 253.6016 253.6231 174.1880 121.6994]
d : [-0.3908 0.1590 0 0]
Comparing the above calibration results, it can be found that the events using the intrinsics calibration method are similar to the image calibration results, which can be extended to event cameras without images (such as dvexplorer), However, attention should be paid to the issue of abnormal distortion in the Kalibr calibration and reconstruction images.