diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 8b385f2291..4e2d49ab1c 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -188,6 +188,11 @@ public: return nullptr; } + // is the EKF backend doing its own sensor logging? + virtual bool have_ekf_logging(void) const { + return false; + } + // Euler angles (radians) float roll; float pitch; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 911539f0dc..3a0db90cb1 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -1272,5 +1272,11 @@ bool AP_AHRS_NavEKF::getGpsGlitchStatus() } +// is the EKF backend doing its own sensor logging? +bool AP_AHRS_NavEKF::have_ekf_logging(void) const +{ + return false; +} + #endif // AP_AHRS_NAVEKF_AVAILABLE diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 486e1c540c..28a855812e 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -219,6 +219,9 @@ public: // used by Replay to force start at right timestamp void force_ekf_start(void) { force_ekf = true; } + + // is the EKF backend doing its own sensor logging? + bool have_ekf_logging(void) const override; private: enum EKF_TYPE {EKF_TYPE_NONE=0,