mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Baro: Fix timestamp wrapping
This commit is contained in:
parent
9f81da1bf9
commit
10b7988092
@ -318,7 +318,7 @@ bool AP_Baro_BMP085::_data_ready()
|
||||
|
||||
// No EOC pin: use time from last read instead.
|
||||
if (_state == 0) {
|
||||
return AP_HAL::millis() > _last_temp_read_command_time + 5;
|
||||
return AP_HAL::millis() - _last_temp_read_command_time > 5u;
|
||||
}
|
||||
|
||||
uint32_t conversion_time_msec;
|
||||
@ -340,5 +340,5 @@ bool AP_Baro_BMP085::_data_ready()
|
||||
break;
|
||||
}
|
||||
|
||||
return AP_HAL::millis() > _last_press_read_command_time + conversion_time_msec;
|
||||
return AP_HAL::millis() - _last_press_read_command_time > conversion_time_msec;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user