mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 18:18:49 -04:00
AP_NMEA_Output: correct 10Hz rate limiting
integer promotion issue
This commit is contained in:
parent
9fd53b0dbc
commit
46c384b412
@ -70,7 +70,7 @@ void AP_NMEA_Output::update()
|
|||||||
const uint16_t now = AP_HAL::millis16();
|
const uint16_t now = AP_HAL::millis16();
|
||||||
|
|
||||||
// only send at 10Hz
|
// only send at 10Hz
|
||||||
if (now - _last_run < 100) {
|
if (uint16_t(now - _last_run) < 100) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
_last_run = now;
|
_last_run = now;
|
||||||
|
Loading…
Reference in New Issue
Block a user