AP_NMEA_Output: 10hz rate limiting uses uint32_t

This commit is contained in:
Randy Mackay 2019-11-29 09:46:02 +09:00
parent de5d8c5480
commit 4407b1ada0
2 changed files with 4 additions and 4 deletions

View File

@ -67,13 +67,13 @@ uint8_t AP_NMEA_Output::_nmea_checksum(const char *str)
void AP_NMEA_Output::update()
{
const uint16_t now = AP_HAL::millis16();
const uint32_t now_ms = AP_HAL::millis();
// only send at 10Hz
if (uint16_t(now - _last_run) < 100) {
if ((now_ms - _last_run_ms) < 100) {
return;
}
_last_run = now;
_last_run_ms = now_ms;
// get time and date
uint64_t time_usec;

View File

@ -47,7 +47,7 @@ private:
uint8_t _num_outputs;
AP_HAL::UARTDriver* _uart[SERIALMANAGER_NUM_PORTS];
uint16_t _last_run;
uint32_t _last_run_ms;
};
#endif // !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE