Skip to content

Commit

Permalink
AP_AHRS: remove not-needed virtual methods from backends
Browse files Browse the repository at this point in the history
we will call non-virtual methods or add them to the data structure rather than having callbacks
  • Loading branch information
peterbarker committed Dec 6, 2023
1 parent e5b8c3a commit 54f45e4
Show file tree
Hide file tree
Showing 4 changed files with 2 additions and 25 deletions.
3 changes: 2 additions & 1 deletion libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2390,7 +2390,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 HAL_EXTERNAL_AHRS_ENABLED
case EKFType::EXTERNAL:
Expand Down
13 changes: 0 additions & 13 deletions libraries/AP_AHRS/AP_AHRS_Backend.h
Original file line number Diff line number Diff line change
Expand Up @@ -261,19 +261,6 @@ class AP_AHRS_Backend
#endif
}

// 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
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 @@ -98,13 +98,6 @@ bool AP_AHRS_SIM::get_filter_status(nav_filter_status &status) const
return true;
}

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 @@ -77,10 +77,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;

void send_ekf_status_report(class GCS_MAVLINK &link) const override;

bool get_innovations(Vector3f &velInnov, Vector3f &posInnov, Vector3f &magInnov, float &tasInnov, float &yawInnov) const override;
Expand Down

0 comments on commit 54f45e4

Please sign in to comment.