AC_Avoidance: handle upward proximity enable and disable

This commit is contained in:
Tatsuya Yamaguchi 2021-07-30 09:17:29 +09:00 committed by Andrew Tridgell
parent 8674409986
commit ca5d307001
1 changed files with 1 additions and 1 deletions

View File

@ -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;