Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Remove unused AHRS methods #28970

Merged
merged 4 commits into from
Dec 31, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 2 additions & 1 deletion libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
37 changes: 0 additions & 37 deletions libraries/AP_AHRS/AP_AHRS_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -72,18 +72,6 @@ class AP_AHRS_Backend
// init sets up INS board orientation
virtual void init();

// return the index of the primary core or -1 if no primary core selected
virtual int8_t get_primary_core_index() const { return -1; }

// get the index of the current primary accelerometer sensor
virtual uint8_t get_primary_accel_index(void) const {
#if AP_INERTIALSENSOR_ENABLED
return AP::ins().get_first_usable_accel();
#else
return 0;
#endif
}

// get the index of the current primary gyro sensor
virtual uint8_t get_primary_gyro_index(void) const {
#if AP_INERTIALSENSOR_ENABLED
Expand Down Expand Up @@ -148,12 +136,6 @@ class AP_AHRS_Backend
return true;
}

// return estimate of true airspeed vector in body frame in m/s
// returns false if estimate is unavailable
virtual bool airspeed_vector_true(Vector3f &vec) const WARN_IF_UNUSED {
return false;
}

// get apparent to true airspeed ratio
static float get_EAS2TAS(void);
static float get_TAS2EAS(void) { return 1.0/get_EAS2TAS(); }
Expand Down Expand Up @@ -194,19 +176,6 @@ class AP_AHRS_Backend
// 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;
Expand Down Expand Up @@ -243,12 +212,6 @@ class AP_AHRS_Backend
// return the quaternion defining the rotation from NED to XYZ (body) axes
virtual bool get_quaternion(Quaternion &quat) const WARN_IF_UNUSED = 0;

// return true if the AHRS object supports inertial navigation,
// with very accurate position and velocity
virtual bool have_inertial_nav(void) const {
return false;
}

// is the AHRS subsystem healthy?
virtual bool healthy(void) const = 0;

Expand Down
7 changes: 0 additions & 7 deletions libraries/AP_AHRS/AP_AHRS_SIM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 0 additions & 4 deletions libraries/AP_AHRS/AP_AHRS_SIM.h
Original file line number Diff line number Diff line change
Expand Up @@ -98,10 +98,6 @@ class AP_AHRS_SIM : public AP_AHRS_Backend {
// 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;
Expand Down
Loading