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.cpp
Views: 1798
/*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 && BOARD_FLASH_SIZE <= 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_External.h"55#include "AP_Airspeed_SITL.h"56extern const AP_HAL::HAL &hal;5758#include <AP_Vehicle/AP_FixedWing.h>5960#ifdef HAL_AIRSPEED_TYPE_DEFAULT61#define ARSPD_DEFAULT_TYPE HAL_AIRSPEED_TYPE_DEFAULT62#ifndef ARSPD_DEFAULT_PIN63#define ARSPD_DEFAULT_PIN 164#endif65#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)66// The HAL_BOARD_SITL setting is required because of current probe process for MS4525 will67// connect and find the SIM_DLVR sensors & fault as there is no way to tell them apart68#if CONFIG_HAL_BOARD == HAL_BOARD_SITL69#define ARSPD_DEFAULT_TYPE TYPE_ANALOG70#define ARSPD_DEFAULT_PIN 171#else72#define ARSPD_DEFAULT_TYPE TYPE_I2C_MS452573#ifdef HAL_DEFAULT_AIRSPEED_PIN74#define ARSPD_DEFAULT_PIN HAL_DEFAULT_AIRSPEED_PIN75#else76#define ARSPD_DEFAULT_PIN 1577#endif78#endif //CONFIG_HAL_BOARD79#else // All Other Vehicle Types80#define ARSPD_DEFAULT_TYPE TYPE_NONE81#define ARSPD_DEFAULT_PIN 1582#endif8384#ifndef HAL_AIRSPEED_BUS_DEFAULT85#define HAL_AIRSPEED_BUS_DEFAULT 186#endif8788#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_CONSISTENCY8990#define ENABLE_PARAMETER !(APM_BUILD_TYPE(APM_BUILD_ArduPlane) || defined(HAL_BUILD_AP_PERIPH))9192// table of user settable parameters93const AP_Param::GroupInfo AP_Airspeed::var_info[] = {9495#if ENABLE_PARAMETER96// @Param: _ENABLE97// @DisplayName: Airspeed Enable98// @Description: Enable airspeed sensor support99// @Values: 0:Disable, 1:Enable100// @User: Standard101AP_GROUPINFO_FLAGS("_ENABLE", 30, AP_Airspeed, _enable, 0, AP_PARAM_FLAG_ENABLE),102#endif103// slots 0-9 (and 63) were previously used by params before being refactored into AP_Airspeed_Params104105// @Param: _TUBE_ORDER106// @DisplayName: Control pitot tube order107// @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.108// @User: Advanced109// @Values: 0:Normal,1:Swapped,2:Auto Detect110111// tube order param had to be shortened so is not preserved in per group descriptions112113#if AIRSPEED_MAX_SENSORS > 1114// @Param: _PRIMARY115// @DisplayName: Primary airspeed sensor116// @Description: This selects which airspeed sensor will be the primary if multiple sensors are found117// @Values: 0:FirstSensor,1:2ndSensor118// @User: Advanced119AP_GROUPINFO("_PRIMARY", 10, AP_Airspeed, primary_sensor, 0),120#endif121122// 11-20 were previously used by second sensor params before being refactored into AP_Airspeed_Params123124#ifndef HAL_BUILD_AP_PERIPH125// @Param: _OPTIONS126// @DisplayName: Airspeed options bitmask127// @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 GCS128// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.129// @Bitmask: 0:SpeedMismatchDisable, 1:AllowSpeedMismatchRecovery, 2:DisableVoltageCorrection, 3:UseEkf3Consistency, 4:ReportOffset130// @User: Advanced131AP_GROUPINFO("_OPTIONS", 21, AP_Airspeed, _options, OPTIONS_DEFAULT),132133// @Param: _WIND_MAX134// @DisplayName: Maximum airspeed and ground speed difference135// @Description: If the difference between airspeed and ground speed is greater than this value the sensor will be marked unhealthy. Using ARSPD_OPTION this health value can be used to disable the sensor.136// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.137// @Units: m/s138// @User: Advanced139AP_GROUPINFO("_WIND_MAX", 22, AP_Airspeed, _wind_max, 0),140141// @Param: _WIND_WARN142// @DisplayName: Airspeed and GPS speed difference that gives a warning143// @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.144// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle. Always set to 0.145// @Units: m/s146// @User: Advanced147AP_GROUPINFO("_WIND_WARN", 23, AP_Airspeed, _wind_warn, 0),148149// @Param: _WIND_GATE150// @DisplayName: Re-enable Consistency Check Gate Size151// @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.152// @Description{Copter, Blimp, Rover, Sub}: This parameter and function is not used by this vehicle.153// @Range: 0.0 10.0154// @User: Advanced155AP_GROUPINFO("_WIND_GATE", 26, AP_Airspeed, _wind_gate, 5.0f),156157// @Param: _OFF_PCNT158// @DisplayName: Maximum offset cal speed error159// @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.160// @Range: 0.0 10.0161// @Units: %162// @User: Advanced163AP_GROUPINFO_FRAME("_OFF_PCNT", 27, AP_Airspeed, max_speed_pcnt, 0, AP_PARAM_FRAME_PLANE),164165#endif166167// @Group: _168// @Path: AP_Airspeed_Params.cpp169AP_SUBGROUPINFO(param[0], "_", 28, AP_Airspeed, AP_Airspeed_Params),170171#if AIRSPEED_MAX_SENSORS > 1172// @Group: 2_173// @Path: AP_Airspeed_Params.cpp174AP_SUBGROUPINFO(param[1], "2_", 29, AP_Airspeed, AP_Airspeed_Params),175#endif176177// index 30 is used by enable at the top of the table178179AP_GROUPEND180};181182/*183this scaling factor converts from the old system where we used a1840 to 4095 raw ADC value for 0-5V to the new system which gets the185voltage in volts directly from the ADC driver186*/187#define SCALING_OLD_CALIBRATION 819 // 4095/5188189AP_Airspeed::AP_Airspeed()190{191AP_Param::setup_object_defaults(this, var_info);192193// Setup defaults that only apply to first sensor194param[0].type.set_default(ARSPD_DEFAULT_TYPE);195#ifndef HAL_BUILD_AP_PERIPH196param[0].bus.set_default(HAL_AIRSPEED_BUS_DEFAULT);197param[0].pin.set_default(ARSPD_DEFAULT_PIN);198#endif199200if (_singleton != nullptr) {201AP_HAL::panic("AP_Airspeed must be singleton");202}203_singleton = this;204}205206void AP_Airspeed::set_fixedwing_parameters(const AP_FixedWing *_fixed_wing_parameters)207{208fixed_wing_parameters = _fixed_wing_parameters;209}210211// macro for use by HAL_INS_PROBE_LIST212#define GET_I2C_DEVICE(bus, address) hal.i2c_mgr->get_device(bus, address)213214bool AP_Airspeed::add_backend(AP_Airspeed_Backend *backend)215{216if (!backend) {217return false;218}219if (num_sensors >= AIRSPEED_MAX_SENSORS) {220AP_HAL::panic("Too many airspeed drivers");221}222const uint8_t i = num_sensors;223sensor[num_sensors++] = backend;224if (!sensor[i]->init()) {225GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i+1);226delete sensor[i];227sensor[i] = nullptr;228}229return true;230}231232/*233macro to add a backend with check for too many sensors234We don't try to start more than the maximum allowed235*/236#define ADD_BACKEND(backend) \237do { add_backend(backend); \238if (num_sensors == AIRSPEED_MAX_SENSORS) { return; } \239} while (0)240241242// convert params to per instance param table243// PARAMETER_CONVERSION - Added: Dec-2022244void AP_Airspeed::convert_per_instance()245{246AP_Param::ConversionInfo info;247#ifndef HAL_BUILD_AP_PERIPH248// Vehicle conversion249if (!AP_Param::find_key_by_pointer(this, info.old_key)) {250return;251}252253static const struct convert_table {254uint32_t element[2];255ap_var_type type;256const char* name;257} conversion_table[] = {258{ {4042, 714}, AP_PARAM_INT8, "TYPE" }, // ARSPD_TYPE, ARSPD2_TYPE259{ {74, 778}, AP_PARAM_INT8, "USE" }, // ARSPD_USE, ARSPD2_USE260{ {138, 842}, AP_PARAM_FLOAT, "OFFSET" }, // ARSPD_OFFSET, ARSPD2_OFFSET261{ {202, 906}, AP_PARAM_FLOAT, "RATIO" }, // ARSPD_RATIO, ARSPD2_RATIO262{ {266, 970}, AP_PARAM_INT8, "PIN" }, // ARSPD_PIN, ARSPD2_PIN263#if AP_AIRSPEED_AUTOCAL_ENABLE264{ {330, 1034}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL265#endif266{ {394, 1098}, AP_PARAM_INT8, "TUBE_ORDR" }, // ARSPD_TUBE_ORDER, ARSPD2_TUBE_ORDR267{ {458, 1162}, AP_PARAM_INT8, "SKIP_CAL" }, // ARSPD_SKIP_CAL, ARSPD2_SKIP_CAL268{ {522, 1226}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE269{ {586, 1290}, AP_PARAM_INT8, "BUS" }, // ARSPD_BUS, ARSPD2_BUS270{ {1546, 1610}, AP_PARAM_INT32, "DEVID" }, // ARSPD_DEVID, ARSPD2_DEVID271};272273#else274// Periph conversion275if (!AP_Param::find_top_level_key_by_pointer(this, info.old_key)) {276return;277}278const struct convert_table {279uint32_t element[2];280ap_var_type type;281const char* name;282} conversion_table[] = {283{ {0, 11}, AP_PARAM_INT8, "TYPE" }, // ARSPD_TYPE, ARSPD2_TYPE284#if AP_AIRSPEED_AUTOCAL_ENABLE285{ {5, 16}, AP_PARAM_INT8, "AUTOCAL" }, // ARSPD_AUTOCAL, ARSPD2_AUTOCAL286#endif287{ {8, 19}, AP_PARAM_FLOAT, "PSI_RANGE" }, // ARSPD_PSI_RANGE, ARSPD2_PSI_RANGE288{ {24, 25}, AP_PARAM_INT32, "DEVID" }, // ARSPD_DEVID, ARSPD2_DEVID289};290#endif291292char param_name[17] {};293info.new_name = param_name;294295for (const auto & elem : conversion_table) {296info.type = elem.type;297for (uint8_t i=0; i < MIN(AIRSPEED_MAX_SENSORS,2); i++) {298info.old_group_element = elem.element[i];299if (i == 0) {300hal.util->snprintf(param_name, sizeof(param_name), "ARSPD_%s", elem.name);301} else {302hal.util->snprintf(param_name, sizeof(param_name), "ARSPD%i_%s", i+1, elem.name);303}304AP_Param::convert_old_parameter(&info, 1.0, 0);305}306}307}308309void AP_Airspeed::init()310{311312convert_per_instance();313314#if ENABLE_PARAMETER315// if either type is set then enable if not manually set316if (!_enable.configured() && ((param[0].type.get() != TYPE_NONE) || (param[1].type.get() != TYPE_NONE))) {317_enable.set_and_save(1);318}319320// Check if enabled321if (!lib_enabled()) {322return;323}324#endif325326if (enabled(0)) {327allocate();328}329}330331void AP_Airspeed::allocate()332{333if (sensor[0] != nullptr) {334// already initialised, periph may call allocate several times to allow CAN detection335return;336}337338#ifdef HAL_AIRSPEED_PROBE_LIST339// load sensors via a list from hwdef.dat340HAL_AIRSPEED_PROBE_LIST;341#else342// look for sensors based on type parameters343for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {344#if AP_AIRSPEED_AUTOCAL_ENABLE345state[i].calibration.init(param[i].ratio);346state[i].last_saved_ratio = param[i].ratio;347#endif348349// Set the enable automatically to false and set the probability that the airspeed is healhy to start with350state[i].failures.health_probability = 1.0f;351352switch ((enum airspeed_type)param[i].type.get()) {353case TYPE_NONE:354// nothing to do355break;356case TYPE_I2C_MS4525:357#if AP_AIRSPEED_MS4525_ENABLED358sensor[i] = NEW_NOTHROW AP_Airspeed_MS4525(*this, i);359#endif360break;361case TYPE_SITL:362#if AP_AIRSPEED_SITL_ENABLED363sensor[i] = NEW_NOTHROW AP_Airspeed_SITL(*this, i);364#endif365break;366case TYPE_ANALOG:367#if AP_AIRSPEED_ANALOG_ENABLED368sensor[i] = NEW_NOTHROW AP_Airspeed_Analog(*this, i);369#endif370break;371case TYPE_I2C_MS5525:372#if AP_AIRSPEED_MS5525_ENABLED373sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_AUTO);374#endif375break;376case TYPE_I2C_MS5525_ADDRESS_1:377#if AP_AIRSPEED_MS5525_ENABLED378sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_1);379#endif380break;381case TYPE_I2C_MS5525_ADDRESS_2:382#if AP_AIRSPEED_MS5525_ENABLED383sensor[i] = NEW_NOTHROW AP_Airspeed_MS5525(*this, i, AP_Airspeed_MS5525::MS5525_ADDR_2);384#endif385break;386case TYPE_I2C_SDP3X:387#if AP_AIRSPEED_SDP3X_ENABLED388sensor[i] = NEW_NOTHROW AP_Airspeed_SDP3X(*this, i);389#endif390break;391case TYPE_I2C_DLVR_5IN:392#if AP_AIRSPEED_DLVR_ENABLED393sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 5);394#endif395break;396case TYPE_I2C_DLVR_10IN:397#if AP_AIRSPEED_DLVR_ENABLED398sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 10);399#endif400break;401case TYPE_I2C_DLVR_20IN:402#if AP_AIRSPEED_DLVR_ENABLED403sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 20);404#endif405break;406case TYPE_I2C_DLVR_30IN:407#if AP_AIRSPEED_DLVR_ENABLED408sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 30);409#endif410break;411case TYPE_I2C_DLVR_60IN:412#if AP_AIRSPEED_DLVR_ENABLED413sensor[i] = NEW_NOTHROW AP_Airspeed_DLVR(*this, i, 60);414#endif // AP_AIRSPEED_DLVR_ENABLED415break;416case TYPE_I2C_ASP5033:417#if AP_AIRSPEED_ASP5033_ENABLED418sensor[i] = NEW_NOTHROW AP_Airspeed_ASP5033(*this, i);419#endif420break;421case TYPE_UAVCAN:422#if AP_AIRSPEED_DRONECAN_ENABLED423sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, uint32_t(param[i].bus_id.get()));424#endif425break;426case TYPE_NMEA_WATER:427#if AP_AIRSPEED_NMEA_ENABLED428#if APM_BUILD_TYPE(APM_BUILD_Rover) || APM_BUILD_TYPE(APM_BUILD_ArduSub)429sensor[i] = NEW_NOTHROW AP_Airspeed_NMEA(*this, i);430#endif431#endif432break;433case TYPE_MSP:434#if AP_AIRSPEED_MSP_ENABLED435sensor[i] = NEW_NOTHROW AP_Airspeed_MSP(*this, i, 0);436#endif437break;438case TYPE_EXTERNAL:439#if AP_AIRSPEED_EXTERNAL_ENABLED440sensor[i] = NEW_NOTHROW AP_Airspeed_External(*this, i);441#endif442break;443}444if (sensor[i] && !sensor[i]->init()) {445GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i + 1);446delete sensor[i];447sensor[i] = nullptr;448}449if (sensor[i] != nullptr) {450num_sensors = i+1;451}452}453454#if AP_AIRSPEED_DRONECAN_ENABLED455// we need a 2nd pass for DroneCAN sensors so we can match order by DEVID456// the 2nd pass accepts any devid457for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {458if (sensor[i] == nullptr && (enum airspeed_type)param[i].type.get() == TYPE_UAVCAN) {459sensor[i] = AP_Airspeed_DroneCAN::probe(*this, i, 0);460if (sensor[i] != nullptr) {461num_sensors = i+1;462}463}464}465#endif // AP_AIRSPEED_DRONECAN_ENABLED466#endif // HAL_AIRSPEED_PROBE_LIST467468// set DEVID to zero for any sensors not found. This allows backends to order469// based on previous value of DEVID. This allows for swapping out sensors470for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {471if (sensor[i] == nullptr) {472// note we use set() not set_and_save() to allow a sensor to be temporarily473// removed for one boot without losing its slot474param[i].bus_id.set(0);475}476}477}478479// read the airspeed sensor480float AP_Airspeed::get_pressure(uint8_t i)481{482if (!enabled(i)) {483return 0;484}485float pressure = 0;486if (sensor[i]) {487state[i].healthy = sensor[i]->get_differential_pressure(pressure);488}489return pressure;490}491492// get a temperature reading if possible493bool AP_Airspeed::get_temperature(uint8_t i, float &temperature)494{495if (!enabled(i)) {496return false;497}498if (sensor[i]) {499return sensor[i]->get_temperature(temperature);500}501return false;502}503504// calibrate the zero offset for the airspeed. This must be called at505// least once before the get_airspeed() interface can be used506void AP_Airspeed::calibrate(bool in_startup)507{508#ifndef HAL_BUILD_AP_PERIPH509if (!lib_enabled()) {510return;511}512if (hal.util->was_watchdog_reset()) {513GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed: skipping cal");514return;515}516for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {517if (!enabled(i)) {518continue;519}520if (state[i].use_zero_offset) {521param[i].offset.set(0);522continue;523}524if (in_startup && param[i].skip_cal) {525continue;526}527if (sensor[i] == nullptr) {528GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u not initialized, cannot cal", i+1);529continue;530}531state[i].cal.start_ms = AP_HAL::millis();532state[i].cal.count = 0;533state[i].cal.sum = 0;534state[i].cal.read_count = 0;535calibration_state[i] = CalibrationState::IN_PROGRESS;536GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed %u calibration started", i+1);537}538#endif // HAL_BUILD_AP_PERIPH539}540541/*542update async airspeed zero offset calibration543*/544void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure)545{546#ifndef HAL_BUILD_AP_PERIPH547if (!enabled(i) || state[i].cal.start_ms == 0) {548return;549}550551// consider calibration complete when we have at least 15 samples552// over at least 1 second553if (AP_HAL::millis() - state[i].cal.start_ms >= 1000 &&554state[i].cal.read_count > 15) {555if (state[i].cal.count == 0) {556GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %u unhealthy", i + 1);557calibration_state[i] = CalibrationState::FAILED;558} else {559float calibrated_offset = state[i].cal.sum / state[i].cal.count;560// check if new offset differs too greatly from last calibration, indicating pitot uncovered in wind561if (fixed_wing_parameters != nullptr) {562float airspeed_min = fixed_wing_parameters->airspeed_min.get();563// use percentage of AIRSPEED_MIN as criteria for max allowed change in offset564float max_change = 0.5*(sq((1 + (max_speed_pcnt * 0.01))*airspeed_min) - sq(airspeed_min));565if (max_speed_pcnt > 0 && (abs(calibrated_offset-param[i].offset) > max_change) && (abs(param[i].offset) > 0)) {566GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Arspd %d offset change large;cover and recal", i +1);567}568}569param[i].offset.set_and_save(calibrated_offset);570calibration_state[i] = CalibrationState::SUCCESS;571if (_options & AP_Airspeed::OptionsMask::REPORT_OFFSET ){572GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated, offset = %4.0f", i + 1, calibrated_offset);573} else {574GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1);575}576}577state[i].cal.start_ms = 0;578return;579}580// we discard the first 5 samples581if (state[i].healthy && state[i].cal.read_count > 5) {582state[i].cal.sum += raw_pressure;583state[i].cal.count++;584}585state[i].cal.read_count++;586#endif // HAL_BUILD_AP_PERIPH587}588589// get aggregate calibration state for the Airspeed library:590AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const591{592for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {593switch (calibration_state[i]) {594case CalibrationState::SUCCESS:595case CalibrationState::NOT_STARTED:596continue;597case CalibrationState::IN_PROGRESS:598return CalibrationState::IN_PROGRESS;599case CalibrationState::FAILED:600return CalibrationState::FAILED;601}602}603return CalibrationState::SUCCESS;604}605606// read one airspeed sensor607void AP_Airspeed::read(uint8_t i)608{609if (!enabled(i) || !sensor[i]) {610return;611}612state[i].last_update_ms = AP_HAL::millis();613614// try and get a direct reading of airspeed615if (sensor[i]->has_airspeed()) {616state[i].healthy = sensor[i]->get_airspeed(state[i].airspeed);617state[i].raw_airspeed = state[i].airspeed; // for logging618return;619}620621#ifndef HAL_BUILD_AP_PERIPH622/*623get the healthy state before we call get_pressure() as624get_pressure() overwrites the healthy state625*/626bool prev_healthy = state[i].healthy;627#endif628629float raw_pressure = get_pressure(i);630float airspeed_pressure = raw_pressure - get_offset(i);631632// remember raw pressure for logging633state[i].corrected_pressure = airspeed_pressure;634635#ifndef HAL_BUILD_AP_PERIPH636if (state[i].cal.start_ms != 0) {637update_calibration(i, raw_pressure);638}639640// filter before clamping positive641if (!prev_healthy) {642// if the previous state was not healthy then we should not643// use an IIR filter, otherwise a bad reading will last for644// some time after the sensor becomes healthy again645state[i].filtered_pressure = airspeed_pressure;646} else {647state[i].filtered_pressure = 0.7f * state[i].filtered_pressure + 0.3f * airspeed_pressure;648}649650/*651we support different pitot tube setups so user can choose if652they want to be able to detect pressure on the static port653*/654switch ((enum pitot_tube_order)param[i].tube_order.get()) {655case PITOT_TUBE_ORDER_NEGATIVE:656state[i].last_pressure = -airspeed_pressure;657state[i].raw_airspeed = sqrtf(MAX(-airspeed_pressure, 0) * param[i].ratio);658state[i].airspeed = sqrtf(MAX(-state[i].filtered_pressure, 0) * param[i].ratio);659break;660case PITOT_TUBE_ORDER_POSITIVE:661state[i].last_pressure = airspeed_pressure;662state[i].raw_airspeed = sqrtf(MAX(airspeed_pressure, 0) * param[i].ratio);663state[i].airspeed = sqrtf(MAX(state[i].filtered_pressure, 0) * param[i].ratio);664break;665case PITOT_TUBE_ORDER_AUTO:666default:667state[i].last_pressure = fabsf(airspeed_pressure);668state[i].raw_airspeed = sqrtf(fabsf(airspeed_pressure) * param[i].ratio);669state[i].airspeed = sqrtf(fabsf(state[i].filtered_pressure) * param[i].ratio);670break;671}672#endif // HAL_BUILD_AP_PERIPH673}674675// read all airspeed sensors676void AP_Airspeed::update()677{678if (!lib_enabled()) {679return;680}681682for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {683read(i);684}685686#if HAL_GCS_ENABLED687// debugging until we get MAVLink support for 2nd airspeed sensor688if (enabled(1)) {689gcs().send_named_float("AS2", get_airspeed(1));690}691#endif692693#if HAL_LOGGING_ENABLED694const uint8_t old_primary = primary;695#endif696697// setup primary698if (healthy(primary_sensor.get())) {699primary = primary_sensor.get();700} else {701for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {702if (healthy(i)) {703primary = i;704break;705}706}707}708709check_sensor_failures();710711#if HAL_LOGGING_ENABLED712if (primary != old_primary) {713AP::logger().Write_Event(LogEvent::AIRSPEED_PRIMARY_CHANGED);714}715if (_log_bit != (uint32_t)-1 && AP::logger().should_log(_log_bit)) {716Log_Airspeed();717}718#endif719}720721#if AP_AIRSPEED_MSP_ENABLED722/*723handle MSP airspeed data724*/725void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt)726{727if (!lib_enabled()) {728return;729}730731if (pkt.instance > 1) {732return; //supporting 2 airspeed sensors at most733}734735for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {736if (sensor[i]) {737sensor[i]->handle_msp(pkt);738}739}740}741#endif742743#if AP_AIRSPEED_EXTERNAL_ENABLED744/*745handle airspeed airspeed data746*/747void AP_Airspeed::handle_external(const AP_ExternalAHRS::airspeed_data_message_t &pkt)748{749if (!lib_enabled()) {750return;751}752753for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {754if (param[i].type == TYPE_EXTERNAL && sensor[i]) {755sensor[i]->handle_external(pkt);756}757}758}759#endif760761#if HAL_LOGGING_ENABLED762// @LoggerMessage: HYGR763// @Description: Hygrometer data764// @Field: TimeUS: Time since system startup765// @Field: Id: sensor ID766// @Field: Humidity: percentage humidity767// @Field: Temp: temperature in degrees C768769void AP_Airspeed::Log_Airspeed()770{771const uint64_t now = AP_HAL::micros64();772for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {773if (!enabled(i) || sensor[i] == nullptr) {774continue;775}776float temperature;777if (!get_temperature(i, temperature)) {778temperature = 0;779}780const struct log_ARSP pkt{781LOG_PACKET_HEADER_INIT(LOG_ARSP_MSG),782time_us : now,783instance : i,784airspeed : get_raw_airspeed(i),785diffpressure : get_differential_pressure(i),786temperature : (int16_t)(temperature * 100.0f),787rawpressure : get_corrected_pressure(i),788offset : get_offset(i),789use : use(i),790healthy : healthy(i),791health_prob : get_health_probability(i),792test_ratio : get_test_ratio(i),793primary : get_primary()794};795AP::logger().WriteBlock(&pkt, sizeof(pkt));796797#if AP_AIRSPEED_HYGROMETER_ENABLE798struct {799uint32_t sample_ms;800float temperature;801float humidity;802} hygrometer;803if (sensor[i]->get_hygrometer(hygrometer.sample_ms, hygrometer.temperature, hygrometer.humidity) &&804hygrometer.sample_ms != state[i].last_hygrometer_log_ms) {805AP::logger().WriteStreaming("HYGR",806"TimeUS,Id,Humidity,Temp",807"s#%O",808"F---",809"QBff",810AP_HAL::micros64(),811i,812hygrometer.humidity,813hygrometer.temperature);814state[i].last_hygrometer_log_ms = hygrometer.sample_ms;815}816#endif817}818}819#endif820821bool AP_Airspeed::use(uint8_t i) const822{823#ifndef HAL_BUILD_AP_PERIPH824if (!lib_enabled()) {825return false;826}827if (_force_disable_use) {828return false;829}830if (!enabled(i) || !param[i].use) {831return false;832}833if (param[i].use == 2 && !is_zero(SRV_Channels::get_output_scaled(SRV_Channel::k_throttle))) {834// special case for gliders with airspeed sensors behind the835// propeller. Allow airspeed to be disabled when throttle is836// running837return false;838}839return true;840#else841return false;842#endif // HAL_BUILD_AP_PERIPH843}844845/*846return true if all enabled sensors are healthy847*/848bool AP_Airspeed::all_healthy(void) const849{850for (uint8_t i=0; i<AIRSPEED_MAX_SENSORS; i++) {851if (enabled(i) && !healthy(i)) {852return false;853}854}855return true;856}857858bool AP_Airspeed::lib_enabled() const {859#if ENABLE_PARAMETER860return _enable > 0;861#endif862return true;863}864865// return true if airspeed is enabled866bool AP_Airspeed::enabled(uint8_t i) const {867if (!lib_enabled()) {868return false;869}870if (i < AIRSPEED_MAX_SENSORS) {871return param[i].type.get() != TYPE_NONE;872}873return false;874}875876// return health status of sensor877bool AP_Airspeed::healthy(uint8_t i) const {878if (!enabled(i)) {879return false;880}881bool ok = state[i].healthy && sensor[i] != nullptr;882#ifndef HAL_BUILD_AP_PERIPH883// sanity check the offset parameter. Zero is permitted if we are skipping calibration.884ok &= (fabsf(param[i].offset) > 0 || state[i].use_zero_offset || param[i].skip_cal);885#endif886return ok;887}888889// return the current airspeed in m/s890float AP_Airspeed::get_airspeed(uint8_t i) const {891if (!enabled(i)) {892// we can't have negative airspeed so sending an obviously invalid value893return -1.0;894}895return state[i].airspeed;896}897898// return the unfiltered airspeed in m/s899float AP_Airspeed::get_raw_airspeed(uint8_t i) const {900if (!enabled(i)) {901// we can't have negative airspeed so sending an obviously invalid value902return -1.0;903}904return state[i].raw_airspeed;905}906907// return the differential pressure in Pascal for the last airspeed reading908float AP_Airspeed::get_differential_pressure(uint8_t i) const {909if (!enabled(i)) {910return 0.0;911}912return state[i].last_pressure;913}914915// return the current corrected pressure916float AP_Airspeed::get_corrected_pressure(uint8_t i) const {917if (!enabled(i)) {918return 0.0;919}920return state[i].corrected_pressure;921}922923#if AP_AIRSPEED_HYGROMETER_ENABLE924bool AP_Airspeed::get_hygrometer(uint8_t i, uint32_t &last_sample_ms, float &temperature, float &humidity) const925{926if (!enabled(i) || sensor[i] == nullptr) {927return false;928}929return sensor[i]->get_hygrometer(last_sample_ms, temperature, humidity);930}931#endif // AP_AIRSPEED_HYGROMETER_ENABLE932933#else // build type is not appropriate; provide a dummy implementation:934const AP_Param::GroupInfo AP_Airspeed::var_info[] = { AP_GROUPEND };935936void AP_Airspeed::update() {};937bool AP_Airspeed::get_temperature(uint8_t i, float &temperature) { return false; }938void AP_Airspeed::calibrate(bool in_startup) {}939AP_Airspeed::CalibrationState AP_Airspeed::get_calibration_state() const { return CalibrationState::NOT_STARTED; }940bool AP_Airspeed::use(uint8_t i) const { return false; }941bool AP_Airspeed::enabled(uint8_t i) const { return false; }942bool AP_Airspeed::healthy(uint8_t i) const { return false; }943float AP_Airspeed::get_airspeed(uint8_t i) const { return 0.0; }944float AP_Airspeed::get_differential_pressure(uint8_t i) const { return 0.0; }945946#if AP_AIRSPEED_MSP_ENABLED947void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {}948#endif949950bool AP_Airspeed::all_healthy(void) const { return false; }951void AP_Airspeed::init(void) {};952AP_Airspeed::AP_Airspeed() {}953954#endif // #if AP_AIRSPEED_DUMMY_METHODS_ENABLED955956// singleton instance957AP_Airspeed *AP_Airspeed::_singleton;958959namespace AP {960961AP_Airspeed *airspeed()962{963return AP_Airspeed::get_singleton();964}965966};967968#endif // AP_AIRSPEED_ENABLED969970971