多目相机、Velodyne标定那些破事

0x01 制作标定板

0x02 相机标定

  • camera_calibration: 使用棋盘格进行标定;
  • kalibr: 这个感觉更专业一些,可以同时标多目和IMU。

0x03 雷达–>相机外参标定

目前我成功的有两种方法:

  • autoware_camera_lidar_calibrator : 不需要自制标定板,需要手动人工点击9个点
  • velo2cam_calibration : 全自动,需要定制一个标定板

3.1. autoware_camera_lidar_calibrator

(1)标定
使用这个工具要安装完整的Autoware,使用方法在这:https://blog.csdn.net/learning_tortosie/article/details/82347694

1
2
# 启动 velodyne(也可以直接从Autoware的Sensing面板打开)
roslaunch velodyne_pointcloud VLP16_points.launch calibration:=/home/s1nh/project/SLAM/velodyne/VLP-16.yaml
1
2
3
# 启动小觅相机
source ~/project/SLAM/mynt-eye-sdk-2-updated/wrappers/ros/devel/setup.bash
roslaunch mynt_eye_ros_wrapper mynteye.launch
1
2
启动标定程序
roslaunch autoware_camera_lidar_calibrator camera_lidar_calibration.launch intrinsics_file:=/home/s1nh/20190215_1853_autoware_camera_calibration.yaml image_src:=/mynteye/left/image_raw

(2)验证
需要注意的是,标定完以后,在Autoware的Sensing面板中使用Calibration PublisherPoints Image 查看标定结果的时候(下图),总会出现错误[ERROR] [1550575174.074463696]: [calibration_publisher] Missing calibration file path ''.

估计是个Bug,因此我直接运行了下面命令绕过了这个Bug:

打开三个终端,分别执行下面三段代码

1
2
3
4
5
6
7
source Autoware/ros/devel/setup.bash
roslaunch velodyne_pointcloud velodyne_vlp16.launch calibration:=/home/s1nh/project/SLAM/velodyne/VLP-16.yaml

# 注意,velodyne教程中的方法:
# roslaunch velodyne_pointcloud VLP16_points.launch calibration:=/home/s1nh/project/SLAM/velodyne/VLP-16.yaml
# roslaunch velodyne_pointcloud 32e_points.launch calibration:=/home/s1nh/project/SLAM/velodyne/VLP-16.yaml
# 都奇迹般的不能用,只能通过autoware的velodyne_vlp16.launch才可以正常使用
1
2
source Autoware/ros/devel/setup.bash
roslaunch src/util/packages/runtime_manager/scripts/calibration_publisher.launch file:=/home/s1nh/20190215_200018_autoware_lidar_camera_calibration.yaml image_topic_src:=/mynteye/left/image_raw
1
2
source Autoware/ros/devel/setup.bash
rosrun points2image points2image

执行完毕后,打开rviz,选择Panels –> Add New Panel –> ImageViewerPlugin,然后在新窗口中选好Image TopicPoint Topic即可

3.2. velo2cam_calibration

上面的工具采用手工选择9个点来实现标定,看起来不是很fancy。velo2cam 可以通过一个特制的标定板进行全自动标定

(1) 测试

velo2cam编译起来很快,但是官方文档没有列出dependence,记得安装好ros-kinetic-opencv-apps ros-kinetic-stereo-image-proc 这两个包,否则运行时会出现如下错误:

