From ad48394b503ba0f1731c5f7b7e9ff75c2d2f8352 Mon Sep 17 00:00:00 2001 From: Samuel Tabor Date: Thu, 10 Sep 2020 10:24:19 +0100 Subject: [PATCH] Plane: Add comment to clarify additional 10m in soaring altitude target. --- ArduPlane/navigation.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 884365c8ae..aa2d0d48dd 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -344,6 +344,8 @@ void Plane::update_fbwb_speed_height(void) // we're in soaring mode with throttle suppressed set_target_altitude_current(); } else { + // we're in soaring mode climbing back to altitude. Set target to SOAR_ALT_CUTOFF plus 10m to ensure we positively climb + // through SOAR_ALT_CUTOFF, thus triggering throttle suppression and return to glide. target_altitude.amsl_cm = 100*plane.g2.soaring_controller.get_alt_cutoff() + 1000 + AP::ahrs().get_home().alt; } }