Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_Params.cpp
Views: 1798
1/*2This program is free software: you can redistribute it and/or modify3it under the terms of the GNU General Public License as published by4the Free Software Foundation, either version 3 of the License, or5(at your option) any later version.67This program is distributed in the hope that it will be useful,8but WITHOUT ANY WARRANTY; without even the implied warranty of9MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the10GNU General Public License for more details.1112You should have received a copy of the GNU General Public License13along with this program. If not, see <http://www.gnu.org/licenses/>.14*/1516#include "AP_Airspeed_config.h"1718#if AP_AIRSPEED_ENABLED1920#include "AP_Airspeed.h"2122#include <AP_Vehicle/AP_Vehicle_Type.h>2324// Dummy the AP_Airspeed class to allow building Airspeed only for plane, rover, sub, and copter & heli 2MB boards25// This could be removed once the build system allows for APM_BUILD_TYPE in header files26// note that this is re-definition of the one in AP_Airspeed.cpp, can't be shared as vehicle dependences cant go in header files27#ifndef AP_AIRSPEED_DUMMY_METHODS_ENABLED28#define AP_AIRSPEED_DUMMY_METHODS_ENABLED ((APM_BUILD_COPTER_OR_HELI && BOARD_FLASH_SIZE <= 1024) || \29APM_BUILD_TYPE(APM_BUILD_AntennaTracker) || APM_BUILD_TYPE(APM_BUILD_Blimp))30#endif3132#if !AP_AIRSPEED_DUMMY_METHODS_ENABLED3334#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO35#define PSI_RANGE_DEFAULT 0.0536#endif3738#ifndef PSI_RANGE_DEFAULT39#define PSI_RANGE_DEFAULT 1.0f40#endif4142// table of user settable parameters43const AP_Param::GroupInfo AP_Airspeed_Params::var_info[] = {4445// @Param: TYPE46// @DisplayName: Airspeed type47// @Description: Type of airspeed sensor48// @Values: 0:None,1:I2C-MS4525D0,2:Analog,3:I2C-MS5525,4:I2C-MS5525 (0x76),5:I2C-MS5525 (0x77),6:I2C-SDP3X,7:I2C-DLVR-5in,8:DroneCAN,9:I2C-DLVR-10in,10:I2C-DLVR-20in,11:I2C-DLVR-30in,12:I2C-DLVR-60in,13:NMEA water speed,14:MSP,15:ASP5033,16:ExternalAHRS,100:SITL49// @User: Standard50AP_GROUPINFO_FLAGS("TYPE", 1, AP_Airspeed_Params, type, 0, AP_PARAM_FLAG_ENABLE),5152#ifndef HAL_BUILD_AP_PERIPH53// @Param: USE54// @DisplayName: Airspeed use55// @Description: Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).56// @Description{Copter, Blimp, Rover, Sub}: This parameter is not used by this vehicle. Always set to 0.57// @Values: 0:DoNotUse,1:Use,2:UseWhenZeroThrottle58// @User: Standard59AP_GROUPINFO("USE", 2, AP_Airspeed_Params, use, 0),6061// @Param: OFFSET62// @DisplayName: Airspeed offset63// @Description: Airspeed calibration offset64// @Increment: 0.165// @User: Advanced66AP_GROUPINFO("OFFSET", 3, AP_Airspeed_Params, offset, 0),6768// @Param: RATIO69// @DisplayName: Airspeed ratio70// @Description: Calibrates pitot tube pressure to velocity. Increasing this value will indicate a higher airspeed at any given dynamic pressure.71// @Increment: 0.172// @User: Advanced73AP_GROUPINFO("RATIO", 4, AP_Airspeed_Params, ratio, 2),7475// @Param: PIN76// @DisplayName: Airspeed pin77// @Description: The pin number that the airspeed sensor is connected to for analog sensors. Values for some autopilots are given as examples. Search wiki for "Analog pins".78// @Values: -1:Disabled, 2:Pixhawk/Pixracer/Navio2/Pixhawk2_PM1, 5:Navigator, 13:Pixhawk2_PM2/CubeOrange_PM2, 14:CubeOrange, 16:Durandal, 100:PX4-v179// @User: Advanced80AP_GROUPINFO("PIN", 5, AP_Airspeed_Params, pin, 0),81#endif // HAL_BUILD_AP_PERIPH8283#if AP_AIRSPEED_AUTOCAL_ENABLE84// @Param: AUTOCAL85// @DisplayName: Automatic airspeed ratio calibration86// @DisplayName{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.87// @Description: Enables automatic adjustment of airspeed ratio during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.88// @User: Advanced89AP_GROUPINFO("AUTOCAL", 6, AP_Airspeed_Params, autocal, 0),90#endif9192#ifndef HAL_BUILD_AP_PERIPH93// @Param: TUBE_ORDR94// @DisplayName: Control pitot tube order95// @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.96// @User: Advanced97// @Values: 0:Normal,1:Swapped,2:Auto Detect98AP_GROUPINFO("TUBE_ORDR", 7, AP_Airspeed_Params, tube_order, 2),99100// @Param: SKIP_CAL101// @DisplayName: Skip airspeed offset calibration on startup102// @Description: This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.103// @Values: 0:Disable,1:Enable104// @User: Advanced105AP_GROUPINFO("SKIP_CAL", 8, AP_Airspeed_Params, skip_cal, 0),106#endif // HAL_BUILD_AP_PERIPH107108// @Param: PSI_RANGE109// @DisplayName: The PSI range of the device110// @Description: This parameter allows you to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device111// @User: Advanced112AP_GROUPINFO("PSI_RANGE", 9, AP_Airspeed_Params, psi_range, PSI_RANGE_DEFAULT),113114#ifndef HAL_BUILD_AP_PERIPH115// @Param: BUS116// @DisplayName: Airspeed I2C bus117// @Description: Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize.118// @Values: 0:Bus0,1:Bus1,2:Bus2119// @RebootRequired: True120// @User: Advanced121AP_GROUPINFO("BUS", 10, AP_Airspeed_Params, bus, 1),122#endif // HAL_BUILD_AP_PERIPH123124// @Param: DEVID125// @DisplayName: Airspeed ID126// @Description: Airspeed sensor ID, taking into account its type, bus and instance127// @ReadOnly: True128// @User: Advanced129AP_GROUPINFO_FLAGS("DEVID", 11, AP_Airspeed_Params, bus_id, 0, AP_PARAM_FLAG_INTERNAL_USE_ONLY),130131AP_GROUPEND132};133134AP_Airspeed_Params::AP_Airspeed_Params(void)135{136AP_Param::setup_object_defaults(this, var_info);137}138139#else // dummy implementation:140141AP_Airspeed_Params::AP_Airspeed_Params(void) {};142const AP_Param::GroupInfo AP_Airspeed_Params::var_info[] = { AP_GROUPEND };143144#endif145146#endif // AP_AIRSPEED_ENABLED147148149