diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.cpp b/libraries/AP_NavEKF3/AP_NavEKF3.cpp index 6889f57825..5ddceac4c1 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.cpp +++ b/libraries/AP_NavEKF3/AP_NavEKF3.cpp @@ -1239,6 +1239,12 @@ void NavEKF3::getAccelBias(int8_t instance, Vector3f &accelBias) const } } +// returns active source set used by EKF3 +uint8_t NavEKF3::get_active_source_set() const +{ + return sources.get_active_source_set(); +} + // reset body axis gyro bias estimates void NavEKF3::resetGyroBias(void) { diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index 98fac0a9cb..7b1487b3cc 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -97,6 +97,9 @@ public: // An out of range instance (eg -1) returns data for the primary instance void getAccelBias(int8_t instance, Vector3f &accelBias) const; + //returns index of the active source set used + uint8_t get_active_source_set() const; + // reset body axis gyro bias estimates void resetGyroBias(void);