Browse Source

Plane: allow for new guided destination during guided takeoff

if you set a very high alt for takeoff this is useful
gps-1.3.1
Andrew Tridgell 4 years ago
parent
commit
7547ad53d3
  1. 5
      ArduPlane/commands.cpp
  2. 4
      ArduPlane/quadplane.cpp

5
ArduPlane/commands.cpp

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

4
ArduPlane/quadplane.cpp

@ -2011,6 +2011,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…
Cancel
Save