diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 0d44f6d9a1..ed0457ab9a 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -107,7 +107,14 @@ public: return Vector3f(0,0,0); } + // return true if yaw has been initialised + bool yaw_initialised(void) { + return _have_initial_yaw; + } + protected: + // whether the yaw value has been intialised with a reference + bool _have_initial_yaw; // pointer to compass object, if available Compass * _compass; diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 885c18f8b7..79dd774d82 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -64,7 +64,6 @@ public: private: float _ki; float _ki_yaw; - bool _have_initial_yaw; // Methods void matrix_update(float _G_Dt); diff --git a/libraries/AP_AHRS/AP_AHRS_MPU6000.h b/libraries/AP_AHRS/AP_AHRS_MPU6000.h index 0a3aa8e8c3..7cbe8bdc3b 100644 --- a/libraries/AP_AHRS/AP_AHRS_MPU6000.h +++ b/libraries/AP_AHRS/AP_AHRS_MPU6000.h @@ -67,7 +67,6 @@ public: private: float _ki; float _ki_yaw; - bool _have_initial_yaw; AP_InertialSensor_MPU6000 *_mpu6000; // Methods diff --git a/libraries/AP_AHRS/AP_AHRS_Quaternion.h b/libraries/AP_AHRS/AP_AHRS_Quaternion.h index 91c41e2ea4..fe322e3958 100644 --- a/libraries/AP_AHRS/AP_AHRS_Quaternion.h +++ b/libraries/AP_AHRS/AP_AHRS_Quaternion.h @@ -58,8 +58,6 @@ private: void update_IMU(float deltat, Vector3f &gyro, Vector3f &accel); void update_MARG(float deltat, Vector3f &gyro, Vector3f &accel, Vector3f &mag); - bool _have_initial_yaw; - // Methods void accel_adjust(void);