AP_NMEA_Output: correct 10Hz rate limiting

integer promotion issue
This commit is contained in:
Peter Barker 2019-11-28 12:24:03 +11:00 committed by Peter Barker
parent 98a4335af4
commit 46d0425fcf
1 changed files with 1 additions and 1 deletions

View File

@ -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;