mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
InertialNav: increase max accel correction to 3m/s
This commit is contained in:
parent
4c40b44563
commit
38b6894712
@ -12,7 +12,7 @@
|
|||||||
#define AP_INTERTIALNAV_TC_XY 3.0 // default time constant for complementary filter's X & Y axis
|
#define AP_INTERTIALNAV_TC_XY 3.0 // default time constant for complementary filter's X & Y axis
|
||||||
#define AP_INTERTIALNAV_TC_Z 7.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
|
||||||
|
|
||||||
#define AP_INTERTIALNAV_ACCEL_CORR_MAX 100.0 // max allowed accelerometer offset correction
|
#define AP_INTERTIALNAV_ACCEL_CORR_MAX 300.0 // max allowed accelerometer offset correction
|
||||||
|
|
||||||
// #defines to control how often historical accel based positions are saved
|
// #defines to control how often historical accel based positions are saved
|
||||||
// so they can later be compared to laggy gps readings
|
// so they can later be compared to laggy gps readings
|
||||||
|
Loading…
Reference in New Issue
Block a user