Plane: don't crosstrack after AUTO VTOL takeoff

This commit is contained in:
Andrew Tridgell 2020-08-01 20:31:53 +10:00
parent e53a43461b
commit 6466912ac0

View File

@ -2762,7 +2762,10 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd)
// takeoff height. // takeoff height.
plane.SpdHgt_Controller->reset(); plane.SpdHgt_Controller->reset();
} }
// don't crosstrack on next WP
plane.auto_state.next_wp_crosstrack = false;
return true; return true;
} }