mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AP_Proximity: fix proximity status for upward facing rangefinder
This commit is contained in:
parent
430ac65123
commit
1954f596b8
@ -75,7 +75,8 @@ void AP_Proximity_RangeFinder::update(void)
|
||||
}
|
||||
|
||||
// check for timeout and set health status
|
||||
if ((_last_update_ms == 0) || (now - _last_update_ms > PROXIMITY_RANGEFIDER_TIMEOUT_MS)) {
|
||||
if ((_last_update_ms == 0 || (now - _last_update_ms > PROXIMITY_RANGEFIDER_TIMEOUT_MS)) &&
|
||||
(_last_upward_update_ms == 0 || (now - _last_upward_update_ms > PROXIMITY_RANGEFIDER_TIMEOUT_MS))) {
|
||||
set_status(AP_Proximity::Status::NoData);
|
||||
} else {
|
||||
set_status(AP_Proximity::Status::Good);
|
||||
|
Loading…
Reference in New Issue
Block a user