mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: don't crosstrack after AUTO VTOL takeoff
This commit is contained in:
parent
e53a43461b
commit
6466912ac0
@ -2763,6 +2763,9 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
|
||||
plane.SpdHgt_Controller->reset();
|
||||
}
|
||||
|
||||
// don't crosstrack on next WP
|
||||
plane.auto_state.next_wp_crosstrack = false;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user