mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Lowering the D filter for less latency and less oscillation.
This commit is contained in:
parent
48ba24a810
commit
4315c06f34
@ -526,8 +526,8 @@ int32_t pitch_axis;
|
||||
AverageFilterInt32_Size3 roll_rate_d_filter; // filtered acceleration
|
||||
AverageFilterInt32_Size3 pitch_rate_d_filter; // filtered pitch acceleration
|
||||
|
||||
AverageFilterInt16_Size5 lat_rate_d_filter; // for filtering D term
|
||||
AverageFilterInt16_Size5 lon_rate_d_filter; // for filtering D term
|
||||
AverageFilterInt16_Size2 lat_rate_d_filter; // for filtering D term
|
||||
AverageFilterInt16_Size2 lon_rate_d_filter; // for filtering D term
|
||||
|
||||
// Barometer filter
|
||||
AverageFilterInt32_Size5 baro_filter; // filtered pitch acceleration
|
||||
|
Loading…
Reference in New Issue
Block a user