From f7a735b990542a1e9161b0ab1f8164893e7ccf57 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 19 Nov 2017 16:05:01 +1100 Subject: [PATCH] Plane: fixed transitions for tailsitters after auto-takeoff need to use angle wait --- ArduPlane/quadplane.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index e3923ea456..43cc8970dd 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1249,6 +1249,11 @@ void QuadPlane::update_transition(void) float aspeed; bool have_airspeed = ahrs.airspeed_estimate(&aspeed); + + // tailsitters use angle wait, not airspeed wait + if (is_tailsitter() && transition_state == TRANSITION_AIRSPEED_WAIT) { + transition_state = TRANSITION_ANGLE_WAIT_FW; + } /* see if we should provide some assistance @@ -2199,7 +2204,7 @@ bool QuadPlane::verify_vtol_takeoff(const AP_Mission::Mission_Command &cmd) if (plane.current_loc.alt < plane.next_WP_loc.alt) { return false; } - transition_state = TRANSITION_AIRSPEED_WAIT; + transition_state = is_tailsitter() ? TRANSITION_ANGLE_WAIT_FW : TRANSITION_AIRSPEED_WAIT; plane.TECS_controller.set_pitch_max_limit(transition_pitch_max); set_alt_target_current();