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_MS4525.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 MS4525D0 sensor17*/18#include "AP_Airspeed_MS4525.h"1920#if AP_AIRSPEED_MS4525_ENABLED2122#include <AP_Common/AP_Common.h>23#include <AP_HAL/AP_HAL.h>24#include <AP_HAL/I2CDevice.h>25#include <AP_Math/AP_Math.h>26#include <GCS_MAVLink/GCS.h>27#include <stdio.h>28#include <utility>2930extern const AP_HAL::HAL &hal;3132#define MS4525D0_I2C_ADDR1 0x2833#define MS4525D0_I2C_ADDR2 0x3634#define MS4525D0_I2C_ADDR3 0x463536AP_Airspeed_MS4525::AP_Airspeed_MS4525(AP_Airspeed &_frontend, uint8_t _instance) :37AP_Airspeed_Backend(_frontend, _instance)38{39}4041// probe for a sensor42bool AP_Airspeed_MS4525::probe(uint8_t bus, uint8_t address)43{44_dev = hal.i2c_mgr->get_device(bus, address);45if (!_dev) {46return false;47}48WITH_SEMAPHORE(_dev->get_semaphore());4950// lots of retries during probe51_dev->set_retries(10);5253_measure();54hal.scheduler->delay(10);55_collect();5657return _last_sample_time_ms != 0;58}5960// probe and initialise the sensor61bool AP_Airspeed_MS4525::init()62{63static const uint8_t addresses[] = { MS4525D0_I2C_ADDR1, MS4525D0_I2C_ADDR2, MS4525D0_I2C_ADDR3 };64if (bus_is_configured()) {65// the user has configured a specific bus66for (uint8_t addr : addresses) {67if (probe(get_bus(), addr)) {68goto found_sensor;69}70}71} else {72// if bus is not configured then fall back to the old73// behaviour of probing all buses, external first74FOREACH_I2C_EXTERNAL(bus) {75for (uint8_t addr : addresses) {76if (probe(bus, addr)) {77goto found_sensor;78}79}80}81FOREACH_I2C_INTERNAL(bus) {82for (uint8_t addr : addresses) {83if (probe(bus, addr)) {84goto found_sensor;85}86}87}88}8990GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MS4525[%u]: no sensor found", get_instance());91return false;9293found_sensor:94_dev->set_device_type(uint8_t(DevType::MS4525));95set_bus_id(_dev->get_bus_id());9697GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS4525[%u]: Found bus %u addr 0x%02x", get_instance(), _dev->bus_num(), _dev->get_bus_address());9899// drop to 2 retries for runtime100_dev->set_retries(2);101102_dev->register_periodic_callback(20000,103FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS4525::_timer, void));104return true;105}106107// start a measurement108void AP_Airspeed_MS4525::_measure()109{110_measurement_started_ms = 0;111uint8_t cmd = 0;112if (_dev->transfer(&cmd, 1, nullptr, 0)) {113_measurement_started_ms = AP_HAL::millis();114}115}116117/*118this equation is an inversion of the equation in the119pressure transfer function figure on page 4 of the datasheet120121We negate the result so that positive differential pressures122are generated when the bottom port is used as the static123port on the pitot and top port is used as the dynamic port124*/125float AP_Airspeed_MS4525::_get_pressure(int16_t dp_raw) const126{127const float P_max = get_psi_range();128const float P_min = - P_max;129const float PSI_to_Pa = 6894.757f;130131float diff_press_PSI = -((dp_raw - 0.1f*16383) * (P_max-P_min)/(0.8f*16383) + P_min);132float press = diff_press_PSI * PSI_to_Pa;133return press;134}135136/*137convert raw temperature to temperature in degrees C138*/139float AP_Airspeed_MS4525::_get_temperature(int16_t dT_raw) const140{141float temp = ((200.0f * dT_raw) / 2047) - 50;142return temp;143}144145// read the values from the sensor146void AP_Airspeed_MS4525::_collect()147{148uint8_t data[4];149uint8_t data2[4];150151_measurement_started_ms = 0;152153if (!_dev->transfer(nullptr, 0, data, sizeof(data))) {154return;155}156// reread the data, so we can attempt to detect bad inputs157if (!_dev->transfer(nullptr, 0, data2, sizeof(data2))) {158return;159}160161uint8_t status = (data[0] & 0xC0) >> 6;162// only check the status on the first read, the second read is expected to be stale163if (status == 2 || status == 3) {164return;165}166167int16_t dp_raw, dT_raw;168dp_raw = (data[0] << 8) + data[1];169dp_raw = 0x3FFF & dp_raw;170dT_raw = (data[2] << 8) + data[3];171dT_raw = (0xFFE0 & dT_raw) >> 5;172173int16_t dp_raw2, dT_raw2;174dp_raw2 = (data2[0] << 8) + data2[1];175dp_raw2 = 0x3FFF & dp_raw2;176dT_raw2 = (data2[2] << 8) + data2[3];177dT_raw2 = (0xFFE0 & dT_raw2) >> 5;178179// reject any values that are the absolute minimum or maximums these180// can happen due to gnd lifts or communication errors on the bus181if (dp_raw == 0x3FFF || dp_raw == 0 || dT_raw == 0x7FF || dT_raw == 0 ||182dp_raw2 == 0x3FFF || dp_raw2 == 0 || dT_raw2 == 0x7FF || dT_raw2 == 0) {183return;184}185186// reject any double reads where the value has shifted in the upper more than187// 0xFF188if (abs(dp_raw - dp_raw2) > 0xFF || abs(dT_raw - dT_raw2) > 0xFF) {189return;190}191192float press = _get_pressure(dp_raw);193float press2 = _get_pressure(dp_raw2);194float temp = _get_temperature(dT_raw);195float temp2 = _get_temperature(dT_raw2);196197if (!disable_voltage_correction()) {198_voltage_correction(press, temp);199_voltage_correction(press2, temp2);200}201202WITH_SEMAPHORE(sem);203204_press_sum += press + press2;205_temp_sum += temp + temp2;206_press_count += 2;207_temp_count += 2;208209_last_sample_time_ms = AP_HAL::millis();210}211212/**213correct for 5V rail voltage if the system_power ORB topic is214available215216See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of217offset versus voltage for 3 sensors218*/219void AP_Airspeed_MS4525::_voltage_correction(float &diff_press_pa, float &temperature)220{221const float slope = 65.0f;222const float temp_slope = 0.887f;223224/*225apply a piecewise linear correction within range given by above graph226*/227float voltage_diff = hal.analogin->board_voltage() - 5.0f;228229voltage_diff = constrain_float(voltage_diff, -0.7f, 0.5f);230231diff_press_pa -= voltage_diff * slope;232temperature -= voltage_diff * temp_slope;233}234235// 50Hz timer236void AP_Airspeed_MS4525::_timer()237{238if (_measurement_started_ms == 0) {239_measure();240return;241}242if ((AP_HAL::millis() - _measurement_started_ms) > 10) {243_collect();244// start a new measurement245_measure();246}247}248249// return the current differential_pressure in Pascal250bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)251{252WITH_SEMAPHORE(sem);253254if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {255return false;256}257258if (_press_count > 0) {259_pressure = _press_sum / _press_count;260_press_count = 0;261_press_sum = 0;262}263264pressure = _pressure;265return true;266}267268// return the current temperature in degrees C, if available269bool AP_Airspeed_MS4525::get_temperature(float &temperature)270{271WITH_SEMAPHORE(sem);272273if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {274return false;275}276277if (_temp_count > 0) {278_temperature = _temp_sum / _temp_count;279_temp_count = 0;280_temp_sum = 0;281}282283temperature = _temperature;284return true;285}286287#endif // AP_AIRSPEED_MS4525_ENABLED288289290