From d4438f0a1c23e0274b7b0e099038cbab97c379ae Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 1 Nov 2019 09:43:16 +1100 Subject: [PATCH] Copter: correct compilation when avoidance disabled --- ArduCopter/surface_tracking.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduCopter/surface_tracking.cpp b/ArduCopter/surface_tracking.cpp index 3a490298e7..0c5c497a17 100644 --- a/ArduCopter/surface_tracking.cpp +++ b/ArduCopter/surface_tracking.cpp @@ -39,11 +39,13 @@ float Copter::SurfaceTracking::adjust_climb_rate(float target_rate) } valid_for_logging = true; +#if AC_AVOID_ENABLED == ENABLED // upward facing terrain following never gets closer than avoidance margin if (surface == Surface::CEILING) { const float margin_cm = copter.avoid.enabled() ? copter.avoid.get_margin() * 100.0f : 0.0f; target_dist_cm = MAX(target_dist_cm, margin_cm); } +#endif // calc desired velocity correction from target rangefinder alt vs actual rangefinder alt (remove the error already passed to Altitude controller to avoid oscillations) const float distance_error = (target_dist_cm - rf_state.alt_cm) - (dir * current_alt_error);