AP_AHRS: remove HIL support

This commit is contained in:
Peter Barker 2021-06-09 21:31:34 +10:00 committed by Andrew Tridgell
parent 42c47d6d84
commit 1122642f50
5 changed files with 0 additions and 35 deletions

View File

@ -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;

View File

@ -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
*/

View File

@ -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;

View File

@ -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
{

View File

@ -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;