Skip to content

Commit

Permalink
AP_Proximity_MAV: healthy if either horiz or vert positions received
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Apr 20, 2017
1 parent 3df5484 commit 09e3d6b
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AP_Proximity/AP_Proximity_MAV.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,8 @@ AP_Proximity_MAV::AP_Proximity_MAV(AP_Proximity &_frontend,
void AP_Proximity_MAV::update(void)
{
// 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);
} else {
set_status(AP_Proximity::Proximity_Good);
Expand Down

0 comments on commit 09e3d6b

Please sign in to comment.