mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: added correct filter defaults
This commit is contained in:
parent
9cf909607f
commit
e7f7afcc4d
@ -238,10 +238,12 @@ static const struct {
|
||||
const char *name;
|
||||
float value;
|
||||
} defaults_table[] = {
|
||||
{ "Q_A_RAT_RLL_P", 0.25 },
|
||||
{ "Q_A_RAT_RLL_I", 0.25 },
|
||||
{ "Q_A_RAT_PIT_P", 0.25 },
|
||||
{ "Q_A_RAT_PIT_I", 0.25 },
|
||||
{ "Q_A_RAT_RLL_P", 0.25 },
|
||||
{ "Q_A_RAT_RLL_I", 0.25 },
|
||||
{ "Q_A_RAT_RLL_FILT", 10.0 },
|
||||
{ "Q_A_RAT_PIT_P", 0.25 },
|
||||
{ "Q_A_RAT_PIT_I", 0.25 },
|
||||
{ "Q_A_RAT_PIT_FILT", 10.0 },
|
||||
};
|
||||
|
||||
QuadPlane::QuadPlane(AP_AHRS_NavEKF &_ahrs) :
|
||||
|
Loading…
Reference in New Issue
Block a user