Skip to content

Commit

Permalink
AP_NMEA_Output: correct 10Hz rate limiting
Browse files Browse the repository at this point in the history
integer promotion issue
  • Loading branch information
peterbarker committed Nov 29, 2019
1 parent 98a4335 commit 46d0425
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_NMEA_Output/AP_NMEA_Output.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,7 @@ void AP_NMEA_Output::update()
const uint16_t now = AP_HAL::millis16();

// only send at 10Hz
if (now - _last_run < 100) {
if (uint16_t(now - _last_run) < 100) {
return;
}
_last_run = now;
Expand Down

0 comments on commit 46d0425

Please sign in to comment.