AP_AHRS: added have_ekf_logging() API
This commit is contained in:
parent
71b121837a
commit
795080742e
@ -188,6 +188,11 @@ public:
|
|||||||
return nullptr;
|
return nullptr;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// is the EKF backend doing its own sensor logging?
|
||||||
|
virtual bool have_ekf_logging(void) const {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// Euler angles (radians)
|
// Euler angles (radians)
|
||||||
float roll;
|
float roll;
|
||||||
float pitch;
|
float pitch;
|
||||||
|
@ -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
|
#endif // AP_AHRS_NAVEKF_AVAILABLE
|
||||||
|
|
||||||
|
@ -220,6 +220,9 @@ public:
|
|||||||
// used by Replay to force start at right timestamp
|
// used by Replay to force start at right timestamp
|
||||||
void force_ekf_start(void) { force_ekf = true; }
|
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:
|
private:
|
||||||
enum EKF_TYPE {EKF_TYPE_NONE=0,
|
enum EKF_TYPE {EKF_TYPE_NONE=0,
|
||||||
#if AP_AHRS_WITH_EKF1
|
#if AP_AHRS_WITH_EKF1
|
||||||
|
Loading…
Reference in New Issue
Block a user