Path: blob/master/libraries/AP_Baro/AP_Baro_SPL06.cpp
9610 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_SPL06.h"1516#if AP_BARO_SPL06_ENABLED1718#include <strings.h>19#include <AP_Math/definitions.h>2021extern const AP_HAL::HAL &hal;2223#define SPL06_CHIP_ID 0x1024#define SPA06_CHIP_ID 0x112526#define SPL06_REG_PRESSURE_B2 0x00 // Pressure MSB Register27#define SPL06_REG_PRESSURE_B1 0x01 // Pressure middle byte Register28#define SPL06_REG_PRESSURE_B0 0x02 // Pressure LSB Register29#define SPL06_REG_PRESSURE_START SPL06_REG_PRESSURE_B230#define SPL06_PRESSURE_LEN 3 // 24 bits, 3 bytes31#define SPL06_REG_TEMPERATURE_B2 0x03 // Temperature MSB Register32#define SPL06_REG_TEMPERATURE_B1 0x04 // Temperature middle byte Register33#define SPL06_REG_TEMPERATURE_B0 0x05 // Temperature LSB Register34#define SPL06_REG_TEMPERATURE_START SPL06_REG_TEMPERATURE_B235#define SPL06_TEMPERATURE_LEN 3 // 24 bits, 3 bytes36#define SPL06_REG_PRESSURE_CFG 0x06 // Pressure config37#define SPL06_REG_TEMPERATURE_CFG 0x07 // Temperature config38#define SPL06_REG_MODE_AND_STATUS 0x08 // Mode and status39#define SPL06_REG_INT_AND_FIFO_CFG 0x09 // Interrupt and FIFO config40#define SPL06_REG_INT_STATUS 0x0A // Interrupt and FIFO config41#define SPL06_REG_FIFO_STATUS 0x0B // Interrupt and FIFO config42#define SPL06_REG_RST 0x0C // Softreset Register43#define SPL06_REG_CHIP_ID 0x0D // Chip ID Register44#define SPL06_REG_CALIB_COEFFS_START 0x1045#define SPL06_REG_CALIB_COEFFS_END 0x2146#define SPA06_REG_CALIB_COEFFS_END 0x244748// PRESSURE_CFG_REG49#define SPL06_PRES_RATE_32HZ (0x05 << 4)5051// TEMPERATURE_CFG_REG52#define SPL06_TEMP_USE_EXT_SENSOR (1<<7)53#define SPL06_TEMP_RATE_32HZ (0x05 << 4)5455// MODE_AND_STATUS_REG56#define SPL06_MEAS_PRESSURE (1<<0) // measure pressure57#define SPL06_MEAS_TEMPERATURE (1<<1) // measure temperature58#define SPL06_MEAS_CON_PRE_TEM 0x075960#define SPL06_MEAS_CFG_CONTINUOUS (1<<2)61#define SPL06_MEAS_CFG_PRESSURE_RDY (1<<4)62#define SPL06_MEAS_CFG_TEMPERATURE_RDY (1<<5)63#define SPL06_MEAS_CFG_SENSOR_RDY (1<<6)64#define SPL06_MEAS_CFG_COEFFS_RDY (1<<7)6566// INT_AND_FIFO_CFG_REG67#define SPL06_PRESSURE_RESULT_BIT_SHIFT (1<<2) // necessary for pressure oversampling > 868#define SPL06_TEMPERATURE_RESULT_BIT_SHIFT (1<<3) // necessary for temperature oversampling > 86970// Don't set oversampling higher than 8 or the measurement time will be higher than 20ms (timer period)71#define SPL06_PRESSURE_OVERSAMPLING 872#define SPL06_TEMPERATURE_OVERSAMPLING 87374#define SPL06_OVERSAMPLING_TO_REG_VALUE(n) (ffs(n)-1)7576#define SPL06_BACKGROUND_SAMPLE_RATE 327778// enable Background Mode for continuous measurement79#ifndef AP_BARO_SPL06_BACKGROUND_ENABLE80#define AP_BARO_SPL06_BACKGROUND_ENABLE 181#endif8283AP_Baro_SPL06::AP_Baro_SPL06(AP_Baro &baro, AP_HAL::Device &dev)84: AP_Baro_Backend(baro)85, _dev(&dev)86{87}8889AP_Baro_Backend *AP_Baro_SPL06::probe(AP_Baro &baro, AP_HAL::Device &dev)90{91if (dev.bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {92dev.set_read_flag(0x80);93}9495AP_Baro_SPL06 *sensor = NEW_NOTHROW AP_Baro_SPL06(baro, dev);96if (!sensor || !sensor->_init()) {97delete sensor;98return nullptr;99}100return sensor;101}102103bool AP_Baro_SPL06::_init()104{105if (!_dev) {106return false;107}108WITH_SEMAPHORE(_dev->get_semaphore());109110_dev->set_speed(AP_HAL::Device::SPEED_HIGH);111112uint8_t whoami;113114// Sometimes SPL06 has init problems, that's due to failure of reading using SPI for the first time. The SPL06 is a dual115// protocol sensor(I2C and SPI), sometimes it takes one SPI operation to convert it to SPI mode after it starts up.116117for (uint8_t i=0; i<5; i++) {118if (_dev->read_registers(SPL06_REG_CHIP_ID, &whoami, 1)) {119switch(whoami) {120case SPL06_CHIP_ID:121type = Type::SPL06;122break;123case SPA06_CHIP_ID:124type = Type::SPA06;125break;126default:127type = Type::UNKNOWN;128break;129}130}131132if (type != Type::UNKNOWN)133break;134}135136if (type == Type::UNKNOWN) {137return false;138}139140// read the calibration data141uint8_t SPL06_CALIB_COEFFS_LEN = 18;142switch(type) {143case Type::SPL06:144SPL06_CALIB_COEFFS_LEN = SPL06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1;145break;146case Type::SPA06:147SPL06_CALIB_COEFFS_LEN = SPA06_REG_CALIB_COEFFS_END - SPL06_REG_CALIB_COEFFS_START + 1;148break;149default:150break;151}152153bool ready = false;154for (uint8_t i=0; i<5; i++) {155uint8_t status = 0;156if (_dev->read_registers(SPL06_REG_MODE_AND_STATUS, &status, 1)) {157if ((status & 1<<7U) && (status & 1<<6U)) {158ready = true;159break;160}161}162hal.scheduler->delay_microseconds(100);163}164165if (!ready) {166return false;167}168169uint8_t buf[SPL06_CALIB_COEFFS_LEN];170171#define READ_LENGTH 9172173for (uint8_t i = 0; i < ARRAY_SIZE(buf); ) {174ssize_t chunk = MIN(READ_LENGTH, SPL06_CALIB_COEFFS_LEN - i);175if (!_dev->read_registers(SPL06_REG_CALIB_COEFFS_START + i, buf + i, chunk)) {176return false;177}178i += chunk;179}180181// 0x11 c0 [3:0] + 0x10 c0 [11:4]182_c0 = get_twos_complement(((uint32_t)buf[0] << 4) | (((uint32_t)buf[1] >> 4) & 0x0F), 12);183// 0x11 c1 [11:8] + 0x12 c1 [7:0]184_c1 = get_twos_complement((((uint32_t)buf[1] & 0x0F) << 8) | (uint32_t)buf[2], 12);185// 0x13 c00 [19:12] + 0x14 c00 [11:4] + 0x15 c00 [3:0]186_c00 = get_twos_complement(((uint32_t)buf[3] << 12) | ((uint32_t)buf[4] << 4) | (((uint32_t)buf[5] >> 4) & 0x0F), 20);187// 0x15 c10 [19:16] + 0x16 c10 [15:8] + 0x17 c10 [7:0]188_c10 = get_twos_complement((((uint32_t)buf[5] & 0x0F) << 16) | ((uint32_t)buf[6] << 8) | (uint32_t)buf[7], 20);189// 0x18 c01 [15:8] + 0x19 c01 [7:0]190_c01 = get_twos_complement(((uint32_t)buf[8] << 8) | (uint32_t)buf[9], 16);191// 0x1A c11 [15:8] + 0x1B c11 [7:0]192_c11 = get_twos_complement(((uint32_t)buf[10] << 8) | (uint32_t)buf[11], 16);193// 0x1C c20 [15:8] + 0x1D c20 [7:0]194_c20 = get_twos_complement(((uint32_t)buf[12] << 8) | (uint32_t)buf[13], 16);195// 0x1E c21 [15:8] + 0x1F c21 [7:0]196_c21 = get_twos_complement(((uint32_t)buf[14] << 8) | (uint32_t)buf[15], 16);197// 0x20 c30 [15:8] + 0x21 c30 [7:0]198_c30 = get_twos_complement(((uint32_t)buf[16] << 8) | (uint32_t)buf[17], 16);199200if(type == Type::SPA06) {201// 0x23 c31 [3:0] + 0x22 c31 [11:4]202_c31 = get_twos_complement(((uint32_t)buf[18] << 4) | (((uint32_t)buf[19] >> 4) & 0x0F), 12);203// 0x23 c40 [11:8] + 0x24 c40 [7:0]204_c40 = get_twos_complement((((uint32_t)buf[19] & 0x0F) << 8) | (uint32_t)buf[20], 12);205}206207const uint8_t tmp_sensor = (type == Type::SPA06 ? 0 : SPL06_TEMP_USE_EXT_SENSOR);208#if AP_BARO_SPL06_BACKGROUND_ENABLE209// setup temperature and pressure measurements210_dev->setup_checked_registers(4, 20);211212//set rate and oversampling213_dev->write_register(SPL06_REG_TEMPERATURE_CFG, tmp_sensor | SPL06_TEMP_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true);214_dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_PRES_RATE_32HZ | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true);215216//enable background mode217_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_CON_PRE_TEM, true);218#else219// setup temperature and pressure measurements220_dev->setup_checked_registers(3, 20);221222_dev->write_register(SPL06_REG_TEMPERATURE_CFG, tmp_sensor | SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_TEMPERATURE_OVERSAMPLING), true);223_dev->write_register(SPL06_REG_PRESSURE_CFG, SPL06_OVERSAMPLING_TO_REG_VALUE(SPL06_PRESSURE_OVERSAMPLING), true);224#endif //AP_BARO_SPL06_BACKGROUND_ENABLE225226uint8_t int_and_fifo_reg_value = 0;227if (SPL06_TEMPERATURE_OVERSAMPLING > 8) {228int_and_fifo_reg_value |= SPL06_TEMPERATURE_RESULT_BIT_SHIFT;229}230if (SPL06_PRESSURE_OVERSAMPLING > 8) {231int_and_fifo_reg_value |= SPL06_PRESSURE_RESULT_BIT_SHIFT;232}233_dev->write_register(SPL06_REG_INT_AND_FIFO_CFG, int_and_fifo_reg_value, true);234235_instance = _frontend.register_sensor();236237if(type == Type::SPA06) {238_dev->set_device_type(DEVTYPE_BARO_SPA06);239} else {240_dev->set_device_type(DEVTYPE_BARO_SPL06);241}242243set_bus_id(_instance, _dev->get_bus_id());244245// request 50Hz update246_timer_counter = -1;247#if AP_BARO_SPL06_BACKGROUND_ENABLE248_dev->register_periodic_callback(1000000/SPL06_BACKGROUND_SAMPLE_RATE, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void));249#else250_dev->register_periodic_callback(20 * AP_USEC_PER_MSEC, FUNCTOR_BIND_MEMBER(&AP_Baro_SPL06::_timer, void));251#endif //AP_BARO_SPL06_BACKGROUND_ENABLE252253return true;254}255256int32_t AP_Baro_SPL06::raw_value_scale_factor(uint8_t oversampling)257{258// From the datasheet page 13259switch(oversampling)260{261case 1: return 524288;262case 2: return 1572864;263case 4: return 3670016;264case 8: return 7864320;265case 16: return 253952;266case 32: return 516096;267case 64: return 1040384;268case 128: return 2088960;269default: return -1; // invalid270}271}272273// accumulate a new sensor reading274void AP_Baro_SPL06::_timer(void)275{276uint8_t buf[3];277278#if AP_BARO_SPL06_BACKGROUND_ENABLE279_dev->read_registers(SPL06_REG_TEMPERATURE_START, buf, sizeof(buf));280_update_temperature((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));281282_dev->read_registers(SPL06_REG_PRESSURE_START, buf, sizeof(buf));283_update_pressure((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));284#else285//command mode286if ((_timer_counter == -1) || (_timer_counter == 49)) {287// First call and every second start a temperature measurement (50Hz call)288_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_TEMPERATURE, false);289_timer_counter = 0; // Next cycle we are reading the temperature290} else if (_timer_counter == 0) {291// A temperature measurement had been started during the previous call292_dev->read_registers(SPL06_REG_TEMPERATURE_START, buf, sizeof(buf));293_update_temperature((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));294_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_PRESSURE, false);295_timer_counter += 1;296} else {297// The rest of the time read the latest pressure and start a new measurement298_dev->read_registers(SPL06_REG_PRESSURE_START, buf, sizeof(buf));299_update_pressure((int32_t)((buf[0] & 0x80 ? 0xFF000000 : 0) | ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | buf[2]));300_dev->write_register(SPL06_REG_MODE_AND_STATUS, SPL06_MEAS_PRESSURE, false);301_timer_counter += 1;302}303#endif //AP_BARO_SPL06_BACKGROUND_ENABLE304305_dev->check_next_register();306}307308// transfer data to the frontend309void AP_Baro_SPL06::update(void)310{311WITH_SEMAPHORE(_sem);312313if (_pressure_count == 0) {314return;315}316317_copy_to_frontend(_instance, _pressure_sum/_pressure_count, _temperature);318319_pressure_sum = 0;320_pressure_count = 0;321}322323// calculate temperature324void AP_Baro_SPL06::_update_temperature(int32_t temp_raw)325{326_temp_raw = (float)temp_raw / raw_value_scale_factor(SPL06_TEMPERATURE_OVERSAMPLING);327const float temp_comp = (float)_c0 / 2 + _temp_raw * _c1;328329WITH_SEMAPHORE(_sem);330331_temperature = temp_comp;332}333334// calculate pressure335void AP_Baro_SPL06::_update_pressure(int32_t press_raw)336{337const float press_raw_sc = (float)press_raw / raw_value_scale_factor(SPL06_PRESSURE_OVERSAMPLING);338float pressure_cal = 0;339float press_temp_comp = 0;340341switch(type) {342case Type::SPL06:343pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * _c30));344press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * _c21));345break;346case Type::SPA06:347pressure_cal = (float)_c00 + press_raw_sc * ((float)_c10 + press_raw_sc * ((float)_c20 + press_raw_sc * ((float)_c30 + press_raw_sc * _c40)));348press_temp_comp = _temp_raw * ((float)_c01 + press_raw_sc * ((float)_c11 + press_raw_sc * ((float)_c21) + press_raw_sc * _c31));349break;350default:351break;352}353354const float press_comp = pressure_cal + press_temp_comp;355356if (!pressure_ok(press_comp)) {357return;358}359360WITH_SEMAPHORE(_sem);361362_pressure_sum += press_comp;363_pressure_count++;364}365366#endif // AP_BARO_SPL06_ENABLED367368369