Browse Source

Copter: fix init of wp_verify_byte so wp alt is always required

mission-4.1.18
Randy Mackay 12 years ago
parent
commit
a1295c042b
  1. 5
      ArduCopter/commands_logic.pde

5
ArduCopter/commands_logic.pde

@ -279,11 +279,6 @@ static void do_nav_wp() @@ -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;

Loading…
Cancel
Save