Path: blob/master/libraries/AP_Baro/AP_Baro_LPS2XH.cpp
9537 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_LPS2XH.h"1516#if AP_BARO_LPS2XH_ENABLED1718#include <stdio.h>1920#include <AP_InertialSensor/AP_InertialSensor_Invensense_registers.h>2122extern const AP_HAL::HAL &hal;2324// WHOAMI values25#define LPS22HB_WHOAMI 0xB126#define LPS25HB_WHOAMI 0xBD2728#define REG_ID 0x0F2930#define LPS22H_ID 0xB131#define LPS22H_CTRL_REG1 0x1032#define LPS22H_CTRL_REG2 0x1133#define LPS22H_CTRL_REG3 0x123435#define LPS22H_CTRL_REG1_SIM (1 << 0)36#define LPS22H_CTRL_REG1_BDU (1 << 1)37#define LPS22H_CTRL_REG1_LPFP_CFG (1 << 2)38#define LPS22H_CTRL_REG1_EN_LPFP (1 << 3)39#define LPS22H_CTRL_REG1_PD (0 << 4)40#define LPS22H_CTRL_REG1_ODR_1H (1 << 4)41#define LPS22H_CTRL_REG1_ODR_10HZ (2 << 4)42#define LPS22H_CTRL_REG1_ODR_25HZ (3 << 4)43#define LPS22H_CTRL_REG1_ODR_50HZ (4 << 4)44#define LPS22H_CTRL_REG1_ODR_75HZ (5 << 4)4546#define LPS25H_CTRL_REG1_ADDR 0x2047#define LPS25H_CTRL_REG2_ADDR 0x2148#define LPS25H_CTRL_REG3_ADDR 0x2249#define LPS25H_CTRL_REG4_ADDR 0x2350#define LPS25H_FIFO_CTRL 0x2E51#define TEMP_OUT_ADDR 0x2B52#define PRESS_OUT_XL_ADDR 0x2853#define STATUS_ADDR 0x275455//putting 1 in the MSB of those two registers turns on Auto increment for faster reading.5657AP_Baro_LPS2XH::AP_Baro_LPS2XH(AP_Baro &baro, AP_HAL::Device &dev)58: AP_Baro_Backend(baro)59, _dev(&dev)60{61}6263AP_Baro_Backend *AP_Baro_LPS2XH::probe(AP_Baro &baro, AP_HAL::Device &dev)64{65AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, dev);66if (!sensor || !sensor->_init()) {67delete sensor;68return nullptr;69}7071return sensor;72}7374AP_Baro_Backend *AP_Baro_LPS2XH::probe_InvensenseIMU(AP_Baro &baro,75AP_HAL::Device &dev,76uint8_t imu_address)77{78AP_Baro_LPS2XH *sensor = NEW_NOTHROW AP_Baro_LPS2XH(baro, dev);79if (sensor) {80if (!sensor->_imu_i2c_init(imu_address)) {81delete sensor;82return nullptr;83}84}8586if (!sensor || !sensor->_init()) {87delete sensor;88return nullptr;89}9091return sensor;92}9394/*95setup invensense IMU to enable barometer, assuming both IMU and baro96on the same i2c bus97*/98bool AP_Baro_LPS2XH::_imu_i2c_init(uint8_t imu_address)99{100_dev->get_semaphore()->take_blocking();101102// as the baro device is already locked we need to re-use it,103// changing its address to match the IMU address104uint8_t old_address = _dev->get_bus_address();105_dev->set_address(imu_address);106107_dev->set_retries(4);108109uint8_t whoami=0;110_dev->read_registers(MPUREG_WHOAMI, &whoami, 1);111DEV_PRINTF("IMU: whoami 0x%02x old_address=%02x\n", whoami, old_address);112113_dev->write_register(MPUREG_FIFO_EN, 0x00);114_dev->write_register(MPUREG_PWR_MGMT_1, BIT_PWR_MGMT_1_CLK_XGYRO);115116// wait for sensor to settle117hal.scheduler->delay(10);118119_dev->write_register(MPUREG_INT_PIN_CFG, BIT_BYPASS_EN);120121_dev->set_address(old_address);122123_dev->get_semaphore()->give();124125return true;126}127128bool AP_Baro_LPS2XH::_init()129{130if (!_dev) {131return false;132}133_dev->get_semaphore()->take_blocking();134135_dev->set_speed(AP_HAL::Device::SPEED_HIGH);136137// top bit is for read on SPI138if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {139_dev->set_read_flag(0x80);140}141142if (!_check_whoami()) {143_dev->get_semaphore()->give();144return false;145}146147//init control registers.148if (_lps2xh_type == BARO_LPS25H) {149_dev->write_register(LPS25H_CTRL_REG1_ADDR,0x00); // turn off for config150_dev->write_register(LPS25H_CTRL_REG2_ADDR,0x00); //FIFO Disabled151_dev->write_register(LPS25H_FIFO_CTRL, 0x01);152_dev->write_register(LPS25H_CTRL_REG1_ADDR,0xc0);153154// request 25Hz update (maximum refresh Rate according to datasheet)155CallTime = 40 * AP_USEC_PER_MSEC;156}157158if (_lps2xh_type == BARO_LPS22H) {159_dev->write_register(LPS22H_CTRL_REG1, 0x00); // turn off for config160_dev->write_register(LPS22H_CTRL_REG1, LPS22H_CTRL_REG1_ODR_75HZ|LPS22H_CTRL_REG1_BDU|LPS22H_CTRL_REG1_EN_LPFP|LPS22H_CTRL_REG1_LPFP_CFG);161if (_dev->bus_type() == AP_HAL::Device::BUS_TYPE_SPI) {162_dev->write_register(LPS22H_CTRL_REG2, 0x18); // disable i2c163} else {164_dev->write_register(LPS22H_CTRL_REG2, 0x10);165}166167// request 75Hz update168CallTime = 1000000/75;169}170171_instance = _frontend.register_sensor();172173_dev->set_device_type(DEVTYPE_BARO_LPS2XH);174set_bus_id(_instance, _dev->get_bus_id());175176_dev->get_semaphore()->give();177178_dev->register_periodic_callback(CallTime, FUNCTOR_BIND_MEMBER(&AP_Baro_LPS2XH::_timer, void));179180return true;181}182183//check ID184bool AP_Baro_LPS2XH::_check_whoami(void)185{186uint8_t whoami;187if (!_dev->read_registers(REG_ID, &whoami, 1)) {188return false;189}190DEV_PRINTF("LPS2XH whoami 0x%02x\n", whoami);191192switch(whoami){193case LPS22HB_WHOAMI:194_lps2xh_type = BARO_LPS22H;195return true;196case LPS25HB_WHOAMI:197_lps2xh_type = BARO_LPS25H;198return true;199}200201return false;202}203204// accumulate a new sensor reading205void AP_Baro_LPS2XH::_timer(void)206{207uint8_t status;208// use status to check if data is available209if (!_dev->read_registers(STATUS_ADDR, &status, 1)) {210return;211}212213if (status & 0x02) {214_update_temperature();215}216217if (status & 0x01) {218_update_pressure();219}220}221222// transfer data to the frontend223void AP_Baro_LPS2XH::update(void)224{225if (_pressure_count == 0) {226return;227}228229WITH_SEMAPHORE(_sem);230_copy_to_frontend(_instance, _pressure_sum/_pressure_count, _temperature);231_pressure_sum = 0;232_pressure_count = 0;233}234235// calculate temperature236void AP_Baro_LPS2XH::_update_temperature(void)237{238uint8_t pu8[2];239if (!_dev->read_registers(TEMP_OUT_ADDR, pu8, 2)) {240return;241}242int16_t Temp_Reg_s16 = (uint16_t)(pu8[1]<<8) | pu8[0];243244WITH_SEMAPHORE(_sem);245246if (_lps2xh_type == BARO_LPS25H) {247_temperature = (Temp_Reg_s16 * (1.0/480)) + 42.5;248}249250if (_lps2xh_type == BARO_LPS22H) {251_temperature = Temp_Reg_s16 * 0.01;252}253}254255// calculate pressure256void AP_Baro_LPS2XH::_update_pressure(void)257{258uint8_t pressure[3];259if (!_dev->read_registers(PRESS_OUT_XL_ADDR, pressure, 3)) {260return;261}262263int32_t Pressure_Reg_s32 = ((uint32_t)pressure[2]<<16)|((uint32_t)pressure[1]<<8)|(uint32_t)pressure[0];264int32_t Pressure_mb = Pressure_Reg_s32 * (100.0f / 4096); // scale for pa265266WITH_SEMAPHORE(_sem);267_pressure_sum += Pressure_mb;268_pressure_count++;269}270271#endif // AP_BARO_LPS2XH_ENABLED272273274