mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: removed have_ekf_logging()
This commit is contained in:
parent
403275beea
commit
1bc82d3118
@ -177,11 +177,6 @@ public:
|
||||
// check all cores providing consistent attitudes for prearm checks
|
||||
virtual bool attitudes_consistent(char *failure_msg, const uint8_t failure_msg_len) const { return true; }
|
||||
|
||||
// is the EKF backend doing its own sensor logging?
|
||||
virtual bool have_ekf_logging(void) const {
|
||||
return false;
|
||||
}
|
||||
|
||||
// see if EKF lane switching is possible to avoid EKF failsafe
|
||||
virtual void check_lane_switch(void) {}
|
||||
|
||||
|
@ -428,8 +428,6 @@ const Vector3f &AP_AHRS_NavEKF::get_accel_ef_blended(void) const
|
||||
return _accel_ef_ekf_blended;
|
||||
}
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
void AP_AHRS_NavEKF::reset(bool recover_eulers)
|
||||
{
|
||||
// support locked access functions to AHRS data
|
||||
@ -2190,32 +2188,6 @@ bool AP_AHRS_NavEKF::getGpsGlitchStatus() const
|
||||
return ekf_status.flags.gps_glitching;
|
||||
}
|
||||
|
||||
// is the EKF backend doing its own sensor logging?
|
||||
bool AP_AHRS_NavEKF::have_ekf_logging(void) const
|
||||
{
|
||||
switch (ekf_type()) {
|
||||
case EKFType::NONE:
|
||||
return false;
|
||||
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
case EKFType::TWO:
|
||||
return EKF2.have_ekf_logging();
|
||||
#endif
|
||||
|
||||
#if HAL_NAVEKF3_AVAILABLE
|
||||
case EKFType::THREE:
|
||||
return EKF3.have_ekf_logging();
|
||||
#endif
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
case EKFType::SITL:
|
||||
return false;
|
||||
#endif
|
||||
}
|
||||
// since there is no default case above, this is unreachable
|
||||
return false;
|
||||
}
|
||||
|
||||
//get the index of the active airspeed sensor, wrt the primary core
|
||||
uint8_t AP_AHRS_NavEKF::get_active_airspeed_index() const
|
||||
{
|
||||
|
@ -277,9 +277,6 @@ public:
|
||||
|
||||
bool getGpsGlitchStatus() const;
|
||||
|
||||
// is the EKF backend doing its own sensor logging?
|
||||
bool have_ekf_logging(void) const override;
|
||||
|
||||
// return the index of the airspeed we should use for airspeed measurements
|
||||
// with multiple airspeed sensors and airspeed affinity in EKF3, it is possible to have switched
|
||||
// over to a lane not using the primary airspeed sensor, so AHRS should know which airspeed sensor
|
||||
|
Loading…
Reference in New Issue
Block a user