mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: default rate max to 75 for quadplane VTOL
this reduces overshoot when VTOL tune is less than ideal
This commit is contained in:
parent
1a33ca3ebe
commit
6d4615ac7a
@ -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 },
|
||||
|
Loading…
Reference in New Issue
Block a user