From d054ca0426db036eb9f06c41957a36105708a451 Mon Sep 17 00:00:00 2001 From: Peter Hall Date: Wed, 10 Nov 2021 02:15:32 +0000 Subject: [PATCH] Plane: quadplane: limit post VTOL transtion pitch rate on tailsitters in maunal modes --- ArduPlane/mode_qstabilize.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ArduPlane/mode_qstabilize.cpp b/ArduPlane/mode_qstabilize.cpp index 73a7ec9acb..8a5f9fef65 100644 --- a/ArduPlane/mode_qstabilize.cpp +++ b/ArduPlane/mode_qstabilize.cpp @@ -64,6 +64,8 @@ void ModeQStabilize::set_tailsitter_roll_pitch(const float roll_input, const flo // angle max for tailsitter pitch plane.nav_pitch_cd = pitch_input * plane.quadplane.aparm.angle_max; + + plane.quadplane.transition->set_VTOL_roll_pitch_limit(plane.nav_roll_cd, plane.nav_pitch_cd); } // set the desired roll and pitch for normal quadplanes, also limited by forward flight limtis