AP_Proximity: fix proximity status for upward facing rangefinder

This commit is contained in:
Tatsuya Yamaguchi 2021-06-16 09:38:56 +09:00 committed by Andrew Tridgell
parent dbc9b0c2f9
commit 9114caf213
1 changed files with 2 additions and 1 deletions

View File

@ -75,7 +75,8 @@ void AP_Proximity_RangeFinder::update(void)
} }
// check for timeout and set health status // 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); set_status(AP_Proximity::Status::NoData);
} else { } else {
set_status(AP_Proximity::Status::Good); set_status(AP_Proximity::Status::Good);