mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
AP_InertialNav: increase time constant for Z axis to 7 seconds
This commit is contained in:
parent
e3ee865dc0
commit
d4b73e7b07
@ -10,7 +10,7 @@
|
||||
|
||||
#define AP_INTERTIALNAV_GRAVITY 9.80665
|
||||
#define AP_INTERTIALNAV_TC_XY 3.0 // default time constant for complementary filter's X & Y axis
|
||||
#define AP_INTERTIALNAV_TC_Z 3.0 // default time constant for complementary filter's Z axis
|
||||
#define AP_INTERTIALNAV_TC_Z 7.0 // default time constant for complementary filter's Z axis
|
||||
|
||||
// #defines to control how often historical accel based positions are saved
|
||||
// so they can later be compared to laggy gps readings
|
||||
|
Loading…
Reference in New Issue
Block a user