From 6816c45c392be8402ccaa0f5f92cea8dbb6b0f5c Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 1 Apr 2013 11:51:12 +0900 Subject: [PATCH] InertialNav: reduce Z-axis time constant to 5 --- libraries/AP_InertialNav/AP_InertialNav.h | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index 4e1148d139..395a6f8143 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -10,9 +10,7 @@ #define AP_INTERTIALNAV_GRAVITY 9.80665f #define AP_INTERTIALNAV_TC_XY 3.0f // default time constant for complementary filter's X & Y axis -#define AP_INTERTIALNAV_TC_Z 7.0f // 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_TC_Z 5.0f // 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