AP_Proximity_MAV: healthy if either horiz or vert positions received

This commit is contained in:
Randy Mackay 2017-04-12 17:59:40 +09:00
parent 3df5484a39
commit 09e3d6b7f0

View File

@ -36,7 +36,8 @@ AP_Proximity_MAV::AP_Proximity_MAV(AP_Proximity &_frontend,
void AP_Proximity_MAV::update(void) void AP_Proximity_MAV::update(void)
{ {
// check for timeout and set health status // check for timeout and set health status
if ((_last_update_ms == 0) || (AP_HAL::millis() - _last_update_ms > PROXIMITY_MAV_TIMEOUT_MS)) { if ((_last_update_ms == 0 || (AP_HAL::millis() - _last_update_ms > PROXIMITY_MAV_TIMEOUT_MS)) &&
(_last_upward_update_ms == 0 || (AP_HAL::millis() - _last_upward_update_ms > PROXIMITY_MAV_TIMEOUT_MS))) {
set_status(AP_Proximity::Proximity_NoData); set_status(AP_Proximity::Proximity_NoData);
} else { } else {
set_status(AP_Proximity::Proximity_Good); set_status(AP_Proximity::Proximity_Good);