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_SDP3X.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*/1415/*16backend driver for airspeed from a I2C SDP3X sensor1718with thanks to https://github.com/PX4/Firmware/blob/master/src/drivers/sdp3x_airspeed19*/20#include "AP_Airspeed_SDP3X.h"2122#if AP_AIRSPEED_SDP3X_ENABLED2324#include <GCS_MAVLink/GCS.h>25#include <AP_Baro/AP_Baro.h>2627#include <stdio.h>2829#define SDP3X_SCALE_TEMPERATURE 200.0f3031#define SDP3XD0_I2C_ADDR 0x2132#define SDP3XD1_I2C_ADDR 0x2233#define SDP3XD2_I2C_ADDR 0x233435#define SDP3X_CONT_MEAS_AVG_MODE 0x361536#define SDP3X_CONT_MEAS_STOP 0x3FF93738#define SDP3X_SCALE_PRESSURE_SDP31 6039#define SDP3X_SCALE_PRESSURE_SDP32 24040#define SDP3X_SCALE_PRESSURE_SDP33 204142extern const AP_HAL::HAL &hal;4344/*45send a 16 bit command code46*/47bool AP_Airspeed_SDP3X::_send_command(uint16_t cmd)48{49uint8_t b[2] {uint8_t(cmd >> 8), uint8_t(cmd & 0xFF)};50return _dev->transfer(b, 2, nullptr, 0);51}5253// probe and initialise the sensor54bool AP_Airspeed_SDP3X::init()55{56const uint8_t addresses[3] = { SDP3XD0_I2C_ADDR,57SDP3XD1_I2C_ADDR,58SDP3XD2_I2C_ADDR59};60bool found = false;61bool ret = false;6263for (uint8_t i=0; i<ARRAY_SIZE(addresses) && !found; i++) {64_dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);65if (!_dev) {66continue;67}68_dev->get_semaphore()->take_blocking();6970// lots of retries during probe71_dev->set_retries(10);7273// stop continuous average mode74if (!_send_command(SDP3X_CONT_MEAS_STOP)) {75_dev->get_semaphore()->give();76continue;77}7879// these delays are needed for reliable operation80_dev->get_semaphore()->give();81hal.scheduler->delay_microseconds(20000);82_dev->get_semaphore()->take_blocking();8384// start continuous average mode85if (!_send_command(SDP3X_CONT_MEAS_AVG_MODE)) {86_dev->get_semaphore()->give();87continue;88}8990// these delays are needed for reliable operation91_dev->get_semaphore()->give();92hal.scheduler->delay_microseconds(20000);93_dev->get_semaphore()->take_blocking();9495// step 3 - get scale96uint8_t val[9];97ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));98if (!ret) {99_dev->get_semaphore()->give();100continue;101}102103// Check the CRC104if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5]) || !_crc(&val[6], 2, val[8])) {105_dev->get_semaphore()->give();106continue;107}108109_scale = (((uint16_t)val[6]) << 8) | val[7];110111_dev->get_semaphore()->give();112113found = true;114115#if HAL_GCS_ENABLED116char c = 'X';117switch (_scale) {118case SDP3X_SCALE_PRESSURE_SDP31:119c = '1';120break;121case SDP3X_SCALE_PRESSURE_SDP32:122c = '2';123break;124case SDP3X_SCALE_PRESSURE_SDP33:125c = '3';126break;127}128GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SDP3%c[%u]: Found bus %u addr 0x%02x scale=%u",129get_instance(),130c, get_bus(), addresses[i], _scale);131#endif132}133134if (!found) {135return false;136}137138/*139this sensor uses zero offset and skips cal140*/141set_use_zero_offset();142set_skip_cal();143set_offset(0);144145_dev->set_device_type(uint8_t(DevType::SDP3X));146set_bus_id(_dev->get_bus_id());147148// drop to 2 retries for runtime149_dev->set_retries(2);150151_dev->register_periodic_callback(20000,152FUNCTOR_BIND_MEMBER(&AP_Airspeed_SDP3X::_timer, void));153return true;154}155156// read the values from the sensor. Called at 50Hz157void AP_Airspeed_SDP3X::_timer()158{159// read 6 bytes from the sensor160uint8_t val[6];161int ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));162uint32_t now = AP_HAL::millis();163if (!ret) {164if (now - _last_sample_time_ms > 200) {165// try and re-connect166_send_command(SDP3X_CONT_MEAS_AVG_MODE);167}168return;169}170// Check the CRC171if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5])) {172return;173}174175int16_t P = (((int16_t)val[0]) << 8) | val[1];176int16_t temp = (((int16_t)val[3]) << 8) | val[4];177178float diff_press_pa = float(P) / float(_scale);179float temperature = float(temp) / SDP3X_SCALE_TEMPERATURE;180181WITH_SEMAPHORE(sem);182183_press_sum += diff_press_pa;184_temp_sum += temperature;185_press_count++;186_temp_count++;187_last_sample_time_ms = now;188}189190/*191correct pressure for barometric height192With thanks to:193https://github.com/PX4/Firmware/blob/master/Tools/models/sdp3x_pitot_model.py194*/195float AP_Airspeed_SDP3X::_correct_pressure(float press)196{197float sign = 1.0f;198199// fix for tube order200AP_Airspeed::pitot_tube_order tube_order = get_tube_order();201switch (tube_order) {202case AP_Airspeed::PITOT_TUBE_ORDER_NEGATIVE:203press = -press;204sign = -1.0f;205break;206case AP_Airspeed::PITOT_TUBE_ORDER_POSITIVE:207break;208case AP_Airspeed::PITOT_TUBE_ORDER_AUTO:209default:210if (press < 0.0f) {211sign = -1.0f;212press = -press;213}214break;215}216217if (press <= 0.0f) {218return 0.0f;219}220221AP_Baro *baro = AP_Baro::get_singleton();222223float baro_pressure;224if (baro == nullptr || baro->num_instances() == 0) {225// with no baro assume sea level226baro_pressure = SSL_AIR_PRESSURE;227} else {228baro_pressure = baro->get_pressure();229}230231float temperature;232if (!get_temperature(temperature)) {233// assume 25C if no temperature234temperature = 25;235}236237float rho_air = baro_pressure / (ISA_GAS_CONSTANT * C_TO_KELVIN(temperature));238if (!is_positive(rho_air)) {239// bad pressure240return press;241}242243/*244the constants in the code below come from a calibrated test of245the drotek pitot tube by Sensiron. They are specific to the droktek pitot tube246247At 25m/s, the rough proportions of each pressure correction are:248249- dp_pitot: 5%250- press_correction: 14%251- press: 81%252253dp_tube has been removed from the Sensiron model as it is254insignificant (less than 0.02% over the supported speed ranges)255*/256257// flow through sensor258float flow_SDP3X = (300.805f - 300.878f / (0.00344205f * (float)powf(press, 0.68698f) + 1.0f)) * 1.29f / rho_air;259if (flow_SDP3X < 0.0f) {260flow_SDP3X = 0.0f;261}262263// differential pressure through pitot tube264float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f)));265266// uncorrected pressure267float press_uncorrected = (press + dp_pitot) / SSL_AIR_DENSITY;268269// correction for speed at pitot-tube tip due to flow through sensor270float dv = 0.0331582f * flow_SDP3X;271272// airspeed ratio273float ratio = get_airspeed_ratio();274if (!is_positive(ratio)) {275// cope with AP_Periph where ratio is 0276ratio = 2.0;277}278279// calculate equivalent pressure correction. This formula comes280// from turning the dv correction above into an equivalent281// pressure correction. We need to do this so the airspeed ratio282// calibrator can work, as it operates on pressure values283float press_correction = sq(sqrtf(press_uncorrected*ratio)+dv)/ratio - press_uncorrected;284285return (press_uncorrected + press_correction) * sign;286}287288// return the current differential_pressure in Pascal289bool AP_Airspeed_SDP3X::get_differential_pressure(float &pressure)290{291WITH_SEMAPHORE(sem);292293if (AP_HAL::millis() - _last_sample_time_ms > 100) {294return false;295}296297if (_press_count > 0) {298_press = _press_sum / _press_count;299_press_count = 0;300_press_sum = 0;301}302303pressure = _correct_pressure(_press);304return true;305}306307// return the current temperature in degrees C, if available308bool AP_Airspeed_SDP3X::get_temperature(float &temperature)309{310WITH_SEMAPHORE(sem);311312if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {313return false;314}315316if (_temp_count > 0) {317_temp = _temp_sum / _temp_count;318_temp_count = 0;319_temp_sum = 0;320}321322temperature = _temp;323return true;324}325326/*327check CRC for a set of bytes328*/329bool AP_Airspeed_SDP3X::_crc(const uint8_t data[], uint8_t size, uint8_t checksum)330{331uint8_t crc_value = 0xff;332333// calculate 8-bit checksum with polynomial 0x31 (x^8 + x^5 + x^4 + 1)334for (uint8_t i = 0; i < size; i++) {335crc_value ^= data[i];336for (uint8_t bit = 8; bit > 0; --bit) {337if (crc_value & 0x80) {338crc_value = (crc_value << 1) ^ 0x31;339} else {340crc_value = (crc_value << 1);341}342}343}344// verify checksum345return (crc_value == checksum);346}347348#endif // AP_AIRSPEED_SDP3X_ENABLED349350351