From 74da3c74acbf0fe1095722704225786d3f1a44c5 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 15 May 2021 08:14:06 +1000 Subject: [PATCH] Plane: cope with Q pitch limit larger than fixed wing limit prevents tailsitter VTOL transition timeout due to not achieving angle --- ArduPlane/tailsitter.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index 08da8c53de..02373f192d 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -278,7 +278,10 @@ bool QuadPlane::tailsitter_transition_vtol_complete(void) const return true; } } - const float trans_angle = get_tailsitter_transition_angle_vtol(); + // limit completion angle to just below fixed wing pitch limit + const float margin_deg = 3; + const float trans_angle = MIN(get_tailsitter_transition_angle_vtol(), + plane.aparm.pitch_limit_max_cd*0.01-margin_deg); if (labs(plane.ahrs.pitch_sensor) > trans_angle*100) { gcs().send_text(MAV_SEVERITY_INFO, "Transition VTOL done"); return true;