mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: added ARSPD_TUBE_ORDER parameter
This allows for either order of tube connection by default, but the order can be specified if need be
This commit is contained in:
parent
2bf7a46c9b
commit
d853d65b84
|
@ -93,6 +93,12 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] PROGMEM = {
|
|||
// @User: Advanced
|
||||
AP_GROUPINFO("AUTOCAL", 5, AP_Airspeed, _autocal, 0),
|
||||
|
||||
// @Param: TUBE_ORDER
|
||||
// @DisplayName: Control pitot tube order
|
||||
// @Description: This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the top connector on the sensor needs to be the dynamic pressure. If set to 1 then the bottom connector needs to be the dynamic pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft it receiving excessive pressure on the static port, which would otherwise be seen as a positive airspeed.
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("TUBE_ORDER", 6, AP_Airspeed, _tube_order, 2),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -180,17 +186,27 @@ void AP_Airspeed::read(void)
|
|||
if (!_enable) {
|
||||
return;
|
||||
}
|
||||
/*
|
||||
when we get negative pressures it means the tubes are probably
|
||||
connected the wrong way around. We don't just use the absolute
|
||||
value as otherwise we could get bad readings in some flight
|
||||
attitudes (eg. a spin) due to pressure on the static port
|
||||
*/
|
||||
airspeed_pressure = get_pressure() - _offset;
|
||||
if (airspeed_pressure < -32) {
|
||||
// we're reading more than about -8m/s. The user probably has
|
||||
// the ports the wrong way around
|
||||
_healthy = false;
|
||||
|
||||
/*
|
||||
we support different pitot tube setups so used can choose if
|
||||
they want to be able to detect pressure on the static port
|
||||
*/
|
||||
switch ((enum pitot_tube_order)_tube_order.get()) {
|
||||
case PITOT_TUBE_ORDER_NEGATIVE:
|
||||
airspeed_pressure = -airspeed_pressure;
|
||||
// fall thru
|
||||
case PITOT_TUBE_ORDER_POSITIVE:
|
||||
if (airspeed_pressure < -32) {
|
||||
// we're reading more than about -8m/s. The user probably has
|
||||
// the ports the wrong way around
|
||||
_healthy = false;
|
||||
}
|
||||
break;
|
||||
case PITOT_TUBE_ORDER_AUTO:
|
||||
default:
|
||||
airspeed_pressure = fabsf(airspeed_pressure);
|
||||
break;
|
||||
}
|
||||
airspeed_pressure = max(airspeed_pressure, 0);
|
||||
_last_pressure = airspeed_pressure;
|
||||
|
|
|
@ -133,6 +133,9 @@ public:
|
|||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE =0,
|
||||
PITOT_TUBE_ORDER_NEGATIVE =1,
|
||||
PITOT_TUBE_ORDER_AUTO =2};
|
||||
|
||||
private:
|
||||
AP_Float _offset;
|
||||
|
@ -141,6 +144,7 @@ private:
|
|||
AP_Int8 _enable;
|
||||
AP_Int8 _pin;
|
||||
AP_Int8 _autocal;
|
||||
AP_Int8 _tube_order;
|
||||
float _raw_airspeed;
|
||||
float _airspeed;
|
||||
float _last_pressure;
|
||||
|
|
Loading…
Reference in New Issue