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_Baro/AP_Baro_MS5611.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*/14#include "AP_Baro_MS5611.h"1516#if AP_BARO_MS56XX_ENABLED1718#include <utility>19#include <stdio.h>2021#include <AP_Math/AP_Math.h>22#include <AP_Math/crc.h>23#include <AP_BoardConfig/AP_BoardConfig.h>2425extern const AP_HAL::HAL &hal;2627static const uint8_t CMD_MS56XX_RESET = 0x1E;28static const uint8_t CMD_MS56XX_READ_ADC = 0x00;2930/* PROM start address */31static const uint8_t CMD_MS56XX_PROM = 0xA0;3233/* write to one of these addresses to start pressure conversion */34#define ADDR_CMD_CONVERT_D1_OSR256 0x4035#define ADDR_CMD_CONVERT_D1_OSR512 0x4236#define ADDR_CMD_CONVERT_D1_OSR1024 0x4437#define ADDR_CMD_CONVERT_D1_OSR2048 0x4638#define ADDR_CMD_CONVERT_D1_OSR4096 0x483940/* write to one of these addresses to start temperature conversion */41#define ADDR_CMD_CONVERT_D2_OSR256 0x5042#define ADDR_CMD_CONVERT_D2_OSR512 0x5243#define ADDR_CMD_CONVERT_D2_OSR1024 0x5444#define ADDR_CMD_CONVERT_D2_OSR2048 0x5645#define ADDR_CMD_CONVERT_D2_OSR4096 0x584647/*48use an OSR of 1024 to reduce the self-heating effect of the49sensor. Information from MS tells us that some individual sensors50are quite sensitive to this effect and that reducing the OSR can51make a big difference52*/53static const uint8_t ADDR_CMD_CONVERT_PRESSURE = ADDR_CMD_CONVERT_D1_OSR1024;54static const uint8_t ADDR_CMD_CONVERT_TEMPERATURE = ADDR_CMD_CONVERT_D2_OSR1024;5556/*57constructor58*/59AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, enum MS56XX_TYPE ms56xx_type)60: AP_Baro_Backend(baro)61, _dev(std::move(dev))62, _ms56xx_type(ms56xx_type)63{64}6566AP_Baro_Backend *AP_Baro_MS56XX::probe(AP_Baro &baro,67AP_HAL::OwnPtr<AP_HAL::Device> dev,68enum MS56XX_TYPE ms56xx_type)69{70if (!dev) {71return nullptr;72}73AP_Baro_MS56XX *sensor = NEW_NOTHROW AP_Baro_MS56XX(baro, std::move(dev), ms56xx_type);74if (!sensor || !sensor->_init()) {75delete sensor;76return nullptr;77}78return sensor;79}8081bool AP_Baro_MS56XX::_init()82{83if (!_dev) {84return false;85}8687_dev->get_semaphore()->take_blocking();8889// high retries for init90_dev->set_retries(10);9192uint16_t prom[8];93bool prom_read_ok = false;9495_dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);96hal.scheduler->delay(4);9798/*99cope with vendors substituting a MS5607 for a MS5611 on Pixhawk1 'clone' boards100*/101if (_ms56xx_type == BARO_MS5611 && _frontend.option_enabled(AP_Baro::Options::TreatMS5611AsMS5607)) {102_ms56xx_type = BARO_MS5607;103}104105const char *name = "MS5611";106switch (_ms56xx_type) {107case BARO_MS5607:108name = "MS5607";109FALLTHROUGH;110case BARO_MS5611:111prom_read_ok = _read_prom_5611(prom);112break;113case BARO_MS5837:114name = "MS5837";115prom_read_ok = _read_prom_5637(prom);116break;117case BARO_MS5637:118name = "MS5637";119prom_read_ok = _read_prom_5637(prom);120break;121}122123if (!prom_read_ok) {124_dev->get_semaphore()->give();125return false;126}127128printf("%s found on bus %u address 0x%02x\n", name, _dev->bus_num(), _dev->get_bus_address());129130// Save factory calibration coefficients131_cal_reg.c1 = prom[1];132_cal_reg.c2 = prom[2];133_cal_reg.c3 = prom[3];134_cal_reg.c4 = prom[4];135_cal_reg.c5 = prom[5];136_cal_reg.c6 = prom[6];137138// Send a command to read temperature first139_dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0);140_state = 0;141142memset(&_accum, 0, sizeof(_accum));143144_instance = _frontend.register_sensor();145146enum DevTypes devtype = DEVTYPE_BARO_MS5611;147switch (_ms56xx_type) {148case BARO_MS5607:149devtype = DEVTYPE_BARO_MS5607;150break;151case BARO_MS5611:152devtype = DEVTYPE_BARO_MS5611;153break;154case BARO_MS5837:155devtype = DEVTYPE_BARO_MS5837;156break;157case BARO_MS5637:158devtype = DEVTYPE_BARO_MS5637;159break;160}161162_dev->set_device_type(devtype);163set_bus_id(_instance, _dev->get_bus_id());164165if (_ms56xx_type == BARO_MS5837) {166_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);167}168169// lower retries for run170_dev->set_retries(3);171172_dev->get_semaphore()->give();173174/* Request 100Hz update */175_dev->register_periodic_callback(10 * AP_USEC_PER_MSEC,176FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void));177return true;178}179180uint16_t AP_Baro_MS56XX::_read_prom_word(uint8_t word)181{182const uint8_t reg = CMD_MS56XX_PROM + (word << 1);183uint8_t val[2];184if (!_dev->transfer(®, 1, val, sizeof(val))) {185return 0;186}187return (val[0] << 8) | val[1];188}189190uint32_t AP_Baro_MS56XX::_read_adc()191{192uint8_t val[3];193if (!_dev->transfer(&CMD_MS56XX_READ_ADC, 1, val, sizeof(val))) {194return 0;195}196return (val[0] << 16) | (val[1] << 8) | val[2];197}198199bool AP_Baro_MS56XX::_read_prom_5611(uint16_t prom[8])200{201/*202* MS5611-01BA datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5611-01BA203* contains a PROM memory with 128-Bit. A 4-bit CRC has been implemented204* to check the data validity in memory."205*206* CRC field must me removed for CRC-4 calculation.207*/208bool all_zero = true;209for (uint8_t i = 0; i < 8; i++) {210prom[i] = _read_prom_word(i);211if (prom[i] != 0) {212all_zero = false;213}214}215216if (all_zero) {217return false;218}219220/* save the read crc */221const uint16_t crc_read = prom[7] & 0xf;222223/* remove CRC byte */224prom[7] &= 0xff00;225226return crc_read == crc_crc4(prom);227}228229bool AP_Baro_MS56XX::_read_prom_5637(uint16_t prom[8])230{231/*232* MS5637-02BA03 datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5637233* contains a PROM memory with 112-Bit. A 4-bit CRC has been implemented234* to check the data validity in memory."235*236* 8th PROM word must be zeroed and CRC field removed for CRC-4237* calculation.238*/239bool all_zero = true;240for (uint8_t i = 0; i < 7; i++) {241prom[i] = _read_prom_word(i);242if (prom[i] != 0) {243all_zero = false;244}245}246247if (all_zero) {248return false;249}250251prom[7] = 0;252253/* save the read crc */254const uint16_t crc_read = (prom[0] & 0xf000) >> 12;255256/* remove CRC byte */257prom[0] &= ~0xf000;258259return crc_read == crc_crc4(prom);260}261262/*263* Read the sensor with a state machine264* We read one time temperature (state=0) and then 4 times pressure (states 1-4)265*266* Temperature is used to calculate the compensated pressure and doesn't vary267* as fast as pressure. Hence we reuse the same temperature for 4 samples of268* pressure.269*/270void AP_Baro_MS56XX::_timer(void)271{272uint8_t next_cmd;273uint8_t next_state;274uint32_t adc_val = _read_adc();275276/*277* If read fails, re-initiate a read command for current state or we are278* stuck279*/280if (adc_val == 0) {281next_state = _state;282} else {283next_state = (_state + 1) % 5;284}285286next_cmd = next_state == 0 ? ADDR_CMD_CONVERT_TEMPERATURE287: ADDR_CMD_CONVERT_PRESSURE;288if (!_dev->transfer(&next_cmd, 1, nullptr, 0)) {289return;290}291292/* if we had a failed read we are all done */293if (adc_val == 0 || adc_val == 0xFFFFFF) {294// a failed read can mean the next returned value will be295// corrupt, we must discard it. This copes with MISO being296// pulled either high or low297_discard_next = true;298return;299}300301if (_discard_next) {302_discard_next = false;303_state = next_state;304return;305}306307WITH_SEMAPHORE(_sem);308309if (_state == 0) {310_update_and_wrap_accumulator(&_accum.s_D2, adc_val,311&_accum.d2_count, 32);312} else if (pressure_ok(adc_val)) {313_update_and_wrap_accumulator(&_accum.s_D1, adc_val,314&_accum.d1_count, 128);315}316317_state = next_state;318}319320void AP_Baro_MS56XX::_update_and_wrap_accumulator(uint32_t *accum, uint32_t val,321uint8_t *count, uint8_t max_count)322{323*accum += val;324*count += 1;325if (*count == max_count) {326*count = max_count / 2;327*accum = *accum / 2;328}329}330331void AP_Baro_MS56XX::update()332{333uint32_t sD1, sD2;334uint8_t d1count, d2count;335336{337WITH_SEMAPHORE(_sem);338339if (_accum.d1_count == 0) {340return;341}342343sD1 = _accum.s_D1;344sD2 = _accum.s_D2;345d1count = _accum.d1_count;346d2count = _accum.d2_count;347memset(&_accum, 0, sizeof(_accum));348}349350if (d1count != 0) {351_D1 = ((float)sD1) / d1count;352}353if (d2count != 0) {354_D2 = ((float)sD2) / d2count;355}356357switch (_ms56xx_type) {358case BARO_MS5607:359_calculate_5607();360break;361case BARO_MS5611:362_calculate_5611();363break;364case BARO_MS5637:365_calculate_5637();366break;367case BARO_MS5837:368_calculate_5837();369}370}371372// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).373void AP_Baro_MS56XX::_calculate_5611()374{375float dT;376float TEMP;377float OFF;378float SENS;379380// we do the calculations using floating point allows us to take advantage381// of the averaging of D1 and D1 over multiple samples, giving us more382// precision383dT = _D2-(((uint32_t)_cal_reg.c5)<<8);384TEMP = (dT * _cal_reg.c6)/8388608;385OFF = _cal_reg.c2 * 65536.0f + (_cal_reg.c4 * dT) / 128;386SENS = _cal_reg.c1 * 32768.0f + (_cal_reg.c3 * dT) / 256;387388TEMP += 2000;389390if (TEMP < 2000) {391// second order temperature compensation when under 20 degrees C392float T2 = (dT*dT) / 0x80000000;393float Aux = sq(TEMP-2000.0);394float OFF2 = 2.5f*Aux;395float SENS2 = 1.25f*Aux;396if (TEMP < -1500) {397// extra compensation for temperatures below -15C398OFF2 += 7 * sq(TEMP+1500);399SENS2 += sq(TEMP+1500) * 11.0*0.5;400}401TEMP = TEMP - T2;402OFF = OFF - OFF2;403SENS = SENS - SENS2;404}405406407float pressure = (_D1*SENS/2097152 - OFF)/32768;408float temperature = TEMP * 0.01f;409_copy_to_frontend(_instance, pressure, temperature);410}411412// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).413void AP_Baro_MS56XX::_calculate_5607()414{415float dT;416float TEMP;417float OFF;418float SENS;419420// we do the calculations using floating point allows us to take advantage421// of the averaging of D1 and D1 over multiple samples, giving us more422// precision423dT = _D2-(((uint32_t)_cal_reg.c5)<<8);424TEMP = (dT * _cal_reg.c6)/8388608;425OFF = _cal_reg.c2 * 131072.0f + (_cal_reg.c4 * dT) / 64;426SENS = _cal_reg.c1 * 65536.0f + (_cal_reg.c3 * dT) / 128;427428TEMP += 2000;429430if (TEMP < 2000) {431// second order temperature compensation when under 20 degrees C432float T2 = (dT*dT) / 0x80000000;433float Aux = sq(TEMP-2000);434float OFF2 = 61.0f*Aux/16.0f;435float SENS2 = 2.0f*Aux;436if (TEMP < -1500) {437OFF2 += 15 * sq(TEMP+1500);438SENS2 += 8 * sq(TEMP+1500);439}440TEMP = TEMP - T2;441OFF = OFF - OFF2;442SENS = SENS - SENS2;443}444445float pressure = (_D1*SENS/2097152 - OFF)/32768;446float temperature = TEMP * 0.01f;447_copy_to_frontend(_instance, pressure, temperature);448}449450// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).451void AP_Baro_MS56XX::_calculate_5637()452{453int32_t dT, TEMP;454int64_t OFF, SENS;455int32_t raw_pressure = _D1;456int32_t raw_temperature = _D2;457458dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);459TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;460OFF = (int64_t)_cal_reg.c2 * (int64_t)131072 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)64;461SENS = (int64_t)_cal_reg.c1 * (int64_t)65536 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)128;462463if (TEMP < 2000) {464// second order temperature compensation when under 20 degrees C465int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);466int64_t aux = (TEMP - 2000) * (TEMP - 2000);467int64_t OFF2 = 61 * aux / 16;468int64_t SENS2 = 29 * aux / 16;469470if (TEMP < -1500) {471OFF2 += 17 * sq(TEMP+1500);472SENS2 += 9 * sq(TEMP+1500);473}474475TEMP = TEMP - T2;476OFF = OFF - OFF2;477SENS = SENS - SENS2;478}479480int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)32768;481float temperature = TEMP * 0.01f;482_copy_to_frontend(_instance, (float)pressure, temperature);483}484485// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).486void AP_Baro_MS56XX::_calculate_5837()487{488int32_t dT, TEMP;489int64_t OFF, SENS;490int32_t raw_pressure = _D1;491int32_t raw_temperature = _D2;492493// note that MS5837 has no compensation for temperatures below -15C in the datasheet494495dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);496TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;497OFF = (int64_t)_cal_reg.c2 * (int64_t)65536 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)128;498SENS = (int64_t)_cal_reg.c1 * (int64_t)32768 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)256;499500if (TEMP < 2000) {501// second order temperature compensation when under 20 degrees C502int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);503int64_t aux = (TEMP - 2000) * (TEMP - 2000);504int64_t OFF2 = 3 * aux / 2;505int64_t SENS2 = 5 * aux / 8;506507TEMP = TEMP - T2;508OFF = OFF - OFF2;509SENS = SENS - SENS2;510}511512int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)8192;513pressure = pressure * 10; // MS5837 only reports to 0.1 mbar514float temperature = TEMP * 0.01f;515516_copy_to_frontend(_instance, (float)pressure, temperature);517}518519#endif // AP_BARO_MS56XX_ENABLED520521522