diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 9745d4abb62b5..75f0aeb0fc77e 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -1139,10 +1139,6 @@ void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &d } AP_Proximity &_proximity = *proximity; - // check for status of the sensor - if (_proximity.get_status() != AP_Proximity::Status::Good) { - return; - } // get total number of obstacles const uint8_t obstacle_num = _proximity.get_obstacle_count(); if (obstacle_num == 0) { @@ -1434,14 +1430,7 @@ void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_ne return; } AP_Proximity &_proximity = *proximity; - - // exit immediately if proximity sensor is not present - if (_proximity.get_status() != AP_Proximity::Status::Good) { - return; - } - const uint8_t obj_count = _proximity.get_object_count(); - // if no objects return if (obj_count == 0) { return; diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 82dc97e7919d0..753b7eb0bc030 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -308,17 +308,19 @@ AP_Proximity::Status AP_Proximity::get_instance_status(uint8_t instance) const return state[instance].status; } +// Returns status of first good sensor. If no good sensor found, returns status of last instance sensor AP_Proximity::Status AP_Proximity::get_status() const { + Status sensors_status = Status::NotConnected; for (uint8_t i=0; i