From 65bc8257a8ab4ed5141b0ddc69457b591744fa26 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Thu, 28 Mar 2013 19:18:39 +0900
Subject: [PATCH] InertialNav: reduce Z-axis time constant to 5

---
 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 2011d97ff..b0427a2ad 100644
--- a/libraries/AP_InertialNav/AP_InertialNav.h
+++ b/libraries/AP_InertialNav/AP_InertialNav.h
@@ -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    7.0 // default time constant for complementary filter's Z axis
+#define AP_INTERTIALNAV_TC_Z    5.0 // default time constant for complementary filter's Z axis
 
 #define AP_INTERTIALNAV_ACCEL_CORR_MAX 300.0    // max allowed accelerometer offset correction
 
-- 
GitLab