mirror of https://github.com/ArduPilot/ardupilot
Copter: fix init of wp_verify_byte so wp alt is always required
This commit is contained in:
parent
551950c573
commit
a1295c042b
|
@ -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…
Reference in New Issue