From d34ea4c1247699c406a88bc6f52e63a4ff77922c Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Thu, 13 Nov 2014 18:38:55 -0800
Subject: [PATCH] AC_PosControl: fix to default force_descend param

---
 libraries/AC_AttitudeControl/AC_PosControl.h | 3 ++-
 1 file changed, 2 insertions(+), 1 deletion(-)

diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h
index 08bc77440..0347c5151 100644
--- a/libraries/AC_AttitudeControl/AC_PosControl.h
+++ b/libraries/AC_AttitudeControl/AC_PosControl.h
@@ -109,7 +109,8 @@ public:
     ///     should be called continuously (with dt set to be the expected time between calls)
     ///     actual position target will be moved no faster than the speed_down and speed_up
     ///     target will also be stopped if the motors hit their limits or leash length is exceeded
-    void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend = true);
+    ///     set force_descend to true during landing to allow target to move low enough to slow the motors
+    void set_alt_target_from_climb_rate(float climb_rate_cms, float dt, bool force_descend = false);
 
     /// set_alt_target_to_current_alt - set altitude target to current altitude
     void set_alt_target_to_current_alt() { _pos_target.z = _inav.get_altitude(); }
-- 
GitLab