AP_AHRS: remove not-needed virtual methods from backends

we will add them to the data structure rather than having callbacks
This commit is contained in:
Peter Barker 2023-11-23 23:22:51 +11:00 committed by Andrew Tridgell
parent 5a62983fba
commit d230e9c552
4 changed files with 2 additions and 25 deletions

View File

@ -2518,7 +2518,8 @@ bool AP_AHRS::getMagOffsets(uint8_t mag_idx, Vector3f &magOffsets) const
#if AP_AHRS_SIM_ENABLED
case EKFType::SIM:
return sim.get_mag_offsets(mag_idx, magOffsets);
magOffsets.zero();
return true;
#endif
#if AP_AHRS_EXTERNAL_ENABLED
case EKFType::EXTERNAL:

View File

@ -176,19 +176,6 @@ public:
// This is different to the vertical velocity from the EKF which is not always consistent with the vertical position due to the various errors that are being corrected for.
virtual bool get_vert_pos_rate_D(float &velocity) const = 0;
// returns the estimated magnetic field offsets in body frame
virtual bool get_mag_field_correction(Vector3f &ret) const WARN_IF_UNUSED {
return false;
}
virtual bool get_mag_field_NED(Vector3f &vec) const {
return false;
}
virtual bool get_mag_offsets(uint8_t mag_idx, Vector3f &magOffsets) const {
return false;
}
//
virtual bool set_origin(const Location &loc) {
return false;

View File

@ -172,13 +172,6 @@ void AP_AHRS_SIM::get_control_limits(float &ekfGndSpdLimit, float &ekfNavVelGain
ekfNavVelGainScaler = 1.0f;
}
bool AP_AHRS_SIM::get_mag_offsets(uint8_t mag_idx, Vector3f &magOffsets) const
{
magOffsets.zero();
return true;
}
void AP_AHRS_SIM::send_ekf_status_report(GCS_MAVLINK &link) const
{
#if HAL_GCS_ENABLED

View File

@ -98,10 +98,6 @@ public:
// get_filter_status - returns filter status as a series of flags
bool get_filter_status(nav_filter_status &status) const override;
// get compass offset estimates
// true if offsets are valid
bool get_mag_offsets(uint8_t mag_idx, Vector3f &magOffsets) const override;
// relative-origin functions for fallback in AP_InertialNav
bool get_origin(Location &ret) const override;
bool get_relative_position_NED_origin(Vector3f &vec) const override;