Browse Source

Copter: bug fix for take-off so it never descends

If copter was already flying when take-off command was received it could
descend to the target altitude if it was below the current altitude.
mission-4.1.18
Randy Mackay 12 years ago
parent
commit
d65d7d95e2
  1. 2
      ArduCopter/commands_logic.pde

2
ArduCopter/commands_logic.pde

@ -245,7 +245,7 @@ static void do_takeoff()
// Set wp navigation target to safe altitude above current position // Set wp navigation target to safe altitude above current position
Vector3f pos = inertial_nav.get_position(); Vector3f pos = inertial_nav.get_position();
pos.z = command_nav_queue.alt; pos.z = max(pos.z, command_nav_queue.alt);
wp_nav.set_destination(pos); wp_nav.set_destination(pos);
// prevent flips // prevent flips

Loading…
Cancel
Save