Skip to content

Rover: fix WHEEL_DISTANCE timestamp overflow#32302

Open
peterbarker wants to merge 1 commit intoArduPilot:masterfrom
peterbarker:pr-claude/wheel-distance-overflow-bugfix
Open

Rover: fix WHEEL_DISTANCE timestamp overflow#32302
peterbarker wants to merge 1 commit intoArduPilot:masterfrom
peterbarker:pr-claude/wheel-distance-overflow-bugfix

Conversation

@peterbarker
Copy link
Contributor

@peterbarker peterbarker commented Feb 26, 2026

Summary

Fixes an integer overflow when sending the WHEEL_DISTANCE telemetry message

Testing (more checks increases chance of being merged)

  • Checked by a human programmer
  • Tested in SITL
  • Tested on hardware
  • Logs attached
  • Logs available on request
  • Autotest included

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:

--- a/ArduPlane/Plane.cpp
+++ b/ArduPlane/Plane.cpp
@@ -392,6 +392,23 @@ void Plane::one_second_loop()
     rollController.set_notch_sample_rate(loop_rate);
     pitchController.set_notch_sample_rate(loop_rate);
     yawController.set_notch_sample_rate(loop_rate);
+
+    // Demonstrate WHEEL_DISTANCE timestamp overflow (fixed in Rover).
+    // On 32-bit ARM sizeof(unsigned long)==4, so 1000UL * millis() is a
+    // 32-bit multiplication that overflows after ~71 minutes.  Use a fixed
+    // sample value to make the result predictable:
+    //   sample_ms = 5000000  (~83 minutes of uptime)
+    //   correct usec         = 5000000000  (high-32 = 1)
+    //   1000UL * sample_ms   = 705032704   (high-32 = 0, data lost)
+    {
+        const uint32_t sample_ms = 5000000;              // ~83 minutes
+        const uint64_t truncated = 1000UL  * sample_ms;  // 32-bit mul: 705032704
+        const uint64_t correct   = 1000ULL * sample_ms;  // 64-bit mul: 5000000000
+        gcs().send_text(MAV_SEVERITY_INFO,
+                        "WD ts overflow: truncated=%llu correct=%llu",
+                        (unsigned long long)truncated,
+                        (unsigned long long)correct);
+    }
 }

That patch on a ZeroOneX6:

AP: WD ts overflow: truncated=705032704 correct=5000000000

Reformatted:

truncated   705032704
correct    5000000000

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]>
Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

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

Great, txs for the fix.

Do we want to get Claude Sonnet co-author credit? :-)

@peterbarker
Copy link
Contributor Author

Do we want to get Claude Sonnet co-author credit? :-)

It's co-authored on the patch already :-)

@rmackay9
Copy link
Contributor

Hi @peterbarker, indeed, that's why I brought it up.. maybe I should have added a "really" into the sentence..

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

Projects

Status: No status

Development

Successfully merging this pull request may close these issues.

2 participants