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_SPL06.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_SPL06.h"1516#if AP_BARO_SPL06_ENABLED1718#include <utility>19#include <strings.h>20#include <AP_Math/definitions.h>2122extern const AP_HAL::HAL &hal;2324#define SPL06_CHIP_ID 0x1025#define SPA06_CHIP_ID 0x112627#define SPL06_REG_PRESSURE_B2 0x00 // Pressure MSB Register28#define SPL06_REG_PRESSURE_B1 0x01 // Pressure middle byte Register29#define SPL06_REG_PRESSURE_B0 0x02 // Pressure LSB Register30#define SPL06_REG_PRESSURE_START SPL06_REG_PRESSURE_B231#define SPL06_PRESSURE_LEN 3 // 24 bits, 3 bytes32#define SPL06_REG_TEMPERATURE_B2 0x03 // Temperature MSB Register33#define SPL06_REG_TEMPERATURE_B1 0x04 // Temperature middle byte Register34#define SPL06_REG_TEMPERATURE_B0 0x05 // Temperature LSB Register35#define SPL06_REG_TEMPERATURE_START SPL06_REG_TEMPERATURE_B236#define SPL06_TEMPERATURE_LEN 3 // 24 bits, 3 bytes37#define SPL06_REG_PRESSURE_CFG 0x06 // Pressure config38#define SPL06_REG_TEMPERATURE_CFG 0x07 // Temperature config39#define SPL06_REG_MODE_AND_STATUS 0x08 // Mode and status40#define SPL06_REG_INT_AND_FIFO_CFG 0x09 // Interrupt and FIFO config41#define SPL06_REG_INT_STATUS 0x0A // Interrupt and FIFO config42#define SPL06_REG_FIFO_STATUS 0x0B // Interrupt and FIFO config43#define SPL06_REG_RST 0x0C // Softreset Register44#define SPL06_REG_CHIP_ID 0x0D // Chip ID Register45#define SPL06_REG_CALIB_COEFFS_START 0x1046#define SPL06_REG_CALIB_COEFFS_END 0x2147#define SPA06_REG_CALIB_COEFFS_END 0x244849// PRESSURE_CFG_REG50#define SPL06_PRES_RATE_32HZ (0x05 << 4)5152// TEMPERATURE_CFG_REG53#define SPL06_TEMP_USE_EXT_SENSOR (1<<7)54#define SPL06_TEMP_RATE_32HZ (0x05 << 4)5556// MODE_AND_STATUS_REG57#define SPL06_MEAS_PRESSURE (1<<0) // measure pressure58#define SPL06_MEAS_TEMPERATURE (1<<1) // measure temperature59#define SPL06_MEAS_CON_PRE_TEM 0x076061#define SPL06_MEAS_CFG_CONTINUOUS (1<<2)62#define SPL06_MEAS_CFG_PRESSURE_RDY (1<<4)63#define SPL06_MEAS_CFG_TEMPERATURE_RDY (1<<5)64#define SPL06_MEAS_CFG_SENSOR_RDY (1<<6)65#define SPL06_MEAS_CFG_COEFFS_RDY (1<<7)6667// INT_AND_FIFO_CFG_REG68#define SPL06_PRESSURE_RESULT_BIT_SHIFT (1<<2) // necessary for pressure oversampling > 869#define SPL06_TEMPERATURE_RESULT_BIT_SHIFT (1<<3) // necessary for temperature oversampling > 87071// Don't set oversampling higher than 8 or the measurement time will be higher than 20ms (timer period)72#define SPL06_PRESSURE_OVERSAMPLING 873#define SPL06_TEMPERATURE_OVERSAMPLING 87475#define SPL06_OVERSAMPLING_TO_REG_VALUE(n) (ffs(n)-1)7677#define SPL06_BACKGROUND_SAMPLE_RATE 327879// enable Background Mode for continuous measurement80#ifndef AP_BARO_SPL06_BACKGROUND_ENABLE81#define AP_BARO_SPL06_BACKGROUND_ENABLE 082#endif8384AP_Baro_SPL06::AP_Baro_SPL06(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)85: AP_Baro_Backend(baro)86, _dev(std::move(dev))87{88}8990AP_Baro_Backend *AP_Baro_SPL06::probe(AP_Baro &baro,91AP_HAL::OwnPtr<AP_HAL::Device> dev)92{93if (!dev) {94return nullptr;95}9697if (dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {98dev->set_read_flag(0x80);99}100101AP_Baro_SPL06 *sensor = NEW_NOTHROW AP_Baro_SPL06(baro, std::move(dev));102if (!sensor || !sensor->_init()) {103delete sensor;104return nullptr;105}106return sensor;107}108109bool AP_Baro_SPL06::_init()110{111if (!_dev) {112return false;113}114WITH_SEMAPHORE(_dev->get_semaphore());115116_dev->set_speed(AP_HAL::Device::SPEED_HIGH);117118uint8_t whoami;119120// Sometimes SPL06 has init problems, that's due to failure of reading using SPI for the first time. The SPL06 is a dual121// protocol sensor(I2C and SPI), sometimes it takes one SPI operation to convert it to SPI mode after it starts up.122123for (uint8_t i=0; i<5; i++) {124if (_dev->read_registers(SPL06_REG_CHIP_ID, &whoami, 1)) {125switch(whoami) {126case SPL06_CHIP_ID:127type = Type::SPL06;128break;129case SPA06_CHIP_ID:130type = Type::SPA06;131break;132default:133type = Type::UNKNOWN;134break;135}136}137138if (type != Type::UNKNOWN)139break;140}141142if (type == Type::UNKNOWN) {143return false;144}145146// read the calibration data147uint8_t SPL06_CALIB_COEFFS_LEN = 18;148switch(type) {149case Type::SPL06:150SPL06_CALIB_COEFFS_LEN = SPL06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1;151break;152case Type::SPA06:153SPL06_CALIB_COEFFS_LEN = SPA06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1;154break;155default:156break;157}158159uint8_t buf[SPL06_CALIB_COEFFS_LEN];160_dev->read_registers(SPL06_REG_CALIB_COEFFS_START, buf, sizeof(buf));161162_c0 = (buf[0] & 0x80 ? 0xF000 : 0) | ((uint16_t)buf[0] << 4) | (((uint16_t)buf[1] & 0xF0) >> 4);163_c1 = ((buf[1] & 0x8 ? 0xF000 : 0) | ((uint16_t)buf[1] & 0x0F) << 8) | (uint16_t)buf[2];164_c00 = (buf[3] & 0x80 ? 0xFFF00000 : 0) | ((uint32_t)buf[3] << 12) | ((uint32_t)buf[4] << 4) | (((uint32_t)buf[5] & 0xF0) >> 4);165_c10 = (buf[5] & 0x8 ? 0xFFF00000 : 0) | (((uint32_t)buf[5] & 0x0F) << 16) | ((uint32_t)buf[6] << 8) | (uint32_t)buf[7];166_c01 = ((uint16_t)buf[8] << 8) | ((uint16_t)buf[9]);167_c11 = ((uint16_t)buf[10] << 8) | (uint16_t)buf[11];168_c20 = ((uint16_t)buf[12] << 8) | (uint16_t)buf[13];169_c21 = ((uint16_t)buf[14] << 8) | (uint16_t)buf[15];170_c30 = ((uint16_t)buf[16] << 8) | (uint16_t)buf[17];171if(type == Type::SPA06) {172_c31 = (buf[18] & 0x80 ? 0xF000 : 0) | ((uint16_t)buf[18] << 4) | (((uint16_t)buf[19] & 0xF0) >> 4);173_c40 = ((buf[19] & 0x8 ? 0xF000 : 0) | ((uint16_t)buf[19] & 0x0F) << 8) | (uint16_t)buf[20];174}175176// setup temperature and pressure measurements177_dev->setup_checked_registers(3, 20);178179#if AP_BARO_SPL06_BACKGROUND_ENABLE180//set rate and oversampling181_dev->write_register(SPL06_REG_TEMPERATURE_CFG, SPL06_TEMP_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true);182_dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_PRES_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true);183184//enable background mode185_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_CON_PRE_TEM, true);186#else187_dev->write_register(SPL06_REG_TEMPERATURE_CFG, SPL06_TEMP_USE_EXT_SENSOR | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true);188_dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true);189#endif //AP_BARO_SPL06_BACKGROUND_ENABLE190191uint8_t int_and_fifo_reg_value = 0;192if (SPL06_TEMPERATURE_OVERSAMPLING > 8) {193int_and_fifo_reg_value |= SPL06_TEMPERATURE_RESULT_BIT_SHIFT;194}195if (SPL06_PRESSURE_OVERSAMPLING > 8) {196int_and_fifo_reg_value |= SPL06_PRESSURE_RESULT_BIT_SHIFT;197}198_dev->write_register(SPL06_REG_INT_AND_FIFO_CFG, int_and_fifo_reg_value, true);199200_instance = _frontend.register_sensor();201202_dev->set_device_type(DEVTYPE_BARO_SPL06);203set_bus_id(_instance, _dev->get_bus_id());204205// request 50Hz update206_timer_counter = -1;207#if AP_BARO_SPL06_BACKGROUND_ENABLE208_dev->register_periodic_callback(1000000/SPL06_BACKGROUND_SAMPLE_RATE, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void));209#else210_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void));211#endif //AP_BARO_SPL06_BACKGROUND_ENABLE212213return true;214}215216int32_t AP_Baro_SPL06::raw_value_scale_factor(uint8_t oversampling)217{218// From the datasheet page 13219switch(oversampling)220{221case 1: return 524288;222case 2: return 1572864;223case 4: return 3670016;224case 8: return 7864320;225case 16: return 253952;226case 32: return 516096;227case 64: return 1040384;228case 128: return 2088960;229default: return -1; // invalid230}231}232233// accumulate a new sensor reading234void AP_Baro_SPL06::_timer(void)235{236uint8_t buf[3];237238#if AP_BARO_SPL06_BACKGROUND_ENABLE239_dev->read_registers(SPL06_REG_TEMPERATURE_START, buf, sizeof(buf));240_update_temperature((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));241242_dev->read_registers(SPL06_REG_PRESSURE_START, buf, sizeof(buf));243_update_pressure((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));244#else245//command mode246if ((_timer_counter == -1) || (_timer_counter == 49)) {247// First call and every second start a temperature measurement (50Hz call)248_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_TEMPERATURE, false);249_timer_counter = 0; // Next cycle we are reading the temperature250} else if (_timer_counter == 0) {251// A temperature measurement had been started during the previous call252_dev->read_registers(SPL06_REG_TEMPERATURE_START, buf, sizeof(buf));253_update_temperature((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));254_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_PRESSURE, false);255_timer_counter += 1;256} else {257// The rest of the time read the latest pressure and start a new measurement258_dev->read_registers(SPL06_REG_PRESSURE_START, buf, sizeof(buf));259_update_pressure((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));260_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_PRESSURE, false);261_timer_counter += 1;262}263#endif //AP_BARO_SPL06_BACKGROUND_ENABLE264265_dev->check_next_register();266}267268// transfer data to the frontend269void AP_Baro_SPL06::update(void)270{271WITH_SEMAPHORE(_sem);272273if (_pressure_count == 0) {274return;275}276277_copy_to_frontend(_instance, _pressure_sum/_pressure_count, _temperature);278279_pressure_sum = 0;280_pressure_count = 0;281}282283// calculate temperature284void AP_Baro_SPL06::_update_temperature(int32_t temp_raw)285{286_temp_raw = (float)temp_raw / raw_value_scale_factor(SPL06_TEMPERATURE_OVERSAMPLING);287const float temp_comp = (float)_c0 / 2 + _temp_raw * _c1;288289WITH_SEMAPHORE(_sem);290291_temperature = temp_comp;292}293294// calculate pressure295void AP_Baro_SPL06::_update_pressure(int32_t press_raw)296{297const float press_raw_sc = (float)press_raw / raw_value_scale_factor(SPL06_PRESSURE_OVERSAMPLING);298float pressure_cal = 0;299float press_temp_comp = 0;300301switch(type) {302case Type::SPL06:303pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * _c30));304press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * _c21));305break;306case Type::SPA06:307pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * ((float)_c30 + press_raw_sc * _c40)));308press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * ((float)_c21) + press_raw_sc * _c31));309break;310default:311break;312}313314const float press_comp = pressure_cal + press_temp_comp;315316if (!pressure_ok(press_comp)) {317return;318}319320WITH_SEMAPHORE(_sem);321322_pressure_sum += press_comp;323_pressure_count++;324}325326#endif // AP_BARO_SPL06_ENABLED327328329