From 532431c284c4073f93af45ac97979c51c7383e49 Mon Sep 17 00:00:00 2001 From: ChrisBird Date: Mon, 14 Jan 2019 04:39:53 -0800 Subject: [PATCH] AP_AHRS: Added get_max_wind to make it available for use in determining if the airspeed sensor is faulty. --- libraries/AP_AHRS/AP_AHRS.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 966792b618..e70b6623d2 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -304,6 +304,11 @@ public: return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy(); } + // return the parameter AHRS_WIND_MAX in metres per second + uint8_t get_max_wind() const { + return _wind_max; + } + // return a ground vector estimate in meters/second, in North/East order virtual Vector2f groundspeed_vector(void);