mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Proximity_MAV: healthy if either horiz or vert positions received
This commit is contained in:
parent
3df5484a39
commit
09e3d6b7f0
@ -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);
|
||||||
|
Loading…
Reference in New Issue
Block a user