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

fix(velodyne): propagate sub-second part of timestamps to pointcloud timestamp #201

Merged
merged 2 commits into from
Oct 1, 2024

Conversation

mojomex
Copy link
Collaborator

@mojomex mojomex commented Sep 27, 2024

PR Type

  • Bug Fix

Related Links

Description

This PR fixes a bug where all Velodyne pointclouds have a cloud timestamp which is rounded down to to the nearest second.

Ths bug was introduced by mistakenly changing the following expression

/* from */ rclcpp::Time(packet.stamp).seconds()
/*   to */ packet.stamp.sec

Review Procedure

Confirm that cloud timestamps are correct (nanosec field increases by 100ms each scan).

Remarks

Tested with Autoware logging simulator:

ros2 topic echo --field header.stamp --csv /sensing/lidar/left/aw_points_ex

Before:

1585897255,0
1585897255,0
1585897255,0
1585897255,0
1585897256,0
1585897256,0
1585897256,0
1585897256,0
1585897256,0
1585897256,0
1585897256,0
1585897256,0
1585897256,0
1585897256,0
1585897257,0
1585897257,0

After:

1585897255,310290688
1585897255,360631040
1585897255,461410560
1585897255,561021440
1585897255,660529152
1585897255,761372928
1585897255,860926720
1585897255,960501248
1585897256, 61242112
1585897256,160895744
1585897256,260359168
1585897256,361232640
1585897256,460778240
1585897256,562444032
1585897256,661132800
1585897256,760673536
1585897256,860208384
1585897256,961116672
1585897257, 60684800
1585897257,160203520

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.

Copy link

codecov bot commented Sep 27, 2024

Codecov Report

Attention: Patch coverage is 75.00000% with 1 line in your changes missing coverage. Please review.

Project coverage is 25.80%. Comparing base (9f706e3) to head (3af07cf).
Report is 1 commits behind head on main.

Files with missing lines Patch % Lines
nebula_ros/src/velodyne/decoder_wrapper.cpp 0.00% 1 Missing ⚠️
Additional details and impacted files
@@            Coverage Diff             @@
##             main     #201      +/-   ##
==========================================
- Coverage   29.65%   25.80%   -3.86%     
==========================================
  Files          99       99              
  Lines        8760     8748      -12     
  Branches     2173     2145      -28     
==========================================
- Hits         2598     2257     -341     
+ Misses       6116     6105      -11     
- Partials       46      386     +340     
Flag Coverage Δ
differential 25.80% <75.00%> (?)
total ?

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

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

@mojomex mojomex requested a review from knzo25 September 30, 2024 05:15
@knzo25
Copy link
Collaborator

knzo25 commented Sep 30, 2024

@mojomex
Just to be clear, is this the bug related to the sample rosbag not working as expected?

@mojomex
Copy link
Collaborator Author

mojomex commented Sep 30, 2024

@knzo25 Correct. This causes concat to only output point clouds at 1 Hz, killing driving performance.

@mojomex mojomex force-pushed the fix/velodyne-cloud-timestamps branch from f622d4e to f3458a7 Compare September 30, 2024 06:11
Copy link
Collaborator

@knzo25 knzo25 left a comment

Choose a reason for hiding this comment

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

nit:
checkAndHandleScanComplete accepts int32, is called using a double, and only uses it to call reset_pointcloud which uses double.

Copy link

sonarcloud bot commented Oct 1, 2024

Copy link
Collaborator

@knzo25 knzo25 left a comment

Choose a reason for hiding this comment

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

LGTM !
(tested that this fixes the error found in autowarefoundation/autoware#5275)

@mojomex mojomex merged commit 6677df3 into main Oct 1, 2024
13 of 14 checks passed
@mojomex mojomex deleted the fix/velodyne-cloud-timestamps branch October 1, 2024 07:19
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.

2 participants