Skip to content

Hot fix for VLP16 timestamp#291

Open
ike-kazu wants to merge 4 commits intotier4:mainfrom
ike-kazu:feat/fix_vlp16_timestamp
Open

Hot fix for VLP16 timestamp#291
ike-kazu wants to merge 4 commits intotier4:mainfrom
ike-kazu:feat/fix_vlp16_timestamp

Conversation

@ike-kazu
Copy link
Contributor

@ike-kazu ike-kazu commented Mar 21, 2025

PR Type

Only vlp16 has problems for timestamp. In this PR, hot fix is created for this.
It's reported in #292

  • Bug Fix

Related Links

VLP16 timestamp problem report

Description

Only VLP16 has problems for timestamps in poincloud from nebula, Last Filtered Pointcloud timestamp problem.
When vlp16 pointcloud is filtered through nebula, last pointcloud timestamp is weird sometime. We research about this problem but we can't discover the cause of this clearly.
But we Discover that VLP16 pointcloud timestamps are weird when it is filtered by hardware.
It's fine when VLP16 pointcloud are filtered by only nebula.

From this discovery, we decide that we create hardware filter offset as hot fix for this problem.

Fixes #292.

Review Procedure

Remarks

Pre-Review Checklist for the PR Author

PR Author should check the checkboxes below when creating the PR.

  • Assign PR to reviewer

Checklist for the PR Reviewer

Reviewers should check the checkboxes below before approval.

  • Commits are properly organized and messages are according to the guideline
  • (Optional) Unit tests have been written for new behavior
  • PR title describes the changes

Post-Review Checklist for the PR Author

PR Author should check the checkboxes below before merging.

  • All open points are addressed and tracked via issues or tickets

CI Checks

  • Build and test for PR: Required to pass before the merge.

@codecov
Copy link

codecov bot commented Mar 21, 2025

Codecov Report

Attention: Patch coverage is 0% with 14 lines in your changes missing coverage. Please review.

Project coverage is 31.12%. Comparing base (ce0448b) to head (c6e2672).
Report is 2 commits behind head on main.

Additional details and impacted files
@@            Coverage Diff             @@
##             main     #291      +/-   ##
==========================================
- Coverage   31.77%   31.12%   -0.66%     
==========================================
  Files         113      112       -1     
  Lines        9702     9562     -140     
  Branches     4478     4048     -430     
==========================================
- Hits         3083     2976     -107     
- Misses       6040     6041       +1     
+ Partials      579      545      -34     
Flag Coverage Δ
differential 31.12% <0.00%> (?)
total ?

Flags with carried forward coverage won't be shown. Click here to find out more.

Components Coverage Δ
Common 39.97% <ø> (-10.34%) ⬇️
Hesai 29.25% <ø> (-1.16%) ⬇️
Velodyne 40.09% <0.00%> (-0.20%) ⬇️
Continental 30.74% <ø> (-0.10%) ⬇️
Robosense 5.58% <ø> (+5.58%) ⬆️
🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

Copy link
Collaborator

@mojomex mojomex left a comment

Choose a reason for hiding this comment

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

Thank you for the PR!
I have left a few comments about simplifying the code, please have a look.

Also, could you add a self-evaluation section where you use a real VLP16 with different settings?

Ones I'm interested in are:

  • 0, 360 -- no gaps should be observed
  • 90, 90 -- should be the same output as 0, 360
  • 0, 180 -- no weird timestamp0s at edges
  • 180, 0 -- same but the other half of the pointcloud is shown
  • 355, 5 -- only 10deg of the pointcloud are shown
  • 5, 355 -- a 10deg gap is shown
  • 3, 357 -- a 6deg gap is shown

Comment on lines +181 to +185
if (setting_cloud_min_angle < 5) {
setting_cloud_min_angle = (setting_cloud_min_angle + 355) % 360;
} else {
setting_cloud_min_angle -= 5;
}
Copy link
Collaborator

Choose a reason for hiding this comment

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

This if/else can be simplified into one generic formula (-5 + 360 might be more understandable than +355):

Suggested change
if (setting_cloud_min_angle < 5) {
setting_cloud_min_angle = (setting_cloud_min_angle + 355) % 360;
} else {
setting_cloud_min_angle -= 5;
}
setting_cloud_min_angle = (setting_cloud_min_angle - 5 + 360) % 360;

Comment on lines +187 to +194
if (setting_cloud_max_angle > 354) {
setting_cloud_max_angle = 359;
} else {
setting_cloud_max_angle += 5;
if (setting_cloud_max_angle >= 360) {
setting_cloud_max_angle = 359;
}
}
Copy link
Collaborator

Choose a reason for hiding this comment

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

Can be simplified to:

Suggested change
if (setting_cloud_max_angle > 354) {
setting_cloud_max_angle = 359;
} else {
setting_cloud_max_angle += 5;
if (setting_cloud_max_angle >= 360) {
setting_cloud_max_angle = 359;
}
}
setting_cloud_max_angle = (setting_cloud_max_angle + 5) % 360;

setting_cloud_min_angle = 359;
int setting_cloud_max_angle = sensor_configuration->cloud_max_angle;

// FIXME: VLP16 has problems for timestamp. Whatch github issue #
Copy link
Collaborator

Choose a reason for hiding this comment

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

Please explain in more detail (combination of hardware and software scan cutting causes timestamping issues at the FoV borders, so the hardware FoV has to be increased for scan cutting to work.


// FIXME: VLP16 has problems for timestamp. Whatch github issue #
if (sensor_configuration->sensor_model == SensorModel::VELODYNE_VLP16) {
int angle_diff = (setting_cloud_max_angle - setting_cloud_min_angle + 360) % 360;
Copy link
Collaborator

Choose a reason for hiding this comment

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

Please define the angle we oversize by as a const int32_t fov_tolerance_deg = 5; and replace all 5s below by that constant.

if (sensor_configuration->sensor_model == SensorModel::VELODYNE_VLP16) {
int angle_diff = (setting_cloud_max_angle - setting_cloud_min_angle + 360) % 360;

if (angle_diff >= 360 || angle_diff == 0) {
Copy link
Collaborator

Choose a reason for hiding this comment

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

Angle diff cannot be >= 360 (it was % 360ed), so the below condition is sufficient:

Suggested change
if (angle_diff >= 360 || angle_diff == 0) {
if (angle_diff == 0) {

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

VLP16: point timestamps at FoV edge are incorrect

2 participants