From c7a38c4350203d8d5652fa0c3e5dee094364a08d Mon Sep 17 00:00:00 2001
From: Jonathan Challinger <mr.challinger@gmail.com>
Date: Thu, 13 Nov 2014 16:57:25 -0800
Subject: [PATCH] Copter: use force_descend option on auto landings

---
 ArduCopter/control_auto.pde | 2 +-
 ArduCopter/control_land.pde | 4 ++--
 ArduCopter/control_rtl.pde  | 2 +-
 3 files changed, 4 insertions(+), 4 deletions(-)

diff --git a/ArduCopter/control_auto.pde b/ArduCopter/control_auto.pde
index 99751ac32..f3b68f81b 100644
--- a/ArduCopter/control_auto.pde
+++ b/ArduCopter/control_auto.pde
@@ -324,7 +324,7 @@ static void auto_land_run()
     wp_nav.update_loiter();
 
     // call z-axis position controller
-    pos_control.set_alt_target_from_climb_rate(get_throttle_land(), G_Dt);
+    pos_control.set_alt_target_from_climb_rate(get_throttle_land(), G_Dt, true);
     pos_control.update_z_controller();
 
     // roll & pitch from waypoint controller, yaw rate from pilot
diff --git a/ArduCopter/control_land.pde b/ArduCopter/control_land.pde
index 62dc55769..68c22e506 100644
--- a/ArduCopter/control_land.pde
+++ b/ArduCopter/control_land.pde
@@ -112,7 +112,7 @@ static void land_gps_run()
     }
 
     // update altitude target and call position controller
-    pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt);
+    pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true);
     pos_control.update_z_controller();
 }
 
@@ -170,7 +170,7 @@ static void land_nogps_run()
     }
 
     // call position controller
-    pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt);
+    pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true);
     pos_control.update_z_controller();
 }
 
diff --git a/ArduCopter/control_rtl.pde b/ArduCopter/control_rtl.pde
index 34476df68..7fc522323 100644
--- a/ArduCopter/control_rtl.pde
+++ b/ArduCopter/control_rtl.pde
@@ -377,7 +377,7 @@ static void rtl_land_run()
 
     // call z-axis position controller
     float cmb_rate = get_throttle_land();
-    pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt);
+    pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true);
     pos_control.update_z_controller();
 
     // roll & pitch from waypoint controller, yaw rate from pilot
-- 
GitLab