Path: blob/master/libraries/AP_Baro/AP_Baro_MS5611.cpp
9699 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*/14#include "AP_Baro_MS5611.h"1516#if AP_BARO_MS56XX_ENABLED1718#include <stdio.h>1920#include <AP_Math/AP_Math.h>21#include <AP_Math/crc.h>22#include <AP_BoardConfig/AP_BoardConfig.h>2324extern const AP_HAL::HAL &hal;2526static const uint8_t CMD_MS56XX_RESET = 0x1E;27static const uint8_t CMD_MS56XX_READ_ADC = 0x00;2829/* PROM start address */30static const uint8_t CMD_MS56XX_PROM = 0xA0;3132/* write to one of these addresses to start pressure conversion */33#define ADDR_CMD_CONVERT_D1_OSR256 0x4034#define ADDR_CMD_CONVERT_D1_OSR512 0x4235#define ADDR_CMD_CONVERT_D1_OSR1024 0x4436#define ADDR_CMD_CONVERT_D1_OSR2048 0x4637#define ADDR_CMD_CONVERT_D1_OSR4096 0x483839/* write to one of these addresses to start temperature conversion */40#define ADDR_CMD_CONVERT_D2_OSR256 0x5041#define ADDR_CMD_CONVERT_D2_OSR512 0x5242#define ADDR_CMD_CONVERT_D2_OSR1024 0x5443#define ADDR_CMD_CONVERT_D2_OSR2048 0x5644#define ADDR_CMD_CONVERT_D2_OSR4096 0x584546/*47use an OSR of 1024 to reduce the self-heating effect of the48sensor. Information from MS tells us that some individual sensors49are quite sensitive to this effect and that reducing the OSR can50make a big difference51*/52static const uint8_t ADDR_CMD_CONVERT_PRESSURE = ADDR_CMD_CONVERT_D1_OSR1024;53static const uint8_t ADDR_CMD_CONVERT_TEMPERATURE = ADDR_CMD_CONVERT_D2_OSR1024;5455/*56constructor57*/58AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::Device &dev)59: AP_Baro_Backend(baro)60, _dev(&dev)61{62}6364// convenience methods for derivative classes to call. Will free65// sensor if it can't init it.66AP_Baro_Backend *AP_Baro_MS56XX::_probe(AP_Baro &baro, AP_Baro_MS56XX *sensor)67{68if (!sensor || !sensor->_init()) {69delete sensor;70return nullptr;71}72return sensor;73}7475#if AP_BARO_MS5611_ENABLED76AP_Baro_Backend *AP_Baro_MS5611::probe(AP_Baro &baro, AP_HAL::Device &dev)77{78#if AP_BARO_MS5607_ENABLED79/*80cope with vendors substituting a MS5607 for a MS5611 on Pixhawk1 'clone' boards81*/82if (AP::baro().option_enabled(AP_Baro::Options::TreatMS5611AsMS5607)) {83return _probe(baro, NEW_NOTHROW AP_Baro_MS5607(baro, dev));84}85#endif // AP_BARO_MS5607_ENABLED8687return _probe(baro, NEW_NOTHROW AP_Baro_MS5611(baro, dev));88}89#endif // AP_BARO_MS5611_ENABLED9091#if AP_BARO_MS5607_ENABLED92AP_Baro_Backend *AP_Baro_MS5607::probe(AP_Baro &baro, AP_HAL::Device &dev)93{94return _probe(baro, NEW_NOTHROW AP_Baro_MS5607(baro, dev));95}96#endif // AP_BARO_MS5607_ENABLED9798#if AP_BARO_MS5637_ENABLED99AP_Baro_Backend *AP_Baro_MS5637::probe(AP_Baro &baro, AP_HAL::Device &dev)100{101return _probe(baro, NEW_NOTHROW AP_Baro_MS5637(baro, dev));102}103#endif // AP_BARO_MS5637_ENABLED104105#if AP_BARO_MS5837_ENABLED106AP_Baro_Backend *AP_Baro_MS5837::probe(AP_Baro &baro, AP_HAL::Device &dev)107{108return _probe(baro, NEW_NOTHROW AP_Baro_MS5837(baro, dev));109}110111bool AP_Baro_MS5837::_init()112{113if (!AP_Baro_MS56XX::_init()) {114return false;115}116_frontend.set_type(_instance, AP_Baro::BARO_TYPE_WATER);117// Use pressure sensitivity as a proxy for range determination118// High sensitivity for the same number size implies the lower-range sensor variant119// Threshold determined from datasheet example values and some sample sensors120uint16_t pressure_sensitivity = _cal_reg.c1;121if (pressure_sensitivity > MS5837_30BA_02BA_SELECTION_THRESHOLD) {122_subtype = DEVTYPE_BARO_MS5837_02BA;123} else {124_subtype = DEVTYPE_BARO_MS5837_30BA;125}126return true;127}128#endif // AP_BARO_MS5837_ENABLED129130bool AP_Baro_MS56XX::_init()131{132if (!_dev) {133return false;134}135136_dev->get_semaphore()->take_blocking();137138// high retries for init139_dev->set_retries(10);140141uint16_t prom[8];142143_dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);144hal.scheduler->delay(4);145146if (!_read_prom(prom)) {147_dev->get_semaphore()->give();148return false;149}150151printf("%s found on bus %u address 0x%02x\n", name(), _dev->bus_num(), _dev->get_bus_address());152153// Save factory calibration coefficients154_cal_reg.c1 = prom[1];155_cal_reg.c2 = prom[2];156_cal_reg.c3 = prom[3];157_cal_reg.c4 = prom[4];158_cal_reg.c5 = prom[5];159_cal_reg.c6 = prom[6];160161// Send a command to read temperature first162_dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0);163_state = 0;164165memset(&_accum, 0, sizeof(_accum));166167_instance = _frontend.register_sensor();168169_dev->set_device_type(devtype());170set_bus_id(_instance, _dev->get_bus_id());171172// lower retries for run173_dev->set_retries(3);174175_dev->get_semaphore()->give();176177/* Request 100Hz update */178_dev->register_periodic_callback(10 * AP_USEC_PER_MSEC,179FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void));180return true;181}182183uint16_t AP_Baro_MS56XX::_read_prom_word(uint8_t word)184{185const uint8_t reg = CMD_MS56XX_PROM + (word << 1);186uint8_t val[2];187if (!_dev->transfer(®, 1, val, sizeof(val))) {188return 0;189}190return (val[0] << 8) | val[1];191}192193uint32_t AP_Baro_MS56XX::_read_adc()194{195uint8_t val[3];196if (!_dev->transfer(&CMD_MS56XX_READ_ADC, 1, val, sizeof(val))) {197return 0;198}199return (val[0] << 16) | (val[1] << 8) | val[2];200}201202bool AP_Baro_MS56XX::_read_prom_5611(uint16_t prom[8])203{204/*205* MS5611-01BA datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5611-01BA206* contains a PROM memory with 128-Bit. A 4-bit CRC has been implemented207* to check the data validity in memory."208*209* CRC field must me removed for CRC-4 calculation.210*/211bool all_zero = true;212for (uint8_t i = 0; i < 8; i++) {213prom[i] = _read_prom_word(i);214if (prom[i] != 0) {215all_zero = false;216}217}218219if (all_zero) {220return false;221}222223/* save the read crc */224const uint16_t crc_read = prom[7] & 0xf;225226/* remove CRC byte */227prom[7] &= 0xff00;228229return crc_read == crc_crc4(prom);230}231232bool AP_Baro_MS56XX::_read_prom_5637(uint16_t prom[8])233{234/*235* MS5637-02BA03 datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5637236* contains a PROM memory with 112-Bit. A 4-bit CRC has been implemented237* to check the data validity in memory."238*239* 8th PROM word must be zeroed and CRC field removed for CRC-4240* calculation.241*/242bool all_zero = true;243for (uint8_t i = 0; i < 7; i++) {244prom[i] = _read_prom_word(i);245if (prom[i] != 0) {246all_zero = false;247}248}249250if (all_zero) {251return false;252}253254prom[7] = 0;255256/* save the read crc */257const uint16_t crc_read = (prom[0] & 0xf000) >> 12;258259/* remove CRC byte */260prom[0] &= ~0xf000;261262return crc_read == crc_crc4(prom);263}264265/*266* Read the sensor with a state machine267* We read one time temperature (state=0) and then 4 times pressure (states 1-4)268*269* Temperature is used to calculate the compensated pressure and doesn't vary270* as fast as pressure. Hence we reuse the same temperature for 4 samples of271* pressure.272*/273void AP_Baro_MS56XX::_timer(void)274{275uint8_t next_cmd;276uint8_t next_state;277uint32_t adc_val = _read_adc();278279/*280* If read fails, re-initiate a read command for current state or we are281* stuck282*/283if (adc_val == 0) {284next_state = _state;285} else {286next_state = (_state + 1) % 5;287}288289next_cmd = next_state == 0 ? ADDR_CMD_CONVERT_TEMPERATURE290: ADDR_CMD_CONVERT_PRESSURE;291if (!_dev->transfer(&next_cmd, 1, nullptr, 0)) {292return;293}294295/* if we had a failed read we are all done */296if (adc_val == 0 || adc_val == 0xFFFFFF) {297// a failed read can mean the next returned value will be298// corrupt, we must discard it. This copes with MISO being299// pulled either high or low300_discard_next = true;301return;302}303304if (_discard_next) {305_discard_next = false;306_state = next_state;307return;308}309310WITH_SEMAPHORE(_sem);311312if (_state == 0) {313_update_and_wrap_accumulator(&_accum.s_D2, adc_val,314&_accum.d2_count, 32);315} else if (pressure_ok(adc_val)) {316_update_and_wrap_accumulator(&_accum.s_D1, adc_val,317&_accum.d1_count, 128);318}319320_state = next_state;321}322323void AP_Baro_MS56XX::_update_and_wrap_accumulator(uint32_t *accum, uint32_t val,324uint8_t *count, uint8_t max_count)325{326*accum += val;327*count += 1;328if (*count == max_count) {329*count = max_count / 2;330*accum = *accum / 2;331}332}333334void AP_Baro_MS56XX::update()335{336uint32_t sD1, sD2;337uint8_t d1count, d2count;338339{340WITH_SEMAPHORE(_sem);341342if (_accum.d1_count == 0) {343return;344}345346sD1 = _accum.s_D1;347sD2 = _accum.s_D2;348d1count = _accum.d1_count;349d2count = _accum.d2_count;350memset(&_accum, 0, sizeof(_accum));351}352353if (d1count != 0) {354_D1 = ((float)sD1) / d1count;355}356if (d2count != 0) {357_D2 = ((float)sD2) / d2count;358}359360_calculate();361}362363#if AP_BARO_MS5611_ENABLED364// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).365void AP_Baro_MS5611::_calculate()366{367float dT;368float TEMP;369float OFF;370float SENS;371372// we do the calculations using floating point allows us to take advantage373// of the averaging of D1 and D1 over multiple samples, giving us more374// precision375dT = _D2-(((uint32_t)_cal_reg.c5)<<8);376TEMP = (dT * _cal_reg.c6)/8388608;377OFF = _cal_reg.c2 * 65536.0f + (_cal_reg.c4 * dT) / 128;378SENS = _cal_reg.c1 * 32768.0f + (_cal_reg.c3 * dT) / 256;379380TEMP += 2000;381382if (TEMP < 2000) {383// second order temperature compensation when under 20 degrees C384float T2 = (dT*dT) / 0x80000000;385float Aux = sq(TEMP-2000.0);386float OFF2 = 2.5f*Aux;387float SENS2 = 1.25f*Aux;388if (TEMP < -1500) {389// extra compensation for temperatures below -15C390OFF2 += 7 * sq(TEMP+1500);391SENS2 += sq(TEMP+1500) * 11.0*0.5;392}393TEMP = TEMP - T2;394OFF = OFF - OFF2;395SENS = SENS - SENS2;396}397398399float pressure = (_D1*SENS/2097152 - OFF)/32768;400float temperature = TEMP * 0.01f;401_copy_to_frontend(_instance, pressure, temperature);402}403#endif // AP_BARO_MS5611_ENABLED404405#if AP_BARO_MS5607_ENABLED406// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).407void AP_Baro_MS5607::_calculate()408{409float dT;410float TEMP;411float OFF;412float SENS;413414// we do the calculations using floating point allows us to take advantage415// of the averaging of D1 and D1 over multiple samples, giving us more416// precision417dT = _D2-(((uint32_t)_cal_reg.c5)<<8);418TEMP = (dT * _cal_reg.c6)/8388608;419OFF = _cal_reg.c2 * 131072.0f + (_cal_reg.c4 * dT) / 64;420SENS = _cal_reg.c1 * 65536.0f + (_cal_reg.c3 * dT) / 128;421422TEMP += 2000;423424if (TEMP < 2000) {425// second order temperature compensation when under 20 degrees C426float T2 = (dT*dT) / 0x80000000;427float Aux = sq(TEMP-2000);428float OFF2 = 61.0f*Aux/16.0f;429float SENS2 = 2.0f*Aux;430if (TEMP < -1500) {431OFF2 += 15 * sq(TEMP+1500);432SENS2 += 8 * sq(TEMP+1500);433}434TEMP = TEMP - T2;435OFF = OFF - OFF2;436SENS = SENS - SENS2;437}438439float pressure = (_D1*SENS/2097152 - OFF)/32768;440float temperature = TEMP * 0.01f;441_copy_to_frontend(_instance, pressure, temperature);442}443#endif // AP_BARO_MS5607_ENABLED444445#if AP_BARO_MS5637_ENABLED446// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).447void AP_Baro_MS5637::_calculate()448{449int32_t dT, TEMP;450int64_t OFF, SENS;451int32_t raw_pressure = _D1;452int32_t raw_temperature = _D2;453454dT = raw_temperature - (((uint32_t)_cal_reg.c5) << 8);455TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;456OFF = (int64_t)_cal_reg.c2 * (int64_t)131072 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)64;457SENS = (int64_t)_cal_reg.c1 * (int64_t)65536 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)128;458459if (TEMP < 2000) {460// second order temperature compensation when under 20 degrees C461int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);462int64_t aux = (TEMP - 2000) * (TEMP - 2000);463int64_t OFF2 = 61 * aux / 16;464int64_t SENS2 = 29 * aux / 16;465466if (TEMP < -1500) {467OFF2 += 17 * sq(TEMP+1500);468SENS2 += 9 * sq(TEMP+1500);469}470471TEMP = TEMP - T2;472OFF = OFF - OFF2;473SENS = SENS - SENS2;474}475476int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)32768;477float temperature = TEMP * 0.01f;478_copy_to_frontend(_instance, (float)pressure, temperature);479}480#endif // AP_BARO_MS5637_ENABLED481482#if AP_BARO_MS5837_ENABLED483// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).484void AP_Baro_MS5837::_calculate()485{486if (_subtype == DEVTYPE_BARO_MS5837_02BA) {487_calculate_5837_02ba();488} else {489_calculate_5837_30ba();490}491}492493// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).494void AP_Baro_MS5837::_calculate_5837_30ba()495{496int32_t dT, TEMP, T2;497int64_t OFF, OFF2, SENS, SENS2;498int32_t raw_pressure = _D1;499int32_t raw_temperature = _D2;500501dT = raw_temperature - ((uint32_t)_cal_reg.c5 << 8);502TEMP = 2000 + ((int64_t)dT * (int64_t)_cal_reg.c6) / 8388608;503OFF = (int64_t)_cal_reg.c2 * (int64_t)65536 + ((int64_t)_cal_reg.c4 * (int64_t)dT) / (int64_t)128;504SENS = (int64_t)_cal_reg.c1 * (int64_t)32768 + ((int64_t)_cal_reg.c3 * (int64_t)dT) / (int64_t)256;505506int64_t aux = sq(TEMP - 2000);507if (TEMP < 2000) {508// second order "low temperature" compensation when under 20 degrees C509T2 = (int64_t)3 * sq((int64_t)dT) / (int64_t)8589934592;510OFF2 = 3 * aux / 2;511SENS2 = 5 * aux / 8;512513if (TEMP < -1500) {514// "very low temperature" compensation, when under -15 degrees C515OFF2 += 7 * sq(TEMP+1500);516SENS2 += 4 * sq(TEMP+1500);517}518} else {519// "high temperature" compensation, when at or over 20 degrees C520T2 = (int64_t)2 * sq((int64_t)dT) / (int64_t)137438953472;521OFF2 = aux / 16;522SENS2 = 0;523}524TEMP = TEMP - T2;525OFF = OFF - OFF2;526SENS = SENS - SENS2;527528int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)8192;529pressure = pressure * 10; // MS5837 only reports to 0.1 mbar530float temperature = TEMP * 0.01f;531532_copy_to_frontend(_instance, (float)pressure, temperature);533}534// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).535void AP_Baro_MS5837::_calculate_5837_02ba() {536int32_t dT = _D2 - ((int32_t)_cal_reg.c5 << 8);537int32_t TEMP = 2000 + ((dT * _cal_reg.c6) >> 23);538539int64_t OFF = ((int64_t)_cal_reg.c2 << 17) + (((int64_t)_cal_reg.c4 * dT) >> 6);540int64_t SENS = ((int64_t)_cal_reg.c1 << 16) + (((int64_t)_cal_reg.c3 * dT) >> 7);541542if (TEMP < 2000) {543// Second-order compensation544int32_t T2 = ((int64_t)11 * (int64_t)sq((int64_t)dT)) >> 35;545int64_t aux = sq(TEMP - 2000);546int64_t OFF2 = 31 * aux >> 3;547int64_t SENS2 = 63 * aux >> 5;548549TEMP -= T2;550OFF -= OFF2;551SENS -= SENS2;552}553554// Cast _D1 to int64_t before performing multiplication and shift555int64_t pressure = ((((int64_t)_D1 * SENS) >> 21) - OFF) >> 15;556557// Update frontend with calculated values558_copy_to_frontend(_instance, (float)pressure, (float)TEMP / 100);559}560561AP_Baro_Backend::DevTypes AP_Baro_MS5837::devtype() const {562return _subtype;563}564565#endif // AP_BARO_MS5837_ENABLED566567#endif // AP_BARO_MS56XX_ENABLED568569570