constfloatEKFGSF_gyroNoise{1.0e-1f};// yaw rate noise used for covariance prediction (rad/sec)
constfloatEKFGSF_accelNoise{2.0f};// horizontal accel noise used for covariance prediction (m/sec**2)
constfloatEKFGSF_tiltGain{0.2f};// gain from tilt error to gyro correction for complementary filter (1/sec)
constfloatEKFGSF_gyroBiasGain{0.04f};// gain applied to integral of gyro correction for complementary filter (1/sec)
constfloatEKFGSF_gyroNoise{1.0e-1f};// yaw rate noise used for covariance prediction (rad/sec)
constfloatEKFGSF_accelNoise{2.0f};// horizontal accel noise used for covariance prediction (m/sec**2)
constfloatEKFGSF_tiltGain{0.2f};// gain from tilt error to gyro correction for complementary filter (1/sec)
constfloatEKFGSF_gyroBiasGain{0.04f};// gain applied to integral of gyro correction for complementary filter (1/sec)
constfloatEKFGSF_accelFiltRatio{10.0f};// ratio of time constant of AHRS tilt correction to time constant of first order LPF applied to accel data used by ahrs
// Declarations used by the bank of AHRS complementary filters that use IMU data augmented by true