From 381bd28518e216b8667b1a6d15fae25669a215b5 Mon Sep 17 00:00:00 2001 From: Randy Mackay <rmackay9@yahoo.com> Date: Mon, 14 Jan 2013 12:40:59 +0900 Subject: [PATCH] Copter: relax altitude check in verify_takeoff Previously we checked if the alt > target_alt but because there is little to no overshoot with the new accel based alt controller this check was failing for some users. --- ArduCopter/commands_logic.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index 2425eae8f..51d80d5f3 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -364,7 +364,7 @@ static bool verify_takeoff() return false; } // are we above our target altitude? - return (current_loc.alt > next_WP.alt); + return (alt_change_flag == REACHED_ALT); } // verify_land - returns true if landing has been completed -- GitLab