2011-12-28 05:32:21 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
2016-01-04 09:59:19 -04:00
|
|
|
#include "AP_Baro_MS5611.h"
|
2013-08-29 02:34:34 -03:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
#include <utility>
|
2014-10-19 16:22:51 -03:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
extern const AP_HAL::HAL &hal;
|
2011-11-27 01:43:34 -04:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
static const uint8_t CMD_MS56XX_RESET = 0x1E;
|
|
|
|
static const uint8_t CMD_MS56XX_READ_ADC = 0x00;
|
2011-11-27 01:43:34 -04:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
/* PROM start address */
|
|
|
|
static const uint8_t CMD_MS56XX_PROM = 0xA0;
|
2011-11-27 01:49:17 -04:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
/* write to one of these addresses to start pressure conversion */
|
|
|
|
#define ADDR_CMD_CONVERT_D1_OSR256 0x40
|
|
|
|
#define ADDR_CMD_CONVERT_D1_OSR512 0x42
|
|
|
|
#define ADDR_CMD_CONVERT_D1_OSR1024 0x44
|
|
|
|
#define ADDR_CMD_CONVERT_D1_OSR2048 0x46
|
|
|
|
#define ADDR_CMD_CONVERT_D1_OSR4096 0x48
|
2015-11-09 17:25:42 -04:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
/* write to one of these addresses to start temperature conversion */
|
|
|
|
#define ADDR_CMD_CONVERT_D2_OSR256 0x50
|
|
|
|
#define ADDR_CMD_CONVERT_D2_OSR512 0x52
|
|
|
|
#define ADDR_CMD_CONVERT_D2_OSR1024 0x54
|
|
|
|
#define ADDR_CMD_CONVERT_D2_OSR2048 0x56
|
|
|
|
#define ADDR_CMD_CONVERT_D2_OSR4096 0x58
|
2015-11-09 17:25:42 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
use an OSR of 1024 to reduce the self-heating effect of the
|
|
|
|
sensor. Information from MS tells us that some individual sensors
|
|
|
|
are quite sensitive to this effect and that reducing the OSR can
|
|
|
|
make a big difference
|
|
|
|
*/
|
2016-01-04 09:59:19 -04:00
|
|
|
static const uint8_t ADDR_CMD_CONVERT_PRESSURE = ADDR_CMD_CONVERT_D1_OSR1024;
|
|
|
|
static const uint8_t ADDR_CMD_CONVERT_TEMPERATURE = ADDR_CMD_CONVERT_D2_OSR1024;
|
2013-01-04 18:26:26 -04:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
/*
|
|
|
|
constructor
|
|
|
|
*/
|
2016-01-04 09:59:19 -04:00
|
|
|
AP_Baro_MS56XX::AP_Baro_MS56XX(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
2016-01-02 10:01:42 -04:00
|
|
|
: AP_Baro_Backend(baro)
|
2016-01-04 09:59:19 -04:00
|
|
|
, _dev(std::move(dev))
|
2016-01-02 10:01:42 -04:00
|
|
|
, _use_timer(use_timer)
|
2015-11-04 18:17:38 -04:00
|
|
|
{
|
|
|
|
}
|
|
|
|
|
|
|
|
void AP_Baro_MS56XX::_init()
|
2014-10-19 16:22:51 -03:00
|
|
|
{
|
2016-01-04 09:59:19 -04:00
|
|
|
if (!_dev) {
|
|
|
|
AP_HAL::panic("AP_Baro_MS56XX: failed to use device");
|
|
|
|
}
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
_instance = _frontend.register_sensor();
|
2015-09-30 08:38:51 -03:00
|
|
|
|
|
|
|
// we need to suspend timers to prevent other SPI drivers grabbing
|
|
|
|
// the bus while we do the long initialisation
|
|
|
|
hal.scheduler->suspend_timer_procs();
|
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
if (!_dev->get_semaphore()->take(10)) {
|
2015-11-19 23:07:59 -04:00
|
|
|
AP_HAL::panic("PANIC: AP_Baro_MS56XX: failed to take serial semaphore for init");
|
2014-10-19 16:22:51 -03:00
|
|
|
}
|
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
_dev->transfer(&CMD_MS56XX_RESET, 1, nullptr, 0);
|
2014-10-19 16:22:51 -03:00
|
|
|
hal.scheduler->delay(4);
|
|
|
|
|
2015-11-26 10:56:10 -04:00
|
|
|
uint16_t prom[8];
|
|
|
|
if (!_read_prom(prom)) {
|
|
|
|
AP_HAL::panic("Can't read PROM");
|
2014-10-19 16:22:51 -03:00
|
|
|
}
|
|
|
|
|
2015-11-26 10:56:10 -04:00
|
|
|
// Save factory calibration coefficients
|
2015-12-07 16:23:48 -04:00
|
|
|
_c1 = prom[1];
|
|
|
|
_c2 = prom[2];
|
|
|
|
_c3 = prom[3];
|
|
|
|
_c4 = prom[4];
|
|
|
|
_c5 = prom[5];
|
|
|
|
_c6 = prom[6];
|
2015-11-26 10:56:10 -04:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
// Send a command to read temperature first
|
|
|
|
_dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0);
|
2015-11-19 23:07:59 -04:00
|
|
|
_last_timer = AP_HAL::micros();
|
2014-10-19 16:22:51 -03:00
|
|
|
_state = 0;
|
|
|
|
|
|
|
|
_s_D1 = 0;
|
|
|
|
_s_D2 = 0;
|
|
|
|
_d1_count = 0;
|
|
|
|
_d2_count = 0;
|
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
_dev->get_semaphore()->give();
|
2014-10-19 16:22:51 -03:00
|
|
|
|
2015-09-30 08:38:51 -03:00
|
|
|
hal.scheduler->resume_timer_procs();
|
|
|
|
|
2015-01-06 01:28:11 -04:00
|
|
|
if (_use_timer) {
|
2015-08-03 13:16:01 -03:00
|
|
|
/* timer needs to be called every 10ms so set the freq_div to 10 */
|
|
|
|
_timesliced = hal.scheduler->register_timer_process(FUNCTOR_BIND_MEMBER(&AP_Baro_MS56XX::_timer, void), 10);
|
2015-01-06 01:28:11 -04:00
|
|
|
}
|
2014-10-19 16:22:51 -03:00
|
|
|
}
|
2013-01-03 14:06:22 -04:00
|
|
|
|
2014-07-07 00:11:41 -03:00
|
|
|
/**
|
2015-11-26 10:56:10 -04:00
|
|
|
* MS56XX crc4 method from datasheet for 16 bytes (8 short values)
|
2014-07-07 00:11:41 -03:00
|
|
|
*/
|
2015-11-26 10:56:10 -04:00
|
|
|
static uint16_t crc4(uint16_t *data)
|
2014-07-07 00:11:41 -03:00
|
|
|
{
|
2015-11-11 19:00:57 -04:00
|
|
|
uint16_t n_rem = 0;
|
2014-07-07 00:11:41 -03:00
|
|
|
uint8_t n_bit;
|
|
|
|
|
2015-11-11 19:00:57 -04:00
|
|
|
for (uint8_t cnt = 0; cnt < 16; cnt++) {
|
2014-07-07 00:11:41 -03:00
|
|
|
/* uneven bytes */
|
|
|
|
if (cnt & 1) {
|
2015-11-11 19:00:57 -04:00
|
|
|
n_rem ^= (uint8_t)((data[cnt >> 1]) & 0x00FF);
|
2014-07-07 00:11:41 -03:00
|
|
|
} else {
|
2015-11-11 19:00:57 -04:00
|
|
|
n_rem ^= (uint8_t)(data[cnt >> 1] >> 8);
|
2014-07-07 00:11:41 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
for (n_bit = 8; n_bit > 0; n_bit--) {
|
|
|
|
if (n_rem & 0x8000) {
|
|
|
|
n_rem = (n_rem << 1) ^ 0x3000;
|
|
|
|
} else {
|
|
|
|
n_rem = (n_rem << 1);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-11-11 19:00:57 -04:00
|
|
|
return (n_rem >> 12) & 0xF;
|
|
|
|
}
|
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
uint16_t AP_Baro_MS56XX::_read_prom_word(uint8_t word)
|
|
|
|
{
|
|
|
|
const uint8_t reg = CMD_MS56XX_PROM + (word << 1);
|
|
|
|
uint8_t val[2];
|
|
|
|
|
|
|
|
if (!_dev->transfer(®, 1, val, 2)) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
return (val[0] << 8) | val[1];
|
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t AP_Baro_MS56XX::_read_adc()
|
|
|
|
{
|
|
|
|
uint8_t val[3];
|
|
|
|
|
|
|
|
if (!_dev->transfer(&CMD_MS56XX_READ_ADC, 1, val, 3)) {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
return (val[0] << 16) | (val[1] << 8) | val[2];
|
|
|
|
}
|
|
|
|
|
2015-11-26 10:56:10 -04:00
|
|
|
bool AP_Baro_MS56XX::_read_prom(uint16_t prom[8])
|
|
|
|
{
|
|
|
|
/*
|
|
|
|
* MS5611-01BA datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5611-01BA
|
|
|
|
* contains a PROM memory with 128-Bit. A 4-bit CRC has been implemented
|
|
|
|
* to check the data validity in memory."
|
|
|
|
*
|
|
|
|
* CRC field must me removed for CRC-4 calculation.
|
|
|
|
*/
|
|
|
|
for (uint8_t i = 0; i < 8; i++) {
|
2016-01-04 09:59:19 -04:00
|
|
|
prom[i] = _read_prom_word(i);
|
2015-11-26 10:56:10 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
/* save the read crc */
|
|
|
|
const uint16_t crc_read = prom[7] & 0xf;
|
|
|
|
|
|
|
|
/* remove CRC byte */
|
|
|
|
prom[7] &= 0xff00;
|
|
|
|
|
|
|
|
return crc_read == crc4(prom);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool AP_Baro_MS5637::_read_prom(uint16_t prom[8])
|
2015-11-11 19:00:57 -04:00
|
|
|
{
|
2015-11-26 10:56:10 -04:00
|
|
|
/*
|
|
|
|
* MS5637-02BA03 datasheet, CYCLIC REDUNDANCY CHECK (CRC): "MS5637
|
|
|
|
* contains a PROM memory with 112-Bit. A 4-bit CRC has been implemented
|
|
|
|
* to check the data validity in memory."
|
|
|
|
*
|
|
|
|
* 8th PROM word must be zeroed and CRC field removed for CRC-4
|
|
|
|
* calculation.
|
|
|
|
*/
|
|
|
|
for (uint8_t i = 0; i < 7; i++) {
|
2016-01-04 09:59:19 -04:00
|
|
|
prom[i] = _read_prom_word(i);
|
2015-11-26 10:56:10 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
prom[7] = 0;
|
2015-11-11 19:00:57 -04:00
|
|
|
|
|
|
|
/* save the read crc */
|
2015-11-26 10:56:10 -04:00
|
|
|
const uint16_t crc_read = (prom[0] & 0xf000) >> 12;
|
2015-11-11 19:00:57 -04:00
|
|
|
|
|
|
|
/* remove CRC byte */
|
2015-11-26 10:56:10 -04:00
|
|
|
prom[0] &= ~0xf000;
|
2014-07-07 00:11:41 -03:00
|
|
|
|
2015-11-26 10:56:10 -04:00
|
|
|
return crc_read == crc4(prom);
|
2014-07-07 00:11:41 -03:00
|
|
|
}
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
/*
|
|
|
|
Read the sensor. This is a state machine
|
|
|
|
We read one time Temperature (state=1) and then 4 times Pressure (states 2-5)
|
|
|
|
temperature does not change so quickly...
|
|
|
|
*/
|
2015-07-10 00:56:06 -03:00
|
|
|
void AP_Baro_MS56XX::_timer(void)
|
2011-11-05 22:11:25 -03:00
|
|
|
{
|
2012-02-12 20:00:06 -04:00
|
|
|
// Throttle read rate to 100hz maximum.
|
2015-08-03 13:16:01 -03:00
|
|
|
if (!_timesliced &&
|
|
|
|
AP_HAL::micros() - _last_timer < 10000) {
|
2012-08-17 03:09:23 -03:00
|
|
|
return;
|
2011-12-21 08:22:37 -04:00
|
|
|
}
|
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
if (!_dev->get_semaphore()->take_nonblocking()) {
|
2013-01-09 05:27:48 -04:00
|
|
|
return;
|
|
|
|
}
|
2012-02-14 12:55:32 -04:00
|
|
|
|
2012-07-02 00:44:02 -03:00
|
|
|
if (_state == 0) {
|
2014-07-07 08:20:05 -03:00
|
|
|
// On state 0 we read temp
|
2016-01-04 09:59:19 -04:00
|
|
|
uint32_t d2 = _read_adc();
|
2014-07-07 08:20:05 -03:00
|
|
|
if (d2 != 0) {
|
|
|
|
_s_D2 += d2;
|
|
|
|
_d2_count++;
|
|
|
|
if (_d2_count == 32) {
|
|
|
|
// we have summed 32 values. This only happens
|
|
|
|
// when we stop reading the barometer for a long time
|
|
|
|
// (more than 1.2 seconds)
|
|
|
|
_s_D2 >>= 1;
|
|
|
|
_d2_count = 16;
|
|
|
|
}
|
2015-08-17 13:44:46 -03:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
if (_dev->transfer(&ADDR_CMD_CONVERT_PRESSURE, 1, nullptr, 0)) {
|
2015-08-17 13:44:46 -03:00
|
|
|
_state++;
|
|
|
|
}
|
2015-09-18 07:19:11 -03:00
|
|
|
} else {
|
|
|
|
/* if read fails, re-initiate a temperature read command or we are
|
|
|
|
* stuck */
|
2016-01-04 09:59:19 -04:00
|
|
|
_dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0);
|
2012-07-02 00:44:02 -03:00
|
|
|
}
|
2011-12-21 08:22:37 -04:00
|
|
|
} else {
|
2016-01-04 09:59:19 -04:00
|
|
|
uint32_t d1 = _read_adc();
|
2014-07-07 08:20:05 -03:00
|
|
|
if (d1 != 0) {
|
|
|
|
// occasional zero values have been seen on the PXF
|
|
|
|
// board. These may be SPI errors, but safest to ignore
|
|
|
|
_s_D1 += d1;
|
|
|
|
_d1_count++;
|
|
|
|
if (_d1_count == 128) {
|
|
|
|
// we have summed 128 values. This only happens
|
|
|
|
// when we stop reading the barometer for a long time
|
|
|
|
// (more than 1.2 seconds)
|
|
|
|
_s_D1 >>= 1;
|
|
|
|
_d1_count = 64;
|
|
|
|
}
|
|
|
|
// Now a new reading exists
|
|
|
|
_updated = true;
|
2015-08-17 13:44:46 -03:00
|
|
|
|
|
|
|
if (_state == 4) {
|
2016-01-04 09:59:19 -04:00
|
|
|
if (_dev->transfer(&ADDR_CMD_CONVERT_TEMPERATURE, 1, nullptr, 0)) {
|
2015-08-17 13:44:46 -03:00
|
|
|
_state = 0;
|
|
|
|
}
|
|
|
|
} else {
|
2016-01-04 09:59:19 -04:00
|
|
|
if (_dev->transfer(&ADDR_CMD_CONVERT_PRESSURE, 1, nullptr, 0)) {
|
2015-08-17 13:44:46 -03:00
|
|
|
_state++;
|
|
|
|
}
|
|
|
|
}
|
2015-09-18 07:19:11 -03:00
|
|
|
} else {
|
|
|
|
/* if read fails, re-initiate a pressure read command or we are
|
|
|
|
* stuck */
|
2016-01-04 09:59:19 -04:00
|
|
|
_dev->transfer(&ADDR_CMD_CONVERT_PRESSURE, 1, nullptr, 0);
|
2012-07-02 00:44:02 -03:00
|
|
|
}
|
2011-12-21 08:22:37 -04:00
|
|
|
}
|
2012-11-19 21:23:26 -04:00
|
|
|
|
2015-11-19 23:07:59 -04:00
|
|
|
_last_timer = AP_HAL::micros();
|
2016-01-04 09:59:19 -04:00
|
|
|
_dev->get_semaphore()->give();
|
2011-12-09 02:35:40 -04:00
|
|
|
}
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
void AP_Baro_MS56XX::update()
|
2011-12-09 02:35:40 -04:00
|
|
|
{
|
2015-01-06 01:28:11 -04:00
|
|
|
if (!_use_timer) {
|
|
|
|
// if we're not using the timer then accumulate one more time
|
|
|
|
// to cope with the calibration loop and minimise lag
|
|
|
|
accumulate();
|
|
|
|
}
|
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
if (!_updated) {
|
|
|
|
return;
|
2011-12-09 02:35:40 -04:00
|
|
|
}
|
2014-10-19 16:22:51 -03:00
|
|
|
uint32_t sD1, sD2;
|
|
|
|
uint8_t d1count, d2count;
|
|
|
|
|
|
|
|
// Suspend timer procs because these variables are written to
|
|
|
|
// in "_update".
|
|
|
|
hal.scheduler->suspend_timer_procs();
|
|
|
|
sD1 = _s_D1; _s_D1 = 0;
|
|
|
|
sD2 = _s_D2; _s_D2 = 0;
|
|
|
|
d1count = _d1_count; _d1_count = 0;
|
|
|
|
d2count = _d2_count; _d2_count = 0;
|
|
|
|
_updated = false;
|
|
|
|
hal.scheduler->resume_timer_procs();
|
2015-09-28 15:43:04 -03:00
|
|
|
|
2014-10-19 16:22:51 -03:00
|
|
|
if (d1count != 0) {
|
2015-07-10 00:56:06 -03:00
|
|
|
_D1 = ((float)sD1) / d1count;
|
2014-10-19 16:22:51 -03:00
|
|
|
}
|
|
|
|
if (d2count != 0) {
|
2015-07-10 00:56:06 -03:00
|
|
|
_D2 = ((float)sD2) / d2count;
|
2012-06-19 23:25:19 -03:00
|
|
|
}
|
2014-10-19 16:22:51 -03:00
|
|
|
_calculate();
|
2011-11-05 22:11:25 -03:00
|
|
|
}
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
/* MS5611 class */
|
2016-01-04 09:59:19 -04:00
|
|
|
AP_Baro_MS5611::AP_Baro_MS5611(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
|
|
|
: AP_Baro_MS56XX(baro, std::move(dev), use_timer)
|
2015-11-04 18:17:38 -04:00
|
|
|
{
|
|
|
|
_init();
|
|
|
|
}
|
2015-07-10 00:56:06 -03:00
|
|
|
|
2011-11-27 01:43:34 -04:00
|
|
|
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
|
2011-12-09 02:35:40 -04:00
|
|
|
void AP_Baro_MS5611::_calculate()
|
2011-11-05 22:11:25 -03:00
|
|
|
{
|
2012-08-17 03:09:23 -03:00
|
|
|
float dT;
|
|
|
|
float TEMP;
|
|
|
|
float OFF;
|
|
|
|
float SENS;
|
2011-11-27 01:43:34 -04:00
|
|
|
|
2012-08-17 03:09:23 -03:00
|
|
|
// Formulas from manufacturer datasheet
|
2015-09-28 15:43:04 -03:00
|
|
|
// sub -15c temperature compensation is not included
|
2012-07-06 02:11:22 -03:00
|
|
|
|
2015-11-03 09:46:29 -04:00
|
|
|
// we do the calculations using floating point allows us to take advantage
|
|
|
|
// of the averaging of D1 and D1 over multiple samples, giving us more
|
|
|
|
// precision
|
2015-12-07 16:23:48 -04:00
|
|
|
dT = _D2-(((uint32_t)_c5)<<8);
|
|
|
|
TEMP = (dT * _c6)/8388608;
|
|
|
|
OFF = _c2 * 65536.0f + (_c4 * dT) / 128;
|
|
|
|
SENS = _c1 * 32768.0f + (_c3 * dT) / 256;
|
2012-07-06 02:11:22 -03:00
|
|
|
|
2012-08-17 03:09:23 -03:00
|
|
|
if (TEMP < 0) {
|
2012-07-06 02:11:22 -03:00
|
|
|
// second order temperature compensation when under 20 degrees C
|
2012-08-17 03:09:23 -03:00
|
|
|
float T2 = (dT*dT) / 0x80000000;
|
|
|
|
float Aux = TEMP*TEMP;
|
2013-01-10 14:42:24 -04:00
|
|
|
float OFF2 = 2.5f*Aux;
|
|
|
|
float SENS2 = 1.25f*Aux;
|
2012-08-17 03:09:23 -03:00
|
|
|
TEMP = TEMP - T2;
|
|
|
|
OFF = OFF - OFF2;
|
|
|
|
SENS = SENS - SENS2;
|
|
|
|
}
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
float pressure = (_D1*SENS/2097152 - OFF)/32768;
|
|
|
|
float temperature = (TEMP + 2000) * 0.01f;
|
|
|
|
_copy_to_frontend(_instance, pressure, temperature);
|
|
|
|
}
|
|
|
|
|
|
|
|
/* MS5607 Class */
|
2016-01-04 09:59:19 -04:00
|
|
|
AP_Baro_MS5607::AP_Baro_MS5607(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
|
|
|
: AP_Baro_MS56XX(baro, std::move(dev), use_timer)
|
2015-11-04 18:17:38 -04:00
|
|
|
{
|
|
|
|
_init();
|
|
|
|
}
|
|
|
|
|
2015-07-10 00:56:06 -03:00
|
|
|
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
|
|
|
|
void AP_Baro_MS5607::_calculate()
|
|
|
|
{
|
|
|
|
float dT;
|
|
|
|
float TEMP;
|
|
|
|
float OFF;
|
|
|
|
float SENS;
|
|
|
|
|
|
|
|
// Formulas from manufacturer datasheet
|
2015-09-28 15:43:04 -03:00
|
|
|
// sub -15c temperature compensation is not included
|
2015-07-10 00:56:06 -03:00
|
|
|
|
2015-11-03 09:46:29 -04:00
|
|
|
// we do the calculations using floating point allows us to take advantage
|
|
|
|
// of the averaging of D1 and D1 over multiple samples, giving us more
|
|
|
|
// precision
|
2015-12-07 16:23:48 -04:00
|
|
|
dT = _D2-(((uint32_t)_c5)<<8);
|
|
|
|
TEMP = (dT * _c6)/8388608;
|
|
|
|
OFF = _c2 * 131072.0f + (_c4 * dT) / 64;
|
|
|
|
SENS = _c1 * 65536.0f + (_c3 * dT) / 128;
|
2015-07-10 00:56:06 -03:00
|
|
|
|
|
|
|
if (TEMP < 0) {
|
|
|
|
// second order temperature compensation when under 20 degrees C
|
|
|
|
float T2 = (dT*dT) / 0x80000000;
|
|
|
|
float Aux = TEMP*TEMP;
|
|
|
|
float OFF2 = 61.0f*Aux/16.0f;
|
|
|
|
float SENS2 = 2.0f*Aux;
|
|
|
|
TEMP = TEMP - T2;
|
|
|
|
OFF = OFF - OFF2;
|
|
|
|
SENS = SENS - SENS2;
|
|
|
|
}
|
|
|
|
|
|
|
|
float pressure = (_D1*SENS/2097152 - OFF)/32768;
|
2014-10-19 16:22:51 -03:00
|
|
|
float temperature = (TEMP + 2000) * 0.01f;
|
|
|
|
_copy_to_frontend(_instance, pressure, temperature);
|
2011-11-05 22:11:25 -03:00
|
|
|
}
|
2015-01-06 01:28:11 -04:00
|
|
|
|
2016-01-04 09:59:19 -04:00
|
|
|
/* MS5637 Class */
|
|
|
|
AP_Baro_MS5637::AP_Baro_MS5637(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev, bool use_timer)
|
|
|
|
: AP_Baro_MS56XX(baro, std::move(dev), use_timer)
|
2015-09-28 15:31:12 -03:00
|
|
|
{
|
2015-11-04 18:17:38 -04:00
|
|
|
_init();
|
2015-09-28 15:31:12 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// Calculate Temperature and compensated Pressure in real units (Celsius degrees*100, mbar*100).
|
|
|
|
void AP_Baro_MS5637::_calculate()
|
|
|
|
{
|
|
|
|
int32_t dT, TEMP;
|
|
|
|
int64_t OFF, SENS;
|
|
|
|
int32_t raw_pressure = _D1;
|
|
|
|
int32_t raw_temperature = _D2;
|
|
|
|
|
|
|
|
// Formulas from manufacturer datasheet
|
|
|
|
// sub -15c temperature compensation is not included
|
|
|
|
|
2015-12-07 16:23:48 -04:00
|
|
|
dT = raw_temperature - (((uint32_t)_c5) << 8);
|
|
|
|
TEMP = 2000 + ((int64_t)dT * (int64_t)_c6) / 8388608;
|
|
|
|
OFF = (int64_t)_c2 * (int64_t)131072 + ((int64_t)_c4 * (int64_t)dT) / (int64_t)64;
|
|
|
|
SENS = (int64_t)_c1 * (int64_t)65536 + ((int64_t)_c3 * (int64_t)dT) / (int64_t)128;
|
2015-09-28 15:31:12 -03:00
|
|
|
|
|
|
|
if (TEMP < 2000) {
|
|
|
|
// second order temperature compensation when under 20 degrees C
|
|
|
|
int32_t T2 = ((int64_t)3 * ((int64_t)dT * (int64_t)dT) / (int64_t)8589934592);
|
|
|
|
int64_t aux = (TEMP - 2000) * (TEMP - 2000);
|
|
|
|
int64_t OFF2 = 61 * aux / 16;
|
|
|
|
int64_t SENS2 = 29 * aux / 16;
|
|
|
|
|
|
|
|
TEMP = TEMP - T2;
|
|
|
|
OFF = OFF - OFF2;
|
|
|
|
SENS = SENS - SENS2;
|
|
|
|
}
|
|
|
|
|
|
|
|
int32_t pressure = ((int64_t)raw_pressure * SENS / (int64_t)2097152 - OFF) / (int64_t)32768;
|
|
|
|
float temperature = TEMP * 0.01f;
|
|
|
|
_copy_to_frontend(_instance, (float)pressure, temperature);
|
|
|
|
}
|
|
|
|
|
2015-01-06 01:28:11 -04:00
|
|
|
/*
|
|
|
|
Read the sensor from main code. This is only used for I2C MS5611 to
|
|
|
|
avoid conflicts on the semaphore from calling it in a timer, which
|
|
|
|
conflicts with the compass driver use of I2C
|
|
|
|
*/
|
2015-07-10 00:56:06 -03:00
|
|
|
void AP_Baro_MS56XX::accumulate(void)
|
2015-01-06 01:28:11 -04:00
|
|
|
{
|
|
|
|
if (!_use_timer) {
|
|
|
|
// the timer isn't being called as a timer, so we need to call
|
|
|
|
// it in accumulate()
|
|
|
|
_timer();
|
|
|
|
}
|
|
|
|
}
|