From 3353568859618d79244b4b6f002e500dd55ab64d Mon Sep 17 00:00:00 2001 From: Mateusz Szczygielski <112629916+msz-rai@users.noreply.github.com> Date: Fri, 16 Jun 2023 21:02:12 +0100 Subject: [PATCH] Add vert offset corrections to VLP16 calib file (#518) --- velodyne_pointcloud/params/VLP16db.yaml | 32 ++++++++++++------------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/velodyne_pointcloud/params/VLP16db.yaml b/velodyne_pointcloud/params/VLP16db.yaml index 4717aea97..debafe7c2 100644 --- a/velodyne_pointcloud/params/VLP16db.yaml +++ b/velodyne_pointcloud/params/VLP16db.yaml @@ -1,51 +1,51 @@ lasers: - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 0, rot_correction: 0.0, - vert_correction: -0.2617993877991494, vert_offset_correction: 0.0} + vert_correction: -0.2617993877991494, vert_offset_correction: 0.0112} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 1, rot_correction: 0.0, - vert_correction: 0.017453292519943295, vert_offset_correction: 0.0} + vert_correction: 0.017453292519943295, vert_offset_correction: -0.0007} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 2, rot_correction: 0.0, - vert_correction: -0.22689280275926285, vert_offset_correction: 0.0} + vert_correction: -0.22689280275926285, vert_offset_correction: 0.0097} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 3, rot_correction: 0.0, - vert_correction: 0.05235987755982989, vert_offset_correction: 0.0} + vert_correction: 0.05235987755982989, vert_offset_correction: -0.0022} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 4, rot_correction: 0.0, - vert_correction: -0.19198621771937624, vert_offset_correction: 0.0} + vert_correction: -0.19198621771937624, vert_offset_correction: 0.0081} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 5, rot_correction: 0.0, - vert_correction: 0.08726646259971647, vert_offset_correction: 0.0} + vert_correction: 0.08726646259971647, vert_offset_correction: -0.0037} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 6, rot_correction: 0.0, - vert_correction: -0.15707963267948966, vert_offset_correction: 0.0} + vert_correction: -0.15707963267948966, vert_offset_correction: 0.0066} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 7, rot_correction: 0.0, - vert_correction: 0.12217304763960307, vert_offset_correction: 0.0} + vert_correction: 0.12217304763960307, vert_offset_correction: -0.0051} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 8, rot_correction: 0.0, - vert_correction: -0.12217304763960307, vert_offset_correction: 0.0} + vert_correction: -0.12217304763960307, vert_offset_correction: 0.0051} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 9, rot_correction: 0.0, - vert_correction: 0.15707963267948966, vert_offset_correction: 0.0} + vert_correction: 0.15707963267948966, vert_offset_correction: -0.0066} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 10, rot_correction: 0.0, - vert_correction: -0.08726646259971647, vert_offset_correction: 0.0} + vert_correction: -0.08726646259971647, vert_offset_correction: 0.0037} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 11, rot_correction: 0.0, - vert_correction: 0.19198621771937624, vert_offset_correction: 0.0} + vert_correction: 0.19198621771937624, vert_offset_correction: -0.0081} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 12, rot_correction: 0.0, - vert_correction: -0.05235987755982989, vert_offset_correction: 0.0} + vert_correction: -0.05235987755982989, vert_offset_correction: 0.0022} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 13, rot_correction: 0.0, - vert_correction: 0.22689280275926285, vert_offset_correction: 0.0} + vert_correction: 0.22689280275926285, vert_offset_correction: -0.0097} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 14, rot_correction: 0.0, - vert_correction: -0.017453292519943295, vert_offset_correction: 0.0} + vert_correction: -0.017453292519943295, vert_offset_correction: 0.0007} - {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0, focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 15, rot_correction: 0.0, - vert_correction: 0.2617993877991494, vert_offset_correction: 0.0} + vert_correction: 0.2617993877991494, vert_offset_correction: -0.0112} num_lasers: 16 distance_resolution: 0.002