diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index d7a3fed232..238a11b86c 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -442,6 +442,14 @@ public: return false; } + // get_variances - provides the innovations normalised using the innovation variance where a value of 0 + // indicates prefect consistency between the measurement and the EKF solution and a value of of 1 is the maximum + // inconsistency that will be accpeted by the filter + // boolean false is returned if variances are not available + virtual bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const { + return false; + } + // time that the AHRS has been up virtual uint32_t uptime_ms(void) const = 0; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 1e5c05b22e..b79b6ac703 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -214,7 +214,7 @@ public: // indicates prefect consistency between the measurement and the EKF solution and a value of of 1 is the maximum // inconsistency that will be accpeted by the filter // boolean false is returned if variances are not available - bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const; + bool get_variances(float &velVar, float &posVar, float &hgtVar, Vector3f &magVar, float &tasVar, Vector2f &offset) const override; // returns the expected NED magnetic field bool get_mag_field_NED(Vector3f& ret) const;