mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Plane: setup SMAX for Q modes
this enables logging of rates, which helps with tuning
This commit is contained in:
parent
b984dd4a62
commit
b749756c29
@ -568,9 +568,12 @@ static const struct AP_Param::defaults_table_struct defaults_table[] = {
|
||||
{ "Q_A_RAT_RLL_P", 0.25 },
|
||||
{ "Q_A_RAT_RLL_I", 0.25 },
|
||||
{ "Q_A_RAT_RLL_FLTD", 10.0 },
|
||||
{ "Q_A_RAT_RLL_SMAX", 50.0 },
|
||||
{ "Q_A_RAT_PIT_P", 0.25 },
|
||||
{ "Q_A_RAT_PIT_I", 0.25 },
|
||||
{ "Q_A_RAT_PIT_FLTD", 10.0 },
|
||||
{ "Q_A_RAT_PIT_SMAX", 50.0 },
|
||||
{ "Q_A_RAT_YAW_SMAX", 50.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