mirror of https://github.com/ArduPilot/ardupilot
Plane: allow for new guided destination during guided takeoff
if you set a very high alt for takeoff this is useful
This commit is contained in:
parent
b6449f41c2
commit
0160782857
|
@ -99,6 +99,9 @@ void Plane::set_guided_WP(void)
|
||||||
auto_state.vtol_loiter = false;
|
auto_state.vtol_loiter = false;
|
||||||
|
|
||||||
loiter_angle_reset();
|
loiter_angle_reset();
|
||||||
|
|
||||||
|
// cancel pending takeoff
|
||||||
|
quadplane.guided_takeoff = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -2508,6 +2508,10 @@ bool QuadPlane::in_vtol_mode(void) const
|
||||||
poscontrol.get_state() > QPOS_APPROACH) {
|
poscontrol.get_state() > QPOS_APPROACH) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
if (plane.control_mode == &plane.mode_guided &&
|
||||||
|
guided_takeoff) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
if (in_vtol_auto()) {
|
if (in_vtol_auto()) {
|
||||||
if (!plane.auto_state.vtol_loiter || poscontrol.get_state() > QPOS_APPROACH) {
|
if (!plane.auto_state.vtol_loiter || poscontrol.get_state() > QPOS_APPROACH) {
|
||||||
return true;
|
return true;
|
||||||
|
|
Loading…
Reference in New Issue