Browse Source

AC_Avoid: adjust for proximity status namespace change

master
Peter Barker 5 years ago committed by Randy Mackay
parent
commit
83b6fdbb04
  1. 4
      libraries/AC_Avoidance/AC_Avoid.cpp

4
libraries/AC_Avoidance/AC_Avoid.cpp

@ -690,7 +690,7 @@ void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector2f &d @@ -690,7 +690,7 @@ void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector2f &d
AP_Proximity &_proximity = *proximity;
if (_proximity.get_status() != AP_Proximity::Proximity_Good) {
if (_proximity.get_status() != AP_Proximity::Status::Good) {
return;
}
@ -858,7 +858,7 @@ void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_ne @@ -858,7 +858,7 @@ void AC_Avoid::get_proximity_roll_pitch_pct(float &roll_positive, float &roll_ne
AP_Proximity &_proximity = *proximity;
// exit immediately if proximity sensor is not present
if (_proximity.get_status() != AP_Proximity::Proximity_Good) {
if (_proximity.get_status() != AP_Proximity::Status::Good) {
return;
}

Loading…
Cancel
Save