mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Mount: Siyi health check avoids race condition
This commit is contained in:
parent
5d97a4b3d6
commit
c7b64dc448
@ -150,7 +150,8 @@ bool AP_Mount_Siyi::healthy() const
|
||||
}
|
||||
|
||||
// unhealthy if attitude information NOT received recently
|
||||
if (AP_HAL::millis() - _last_current_angle_rad_ms > 1000) {
|
||||
const uint32_t now_ms = AP_HAL::millis();
|
||||
if (now_ms - _last_current_angle_rad_ms > 1000) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user