Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add vert offset corrections to VLP16 calib file #518

Merged

Conversation

msz-rai
Copy link

@msz-rai msz-rai commented Jun 1, 2023

According to the VLP-16 User Manual (page 54) lidar lasers have vertical offsets in their position. This PR corrects the calibration file.
image
image

@JWhitleyWork
Copy link
Contributor

@msz-rai Have you tested this on real hardware?

@JWhitleyWork JWhitleyWork force-pushed the fix/vlp16-vert-offset-corrections branch from f999603 to 5da836b Compare June 1, 2023 04:21
@JWhitleyWork
Copy link
Contributor

Rebased on ros2 branch to get CI updates.

@JWhitleyWork
Copy link
Contributor

I'm also wondering - are we missing these values for all of the other sensors? I don't see them being populated in any other param files.

@msz-rai
Copy link
Author

msz-rai commented Jun 1, 2023

@JWhitleyWork

Have you tested this on real hardware?

No, I haven't. I don't have physical lidar. I'm developing VLP16 in the simulation.

I'm also wondering - are we missing these values for all of the other sensors? I don't see them being populated in any other param files.

Yes, this is correct, but at the moment, I'm focused on VLP16 only. I am not sure if other models need this offset.

@valgur valgur mentioned this pull request May 25, 2023
23 tasks
@valgur
Copy link
Contributor

valgur commented Jun 5, 2023

The optical drawing in the VLP-16 manual further reinforces that this correction is indeed warranted:
VLP-16_optical_drawing

While the correction would be applied in the correct direction in the driver code, I'm suspicious of the multiplication with cos_vert_angle: https://github.com/ros-drivers/velodyne/blob/master/velodyne_pointcloud/src/lib/rawdata.cc#L796
That does not look correct to me and also the HDL-64E sample code does not do this (although it is included in a commented-out formula for some reason): https://www.termocam.it/pdf/manuale-HDL-64E.pdf#page=34

@valgur
Copy link
Contributor

valgur commented Jun 5, 2023

As for the other sensors - only VLP-16 appears to include this info its manual. However, these values can be estimated from the distance of the focal point and the vertical angle of the beam as vert_offset_correction = focal_distance * tan(-vert_correction).

For example, here are the values for VLP-16 LITE (focal distance = 41.910 mm):

Vertical Angle (deg) Vertical Correction (mm) f * tan(-angle)
-15 11.2 11.23
1 -0.7 -0.73
-13 9.7 9.68
3 -2.2 -2.20
-11 8.1 8.15
5 -3.7 -3.67
-9 6.6 6.64
7 -5.1 -5.15
-7 5.1 5.15
9 -6.6 -6.64
-5 3.7 3.67
11 -8.1 -8.15
-3 2.2 2.20
13 -9.7 -9.68
-1 0.7 0.73
15 -11.2 -11.23

However, this does not work as well for VLP-16 Hi-Res:

Vertical Angle (deg) Vertical Correction (mm) f * tan(-angle)
-10 7.4 7.39
0.67 -0.9 -0.49
-8.67 6.5 6.39
2 -1.8 -1.46
-7.33 5.5 5.39
3.33 -2.7 -2.44
-6 4.6 4.40
4.67 -3.7 -3.42
-4.67 3.7 3.42
6 -4.6 -4.40
-3.33 2.7 2.44
7.33 -5.5 -5.39
-2 1.8 1.46
8.67 -6.5 -6.39
-0.67 0.9 0.49
10 -7.4 -7.39

Here the placement appears to follow approx f * tan(-angle) * 0.93 + 0.5 * sign(-angle) instead. Still, even the rough estimate should produce a more accurate values than without it.

For VLP-32C and Alpha prime the largest correction values would be around 2 cm. I'm a bit confused and surprised by the manual and VeloView not accounting for this.

@valgur
Copy link
Contributor

valgur commented Jun 5, 2023

Have you tested this on real hardware?

I found this article titled "Analysis and calibration of the VLP-16 for automotive applications", which analyzes the vertical angular accuracy of VLP-16. They appear to be using the simpler sensor model without the vertical offset correction (which is not mentioned in this article, but is in another one by the same author).

They measured the vertical angles of the beams at varying distances relative to the center of the sensor:
Screenshot from 2023-06-05 22-39-22

Based on that table, the errors of the simpler model vs the "theoretical elevation angle" are:
Screenshot from 2023-06-05 22-32-07

However, after taking the vertical offset into account the expected angles at given distances agree much better with the measurements:
Screenshot from 2023-06-05 22-31-58

Here's a notebook containing the above analysis: https://gist.github.com/valgur/217470899f9b74c5901769deb62f10be

Based on this, I would feel quite comfortable with including these additional corrections in the driver.

@msz-rai
Copy link
Author

msz-rai commented Jun 6, 2023

@valgur
Thank you for the detailed analysis. It sounds good to me, also.

valgur added a commit to valgur/velodyne_decoder that referenced this pull request Jun 7, 2023
Accounts for each laser having a slight vertical offset instead of implicitly assuming they are all placed in the optical center.
Corrects for up to 2 cm of systematic error in the vertical direction.

Related to ros-drivers/velodyne#518
Copy link
Contributor

@JWhitleyWork JWhitleyWork left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Can you please back-port this change to at least the humble-devel and noetic branches?

@JWhitleyWork JWhitleyWork merged commit 3353568 into ros-drivers:ros2 Jun 16, 2023
2 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants