Path: blob/master/libraries/AP_Airspeed/AP_Airspeed.cpp
9623 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15* AP_Airspeed.cpp - airspeed (pitot) driver16*/1718#include "AP_Airspeed_config.h"1920#if AP_AIRSPEED_ENABLED2122#include "AP_Airspeed.h"2324#include <AP_Vehicle/AP_Vehicle_Type.h>2526// Dummy the AP_Airspeed class to allow building Airspeed only for plane, rover, sub, and copter & heli 2MB boards27// This could be removed once the build system allows for APM_BUILD_TYPE in header files28// Note that this is also defined in AP_Airspeed_Params.cpp29#ifndef AP_AIRSPEED_DUMMY_METHODS_ENABLED30#define AP_AIRSPEED_DUMMY_METHODS_ENABLED ((APM_BUILD_COPTER_OR_HELI && HAL_PROGRAM_SIZE_LIMIT_KB <= 1024) || \31APM_BUILD_TYPE(APM_BUILD_AntennaTracker) || APM_BUILD_TYPE(APM_BUILD_Blimp))32#endif3334#if !AP_AIRSPEED_DUMMY_METHODS_ENABLED3536#include <AP_Common/AP_Common.h>37#include <AP_HAL/AP_HAL.h>38#include <AP_HAL/I2CDevice.h>39#include <AP_Math/AP_Math.h>40#include <GCS_MAVLink/GCS.h>41#include <SRV_Channel/SRV_Channel.h>42#include <AP_Logger/AP_Logger.h>43#include <utility>44#include "AP_Airspeed_MS4525.h"45#include "AP_Airspeed_MS5525.h"46#include "AP_Airspeed_SDP3X.h"47#include "AP_Airspeed_DLVR.h"48#include "AP_Airspeed_analog.h"49#include "AP_Airspeed_ASP5033.h"50#include "AP_Airspeed_Backend.h"51#include "AP_Airspeed_DroneCAN.h"52#include "AP_Airspeed_NMEA.h"53#include "AP_Airspeed_MSP.h"54#include "AP_Airspeed_AUAV.h"55#include "AP_Airspeed_External.h"56#include "AP_Airspeed_SITL.h"57extern const AP_HAL::HAL &hal;5859#include <AP_Vehicle/AP_FixedWing.h>6061#ifdef HAL_AIRSPEED_TYPE_DEFAULT62#define ARSPD_DEFAULT_TYPE HAL_AIRSPEED_TYPE_DEFAULT63#ifndef ARSPD_DEFAULT_PIN64#define ARSPD_DEFAULT_PIN 165#endif66#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)67// The HAL_BOARD_SITL setting is required because of current probe process for MS4525 will68// connect and find the SIM_DLVR sensors & fault as there is no way to tell them apart69#if CONFIG_HAL_BOARD == HAL_BOARD_SITL70#define ARSPD_DEFAULT_TYPE TYPE_ANALOG71#define ARSPD_DEFAULT_PIN 172#elif AP_AIRSPEED_MS4525_ENABLED73#define ARSPD_DEFAULT_TYPE TYPE_I2C_MS452574#ifdef HAL_DEFAULT_AIRSPEED_PIN75#define ARSPD_DEFAULT_PIN HAL_DEFAULT_AIRSPEED_PIN76#else77#define ARSPD_DEFAULT_PIN 1578#endif79#else80#define ARSPD_DEFAULT_TYPE TYPE_NONE81#define ARSPD_DEFAULT_PIN 1582#endif //CONFIG_HAL_BOARD83#else // All Other Vehicle Types84#define ARSPD_DEFAULT_TYPE TYPE_NONE85#define ARSPD_DEFAULT_PIN 1586#endif8788#ifndef HAL_AIRSPEED_BUS_DEFAULT89#define HAL_AIRSPEED_BUS_DEFAULT 190#endif9192#define OPTIONS_DEFAULT AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_DO_DISABLE | AP_Airspeed::OptionsMask::ON_FAILURE_AHRS_WIND_MAX_RECOVERY_DO_REENABLE | AP_Airspeed::OptionsMask::USE_EKF_CONSISTENCY9394#define ENABLE_PARAMETER !(APM_BUILD_TYPE(APM_BUILD_ArduPlane) || defined(HAL_BUILD_AP_PERIPH))9596// table of user settable parameters97const AP_Param::GroupInfo AP_Airspeed::var_info[] = {9899#if ENABLE_PARAMETER100// @Param: _ENABLE101// @DisplayName: Airspeed Enable102// @Description: Enable airspeed sensor support103// @Values: 0:Disable, 1:Enable104// @User: Standard105AP_GROUPINFO_FLAGS("_ENABLE", 30, AP_Airspeed, _enable, 0, AP_PARAM_FLAG_ENABLE),106#endif107// slots 0-9 (and 63) were previously used by params before being refactored into AP_Airspeed_Params108109// @Param: _TUBE_ORDER110// @DisplayName: Control pitot tube order111// @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.112// @User: Advanced113// @Values: 0:Normal,1:Swapped,2:Auto Detect114115// tube order param had to be shortened so is not preserved in per group descriptions116117#if AIRSPEED_MAX_SENSORS > 1118// @Param: _PRIMARY119// @DisplayName: Primary airspeed sensor120// @Description: This selects which airspeed sensor will be the primary if multiple sensors are found121// @Values: 0:FirstSensor, 1:2nd Sensor, 2:3rd Sensor, 3:4th Sensor, 4:5th Sensor, 5:6th Sensor122// @User: Advanced123AP_GROUPINFO("_PRIMARY", 10, AP_Airspeed, primary_sensor, 0),124#endif125126// 11-20 were previously used by second sensor params before being refactored into AP_Airspeed_Params127128#ifndef HAL_BUILD_AP_PERIPH129// @Param: _OPTIONS130// @DisplayName: Airspeed options bitmask131// @Description: Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction, 3:Check that the airspeed is statistically consistent with the navigation EKF vehicle and wind velocity estimates using EKF3 (requires AHRS_EKF_TYPE = 3), 4:Report cal offset to GCS132// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.133// @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection, 3:UseEkf3Consistency, 4:ReportOffset134// @User: Advanced135AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT),136137// @Param: _WIND_MAX138// @DisplayName: Maximum airspeed and ground speed difference139// @Description: If the difference between airspeed and ground speed is greater than this value the sensor will be marked unhealthy. Using ARSPD_OPTIONS this health value can be used to disable the sensor.140// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.141// @Units: m/s142// @User: Advanced143AP_GROUPINFO("_WIND_MAX", 22, AP_Airspeed, _wind_max, 0),144145// @Param: _WIND_WARN146// @DisplayName: Airspeed and GPS speed difference that gives a warning147// @Description: If the difference between airspeed and GPS speed is greater than this value the sensor will issue a warning. If 0 ARSPD_WIND_MAX is used.148// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.149// @Units: m/s150// @User: Advanced151AP_GROUPINFO("_WIND_WARN", 23, AP_Airspeed, _wind_warn, 0),152153// @Param: _WIND_GATE154// @DisplayName: Re-enable Consistency Check Gate Size155// @Description: Number of standard deviations applied to the re-enable EKF consistency check that is used when ARSPD_OPTIONS bit position 3 is set. Larger values will make the re-enabling of the airspeed sensor faster, but increase the likelihood of re-enabling a degraded sensor. The value can be tuned by using the ARSP.TR log message by setting ARSPD_WIND_GATE to a value that is higher than the value for ARSP.TR observed with a healthy airspeed sensor. Occasional transients in ARSP.TR above the value set by ARSPD_WIND_GATE can be tolerated provided they are less than 5 seconds in duration and less than 10% duty cycle.156// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle.157// @Range: 0.0 10.0158// @User: Advanced159AP_GROUPINFO("_WIND_GATE", 26, AP_Airspeed, _wind_gate, 5.0f),160161// @Param{Plane}: _OFF_PCNT162// @DisplayName: Maximum offset cal speed error163// @Description: The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of AIRSPEED_MIN. 0 disables. Helps warn of calibrations without pitot being covered.164// @Range: 0.0 10.0165// @Units: %166// @User: Advanced167AP_GROUPINFO_FRAME("_OFF_PCNT", 27, AP_Airspeed, max_speed_pcnt, 0, AP_PARAM_FRAME_PLANE),168169#endif170171// @Group: _172// @Path: AP_Airspeed_Params.cpp173AP_SUBGROUPINFO(param[0], "_", 28, AP_Airspeed, AP_Airspeed_Params),174175#if AIRSPEED_MAX_SENSORS > 1176// @Group: 2_177// @Path: AP_Airspeed_Params.cpp178AP_SUBGROUPINFO(param[1], "2_", 29, AP_Airspeed, AP_Airspeed_Params),179#endif180181// index 30 is used by enable at the top of the table182183#if AIRSPEED_MAX_SENSORS > 2184// @Group: 3_185// @Path: AP_Airspeed_Params.cpp186AP_SUBGROUPINFO(param[2], "3_", 31, AP_Airspeed, AP_Airspeed_Params),187#endif188189#if AIRSPEED_MAX_SENSORS > 3190// @Group: 4_191// @Path: AP_Airspeed_Params.cpp192AP_SUBGROUPINFO(param[3], "4_", 32, AP_Airspeed, AP_Airspeed_Params),193#endif194195#if AIRSPEED_MAX_SENSORS > 4196// @Group: 5_197// @Path: AP_Airspeed_Params.cpp198AP_SUBGROUPINFO(param[4], "5_", 33, AP_Airspeed, AP_Airspeed_Params),199#endif200201#if AIRSPEED_MAX_SENSORS > 5202// @Group: 6_203// @Path: AP_Airspeed_Params.cpp204AP_SUBGROUPINFO(param[5], "6_", 34, AP_Airspeed, AP_Airspeed_Params),205#endif206207AP_GROUPEND208};209210/*211this scaling factor converts from the old system where we used a2120 to 4095 raw ADC value for 0-5V to the new system which gets the213voltage in volts directly from the ADC driver214*/215#define SCALING_OLD_CALIBRATION 819 // 4095/5216217AP_Airspeed::AP_Airspeed()218{219AP_Param::setup_object_defaults(this, var_info);220221// Setup defaults that only apply to first sensor222param[0].type.set_default(ARSPD_DEFAULT_TYPE);223#ifndef HAL_BUILD_AP_PERIPH224param[0].bus.set_default(HAL_AIRSPEED_BUS_DEFAULT);225param[0].pin.set_default(ARSPD_DEFAULT_PIN);226#endif227228if (_singleton != nullptr) {229AP_HAL::panic("AP_Airspeed must be singleton");230}231_singleton = this;232}233234void AP_Airspeed::set_fixedwing_parameters(const AP_FixedWing *_fixed_wing_parameters)235{236fixed_wing_parameters = _fixed_wing_parameters;237}238239// macro for use by HAL_INS_PROBE_LIST240#define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device_ptr(bus, address)241242bool AP_Airspeed::add_backend(AP_Airspeed_Backend *backend)243{244if (!backend) {245return false;246}247if (num_sensors >= AIRSPEED_MAX_SENSORS) {248AP_HAL::panic("Too many airspeed drivers");249}250const uint8_t i = num_sensors;251sensor[num_sensors++] = backend;252if (!sensor[i]->init()) {253GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i+1);254delete sensor[i];255sensor[i] = nullptr;256}257return true;258}259260/*261macro to add a backend with check for too many sensors262We don't try to start more than the maximum allowed263*/264#define ADD_BACKEND(backend) \265do { add_backend(backend); \266if (num_sensors == AIRSPEED_MAX_SENSORS) { return; } \267} while (0)268269270// convert params to per instance param table271// PARAMETER_CONVERSION - Added: Dec-2022272void AP_Airspeed::convert_per_instance()273{274AP_Param::ConversionInfo info;275#ifndef HAL_BUILD_AP_PERIPH276// Vehicle conversion277if (!AP_Param::find_key_by_pointer(this, info.old_key)) {278return;279}280281static const struct convert_table {282uint32_t element[2];283ap_var_type type;284const char* name;285} conversion_table[] = {286{ {4042, 714}, AP_PARAM_INT8, "TYPE" }, // ARSPD_TYPE, ARSPD2_TYPE287{ {74, 778}, AP_PARAM_INT8, "USE" }, // ARSPD_USE, ARSPD2_USE288{ {138, 842}, AP_PARAM_FLOAT, "OFFSET" }, // ARSPD_OFFSET, ARSPD2_OFFSET289{ {202, 906}, AP_PARAM_FLOAT, "RATIO" }, // ARSPD_RATIO, ARSPD2_RATIO290{ {266, 970}, AP_PARAM_INT8, "PIN" }, // ARSPD_PIN, ARSPD2_PIN291#if AP_AIRSPEED_AUTOCAL_ENABLE292{ {330, 1034}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL293#endif294{ {394, 1098}, AP_PARAM_INT8, "TUBE_ORDR" }, // ARSPD_TUBE_ORDER, ARSPD2_TUBE_ORDR295{ {458, 1162}, AP_PARAM_INT8, "SKIP_CAL" }, // ARSPD_SKIP_CAL, ARSPD2_SKIP_CAL296{ {522, 1226}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE297{ {586, 1290}, AP_PARAM_INT8, "BUS" }, // ARSPD_BUS, ARSPD2_BUS298{ {1546, 1610}, AP_PARAM_INT32, "DEVID" }, // ARSPD_DEVID, ARSPD2_DEVID299};300301#else302// Periph conversion303if (!AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {304return;305}306const struct convert_table {307uint32_t element[2];308ap_var_type type;309const char* name;310} conversion_table[] = {311{ {0, 11}, AP_PARAM_INT8, "TYPE" }, // ARSPD_TYPE, ARSPD2_TYPE312#if AP_AIRSPEED_AUTOCAL_ENABLE313{ {5, 16}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL314#endif315{ {8, 19}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE316{ {24, 25}, AP_PARAM_INT32, "DEVID" }, // ARSPD_DEVID, ARSPD2_DEVID317};318#endif319320char param_name[17] {};321info.new_name = param_name;322323for (const auto & elem : conversion_table) {324info.type = elem.type;325for (uint8_t i=0; i < MIN(AIRSPEED_MAX_SENSORS,2); i++) {326info.old_group_element = elem.element[i];327if (i == 0) {328hal.util->snprintf(param_name, sizeof(param_name), "ARSPD_%s", elem.name);329} else {330hal.util->snprintf(param_name, sizeof(param_name), "ARSPD%i_%s", i+1, elem.name);331}332AP_Param::convert_old_parameter(&info, 1.0, 0);333}334}335}336337void AP_Airspeed::init()338{339340convert_per_instance();341342// Set primary from parameter to avoid primary changed message at boot343primary = primary_sensor.get();344345#if ENABLE_PARAMETER346// if either type is set then enable if not manually set347if (!_enable.configured() && ((param[0].type.get() != TYPE_NONE) || (param[1].type.get() != TYPE_NONE))) {348_enable.set_and_save(1);349}350351// Check if enabled352if (!lib_enabled()) {353return;354}355#endif356357if (enabled(0)) {358allocate();359}360}361362void AP_Airspeed::allocate()363{364if (sensor[0] != nullptr) {365// already initialised, periph may call allocate several times to allow CAN detection366return;367}368369#ifdef HAL_AIRSPEED_PROBE_LIST370// load sensors via a list from hwdef.dat371HAL_AIRSPEED_PROBE_LIST;372#else373// look for sensors based on type parameters374for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {375#if AP_AIRSPEED_AUTOCAL_ENABLE376state[i].calibration.init(param[i].ratio);377state[i].last_saved_ratio = param[i].ratio;378#endif379380// Set the enable automatically to false and set the probability that the airspeed is healhy to start with381state[i].failures.health_probability = 1.0f;382383switch ((enum airspeed_type)param[i].type.get()) {384case TYPE_NONE:385// nothing to do386break;387#if AP_AIRSPEED_MS4525_ENABLED388case TYPE_I2C_MS4525:389sensor[i] = NEW_NOTHROW AP_Airspeed_MS4525(*this, i);390break;391#endif // AP_AIRSPEED_MS4525_ENABLED392#if AP_AIRSPEED_SITL_ENABLED393case TYPE_SITL:394sensor[i] = NEW_NOTHROW AP_Airspeed_SITL(*this, i);395break;396#endif // AP_AIRSPEED_SITL_ENABLED397#if AP_AIRSPEED_ANALOG_ENABLED398case TYPE_ANALOG:399sensor[i] = NEW_NOTHROW AP_Airspeed_Analog(*this, i);400break;401#endif // AP_AIRSPEED_ANALOG_ENABLED402#if AP_AIRSPEED_MS5525_ENABLED403case TYPE_I2C_MS5525:404sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);405break;406#endif // AP_AIRSPEED_MS5525_ENABLED407#if AP_AIRSPEED_MS5525_ENABLED408case TYPE_I2C_MS5525_ADDRESS_1:409sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1);410break;411#endif // AP_AIRSPEED_MS5525_ENABLED412#if AP_AIRSPEED_MS5525_ENABLED413case TYPE_I2C_MS5525_ADDRESS_2:414sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2);415break;416#endif // AP_AIRSPEED_MS5525_ENABLED417#if AP_AIRSPEED_SDP3X_ENABLED418case TYPE_I2C_SDP3X:419sensor[i] = NEW_NOTHROW AP_Airspeed_SDP3X(*this, i);420break;421#endif // AP_AIRSPEED_SDP3X_ENABLED422#if AP_AIRSPEED_DLVR_ENABLED423case TYPE_I2C_DLVR_5IN:424sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 5);425break;426case TYPE_I2C_DLVR_10IN:427sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 10);428break;429case TYPE_I2C_DLVR_20IN:430sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 20);431break;432case TYPE_I2C_DLVR_30IN:433sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 30);434break;435case TYPE_I2C_DLVR_60IN:436sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 60);437break;438#endif // AP_AIRSPEED_DLVR_ENABLED439#if AP_AIRSPEED_ASP5033_ENABLED440case TYPE_I2C_ASP5033:441sensor[i] = NEW_NOTHROW AP_Airspeed_ASP5033(*this, i);442break;443#endif // AP_AIRSPEED_ASP5033_ENABLED444#if AP_AIRSPEED_DRONECAN_ENABLED445case TYPE_UAVCAN:446sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, uint32_t(param[i].bus_id.get()));447break;448#endif // AP_AIRSPEED_DRONECAN_ENABLED449#if AP_AIRSPEED_NMEA_ENABLED450case TYPE_NMEA_WATER:451#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)452sensor[i] = NEW_NOTHROW AP_Airspeed_NMEA(*this, i);453#endif454break;455#endif // AP_AIRSPEED_NMEA_ENABLED456#if AP_AIRSPEED_MSP_ENABLED457case TYPE_MSP:458sensor[i] = NEW_NOTHROW AP_Airspeed_MSP(*this, i, 0);459break;460#endif // AP_AIRSPEED_MSP_ENABLED461#if AP_AIRSPEED_EXTERNAL_ENABLED462case TYPE_EXTERNAL:463sensor[i] = NEW_NOTHROW AP_Airspeed_External(*this, i);464break;465#endif // AP_AIRSPEED_EXTERNAL_ENABLED466#if AP_AIRSPEED_AUAV_ENABLED467case TYPE_AUAV_5IN:468sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 5);469break;470case TYPE_AUAV_10IN:471sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 10);472break;473case TYPE_AUAV_30IN:474sensor[i] = NEW_NOTHROW AP_Airspeed_AUAV(*this, i, 30);475break;476#endif // AP_AIRSPEED_AUAV_ENABLED477}478if (sensor[i] && !sensor[i]->init()) {479GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i + 1);480delete sensor[i];481sensor[i] = nullptr;482}483if (sensor[i] != nullptr) {484num_sensors = i+1;485}486}487488#if AP_AIRSPEED_DRONECAN_ENABLED489// we need a 2nd pass for DroneCAN sensors so we can match order by DEVID490// the 2nd pass accepts any devid491for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {492if (sensor[i] == nullptr && (enum airspeed_type)param[i].type.get() == TYPE_UAVCAN) {493sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, 0);494if (sensor[i] != nullptr) {495num_sensors = i+1;496}497}498}499#endif // AP_AIRSPEED_DRONECAN_ENABLED500#endif // HAL_AIRSPEED_PROBE_LIST501502// set DEVID to zero for any sensors not found. This allows backends to order503// based on previous value of DEVID. This allows for swapping out sensors504for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {505if (sensor[i] == nullptr) {506// note we use set() not set_and_save() to allow a sensor to be temporarily507// removed for one boot without losing its slot508param[i].bus_id.set(0);509}510}511}512513// get a temperature reading if possible514bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) const515{516if (!enabled(i)) {517return false;518}519if (sensor[i]) {520return sensor[i]->get_temperature(temperature);521}522return false;523}524525// calibrate the zero offset for the airspeed. This must be called at526// least once before the get_airspeed() interface can be used527void AP_Airspeed::calibrate(bool in_startup)528{529#ifndef HAL_BUILD_AP_PERIPH530if (!lib_enabled()) {531return;532}533if (hal.util->was_watchdog_reset()) {534GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed: skipping cal");535return;536}537for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {538if (!enabled(i)) {539continue;540}541if (state[i].cal.state == CalibrationState::NOT_REQUIRED_ZERO_OFFSET) {542continue;543}544if (in_startup) {545switch ((AP_Airspeed_Params::SkipCalType)param[i].skip_cal.get()) {546case AP_Airspeed_Params::SkipCalType::None:547break;548549case AP_Airspeed_Params::SkipCalType::NoCalRequired:550// Skip startup calibration, use saved value.551state[i].cal.state = CalibrationState::SUCCESS;552continue;553554case AP_Airspeed_Params::SkipCalType::SkipBootCal:555// Skip startup calibration, calibration state remains NOT_STARTED.556continue;557}558}559if (sensor[i] == nullptr) {560GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u not initialized, cannot cal", i+1);561continue;562}563state[i].cal.start_ms = AP_HAL::millis();564state[i].cal.count = 0;565state[i].cal.sum = 0;566state[i].cal.read_count = 0;567state[i].cal.state = CalibrationState::IN_PROGRESS;568GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed %u calibration started", i+1);569}570#endif // HAL_BUILD_AP_PERIPH571}572573/*574update async airspeed zero offset calibration575*/576void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)577{578#ifndef HAL_BUILD_AP_PERIPH579if (!enabled(i) || state[i].cal.start_ms == 0) {580return;581}582583// consider calibration complete when we have at least 15 samples584// over at least 1 second585if (AP_HAL::millis() - state[i].cal.start_ms >= 1000 &&586state[i].cal.read_count > 15) {587if (state[i].cal.count == 0) {588GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %u unhealthy", i + 1);589state[i].cal.state = CalibrationState::FAILED;590} else {591float calibrated_offset = state[i].cal.sum / state[i].cal.count;592// check if new offset differs too greatly from last calibration, indicating pitot uncovered in wind593if (fixed_wing_parameters != nullptr) {594float airspeed_min = fixed_wing_parameters->airspeed_min.get();595// use percentage of AIRSPEED_MIN as criteria for max allowed change in offset596float max_change = 0.5*(sq((1 + (max_speed_pcnt * 0.01))*airspeed_min) - sq(airspeed_min));597if (max_speed_pcnt > 0 && (abs(calibrated_offset-param[i].offset) > max_change) && (abs(param[i].offset) > 0)) {598GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Arspd %d offset change large;cover and recal", i +1);599}600}601param[i].offset.set_and_save(calibrated_offset);602state[i].cal.state = CalibrationState::SUCCESS;603if (_options & AP_Airspeed::OptionsMask::REPORT_OFFSET ){604GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated, offset = %4.0f", i + 1, calibrated_offset);605} else {606GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1);607}608}609state[i].cal.start_ms = 0;610return;611}612// we discard the first 5 samples613if (state[i].healthy && state[i].cal.read_count > 5) {614state[i].cal.sum += raw_pressure;615state[i].cal.count++;616}617state[i].cal.read_count++;618#endif // HAL_BUILD_AP_PERIPH619}620621// get aggregate calibration state for the Airspeed library:622AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const623{624for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {625if (!enabled(i)) {626continue;627}628629switch (state[i].cal.state) {630case CalibrationState::SUCCESS:631case CalibrationState::NOT_REQUIRED_ZERO_OFFSET:632continue;633case CalibrationState::NOT_STARTED:634return CalibrationState::NOT_STARTED;635case CalibrationState::IN_PROGRESS:636return CalibrationState::IN_PROGRESS;637case CalibrationState::FAILED:638return CalibrationState::FAILED;639}640}641return CalibrationState::SUCCESS;642}643644// read one airspeed sensor645void AP_Airspeed::read(uint8_t i)646{647if (!enabled(i) || !sensor[i]) {648return;649}650state[i].last_update_ms = AP_HAL::millis();651652// try and get a direct reading of airspeed653if (sensor[i]->has_airspeed()) {654state[i].healthy = sensor[i]->get_airspeed(state[i].airspeed);655state[i].raw_airspeed = state[i].airspeed; // for logging656return;657}658659#ifndef HAL_BUILD_AP_PERIPH660/*661remember the old healthy state662*/663bool prev_healthy = state[i].healthy;664#endif665666float raw_pressure = 0;667state[i].healthy = sensor[i]->get_differential_pressure(raw_pressure);668669float airspeed_pressure = raw_pressure - get_offset(i);670671// remember raw pressure for logging672state[i].corrected_pressure = airspeed_pressure;673674#ifndef HAL_BUILD_AP_PERIPH675if (state[i].cal.start_ms != 0) {676update_calibration(i, raw_pressure);677}678679// filter before clamping positive680if (!prev_healthy) {681// if the previous state was not healthy then we should not682// use an IIR filter, otherwise a bad reading will last for683// some time after the sensor becomes healthy again684state[i].filtered_pressure = airspeed_pressure;685} else {686state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;687}688689/*690we support different pitot tube setups so user can choose if691they want to be able to detect pressure on the static port692*/693switch ((enum pitot_tube_order)param[i].tube_order.get()) {694case PITOT_TUBE_ORDER_NEGATIVE:695state[i].last_pressure = -airspeed_pressure;696state[i].raw_airspeed = sqrtf(MAX(-airspeed_pressure, 0) * param[i].ratio);697state[i].airspeed = sqrtf(MAX(-state[i].filtered_pressure, 0) * param[i].ratio);698break;699case PITOT_TUBE_ORDER_POSITIVE:700state[i].last_pressure = airspeed_pressure;701state[i].raw_airspeed = sqrtf(MAX(airspeed_pressure, 0) * param[i].ratio);702state[i].airspeed = sqrtf(MAX(state[i].filtered_pressure, 0) * param[i].ratio);703break;704case PITOT_TUBE_ORDER_AUTO:705default:706state[i].last_pressure = fabsf(airspeed_pressure);707state[i].raw_airspeed = sqrtf(fabsf(airspeed_pressure) * param[i].ratio);708state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);709break;710}711#endif // HAL_BUILD_AP_PERIPH712}713714// Select primary sensor based on user parameters and health715uint8_t AP_Airspeed::select_primary()716{717// user selected primary from parameter, track changes718const uint8_t user_primary = primary_sensor.get();719const bool user_primary_changed = user_primary != last_user_primary;720last_user_primary = user_primary;721722// If user selected instance is both healthy and set to use then it is a valid primary723const bool user_healthy = healthy(user_primary);724const bool user_healthy_and_use = user_healthy && use(user_primary);725726if ((user_primary_changed || !hal.util->get_soft_armed()) && user_healthy_and_use) {727/*728If user selected primary is healthy and set to use then:729Always change when the user changes the parameter.730Always change if disarmed, if armed its better to stick with the current sensor to avoid needless switching.731732The EKF3 innovation check only applies to the active sensor so a bad sensor will appear good after some time because733the EKF is no longer using the sensor so cannot provide feedback.734735We can't just stick with the current primary when disarmed due to variation in detection time.736*/737return user_primary;738}739740// If the currently selected primary is valid there is no need to change741const bool primary_healthy = healthy(primary);742if (primary_healthy && use(primary)) {743return primary;744}745746if (user_healthy_and_use) {747// The current primary is not valid, try the user set primary first748return user_primary;749}750751// Select the first sensor which is both healthy and set to use752for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {753if ((i == primary) || (i == user_primary)) {754// No need to re-check current/user primary755continue;756}757if (healthy(i) && use(i)) {758return i;759}760}761762// No sensor is both healthy and set to use763764// Continue with current primary if healthy765if (primary_healthy) {766return primary;767}768769// Use user selected instance if healthy770if (user_healthy) {771return user_primary;772}773774// Select the first sensor which is healthy775for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {776if ((i == primary) || (i == user_primary)) {777// No need to re-check current/user primary778continue;779}780if (healthy(i)) {781return i;782}783}784785// No healthy sensor, don't change primary786return primary;787}788789// read all airspeed sensors790void AP_Airspeed::update()791{792if (!lib_enabled()) {793return;794}795796for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {797read(i);798}799800#if HAL_GCS_ENABLED801// debugging until we get MAVLink support for 2nd airspeed sensor802if (enabled(1)) {803gcs().send_named_float("AS2", get_airspeed(1));804}805#endif806807// Check for failures possibly marking sensors and unhealthy808check_sensor_failures();809810// Record old primary sensor for reporting811const uint8_t old_primary = primary;812813// Select primary sensor based on user parameters and health814primary = select_primary();815816if (primary != old_primary) {817GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Airspeed primary changed: %i", primary+1);818}819820#if HAL_LOGGING_ENABLED821if (primary != old_primary) {822AP::logger().Write_Event(LogEvent::AIRSPEED_PRIMARY_CHANGED);823}824if (_log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit)) {825Log_Airspeed();826}827#endif828}829830#if AP_AIRSPEED_MSP_ENABLED831/*832handle MSP airspeed data833*/834void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt)835{836if (!lib_enabled()) {837return;838}839840if (pkt.instance > 1) {841return; //supporting 2 airspeed sensors at most842}843844for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {845if (sensor[i]) {846sensor[i]->handle_msp(pkt);847}848}849}850#endif851852#if AP_AIRSPEED_EXTERNAL_ENABLED853/*854handle airspeed airspeed data855*/856void AP_Airspeed::handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt)857{858if (!lib_enabled()) {859return;860}861862for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {863if (param[i].type == TYPE_EXTERNAL && sensor[i]) {864sensor[i]->handle_external(pkt);865}866}867}868#endif869870#if HAL_LOGGING_ENABLED871// @LoggerMessage: HYGR872// @Description: Hygrometer data873// @Field: TimeUS: Time since system startup874// @Field: Id: sensor ID875// @Field: Humidity: percentage humidity876// @Field: Temp: temperature in degrees C877878void AP_Airspeed::Log_Airspeed()879{880const uint64_t now = AP_HAL::micros64();881for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {882if (!enabled(i) || sensor[i] == nullptr) {883continue;884}885float temperature;886if (!get_temperature(i, temperature)) {887temperature = 0;888}889const struct log_ARSP pkt{890LOG_PACKET_HEADER_INIT(LOG_ARSP_MSG),891time_us : now,892instance : i,893airspeed : get_raw_airspeed(i),894diffpressure : get_differential_pressure(i),895temperature : (int16_t)(temperature * 100.0f),896rawpressure : get_corrected_pressure(i),897offset : get_offset(i),898use : use(i),899healthy : healthy(i),900health_prob : get_health_probability(i),901test_ratio : get_test_ratio(i),902primary : get_primary()903};904AP::logger().WriteBlock(&pkt, sizeof(pkt));905906#if AP_AIRSPEED_HYGROMETER_ENABLE907struct {908uint32_t sample_ms;909float temperature;910float humidity;911} hygrometer;912if (sensor[i]->get_hygrometer(hygrometer.sample_ms, hygrometer.temperature, hygrometer.humidity) &&913hygrometer.sample_ms != state[i].last_hygrometer_log_ms) {914AP::logger().WriteStreaming("HYGR",915"TimeUS,Id,Humidity,Temp",916"s#%O",917"F---",918"QBff",919AP_HAL::micros64(),920i,921hygrometer.humidity,922hygrometer.temperature);923state[i].last_hygrometer_log_ms = hygrometer.sample_ms;924}925#endif926}927}928#endif929930bool AP_Airspeed::use(uint8_t i) const931{932#ifndef HAL_BUILD_AP_PERIPH933if (!lib_enabled()) {934return false;935}936if (_force_disable_use) {937return false;938}939if (!enabled(i) || !param[i].use) {940return false;941}942if (param[i].use == 2 && !is_zero(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))) {943// special case for gliders with airspeed sensors behind the944// propeller. Allow airspeed to be disabled when throttle is945// running946return false;947}948return true;949#else950return false;951#endif // HAL_BUILD_AP_PERIPH952}953954/*955return true if all enabled sensors are healthy956*/957bool AP_Airspeed::all_healthy(void) const958{959for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {960if (enabled(i) && !healthy(i)) {961return false;962}963}964return true;965}966967bool AP_Airspeed::lib_enabled() const {968#if ENABLE_PARAMETER969return _enable > 0;970#endif971return true;972}973974// return true if airspeed is enabled975bool AP_Airspeed::enabled(uint8_t i) const {976if (!lib_enabled()) {977return false;978}979if (i < AIRSPEED_MAX_SENSORS) {980return param[i].type.get() != TYPE_NONE;981}982return false;983}984985// return health status of sensor986bool AP_Airspeed::healthy(uint8_t i) const {987if (!enabled(i)) {988return false;989}990bool ok = state[i].healthy && sensor[i] != nullptr;991#ifndef HAL_BUILD_AP_PERIPH992// sanity check the offset parameter. Zero is permitted if we are skipping calibration.993const bool allowZeroOffset = (state[i].cal.state == CalibrationState::NOT_REQUIRED_ZERO_OFFSET) ||994((AP_Airspeed_Params::SkipCalType)param[i].skip_cal == AP_Airspeed_Params::SkipCalType::NoCalRequired);995ok &= allowZeroOffset || !is_zero(param[i].offset);996#endif997return ok;998}9991000// return the current airspeed in m/s1001float AP_Airspeed::get_airspeed(uint8_t i) const {1002if (!enabled(i)) {1003// we can't have negative airspeed so sending an obviously invalid value1004return -1.0;1005}1006return state[i].airspeed;1007}10081009// return the unfiltered airspeed in m/s1010float AP_Airspeed::get_raw_airspeed(uint8_t i) const {1011if (!enabled(i)) {1012// we can't have negative airspeed so sending an obviously invalid value1013return -1.0;1014}1015return state[i].raw_airspeed;1016}10171018// return the differential pressure in Pascal for the last airspeed reading1019float AP_Airspeed::get_differential_pressure(uint8_t i) const {1020if (!enabled(i)) {1021return 0.0;1022}1023return state[i].last_pressure;1024}10251026// return the current corrected pressure1027float AP_Airspeed::get_corrected_pressure(uint8_t i) const {1028if (!enabled(i)) {1029return 0.0;1030}1031return state[i].corrected_pressure;1032}10331034// return the current calibration offset1035float AP_Airspeed::get_offset(uint8_t i) const {1036#ifndef HAL_BUILD_AP_PERIPH1037if (state[i].cal.state == CalibrationState::NOT_REQUIRED_ZERO_OFFSET) {1038return 0.0;1039}1040return param[i].offset;1041#else1042return 0.0;1043#endif1044}10451046#if AP_AIRSPEED_HYGROMETER_ENABLE1047bool AP_Airspeed::get_hygrometer(uint8_t i, uint32_t &last_sample_ms, float &temperature, float &humidity) const1048{1049if (!enabled(i) || sensor[i] == nullptr) {1050return false;1051}1052return sensor[i]->get_hygrometer(last_sample_ms, temperature, humidity);1053}1054#endif // AP_AIRSPEED_HYGROMETER_ENABLE10551056// returns false if we fail arming checks, in which case the buffer will be populated with a failure message1057#ifndef HAL_BUILD_AP_PERIPH1058bool AP_Airspeed::arming_checks(size_t buflen, char *buffer) const1059{1060for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {1061if (!enabled(i) || !use(i)) {1062continue;1063}10641065switch (state[i].cal.state) {1066case CalibrationState::SUCCESS:1067case CalibrationState::NOT_REQUIRED_ZERO_OFFSET:1068break;10691070case CalibrationState::NOT_STARTED:1071case CalibrationState::FAILED:1072hal.util->snprintf(buffer, buflen, "%d need pre-flight calibration", i + 1);1073return false;10741075case CalibrationState::IN_PROGRESS:1076hal.util->snprintf(buffer, buflen, "%d pre-flight calibration in progress", i + 1);1077return false;1078}10791080if (!healthy(i)) {1081hal.util->snprintf(buffer, buflen, "%d not healthy", i + 1);1082return false;1083}1084}108510861087// If the primary sensor is marked to not use then user should either:1088// - change primary to a sensor which is marked to to use1089// - allow using the primary1090// If no sensors are marked for use then the check passes1091if (!use(primary_sensor.get())) {1092for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {1093if (use(i)) {1094hal.util->snprintf(buffer, buflen, "not using Primary (%i)", primary_sensor.get() + 1);1095return false;1096}1097}1098}10991100return true;1101}1102#endif11031104#else // build type is not appropriate; provide a dummy implementation:1105const AP_Param::GroupInfo AP_Airspeed::var_info[] = { AP_GROUPEND };11061107void AP_Airspeed::update() {};1108bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) const { return false; }1109void AP_Airspeed::calibrate(bool in_startup) {}1110AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const { return CalibrationState::NOT_STARTED; }1111bool AP_Airspeed::use(uint8_t i) const { return false; }1112bool AP_Airspeed::enabled(uint8_t i) const { return false; }1113bool AP_Airspeed::healthy(uint8_t i) const { return false; }1114float AP_Airspeed::get_airspeed(uint8_t i) const { return 0.0; }1115float AP_Airspeed::get_differential_pressure(uint8_t i) const { return 0.0; }1116bool AP_Airspeed::arming_checks(size_t buflen, char *buffer) const { return true; }11171118#if AP_AIRSPEED_MSP_ENABLED1119void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {}1120#endif11211122bool AP_Airspeed::all_healthy(void) const { return false; }1123void AP_Airspeed::init(void) {};1124AP_Airspeed::AP_Airspeed() {}11251126#endif // #if AP_AIRSPEED_DUMMY_METHODS_ENABLED11271128// singleton instance1129AP_Airspeed *AP_Airspeed::_singleton;11301131namespace AP {11321133AP_Airspeed *airspeed()1134{1135return AP_Airspeed::get_singleton();1136}11371138};11391140#endif // AP_AIRSPEED_ENABLED114111421143