Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp
9608 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 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 0x463536// probe for a sensor37bool AP_Airspeed_MS4525::probe(uint8_t bus, uint8_t address)38{39_dev = hal.i2c_mgr->get_device_ptr(bus, address);40if (!_dev) {41return false;42}43WITH_SEMAPHORE(_dev->get_semaphore());4445// lots of retries during probe46_dev->set_retries(10);4748_measure();49hal.scheduler->delay(10);50_collect();5152return _last_sample_time_ms != 0;53}5455// probe and initialise the sensor56bool AP_Airspeed_MS4525::init()57{58static const uint8_t addresses[] = { MS4525D0_I2C_ADDR1, MS4525D0_I2C_ADDR2, MS4525D0_I2C_ADDR3 };59if (bus_is_configured()) {60// the user has configured a specific bus61for (uint8_t addr : addresses) {62if (probe(get_bus(), addr)) {63goto found_sensor;64}65}66} else {67// if bus is not configured then fall back to the old68// behaviour of probing all buses, external first69FOREACH_I2C_EXTERNAL(bus) {70for (uint8_t addr : addresses) {71if (probe(bus, addr)) {72goto found_sensor;73}74}75}76FOREACH_I2C_INTERNAL(bus) {77for (uint8_t addr : addresses) {78if (probe(bus, addr)) {79goto found_sensor;80}81}82}83}8485GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MS4525[%u]: no sensor found", get_instance());86return false;8788found_sensor:89_dev->set_device_type(uint8_t(DevType::MS4525));90set_bus_id(_dev->get_bus_id());9192GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS4525[%u]: Found bus %u addr 0x%02x", get_instance(), _dev->bus_num(), _dev->get_bus_address());9394// drop to 2 retries for runtime95_dev->set_retries(2);9697_dev->register_periodic_callback(20000,98FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS4525::_timer, void));99return true;100}101102// start a measurement103void AP_Airspeed_MS4525::_measure()104{105_measurement_started_ms = 0;106uint8_t cmd = 0;107if (_dev->transfer(&cmd, 1, nullptr, 0)) {108_measurement_started_ms = AP_HAL::millis();109}110}111112/*113this equation is an inversion of the equation in the114pressure transfer function figure on page 4 of the datasheet115116We negate the result so that positive differential pressures117are generated when the bottom port is used as the static118port on the pitot and top port is used as the dynamic port119*/120float AP_Airspeed_MS4525::_get_pressure(int16_t dp_raw) const121{122const float P_max = get_psi_range();123const float P_min = - P_max;124const float PSI_to_Pa = 6894.757f;125126float diff_press_PSI = -((dp_raw - 0.1f*16383) * (P_max-P_min)/(0.8f*16383) + P_min);127float press = diff_press_PSI * PSI_to_Pa;128return press;129}130131/*132convert raw temperature to temperature in degrees C133*/134float AP_Airspeed_MS4525::_get_temperature(int16_t dT_raw) const135{136float temp = ((200.0f * dT_raw) / 2047) - 50;137return temp;138}139140// read the values from the sensor141void AP_Airspeed_MS4525::_collect()142{143uint8_t data[4];144uint8_t data2[4];145146_measurement_started_ms = 0;147148if (!_dev->transfer(nullptr, 0, data, sizeof(data))) {149return;150}151// reread the data, so we can attempt to detect bad inputs152if (!_dev->transfer(nullptr, 0, data2, sizeof(data2))) {153return;154}155156uint8_t status = (data[0] & 0xC0) >> 6;157// only check the status on the first read, the second read is expected to be stale158if (status == 2 || status == 3) {159return;160}161162int16_t dp_raw, dT_raw;163dp_raw = (data[0] << 8) + data[1];164dp_raw = 0x3FFF & dp_raw;165dT_raw = (data[2] << 8) + data[3];166dT_raw = (0xFFE0 & dT_raw) >> 5;167168int16_t dp_raw2, dT_raw2;169dp_raw2 = (data2[0] << 8) + data2[1];170dp_raw2 = 0x3FFF & dp_raw2;171dT_raw2 = (data2[2] << 8) + data2[3];172dT_raw2 = (0xFFE0 & dT_raw2) >> 5;173174// reject any values that are the absolute minimum or maximums these175// can happen due to gnd lifts or communication errors on the bus176if (dp_raw == 0x3FFF || dp_raw == 0 || dT_raw == 0x7FF || dT_raw == 0 ||177dp_raw2 == 0x3FFF || dp_raw2 == 0 || dT_raw2 == 0x7FF || dT_raw2 == 0) {178return;179}180181// reject any double reads where the value has shifted in the upper more than182// 0xFF183if (abs(dp_raw - dp_raw2) > 0xFF || abs(dT_raw - dT_raw2) > 0xFF) {184return;185}186187float press = _get_pressure(dp_raw);188float press2 = _get_pressure(dp_raw2);189float temp = _get_temperature(dT_raw);190float temp2 = _get_temperature(dT_raw2);191192if (!disable_voltage_correction()) {193_voltage_correction(press, temp);194_voltage_correction(press2, temp2);195}196197WITH_SEMAPHORE(sem);198199_press_sum += press + press2;200_temp_sum += temp + temp2;201_press_count += 2;202_temp_count += 2;203204_last_sample_time_ms = AP_HAL::millis();205}206207/**208correct for 5V rail voltage if the system_power ORB topic is209available210211See http://uav.tridgell.net/MS4525/MS4525-offset.png for a graph of212offset versus voltage for 3 sensors213*/214void AP_Airspeed_MS4525::_voltage_correction(float &diff_press_pa, float &temperature)215{216const float slope = 65.0f;217const float temp_slope = 0.887f;218219/*220apply a piecewise linear correction within range given by above graph221*/222float voltage_diff = hal.analogin->board_voltage() - 5.0f;223224voltage_diff = constrain_float(voltage_diff, -0.7f, 0.5f);225226diff_press_pa -= voltage_diff * slope;227temperature -= voltage_diff * temp_slope;228}229230// 50Hz timer231void AP_Airspeed_MS4525::_timer()232{233if (_measurement_started_ms == 0) {234_measure();235return;236}237if ((AP_HAL::millis() - _measurement_started_ms) > 10) {238_collect();239// start a new measurement240_measure();241}242}243244// return the current differential_pressure in Pascal245bool AP_Airspeed_MS4525::get_differential_pressure(float &pressure)246{247WITH_SEMAPHORE(sem);248249if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {250return false;251}252253if (_press_count > 0) {254_pressure = _press_sum / _press_count;255_press_count = 0;256_press_sum = 0;257}258259pressure = _pressure;260return true;261}262263// return the current temperature in degrees C, if available264bool AP_Airspeed_MS4525::get_temperature(float &temperature)265{266WITH_SEMAPHORE(sem);267268if ((AP_HAL::millis() - _last_sample_time_ms) > 100) {269return false;270}271272if (_temp_count > 0) {273_temperature = _temp_sum / _temp_count;274_temp_count = 0;275_temp_sum = 0;276}277278temperature = _temperature;279return true;280}281282#endif // AP_AIRSPEED_MS4525_ENABLED283284285