From 83b6fdbb04d6cf0471680c8591fd745176b89388 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 27 Sep 2019 18:59:19 +1000 Subject: [PATCH] AC_Avoid: adjust for proximity status namespace change --- libraries/AC_Avoidance/AC_Avoid.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 9c24daed2d..4fe87078fe 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -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 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; }