mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
InertialNav: reduce XY TC to 2.5 (was 3)
More objective testing is required to arrive at the ideal number but 2.5 seem better than 3.0 at reducing "toiletbowling" and anecdotal evidence does not show much downside.
This commit is contained in:
parent
c139134192
commit
8122a32114
@ -8,7 +8,7 @@
|
||||
#include <AP_Baro.h> // ArduPilot Mega Barometer Library
|
||||
#include <AP_Buffer.h> // FIFO buffer library
|
||||
|
||||
#define AP_INTERTIALNAV_TC_XY 3.0f // default time constant for complementary filter's X & Y axis
|
||||
#define AP_INTERTIALNAV_TC_XY 2.5f // default time constant for complementary filter's X & Y axis
|
||||
#define AP_INTERTIALNAV_TC_Z 5.0f // default time constant for complementary filter's Z axis
|
||||
|
||||
// #defines to control how often historical accel based positions are saved
|
||||
|
Loading…
Reference in New Issue
Block a user