Browse Source

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.
master
Randy Mackay 12 years ago
parent
commit
8122a32114
  1. 2
      libraries/AP_InertialNav/AP_InertialNav.h

2
libraries/AP_InertialNav/AP_InertialNav.h

@ -8,7 +8,7 @@ @@ -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…
Cancel
Save