参考视频
D435i标定摄像头和IMU笔记一(配置环境篇)
D435i标定摄像头和IMU笔记二(RGB摄像头标定篇)
D435i标定摄像头和IMU笔记二-2(RGB+双目多摄像头标定篇)
D435i标定摄像头和IMU笔记三(IMU标定篇)
D435i标定摄像头和IMU笔记四(RGB摄像头和IMU联合标定篇)
D435i标定摄像头和IMU笔记四-2(双目摄像头与IMU联合标定篇)
一、文件准备
- 创建一个文件夹保存校正数据
mkdir ~/calibr_data/mii-d435i/multi_camera_cali
cd ~/calib_data/mii-d435i/multi_camera_cali
- 建立标定yaml文件(同前):
touch checkerboard.yaml
内容为:
target_type: 'checkerboard' #gridtype
targetCols: 5 #number of internal chessboard corners
targetRows: 8 #number of internal chessboard corners
rowSpacingMeters: 0.045 #size of one chessboard square [m]
colSpacingMeters: 0.045 #size of one chessboard square [m]
二、标定准备
- 关闭结构光
参考:这里说的是默认开始结构光时,双目图像会有很多点,这些点可能对标定有影响,所以使用时需要关闭结构光。
注:一次性的,不用担心关了就会影响其他的。
1)启动realsense_ros
roslaunch realsense2_camera rs_camera.launch
2)打开设置
rosrun rqt_reconfigure rqt_reconfigure
将camera->stereo_module下的emitter_enable设置为off即可。
3)查看图像(可选,因为下一步也要看)
rviz
先把左上角的Fixed Frame设置为camera_link,然后左下角add>By topic>/infra1/imgage_rect_raw下双击camera。
关闭结构光前:
关闭结构光后:
- 查看RGB和双目视角
rviz
依次打开/camera/color/image_raw、/camera/infra1/image_rect_raw、/camera/infra2/image_rect_raw。打开方式同上。
- 录制rosbag
1)将图像发布频率降低到4Hz
rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /color
rosrun topic_tools throttle messages /camera/infra1/image_rect_raw 4.0 /infra_left
rosrun topic_tools throttle messages /camera/infra2/image_rect_raw 4.0 /infra_right
或者合一起
rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /color & rosrun topic_tools throttle messages /camera/infra1/image_rect_raw 4.0 /infra_left & rosrun topic_tools throttle messages /camera/infra2/image_rect_raw 4.0 /infra_right
如果是t265相机:
rosrun topic_tools throttle messages /camera/fisheye1/image_raw 4.0 /fisheye1 & rosrun topic_tools throttle messages /camera/fisheye2/image_raw 4.0 /fisheye2
2)开始录制
ctrl+c结束录制,-O为重命名包的名字,这里命名为mult_cam_d435i,-o会自动给名字后面添加时间
cd ~/calibr_data/mii-d435i/multi_camera_cali
rosbag record -O mult_cam_d435i /color /infra_left /infra_right
如果是t265:
rosbag record -O camer_t265 /fisheye1 /fisheye2
各个角度都录制两个来回就差不多了,移动不要太快。
三、开始标定
cd ~/calibr_data/mii-d435i/multi_camera_cali
kalibr_calibrate_cameras --target checkerboard.yaml --bag mult_cam_d435i.bag --models pinhole-radtan pinhole-radtan pinhole-radtan --topics /color /infra_left /infra_right
如果是t265:
kalibr_calibrate_cameras --target checkerboard.yaml --bag camer_t265.bag --models omni-radtan omni-radtan --topics /fisheye1 /fisheye2
老问题:OverflowError: bad numeric conversion: positive overflow
解决:重新录制。注意线材。
四、标定结果
生成了三个标定文件:
- camchain-mult_cam_d435i.yaml:摄像头标定结果参数
- results-cam-mult_cam_d435i.txt:标定结果和标定数据配置
- report-cam-mult_cam_d435i.pdf:可视化结果
camchain-mult_cam_d435i.yaml:
cam0:
cam_overlaps: [1, 2]
camera_model: pinhole
distortion_coeffs: [0.14666804337664086, -0.22145391026179087, 0.0012855284181247538,
-0.00010369581505594032]
distortion_model: radtan
intrinsics: [593.5669340597368, 593.6233357787834, 311.9915696187866, 244.07436963399235]
resolution: [640, 480]
rostopic: /color
cam1:
T_cn_cnm1:
- [0.9999060579801039, 0.006187309239286005, -0.012230797973450003, -0.012504540979490943]
- [-0.006157939420205711, 0.9999780689386636, 0.0024375035998556514, 0.00041303794737816035]
- [0.012245611327613627, -0.002361958102862696, 0.9999222300544849, 0.008441266367516128]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0, 2]
camera_model: pinhole
distortion_coeffs: [0.00590432014031773, -0.0038710343988133944, 0.002729676970436722,
0.0012954618097941984]
distortion_model: radtan
intrinsics: [380.9803345158986, 382.154386188639, 318.93609497258376, 243.05040693225402]
resolution: [640, 480]
rostopic: /infra_left
cam2:
T_cn_cnm1:
- [0.9999995420794539, -1.706596334366713e-05, 0.0009568435799698138, -0.050147210065992716]
- [1.631076929976035e-05, 0.9999996884030464, 0.0007892577334999778, 0.00018452290007793878]
- [-0.0009568567512638174, -0.0007892417652277561, 0.9999992307610014, 0.0006634244462778601]
- [0.0, 0.0, 0.0, 1.0]
cam_overlaps: [0, 1]
camera_model: pinhole
distortion_coeffs: [0.005132541874724565, -0.0023236481550731013, 0.0020455150943863563,
0.0007867398316885759]
distortion_model: radtan
intrinsics: [381.2139619547049, 382.4422285681291, 318.87898121166836, 242.8507951458829]
resolution: [640, 480]
rostopic: /infra_right