Browse Source

Copter: bug fix to take-off in Loiter and AltHold

Always set the target altitude after take-off to be current altitude +
20cm.  This resolves a bug in which the target altitude could end up
being a couple of meters higher than the current altitude if the user
entered Loiter / Alt Hold mode before inertial nav altitude estimate had
settled.
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
f29f7d9777
  1. 5
      ArduCopter/Attitude.pde

5
ArduCopter/Attitude.pde

@ -979,9 +979,8 @@ static void @@ -979,9 +979,8 @@ static void
set_throttle_takeoff()
{
// set alt target
if (controller_desired_alt < current_loc.alt) {
controller_desired_alt = current_loc.alt + ALT_HOLD_TAKEOFF_JUMP;
}
controller_desired_alt = current_loc.alt + ALT_HOLD_TAKEOFF_JUMP;
// clear i term from acceleration controller
if (g.pid_throttle_accel.get_integrator() < 0) {
g.pid_throttle_accel.reset_I();

Loading…
Cancel
Save