From 8122a32114ce8ba7223489d28bfb64403808e1a4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 30 Apr 2013 12:52:28 +0900 Subject: [PATCH] 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. --- libraries/AP_InertialNav/AP_InertialNav.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index b10fbe880a..d99582d686 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -8,7 +8,7 @@ #include // ArduPilot Mega Barometer Library #include // 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