Plane: default Q_TRANS_DECEL to 6 for tailsitters
This commit is contained in:
parent
a7b809d5d4
commit
46722500b0
@ -599,6 +599,7 @@ static const struct AP_Param::defaults_table_struct defaults_table_tailsitter[]
|
|||||||
{ "MIXING_GAIN", 1.0 },
|
{ "MIXING_GAIN", 1.0 },
|
||||||
{ "RUDD_DT_GAIN", 10 },
|
{ "RUDD_DT_GAIN", 10 },
|
||||||
{ "Q_TRANSITION_MS", 2000 },
|
{ "Q_TRANSITION_MS", 2000 },
|
||||||
|
{ "Q_TRANS_DECEL", 6 },
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user