1
2
3
[ERROR] [1550561705.487407242]: Failed to load nodelet [/stereo_camera/disparity] of type [stereo_image_proc/disparity] even after refreshing the cache: According to the loaded plugin descriptions the class stereo_image_proc/disparity with base class type nodelet::Nodelet does not exist. Declared types are  adding_images/adding_images camshift/camshift contour_moments/contour_moments convex_hull/convex_hull corner_harris/corner_harris discrete_fourier_transform/discrete_fourier_transform edge_detection/edge_detection face_detection/face_detection face_recognition/face_recognition fback_flow/fback_flow find_contours/find_contours general_contours/general_contours goodfeature_track/goodfeature_track gscam/GSCamNodelet hls_color_filter/hls_color_filter hough_circles/hough_circles hough_lines/hough_lines hsv_color_filter/hsv_color_filter image_view/disparity image_view/image imu_filter_madgwick/ImuFilterNodelet jsk_topic_tools/Block jsk_topic_tools/DeprecatedRelay jsk_topic_tools/HzMeasure jsk_topic_tools/LightweightThrottle jsk_topic_tools/MUX jsk_topic_tools/Passthrough jsk_topic_tools/Relay jsk_topic_tools/Snapshot jsk_topic_tools/StealthRelay jsk_topic_tools/StringRelay jsk_topic_tools/SynchronizedThrottle jsk_topic_tools/VitalCheckerNodelet jsk_topic_tools_test/LogUtils lk_flow/lk_flow nodelet_tutorial_math/Plus opencv_apps/adding_images opencv_apps/camshift opencv_apps/contour_moments opencv_apps/convex_hull opencv_apps/corner_harris opencv_apps/discrete_fourier_transform opencv_apps/edge_detection opencv_apps/face_detection opencv_apps/face_recognition opencv_apps/fback_flow opencv_apps/find_contours opencv_apps/general_contours opencv_apps/goodfeature_track opencv_apps/hls_color_filter opencv_apps/hough_circles opencv_apps/hough_lines opencv_apps/hsv_color_filter opencv_apps/lk_flow opencv_apps/people_detect opencv_apps/phase_corr opencv_apps/pyramids opencv_apps/rgb_color_filter opencv_apps/segment_objects opencv_apps/simple_compressed_example opencv_apps/simple_example opencv_apps/simple_flow opencv_apps/smoothing opencv_apps/threshold opencv_apps/watershed_segmentation pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid people_detect/people_detect phase_corr/phase_corr pyramids/pyramids rgb_color_filter/rgb_color_filter segment_objects/segment_objects simple_compressed_example/simple_compressed_example simple_example/simple_example simple_flow/simple_flow smoothing/smoothing threshold/threshold velodyne_driver/DriverNodelet velodyne_laserscan/LaserScanNodelet velodyne_pointcloud/CloudNodelet velodyne_pointcloud/RingColorsNodelet velodyne_pointcloud/TransformNodelet watershed_segmentation/watershed_segmentation
[ERROR] [1550561705.488020647]: The error before refreshing the cache was: According to the loaded plugin descriptions the class stereo_image_proc/disparity with base class type nodelet::Nodelet does not exist. Declared types are adding_images/adding_images camshift/camshift contour_moments/contour_moments convex_hull/convex_hull corner_harris/corner_harris discrete_fourier_transform/discrete_fourier_transform edge_detection/edge_detection face_detection/face_detection face_recognition/face_recognition fback_flow/fback_flow find_contours/find_contours general_contours/general_contours goodfeature_track/goodfeature_track gscam/GSCamNodelet hls_color_filter/hls_color_filter hough_circles/hough_circles hough_lines/hough_lines hsv_color_filter/hsv_color_filter image_view/disparity image_view/image imu_filter_madgwick/ImuFilterNodelet jsk_topic_tools/Block jsk_topic_tools/DeprecatedRelay jsk_topic_tools/HzMeasure jsk_topic_tools/LightweightThrottle jsk_topic_tools/MUX jsk_topic_tools/Passthrough jsk_topic_tools/Relay jsk_topic_tools/Snapshot jsk_topic_tools/StealthRelay jsk_topic_tools/StringRelay jsk_topic_tools/SynchronizedThrottle jsk_topic_tools/VitalCheckerNodelet jsk_topic_tools_test/LogUtils lk_flow/lk_flow nodelet_tutorial_math/Plus opencv_apps/adding_images opencv_apps/camshift opencv_apps/contour_moments opencv_apps/convex_hull opencv_apps/corner_harris opencv_apps/discrete_fourier_transform opencv_apps/edge_detection opencv_apps/face_detection opencv_apps/face_recognition opencv_apps/fback_flow opencv_apps/find_contours opencv_apps/general_contours opencv_apps/goodfeature_track opencv_apps/hls_color_filter opencv_apps/hough_circles opencv_apps/hough_lines opencv_apps/hsv_color_filter opencv_apps/lk_flow opencv_apps/people_detect opencv_apps/phase_corr opencv_apps/pyramids opencv_apps/rgb_color_filter opencv_apps/segment_objects opencv_apps/simple_compressed_example opencv_apps/simple_example opencv_apps/simple_flow opencv_apps/smoothing opencv_apps/threshold opencv_apps/watershed_segmentation pcl/BAGReader pcl/BoundaryEstimation pcl/ConvexHull2D pcl/CropBox pcl/EuclideanClusterExtraction pcl/ExtractIndices pcl/ExtractPolygonalPrismData pcl/FPFHEstimation pcl/FPFHEstimationOMP pcl/MomentInvariantsEstimation pcl/MovingLeastSquares pcl/NodeletDEMUX pcl/NodeletMUX pcl/NormalEstimation pcl/NormalEstimationOMP pcl/NormalEstimationTBB pcl/PCDReader pcl/PCDWriter pcl/PFHEstimation pcl/PassThrough pcl/PointCloudConcatenateDataSynchronizer pcl/PointCloudConcatenateFieldsSynchronizer pcl/PrincipalCurvaturesEstimation pcl/ProjectInliers pcl/RadiusOutlierRemoval pcl/SACSegmentation pcl/SACSegmentationFromNormals pcl/SHOTEstimation pcl/SHOTEstimationOMP pcl/SegmentDifferences pcl/StatisticalOutlierRemoval pcl/VFHEstimation pcl/VoxelGrid people_detect/people_detect phase_corr/phase_corr pyramids/pyramids rgb_color_filter/rgb_color_filter segment_objects/segment_objects simple_compressed_example/simple_compressed_example simple_example/simple_example simple_flow/simple_flow smoothing/smoothing threshold/threshold velodyne_driver/DriverNodelet velodyne_laserscan/LaserScanNodelet velodyne_pointcloud/CloudNodelet velodyne_pointcloud/RingColorsNodelet velodyne_pointcloud/TransformNodelet watershed_segmentation/watershed_segmentation
[FATAL] [1550561705.488279617]: Failed to load nodelet '/stereo_camera/disparity` of type `stereo_image_proc/disparity` to manager `stereo_manager'

