From 42d1ce635b8756eddbf738888a3ac1ebdc512280 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Mon, 28 Feb 2022 16:06:36 -0500 Subject: [PATCH] AP_Airspeed: improve description of ARSPD_TUBE_ORDR --- libraries/AP_Airspeed/AP_Airspeed.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 12a03c4720..7efb651be1 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -150,8 +150,9 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: _TUBE_ORDER // @DisplayName: Control pitot tube order - // @Description: Changes the pitot tube order to specify the dynamic pressure side of the sensor. Accepts either if set to 2. Accepts only one side if set to 0 or 1 and can help detect excessive pressure on the static port without indicating positive airspeed. + // @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 first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation 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 is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed. // @User: Advanced + // @Values: 0:Normal,1:Swapped,2:Auto Detect AP_GROUPINFO("_TUBE_ORDER", 6, AP_Airspeed, param[0].tube_order, 2), #ifndef HAL_BUILD_AP_PERIPH @@ -253,8 +254,9 @@ const AP_Param::GroupInfo AP_Airspeed::var_info[] = { // @Param: 2_TUBE_ORDR // @DisplayName: Control pitot tube order of 2nd airspeed sensor - // @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. + // @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 first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation 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 is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed. // @User: Advanced + // @Values: 0:Normal,1:Swapped,2:Auto Detect AP_GROUPINFO("2_TUBE_ORDR", 17, AP_Airspeed, param[1].tube_order, 2), // @Param: 2_SKIP_CAL