Browse Source

Plane: allow for new guided destination during guided takeoff

if you set a very high alt for takeoff this is useful
c415-sdk
Andrew Tridgell 3 years ago committed by Randy Mackay
parent
commit
ab9a453b47
  1. 3
      ArduPlane/commands.cpp
  2. 4
      ArduPlane/quadplane.cpp

3
ArduPlane/commands.cpp

@ -99,6 +99,9 @@ void Plane::set_guided_WP(void) @@ -99,6 +99,9 @@ void Plane::set_guided_WP(void)
auto_state.vtol_loiter = false;
loiter_angle_reset();
// cancel pending takeoff
quadplane.guided_takeoff = false;
}
/*

4
ArduPlane/quadplane.cpp

@ -2508,6 +2508,10 @@ bool QuadPlane::in_vtol_mode(void) const @@ -2508,6 +2508,10 @@ bool QuadPlane::in_vtol_mode(void) const
poscontrol.get_state() > QPOS_APPROACH) {
return true;
}
if (plane.control_mode == &plane.mode_guided &&
guided_takeoff) {
return true;
}
if (in_vtol_auto()) {
if (!plane.auto_state.vtol_loiter || poscontrol.get_state() > QPOS_APPROACH) {
return true;

Loading…
Cancel
Save