Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp
9645 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*/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 sensor54__INITFUNC__ bool 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_ptr(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// this sensor uses zero offset139set_use_zero_offset();140141_dev->set_device_type(uint8_t(DevType::SDP3X));142set_bus_id(_dev->get_bus_id());143144// drop to 2 retries for runtime145_dev->set_retries(2);146147_dev->register_periodic_callback(20000,148FUNCTOR_BIND_MEMBER(&AP_Airspeed_SDP3X::_timer, void));149return true;150}151152// read the values from the sensor. Called at 50Hz153void AP_Airspeed_SDP3X::_timer()154{155// read 6 bytes from the sensor156uint8_t val[6];157int ret = _dev->transfer(nullptr, 0, &val[0], sizeof(val));158uint32_t now = AP_HAL::millis();159if (!ret) {160if (now - _last_sample_time_ms > 200) {161// try and re-connect162_send_command(SDP3X_CONT_MEAS_AVG_MODE);163}164return;165}166// Check the CRC167if (!_crc(&val[0], 2, val[2]) || !_crc(&val[3], 2, val[5])) {168return;169}170171int16_t P = (((int16_t)val[0]) << 8) | val[1];172int16_t temp = (((int16_t)val[3]) << 8) | val[4];173174float diff_press_pa = float(P) / float(_scale);175float temperature = float(temp) / SDP3X_SCALE_TEMPERATURE;176177WITH_SEMAPHORE(sem);178179_press_sum += diff_press_pa;180_temp_sum += temperature;181_press_count++;182_temp_count++;183_last_sample_time_ms = now;184}185186/*187correct pressure for barometric height188With thanks to:189https://github.com/PX4/Firmware/blob/master/Tools/models/sdp3x_pitot_model.py190*/191float AP_Airspeed_SDP3X::_correct_pressure(float press)192{193float sign = 1.0f;194195// fix for tube order196AP_Airspeed::pitot_tube_order tube_order = get_tube_order();197switch (tube_order) {198case AP_Airspeed::PITOT_TUBE_ORDER_NEGATIVE:199press = -press;200sign = -1.0f;201break;202case AP_Airspeed::PITOT_TUBE_ORDER_POSITIVE:203break;204case AP_Airspeed::PITOT_TUBE_ORDER_AUTO:205default:206if (press < 0.0f) {207sign = -1.0f;208press = -press;209}210break;211}212213if (press <= 0.0f) {214return 0.0f;215}216217AP_Baro *baro = AP_Baro::get_singleton();218219float baro_pressure;220if (baro == nullptr || baro->num_instances() == 0) {221// with no baro assume sea level222baro_pressure = SSL_AIR_PRESSURE;223} else {224baro_pressure = baro->get_pressure();225}226227float temperature;228if (!get_temperature(temperature)) {229// assume 25C if no temperature230temperature = 25;231}232233float rho_air = baro_pressure / (ISA_GAS_CONSTANT * C_TO_KELVIN(temperature));234if (!is_positive(rho_air)) {235// bad pressure236return press;237}238239/*240the constants in the code below come from a calibrated test of241the drotek pitot tube by Sensiron. They are specific to the droktek pitot tube242243At 25m/s, the rough proportions of each pressure correction are:244245- dp_pitot: 5%246- press_correction: 14%247- press: 81%248249dp_tube has been removed from the Sensiron model as it is250insignificant (less than 0.02% over the supported speed ranges)251*/252253// flow through sensor254float flow_SDP3X = (300.805f - 300.878f / (0.00344205f * (float)powf(press, 0.68698f) + 1.0f)) * 1.29f / rho_air;255if (flow_SDP3X < 0.0f) {256flow_SDP3X = 0.0f;257}258259// differential pressure through pitot tube260float dp_pitot = 28557670.0f * (1.0f - 1.0f / (1.0f + (float)powf((flow_SDP3X / 5027611.0f), 1.227924f)));261262// uncorrected pressure263float press_uncorrected = (press + dp_pitot) / SSL_AIR_DENSITY;264265// correction for speed at pitot-tube tip due to flow through sensor266float dv = 0.0331582f * flow_SDP3X;267268// airspeed ratio269float ratio = get_airspeed_ratio();270if (!is_positive(ratio)) {271// cope with AP_Periph where ratio is 0272ratio = 2.0;273}274275// calculate equivalent pressure correction. This formula comes276// from turning the dv correction above into an equivalent277// pressure correction. We need to do this so the airspeed ratio278// calibrator can work, as it operates on pressure values279float press_correction = sq(sqrtf(press_uncorrected*ratio)+dv)/ratio - press_uncorrected;280281return (press_uncorrected + press_correction) * sign;282}283284// return the current differential_pressure in Pascal285bool AP_Airspeed_SDP3X::get_differential_pressure(float &pressure)286{287WITH_SEMAPHORE(sem);288289if (AP_HAL::millis() - _last_sample_time_ms > 100) {290return false;291}292293if (_press_count > 0) {294_press = _press_sum / _press_count;295_press_count = 0;296_press_sum = 0;297}298299pressure = _correct_pressure(_press);300return true;301}302303// return the current temperature in degrees C, if available304bool AP_Airspeed_SDP3X::get_temperature(float &temperature)305{306WITH_SEMAPHORE(sem);307308if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {309return false;310}311312if (_temp_count > 0) {313_temp = _temp_sum / _temp_count;314_temp_count = 0;315_temp_sum = 0;316}317318temperature = _temp;319return true;320}321322/*323check CRC for a set of bytes324*/325bool AP_Airspeed_SDP3X::_crc(const uint8_t data[], uint8_t size, uint8_t checksum)326{327uint8_t crc_value = 0xff;328329// calculate 8-bit checksum with polynomial 0x31 (x^8 + x^5 + x^4 + 1)330for (uint8_t i = 0; i < size; i++) {331crc_value ^= data[i];332for (uint8_t bit = 8; bit > 0; --bit) {333if (crc_value & 0x80) {334crc_value = (crc_value << 1) ^ 0x31;335} else {336crc_value = (crc_value << 1);337}338}339}340// verify checksum341return (crc_value == checksum);342}343344#endif // AP_AIRSPEED_SDP3X_ENABLED345346347