From c857f889b305b34dce308c586af30f2a461c473c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 6 Nov 2021 21:40:14 +1100 Subject: [PATCH] Plane: default rate max to 75 for quadplane VTOL this reduces overshoot when VTOL tune is less than ideal --- ArduPlane/quadplane.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index ddad00e32a..36c7f525c4 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -575,6 +575,9 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = { { "Q_A_RAT_PIT_FLTD", 10.0 }, { "Q_A_RAT_PIT_SMAX", 50.0 }, { "Q_A_RAT_YAW_SMAX", 50.0 }, + { "Q_A_RATE_R_MAX", 75.0 }, + { "Q_A_RATE_P_MAX", 75.0 }, + { "Q_A_RATE_Y_MAX", 75.0 }, { "Q_M_SPOOL_TIME", 0.25 }, { "Q_LOIT_ANG_MAX", 15.0 }, { "Q_LOIT_ACC_MAX", 250.0 },