Browse Source

AP_NMEA_Output: correct 10Hz rate limiting

integer promotion issue
master
Peter Barker 5 years ago committed by Randy Mackay
parent
commit
de5d8c5480
  1. 2
      libraries/AP_NMEA_Output/AP_NMEA_Output.cpp

2
libraries/AP_NMEA_Output/AP_NMEA_Output.cpp

@ -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…
Cancel
Save