From f26b9ab286c7d45ce8c4606e98c183079174dcba Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 2 Sep 2012 11:28:32 +1000 Subject: [PATCH] APM: prevent crosstrack from takeoff point after takeoff completion --- ArduPlane/commands_logic.pde | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index f21a2ef225..aee57bb671 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -304,6 +304,7 @@ static bool verify_takeoff() if (current_loc.alt > takeoff_altitude) { hold_course = -1; takeoff_complete = true; + next_WP = current_loc; return true; } else { return false;