Browse Source

Copter: ensure take-off alt is at least 1m

fixes issue #377
mission-4.1.18
Randy Mackay 12 years ago
parent
commit
1dcc5886d0
  1. 1
      ArduCopter/commands_logic.pde

1
ArduCopter/commands_logic.pde

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

Loading…
Cancel
Save