but_calibration_camera_velodyne
ROS packages for extrinsic calibration Velodyne 3D LIDARs(vlp16) with ZED stereo camera. The package follows the methods proposed by:
-
[1] Velas, Spanel, Materna, Herout: Calibration of RGB Camera with Velodyne LiDAR
-
[2] Jingfeng Sui, Shuo Wang, Extrinsic Calibration of Camera and 3D Laser Sensor System. pdf
Requirements
- PCl 1.7 and OpenCV 3.x library
Usage
-
roslaunch but_calibration_camera_velodyne calibration_coarse.launch
- command will run the coarse calibration using 3D marker (described in the [1])
- if the 3D marker detection fails, the attempt will be repeated after 5s
- upon the cuccess the node ends and prints the 6 Degrees of Freedom of the Velodyne related to the camera
-
roslaunch but_calibration_camera_velodyne calibration_fine.launch
- will runs the calibration with the refinement. This process will take a longer time (approx. 1 minute)
-
roslaunch but_calibration_camera_velodyne coloring.launch
- launches the publisher of colored pointclouds created by the camera -- Velodyne fusion
- the calibration parameters (6DoF) computed by the
calibration
process must be set in configuration fileconf/coloring.yaml
(see below)
Configuration:
Configuration *.yaml files are stored in the direcotry conf/
:
conf/calibration.yaml
contains folowing parameters:camera_frame_topic
: name of the topic, where camera RGB image is publishedcamera_info_topic
: topic ofCameraInfo
typevelodyne_topic
: topic, where the Velodyne pointcloud is publishedmarker
: physical size of the 3D markercircles_distance
: distance between the circles centres (see [1])circles_radius
: radius of the circles in marker (also see [1])
- in
conf/calibration.yaml
you can specify:6DoF
: vector of the calibration parameters computed by the calibration processvelodyne_color_topic
: name of the topic, where the colored pointcloud will be published