From 7b730048821423f069873a70ded6cce99aea9caf Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 29 Apr 2017 16:53:39 +1000 Subject: [PATCH] AP_Airspeed: added ARSPD_USE=2 for gliders --- libraries/AP_Airspeed/AP_Airspeed.cpp | 19 +++++++++++++++++-- libraries/AP_Airspeed/AP_Airspeed.h | 4 +--- 2 files changed, 18 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 55244a8c542066..8e01c36fba8ee5 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -22,6 +22,7 @@ #include #include #include +#include #include #include "AP_Airspeed.h" #include "AP_Airspeed_MS4525.h" @@ -58,8 +59,8 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: USE // @DisplayName: Airspeed use - // @Description: use airspeed for flight control - // @Values: 1:Use,0:Don't Use + // @Description: use airspeed for flight control. When set to 0 airspeed sensor can be logged and displayed on a GCS but won't be used for flight. When set to 1 it will be logged and used. When set to 2 it will be only used when the throttle is zero, which can be useful in gliders with airspeed sensors behind a propeller + // @Values: 0:Don't Use,1:use,2:UseWhenZeroThrottle // @User: Standard AP_GROUPINFO("USE", 1, AP_Airspeed, _use, 0), @@ -292,3 +293,17 @@ void AP_Airspeed::setHIL(float airspeed, float diff_pressure, float temperature) _hil_set = true; _healthy = true; } + +bool AP_Airspeed::use(void) const +{ + if (!enabled() || !_use) { + return false; + } + if (_use == 2 && SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) != 0) { + // special case for gliders with airspeed sensors behind the + // propeller. Allow airspeed to be disabled when throttle is + // running + return false; + } + return true; +} diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index 2289f549daaf52..abc0e6b9d8b58c 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -75,9 +75,7 @@ class AP_Airspeed } // return true if airspeed is enabled, and airspeed use is set - bool use(void) const { - return enabled() && _use; - } + bool use(void) const; // return true if airspeed is enabled bool enabled(void) const {