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
// airspeed data when in fixed wing mode to estimate the quaternions that are used to rotate IMU data into a
// Front, Right, Yaw frame of reference.
Vector3fdelta_angle;
Vector3fdelta_velocity;
floatangle_dt;
floatvelocity_dt;
structahrs_struct{
Matrix3fR;// matrix that rotates a vector from body to earth frame
Vector3fgyro_bias;// gyro bias learned and used by the quaternion calculation
boolaligned{false};// true when AHRS has been aligned
floataccel_FR[2];// front-right acceleration vector in a horizontal plane (m/s/s)
floatvel_NE[2];// NE velocity vector from last GPS measurement (m/s)
boolfuse_gps;// true when GPS should be fused on that frame
floataccel_dt;// time step used when generating _simple_accel_FR data (sec)
};
ahrs_structAHRS[N_MODELS_EKFGSF];
boolahrs_tilt_aligned;// true the initial tilt alignment has been calculated
floataccel_gain;// gain from accel vector tilt error to rate gyro correction used by AHRS calculation
Vector3fahrs_accel;// filtered body frame specific force vector used by AHRS calculation (m/s/s)
floatahrs_accel_norm;// length of body frame specific force vector used by AHRS calculation (m/s/s)
boolahrs_turn_comp_enabled;// true when compensation for centripetal acceleration in coordinated turns using true airspeed is being used.
floattrue_airspeed;// true airspeed used to correct for centripetal acceleratoin in coordinated turns (m/s)
// Runs quaternion prediction for the selected AHRS using IMU (and optionally true airspeed) data
voidpredictAHRS(constuint8_tmdl_idx);
// Applies a body frame delta angle to a body to earth frame rotation matrix using a small angle approximation