From 1dcc5886d04b4f42eca28b2934432d6762b7aab1 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 16 Jul 2013 15:51:18 +0900 Subject: [PATCH] Copter: ensure take-off alt is at least 1m fixes issue #377 --- ArduCopter/commands_logic.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 5076cd2f45..9ac54e83b2 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -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