很简单的跑一下官方的bag,就可以显示以下标定结果:

(2) 真机

  1. 使用 kalibr 标定小觅左右目的内参 ;
  2. 使用 image_undistort 发布去畸变的 image_rect 图像(千万不要尝试采用小觅相机自带SDK来获得 image_rect );
1
2
3
4
5
6
7
8
9
10
11
# 双目
roslaunch /home/s1nh/project/SLAM/MYNT-EYE-S-SDK/wrappers/ros/src/mynt_eye_ros_wrapper/launch/mynteye.launch
roslaunch /home/s1nh/catkin_ws/src/image_undistort/launch/stereo_undistort.launch
roslaunch /home/s1nh/catkin_ws/src/velo2cam_calibration/launch/real_stereo_pattern.launch

# Velodyne
roslaunch velodyne_pointcloud VLP16_points.launch calibration:=/home/s1nh/project/SLAM/velodyne/VLP-16.yaml
roslaunch /home/s1nh/catkin_ws/src/velo2cam_calibration/launch/real_laser_pattern.launch

# 标定
roslaunch velo2cam_calibration velo2cam_calibration.launch

一边调算法,一边跟小觅相机和它狗日的驱动作斗争。动不动就会出下面酱紫的错误:

1
2
3
4
5
6
7
8
9
10
# 错误1:
[mynteye/mynteye_wrapper_node-2] process has died [pid 26183, exit code -11, cmd /home/s1nh/project/SLAM/MYNT-EYE-S-SDK/wrappers/ros/devel/lib/mynt_eye_ros_wrapper/mynteye_wrapper_node __name:=mynteye_wrapper_node __log:=/home/s1nh/.ros/log/1326b704-38e2-11e9-88d1-f01898375fa7/mynteye-mynteye_wrapper_node-2.log].
log file: /home/s1nh/.ros/log/1326b704-38e2-11e9-88d1-f01898375fa7/mynteye-mynteye_wrapper_node-2*.log

# 错误2:
W/uvc-v4l2.cc:414 poll failed: v4l2 get stream time out, Try to reboot!
W/uvc-v4l2.cc:414 poll failed: v4l2 get stream time out, Try to reboot!
W/uvc-v4l2.cc:414 poll failed: v4l2 get stream time out, Try to reboot!
W/uvc-v4l2.cc:414 poll failed: v4l2 get stream time out, Try to reboot!
W/uvc-v4l2.cc:414 poll failed: v4l2 get stream time out, Try to reboot!

0xFF 其它破事

  1. Velodyne 的 GPS 时间戳同步失败

Velodyne 时间同步需要 PPS 和 GPRMC 信号,其中PPS需要TTL电平,GPRMC需要RS232电平。然而,自带U里的用户手册写着GPRMC信号为TTL电平,因此调试了一下午才找到问题所在。

具体表现在,即使只有PPS信号,配置网页中也会显示已经Locked,但是抓包UDP 8308端口不会有时间戳显示。