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_MS5525.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 MS5525D0 sensor17*/18#include "AP_Airspeed_MS5525.h"1920#if AP_AIRSPEED_MS5525_ENABLED2122#include <stdio.h>23#include <utility>2425#include <AP_Common/AP_Common.h>26#include <AP_HAL/AP_HAL.h>27#include <AP_HAL/I2CDevice.h>28#include <AP_HAL/utility/sparse-endian.h>29#include <AP_Math/AP_Math.h>30#include <AP_Math/crc.h>31#include <GCS_MAVLink/GCS.h>3233extern const AP_HAL::HAL &hal;3435#define MS5525D0_I2C_ADDR_1 0x7636#define MS5525D0_I2C_ADDR_2 0x773738#define REG_RESET 0x1E39#define REG_CONVERT_D1_OSR_256 0x4040#define REG_CONVERT_D1_OSR_512 0x4241#define REG_CONVERT_D1_OSR_1024 0x4442#define REG_CONVERT_D1_OSR_2048 0x4643#define REG_CONVERT_D1_OSR_4096 0x4844#define REG_CONVERT_D2_OSR_256 0x5045#define REG_CONVERT_D2_OSR_512 0x5246#define REG_CONVERT_D2_OSR_1024 0x5447#define REG_CONVERT_D2_OSR_2048 0x5648#define REG_CONVERT_D2_OSR_4096 0x5849#define REG_ADC_READ 0x0050#define REG_PROM_BASE 0xA05152// go for 1024 oversampling. This should be fast enough to reduce53// noise but low enough to keep self-heating small54#define REG_CONVERT_PRESSURE REG_CONVERT_D1_OSR_102455#define REG_CONVERT_TEMPERATURE REG_CONVERT_D2_OSR_10245657AP_Airspeed_MS5525::AP_Airspeed_MS5525(AP_Airspeed &_frontend, uint8_t _instance, MS5525_ADDR address) :58AP_Airspeed_Backend(_frontend, _instance)59{60_address = address;61}6263// probe and initialise the sensor64bool AP_Airspeed_MS5525::init()65{66const uint8_t addresses[] = { MS5525D0_I2C_ADDR_1, MS5525D0_I2C_ADDR_2 };67bool found = false;68for (uint8_t i=0; i<ARRAY_SIZE(addresses); i++) {69if (_address != MS5525_ADDR_AUTO && i != (uint8_t)_address) {70continue;71}72dev = hal.i2c_mgr->get_device(get_bus(), addresses[i]);73if (!dev) {74continue;75}76WITH_SEMAPHORE(dev->get_semaphore());7778// lots of retries during probe79dev->set_retries(5);8081found = read_prom();8283if (found) {84GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS5525[%u]: Found on bus %u addr 0x%02x", get_instance(), get_bus(), addresses[i]);85break;86}87}88if (!found) {89GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MS5525[%u]: no sensor found", get_instance());90return false;91}9293// Send a command to read temperature first94WITH_SEMAPHORE(dev->get_semaphore());95uint8_t reg = REG_CONVERT_TEMPERATURE;96dev->transfer(®, 1, nullptr, 0);97state = 0;98command_send_us = AP_HAL::micros();99100dev->set_device_type(uint8_t(DevType::MS5525));101set_bus_id(dev->get_bus_id());102103// drop to 2 retries for runtime104dev->set_retries(2);105106// read at 80Hz107dev->register_periodic_callback(1000000UL/80U,108FUNCTOR_BIND_MEMBER(&AP_Airspeed_MS5525::timer, void));109return true;110}111112113/**114* CRC used by MS pressure devices115*/116uint16_t AP_Airspeed_MS5525::crc4_prom(void)117{118return crc_crc4(prom);119}120121bool AP_Airspeed_MS5525::read_prom(void)122{123// reset the chip to ensure it has correct prom values loaded124uint8_t reg = REG_RESET;125if (!dev->transfer(®, 1, nullptr, 0)) {126return false;127}128hal.scheduler->delay(5);129130bool all_zero = true;131for (uint8_t i = 0; i < 8; i++) {132be16_t val;133if (!dev->read_registers(REG_PROM_BASE+i*2, (uint8_t *) &val,134sizeof(uint16_t))) {135return false;136}137prom[i] = be16toh(val);138if (prom[i] != 0) {139all_zero = false;140}141}142143if (all_zero) {144return false;145}146147/* save the read crc */148const uint16_t crc_read = prom[7] & 0xf;149150/* remove CRC byte */151prom[7] &= 0xff00;152153uint16_t crc_calc = crc4_prom();154if (crc_read != crc_calc) {155printf("MS5525: CRC mismatch 0x%04x 0x%04x\n", crc_read, crc_calc);156}157return crc_read == crc_calc;158}159160161/*162read from the ADC163*/164int32_t AP_Airspeed_MS5525::read_adc()165{166uint8_t val[3];167if (!dev->read_registers(REG_ADC_READ, val, 3)) {168return 0;169}170return (val[0] << 16) | (val[1] << 8) | val[2];171}172173/*174calculate pressure and temperature175*/176void AP_Airspeed_MS5525::calculate(void)177{178// table for the 001DS part, 1PSI range179const uint8_t Q1 = 15;180const uint8_t Q2 = 17;181const uint8_t Q3 = 7;182const uint8_t Q4 = 5;183const uint8_t Q5 = 7;184const uint8_t Q6 = 21;185186float dT = float(D2) - int64_t(prom[5]) * (1L<<Q5);187float TEMP = 2000 + (dT*int64_t(prom[6]))/(1L<<Q6);188float OFF = int64_t(prom[2])*(1L<<Q2) + (int64_t(prom[4])*dT)/(1L<<Q4);189float SENS = int64_t(prom[1])*(1L<<Q1) + (int64_t(prom[3])*dT)/(1L<<Q3);190float P = (float(D1)*SENS/(1L<<21)-OFF)/(1L<<15);191const float PSI_to_Pa = 6894.757f;192float P_Pa = PSI_to_Pa * 1.0e-4 * P;193float Temp_C = TEMP * 0.01;194195#if 0196static uint16_t counter;197if (counter++ == 100) {198printf("P=%.6f T=%.2f D1=%d D2=%d\n", P_Pa, Temp_C, D1, D2);199counter=0;200}201#endif202203WITH_SEMAPHORE(sem);204205pressure_sum += P_Pa;206temperature_sum += Temp_C;207press_count++;208temp_count++;209last_sample_time_ms = AP_HAL::millis();210}211212// 80Hz timer213void AP_Airspeed_MS5525::timer()214{215if (AP_HAL::micros() - command_send_us < 10000) {216// we should avoid trying to read the ADC too soon after217// sending the command218return;219}220221uint32_t adc_val = read_adc();222223if (adc_val == 0) {224// we have either done a read too soon after sending the225// request or we have tried to read the same sample twice. We226// re-send the command now as we don't know what state the227// sensor is in, and we do want to trigger it sending a value,228// which we will discard229if (dev->transfer(&cmd_sent, 1, nullptr, 0)) {230command_send_us = AP_HAL::micros();231}232// when we get adc_val == 0 then then both the current value and233// the next value we read from the sensor are invalid234ignore_next = true;235return;236}237238/*239* If read fails, re-initiate a read command for current state or we are240* stuck241*/242if (!ignore_next) {243if (cmd_sent == REG_CONVERT_TEMPERATURE) {244D2 = adc_val;245} else if (cmd_sent == REG_CONVERT_PRESSURE) {246D1 = adc_val;247calculate();248}249}250251ignore_next = false;252253cmd_sent = (state == 0) ? REG_CONVERT_TEMPERATURE : REG_CONVERT_PRESSURE;254if (!dev->transfer(&cmd_sent, 1, nullptr, 0)) {255// we don't know for sure what state the sensor is in when we256// fail to send the command, so ignore the next response257ignore_next = true;258return;259}260command_send_us = AP_HAL::micros();261262state = (state + 1) % 5;263}264265// return the current differential_pressure in Pascal266bool AP_Airspeed_MS5525::get_differential_pressure(float &_pressure)267{268WITH_SEMAPHORE(sem);269270if ((AP_HAL::millis() - last_sample_time_ms) > 100) {271return false;272}273274if (press_count > 0) {275pressure = pressure_sum / press_count;276press_count = 0;277pressure_sum = 0;278}279_pressure = pressure;280281return true;282}283284// return the current temperature in degrees C, if available285bool AP_Airspeed_MS5525::get_temperature(float &_temperature)286{287WITH_SEMAPHORE(sem);288289if ((AP_HAL::millis() - last_sample_time_ms) > 100) {290return false;291}292293if (temp_count > 0) {294temperature = temperature_sum / temp_count;295temp_count = 0;296temperature_sum = 0;297}298299_temperature = temperature;300return true;301}302303#endif // AP_AIRSPEED_MS5525_ENABLED304305306