Rover: fix WHEEL_DISTANCE timestamp overflow#32302
Open
peterbarker wants to merge 1 commit intoArduPilot:masterfrom
Open
Rover: fix WHEEL_DISTANCE timestamp overflow#32302peterbarker wants to merge 1 commit intoArduPilot:masterfrom
peterbarker wants to merge 1 commit intoArduPilot:masterfrom
Conversation
The time_usec field (uint64_t, units=us) was computed as 1000UL * AP_HAL::millis(). On ARM, UL is 32-bit, so the multiplication overflows after ~71 minutes and the 32-bit result is then zero-extended to 64 bits, producing a garbage timestamp. Use AP_HAL::micros64() which returns a proper 64-bit microsecond value. Co-Authored-By: Claude Sonnet 4.6 <[email protected]>
rmackay9
approved these changes
Feb 26, 2026
Contributor
rmackay9
left a comment
There was a problem hiding this comment.
Great, txs for the fix.
Do we want to get Claude Sonnet co-author credit? :-)
Contributor
Author
It's co-authored on the patch already :-) |
Contributor
|
Hi @peterbarker, indeed, that's why I brought it up.. maybe I should have added a "really" into the sentence.. |
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment
Add this suggestion to a batch that can be applied as a single commit.This suggestion is invalid because no changes were made to the code.Suggestions cannot be applied while the pull request is closed.Suggestions cannot be applied while viewing a subset of changes.Only one suggestion per line can be applied in a batch.Add this suggestion to a batch that can be applied as a single commit.Applying suggestions on deleted lines is not supported.You must change the existing code in this line in order to create a valid suggestion.Outdated suggestions cannot be applied.This suggestion has been applied or marked resolved.Suggestions cannot be applied from pending reviews.Suggestions cannot be applied on multi-line comments.Suggestions cannot be applied while the pull request is queued to merge.Suggestion cannot be applied right now. Please check back later.
Summary
Fixes an integer overflow when sending the
WHEEL_DISTANCEtelemetry messageTesting (more checks increases chance of being merged)
Description
The time_usec field (uint64_t, units=us) was computed as 1000UL * AP_HAL::millis(). On ARM, UL is 32-bit, so the multiplication overflows after ~71 minutes and the 32-bit result is then zero-extended to 64 bits, producing a garbage timestamp.
Use AP_HAL::micros64() which returns a proper 64-bit microsecond value.
Tested with the following patch:
That patch on a ZeroOneX6:
Reformatted: