Plane: lower default Q_M_SPOOL_TIME to 0.25

This commit is contained in:
Andrew Tridgell 2017-02-13 21:35:41 +11:00 committed by Randy Mackay
parent 2187417d74
commit c294519925
1 changed files with 1 additions and 0 deletions

View File

@ -347,6 +347,7 @@ static const struct {
{ "Q_A_RAT_PIT_P", 0.25 },
{ "Q_A_RAT_PIT_I", 0.25 },
{ "Q_A_RAT_PIT_FILT", 10.0 },
{ "Q_M_SPOOL_TIME", 0.25 },
};
QuadPlane::QuadPlane(AP_AHRS_NavEKF &_ahrs) :