From a1295c042b8030adf4dbb6703d4707c7e6efe864 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 17 Mar 2013 16:37:30 +0900 Subject: [PATCH] Copter: fix init of wp_verify_byte so wp alt is always required --- ArduCopter/commands_logic.pde | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index c215a4b763..50397d50a8 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -279,11 +279,6 @@ static void do_nav_wp() // this is our bitmask to verify we have met all conditions to move on wp_verify_byte = 0; - // if no alt requirement in the waypoint, set the altitude achieved bit of wp_verify_byte - if((next_WP.options & WP_OPTION_ALT_REQUIRED) == false) { - wp_verify_byte |= NAV_ALTITUDE; - } - // if not delay requirement, set the delay achieved bit of wp_verify_byte if( command_nav_queue.p1 == 0 ) { wp_verify_byte |= NAV_DELAY;