diff --git a/libraries/AP_NavEKF/EKFGSF_yaw.h b/libraries/AP_NavEKF/EKFGSF_yaw.h index a141b3adf8..80aee7977c 100644 --- a/libraries/AP_NavEKF/EKFGSF_yaw.h +++ b/libraries/AP_NavEKF/EKFGSF_yaw.h @@ -80,7 +80,6 @@ private: float accel_gain; // gain from accel vector tilt error to rate gyro correction used by AHRS calculation Vector3f ahrs_accel; // filtered body frame specific force vector used by AHRS calculation (m/s/s) float ahrs_accel_norm; // length of body frame specific force vector used by AHRS calculation (m/s/s) - bool ahrs_turn_comp_enabled; // true when compensation for centripetal acceleration in coordinated turns using true airspeed is being used. float true_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