Browse Source

Copter: use force_descend option on auto landings

master
Jonathan Challinger 10 years ago committed by Randy Mackay
parent
commit
c7a38c4350
  1. 2
      ArduCopter/control_auto.pde
  2. 4
      ArduCopter/control_land.pde
  3. 2
      ArduCopter/control_rtl.pde

2
ArduCopter/control_auto.pde

@ -324,7 +324,7 @@ static void auto_land_run() @@ -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

4
ArduCopter/control_land.pde

@ -112,7 +112,7 @@ static void land_gps_run() @@ -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() @@ -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();
}

2
ArduCopter/control_rtl.pde

@ -377,7 +377,7 @@ static void rtl_land_run() @@ -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

Loading…
Cancel
Save