From 5d49d29c273fbead6dc91d386edc7600a862eeae Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 17 Aug 2021 12:34:15 +1000 Subject: [PATCH] AP_AHRS: move wind-estimation-enabled state to frontend --- libraries/AP_AHRS/AP_AHRS.cpp | 2 +- libraries/AP_AHRS/AP_AHRS.h | 20 ++++++++++++++++++++ libraries/AP_AHRS/AP_AHRS_Backend.h | 9 --------- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 4 ++-- 4 files changed, 23 insertions(+), 12 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index 868445d2b5..6d8e4f8148 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -808,7 +808,7 @@ bool AP_AHRS::airspeed_estimate(float &airspeed_ret) const return true; } - if (!_flags.wind_estimation) { + if (!get_wind_estimation_enabled()) { return false; } diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index fd5517de59..a59371b18d 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -103,9 +103,24 @@ public: float get_error_rp() const override; float get_error_yaw() const override; + /* + * wind estimation support + */ + + // enable wind estimation + void set_wind_estimation_enabled(bool b) { wind_estimation_enabled = b; } + + // wind_estimation_enabled returns true if wind estimation is enabled + bool get_wind_estimation_enabled() const { return wind_estimation_enabled; } + // return a wind estimation vector, in m/s Vector3f wind_estimate() const override; + + /* + * airspeed support + */ + // return an airspeed estimate if available. return true // if we have an estimate bool airspeed_estimate(float &airspeed_ret) const override; @@ -567,6 +582,11 @@ private: bool touchdown_expected; // true if the vehicle is in a state that touchdown might be expected. Ground effect may be in play. uint32_t touchdown_expected_start_ms; + /* + * wind estimation support + */ + bool wind_estimation_enabled; + /* * fly_forward is set by the vehicles to indicate the vehicle * should generally be moving in the direction of its heading. diff --git a/libraries/AP_AHRS/AP_AHRS_Backend.h b/libraries/AP_AHRS/AP_AHRS_Backend.h index be8a52da7b..aeb6a7ffa5 100644 --- a/libraries/AP_AHRS/AP_AHRS_Backend.h +++ b/libraries/AP_AHRS/AP_AHRS_Backend.h @@ -46,10 +46,6 @@ public: // init sets up INS board orientation virtual void init(); - void set_wind_estimation(bool b) { - _flags.wind_estimation = b; - } - // return the index of the primary core or -1 if no primary core selected virtual int8_t get_primary_core_index() const { return -1; } @@ -472,11 +468,6 @@ protected: Matrix3f _custom_rotation; - // flags structure - struct ahrs_flags { - uint8_t wind_estimation : 1; // 1 if we should do wind estimation - } _flags; - // calculate sin/cos of roll/pitch/yaw from rotation void calc_trig(const Matrix3f &rot, float &cr, float &cp, float &cy, diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index f0517c666b..8b81f3e66d 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -957,7 +957,7 @@ AP_AHRS_DCM::drift_correction(float deltat) // update our wind speed estimate void AP_AHRS_DCM::estimate_wind(void) { - if (!_flags.wind_estimation) { + if (!AP::ahrs().get_wind_estimation_enabled()) { return; } const Vector3f &velocity = _last_velocity; @@ -1074,7 +1074,7 @@ bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret) { if (airspeed_sensor_enabled(airspeed_index)) { airspeed_ret = AP::airspeed()->get_airspeed(airspeed_index); - } else if (_flags.wind_estimation && have_gps()) { + } else if (AP::ahrs().get_wind_estimation_enabled() && have_gps()) { // estimate it via GPS speed and wind airspeed_ret = _last_airspeed; } else {