diff --git a/ArduCopter/control_auto.pde b/ArduCopter/control_auto.pde index 6648f46bbceefa47be23aba3f6009b603306818c..6f28aa72298494dcfa29a86c3d8a700c44816080 100644 --- a/ArduCopter/control_auto.pde +++ b/ArduCopter/control_auto.pde @@ -315,7 +315,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 62dc557690877b26c6323ccd641113f69d3b9833..68c22e5068f1afc267e49e7236aacaf9d7a4135a 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 34476df681c5719c6c577cd2f0c70e4a1399511c..7fc5223232866993076390f6426ee5278cdbd8d0 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