From 1122642f50d2205404ab9f2718a6409f1e1f27d7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 9 Jun 2021 21:31:34 +1000 Subject: [PATCH] AP_AHRS: remove HIL support --- libraries/AP_AHRS/AP_AHRS.h | 3 --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 6 ------ libraries/AP_AHRS/AP_AHRS_DCM.h | 3 --- libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 20 -------------------- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 3 --- 5 files changed, 35 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 6cabb5c32b..9688d54b6c 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -220,9 +220,6 @@ public: // reset the current attitude, used on new IMU calibration virtual void reset(bool recover_eulers=false) = 0; - // reset the current attitude, used on new IMU calibration - virtual void reset_attitude(const float &roll, const float &pitch, const float &yaw) = 0; - // return the average size of the roll/pitch error estimate // since last call virtual float get_error_rp(void) const = 0; diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 7095a80180..6f6486b42e 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -239,12 +239,6 @@ AP_AHRS_DCM::reset(bool recover_eulers) _last_startup_ms = AP_HAL::millis(); } -// reset the current attitude, used by HIL -void AP_AHRS_DCM::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw) -{ - _dcm_matrix.from_euler(_roll, _pitch, _yaw); -} - /* * check the DCM matrix for pathological values */ diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index c4a2f580e3..84ae8addb7 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -69,9 +69,6 @@ public: void update(bool skip_ins_update=false) override; void reset(bool recover_eulers = false) override; - // reset the current attitude, used on new IMU calibration - void reset_attitude(const float &roll, const float &pitch, const float &yaw) override; - // dead-reckoning support virtual bool get_position(struct Location &loc) const override; diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 22618c57b3..b9eed933c6 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -517,26 +517,6 @@ void AP_AHRS_NavEKF::reset(bool recover_eulers) #endif } -// reset the current attitude, used on new IMU calibration -void AP_AHRS_NavEKF::reset_attitude(const float &_roll, const float &_pitch, const float &_yaw) -{ - // support locked access functions to AHRS data - WITH_SEMAPHORE(_rsem); - - AP_AHRS_DCM::reset_attitude(_roll, _pitch, _yaw); - _dcm_attitude = {roll, pitch, yaw}; -#if HAL_NAVEKF2_AVAILABLE - if (_ekf2_started) { - _ekf2_started = EKF2.InitialiseFilter(); - } -#endif -#if HAL_NAVEKF3_AVAILABLE - if (_ekf3_started) { - _ekf3_started = EKF3.InitialiseFilter(); - } -#endif -} - // dead-reckoning support bool AP_AHRS_NavEKF::get_position(struct Location &loc) const { diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 494b3828b7..35ef8447ea 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -78,9 +78,6 @@ public: void update(bool skip_ins_update=false) override; void reset(bool recover_eulers = false) override; - // reset the current attitude, used on new IMU calibration - void reset_attitude(const float &roll, const float &pitch, const float &yaw) override; - // dead-reckoning support bool get_position(struct Location &loc) const override;