Path: blob/master/libraries/AP_Baro/AP_Baro_BMP085.cpp
9592 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_BMP085.h"1516#if AP_BARO_BMP085_ENABLED1718#include <stdio.h>1920#include <AP_Common/AP_Common.h>21#include <AP_HAL/AP_HAL.h>2223extern const AP_HAL::HAL &hal;2425#define BMP085_OVERSAMPLING_ULTRALOWPOWER 026#define BMP085_OVERSAMPLING_STANDARD 127#define BMP085_OVERSAMPLING_HIGHRES 228#define BMP085_OVERSAMPLING_ULTRAHIGHRES 32930#ifndef BMP085_EOC31#define BMP085_EOC -132#define OVERSAMPLING BMP085_OVERSAMPLING_ULTRAHIGHRES33#else34#define OVERSAMPLING BMP085_OVERSAMPLING_HIGHRES35#endif3637AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::Device &dev)38: AP_Baro_Backend(baro)39, _dev(&dev)40{ }4142AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::Device &dev)43{44AP_Baro_BMP085 *sensor = NEW_NOTHROW AP_Baro_BMP085(baro, dev);45if (!sensor || !sensor->_init()) {46delete sensor;47return nullptr;48}49return sensor;5051}5253bool AP_Baro_BMP085::_init()54{55if (!_dev) {56return false;57}58union {59uint8_t buff[22];60uint16_t wb[11];61} bb;6263// get pointer to i2c bus semaphore64AP_HAL::Semaphore *sem = _dev->get_semaphore();6566// take i2c bus semaphore67WITH_SEMAPHORE(sem);6869if (BMP085_EOC >= 0) {70_eoc = hal.gpio->channel(BMP085_EOC);71_eoc->mode(HAL_GPIO_INPUT);72}737475uint8_t id;7677if (!_dev->read_registers(0xD0, &id, 1)) {78return false;79}8081if (id!=0x55) {82return false; // not BMP18083}848586_dev->read_registers(0xD1, &_vers, 1);8788bool prom_ok=false;89_type=0;9091// We read the calibration data registers92if (_dev->read_registers(0xAA, bb.buff, sizeof(bb.buff))) {93prom_ok=true;9495}9697if (!prom_ok) {98if (_read_prom((uint16_t *)&bb.wb[0])) { // BMP180 requires reads by 2 bytes99prom_ok=true;100_type=1;101}102}103if (!prom_ok) {104return false;105}106107ac1 = ((int16_t)bb.buff[0] << 8) | bb.buff[1];108ac2 = ((int16_t)bb.buff[2] << 8) | bb.buff[3];109ac3 = ((int16_t)bb.buff[4] << 8) | bb.buff[5];110ac4 = ((int16_t)bb.buff[6] << 8) | bb.buff[7];111ac5 = ((int16_t)bb.buff[8] << 8) | bb.buff[9];112ac6 = ((int16_t)bb.buff[10]<< 8) | bb.buff[11];113b1 = ((int16_t)bb.buff[12] << 8) | bb.buff[13];114b2 = ((int16_t)bb.buff[14] << 8) | bb.buff[15];115mb = ((int16_t)bb.buff[16] << 8) | bb.buff[17];116mc = ((int16_t)bb.buff[18] << 8) | bb.buff[19];117md = ((int16_t)bb.buff[20] << 8) | bb.buff[21];118119if ((ac1==0 || ac1==-1) ||120(ac2==0 || ac2==-1) ||121(ac3==0 || ac3==-1) ||122(ac4==0 || ac4==0xFFFF) ||123(ac5==0 || ac5==0xFFFF) ||124(ac6==0 || ac6==0xFFFF)) {125return false;126}127128_last_press_read_command_time = 0;129_last_temp_read_command_time = 0;130131// Send a command to read temperature132_cmd_read_temp();133134_state = 0;135136_instance = _frontend.register_sensor();137138_dev->set_device_type(DEVTYPE_BARO_BMP085);139set_bus_id(_instance, _dev->get_bus_id());140141_dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP085::_timer, void));142return true;143}144145uint16_t AP_Baro_BMP085::_read_prom_word(uint8_t word)146{147const uint8_t reg = 0xAA + (word << 1);148uint8_t val[2];149if (!_dev->transfer(®, 1, val, sizeof(val))) {150return 0;151}152return (val[0] << 8) | val[1];153}154155bool AP_Baro_BMP085::_read_prom(uint16_t *prom)156{157bool all_zero = true;158for (uint8_t i = 0; i < 11; i++) {159prom[i] = _read_prom_word(i);160if (prom[i] != 0) {161all_zero = false;162}163}164165if (all_zero) {166return false;167}168169return true;170}171172/*173This is a state machine. Accumulate a new sensor reading.174*/175void AP_Baro_BMP085::_timer(void)176{177if (!_data_ready()) {178return;179}180181if (_state == 0) {182_read_temp();183} else if (_read_pressure()) {184_calculate();185}186187_state++;188if (_state == 25) {189_state = 0;190_cmd_read_temp();191} else {192_cmd_read_pressure();193}194}195196/*197transfer data to the frontend198*/199void AP_Baro_BMP085::update(void)200{201WITH_SEMAPHORE(_sem);202203if (!_has_sample) {204return;205}206207float temperature = 0.1f * _temp;208float pressure = _pressure_filter.getf();209210_copy_to_frontend(_instance, pressure, temperature);211}212213// Send command to Read Pressure214void AP_Baro_BMP085::_cmd_read_pressure()215{216_dev->write_register(0xF4, 0x34 + (OVERSAMPLING << 6));217_last_press_read_command_time = AP_HAL::millis();218}219220// Read raw pressure values221bool AP_Baro_BMP085::_read_pressure()222{223uint8_t buf[3];224if (_dev->read_registers(0xF6, buf, sizeof(buf))) {225_raw_pressure = (((uint32_t)buf[0] << 16)226| ((uint32_t)buf[1] << 8)227| ((uint32_t)buf[2])) >> (8 - OVERSAMPLING);228return true;229}230231uint8_t xlsb;232if (_dev->read_registers(0xF6, buf, 2) && _dev->read_registers(0xF8, &xlsb, 1)) {233_raw_pressure = (((uint32_t)buf[0] << 16)234| ((uint32_t)buf[1] << 8)235| ((uint32_t)xlsb)) >> (8 - OVERSAMPLING);236return true;237}238239_last_press_read_command_time = AP_HAL::millis() + 1000;240_dev->set_speed(AP_HAL::Device::SPEED_LOW);241return false;242}243244// Send Command to Read Temperature245void AP_Baro_BMP085::_cmd_read_temp()246{247_dev->write_register(0xF4, 0x2E);248_last_temp_read_command_time = AP_HAL::millis();249}250251// Read raw temperature values252void AP_Baro_BMP085::_read_temp()253{254uint8_t buf[2];255int32_t _temp_sensor;256257if (!_dev->read_registers(0xF6, buf, sizeof(buf))) {258_dev->set_speed(AP_HAL::Device::SPEED_LOW);259return;260}261_temp_sensor = buf[0];262_temp_sensor = (_temp_sensor << 8) | buf[1];263264_raw_temp = _temp_sensor;265}266267// _calculate Temperature and Pressure in real units.268void AP_Baro_BMP085::_calculate()269{270int32_t x1, x2, x3, b3, b5, b6, p;271uint32_t b4, b7;272int32_t tmp;273274// See Datasheet page 13 for this formulas275// Based also on Jee Labs BMP085 example code. Thanks for share.276// Temperature calculations277x1 = ((int32_t)_raw_temp - ac6) * ac5 >> 15;278x2 = ((int32_t) mc << 11) / (x1 + md);279b5 = x1 + x2;280_temp = (b5 + 8) >> 4;281282// Pressure calculations283b6 = b5 - 4000;284x1 = (b2 * (b6 * b6 >> 12)) >> 11;285x2 = ac2 * b6 >> 11;286x3 = x1 + x2;287//b3 = (((int32_t) ac1 * 4 + x3)<<OVERSAMPLING + 2) >> 2; // BAD288//b3 = ((int32_t) ac1 * 4 + x3 + 2) >> 2; //OK for OVERSAMPLING=0289tmp = ac1;290tmp = (tmp*4 + x3)<<OVERSAMPLING;291b3 = (tmp+2)/4;292x1 = ac3 * b6 >> 13;293x2 = (b1 * (b6 * b6 >> 12)) >> 16;294x3 = ((x1 + x2) + 2) >> 2;295b4 = (ac4 * (uint32_t)(x3 + 32768)) >> 15;296b7 = ((uint32_t) _raw_pressure - b3) * (50000 >> OVERSAMPLING);297p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;298299x1 = (p >> 8) * (p >> 8);300x1 = (x1 * 3038) >> 16;301x2 = (-7357 * p) >> 16;302p += ((x1 + x2 + 3791) >> 4);303304if (!pressure_ok(p)) {305return;306}307308WITH_SEMAPHORE(_sem);309310_pressure_filter.apply(p);311_has_sample = true;312}313314bool AP_Baro_BMP085::_data_ready()315{316if (BMP085_EOC >= 0) {317return _eoc->read();318}319320// No EOC pin: use time from last read instead.321if (_state == 0) {322return AP_HAL::millis() - _last_temp_read_command_time > 5u;323}324325uint32_t conversion_time_msec;326327switch (OVERSAMPLING) {328case BMP085_OVERSAMPLING_ULTRALOWPOWER:329conversion_time_msec = 5;330break;331case BMP085_OVERSAMPLING_STANDARD:332conversion_time_msec = 8;333break;334case BMP085_OVERSAMPLING_HIGHRES:335conversion_time_msec = 14;336break;337case BMP085_OVERSAMPLING_ULTRAHIGHRES:338conversion_time_msec = 26;339break;340default:341break;342}343344return AP_HAL::millis() - _last_press_read_command_time > conversion_time_msec;345}346347#endif // AP_BARO_BMP085_ENABLED348349350