From ca5d307001cd4769dd15f6cd6af6ffaeeb2b65b8 Mon Sep 17 00:00:00 2001 From: Tatsuya Yamaguchi Date: Fri, 30 Jul 2021 09:17:29 +0900 Subject: [PATCH] AC_Avoidance: handle upward proximity enable and disable --- libraries/AC_Avoidance/AC_Avoid.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index 46596e069f..63060052aa 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -390,7 +390,7 @@ void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_c // get distance from proximity sensor float proximity_alt_diff; AP_Proximity *proximity = AP::proximity(); - if (proximity && proximity->get_upward_distance(proximity_alt_diff)) { + if (proximity && _proximity_enabled && proximity->get_upward_distance(proximity_alt_diff)) { proximity_alt_diff -= _margin; if (!limit_alt || proximity_alt_diff < alt_diff) { alt_diff = proximity_alt_diff;