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_BMP085.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_BMP085.h"1516#if AP_BARO_BMP085_ENABLED1718#include <utility>19#include <stdio.h>2021#include <AP_Common/AP_Common.h>22#include <AP_HAL/AP_HAL.h>2324extern const AP_HAL::HAL &hal;2526#define BMP085_OVERSAMPLING_ULTRALOWPOWER 027#define BMP085_OVERSAMPLING_STANDARD 128#define BMP085_OVERSAMPLING_HIGHRES 229#define BMP085_OVERSAMPLING_ULTRAHIGHRES 33031#ifndef BMP085_EOC32#define BMP085_EOC -133#define OVERSAMPLING BMP085_OVERSAMPLING_ULTRAHIGHRES34#else35#define OVERSAMPLING BMP085_OVERSAMPLING_HIGHRES36#endif3738AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)39: AP_Baro_Backend(baro)40, _dev(std::move(dev))41{ }4243AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)44{4546if (!dev) {47return nullptr;48}4950AP_Baro_BMP085 *sensor = NEW_NOTHROW AP_Baro_BMP085(baro, std::move(dev));51if (!sensor || !sensor->_init()) {52delete sensor;53return nullptr;54}55return sensor;5657}5859bool AP_Baro_BMP085::_init()60{61if (!_dev) {62return false;63}64union {65uint8_t buff[22];66uint16_t wb[11];67} bb;6869// get pointer to i2c bus semaphore70AP_HAL::Semaphore *sem = _dev->get_semaphore();7172// take i2c bus semaphore73WITH_SEMAPHORE(sem);7475if (BMP085_EOC >= 0) {76_eoc = hal.gpio->channel(BMP085_EOC);77_eoc->mode(HAL_GPIO_INPUT);78}798081uint8_t id;8283if (!_dev->read_registers(0xD0, &id, 1)) {84return false;85}8687if (id!=0x55) {88return false; // not BMP18089}909192_dev->read_registers(0xD1, &_vers, 1);9394bool prom_ok=false;95_type=0;9697// We read the calibration data registers98if (_dev->read_registers(0xAA, bb.buff, sizeof(bb.buff))) {99prom_ok=true;100101}102103if (!prom_ok) {104if (_read_prom((uint16_t *)&bb.wb[0])) { // BMP180 requires reads by 2 bytes105prom_ok=true;106_type=1;107}108}109if (!prom_ok) {110return false;111}112113ac1 = ((int16_t)bb.buff[0] << 8) | bb.buff[1];114ac2 = ((int16_t)bb.buff[2] << 8) | bb.buff[3];115ac3 = ((int16_t)bb.buff[4] << 8) | bb.buff[5];116ac4 = ((int16_t)bb.buff[6] << 8) | bb.buff[7];117ac5 = ((int16_t)bb.buff[8] << 8) | bb.buff[9];118ac6 = ((int16_t)bb.buff[10]<< 8) | bb.buff[11];119b1 = ((int16_t)bb.buff[12] << 8) | bb.buff[13];120b2 = ((int16_t)bb.buff[14] << 8) | bb.buff[15];121mb = ((int16_t)bb.buff[16] << 8) | bb.buff[17];122mc = ((int16_t)bb.buff[18] << 8) | bb.buff[19];123md = ((int16_t)bb.buff[20] << 8) | bb.buff[21];124125if ((ac1==0 || ac1==-1) ||126(ac2==0 || ac2==-1) ||127(ac3==0 || ac3==-1) ||128(ac4==0 || ac4==0xFFFF) ||129(ac5==0 || ac5==0xFFFF) ||130(ac6==0 || ac6==0xFFFF)) {131return false;132}133134_last_press_read_command_time = 0;135_last_temp_read_command_time = 0;136137// Send a command to read temperature138_cmd_read_temp();139140_state = 0;141142_instance = _frontend.register_sensor();143144_dev->set_device_type(DEVTYPE_BARO_BMP085);145set_bus_id(_instance, _dev->get_bus_id());146147_dev->register_periodic_callback(20000, FUNCTOR_BIND_MEMBER(&AP_Baro_BMP085::_timer, void));148return true;149}150151uint16_t AP_Baro_BMP085::_read_prom_word(uint8_t word)152{153const uint8_t reg = 0xAA + (word << 1);154uint8_t val[2];155if (!_dev->transfer(®, 1, val, sizeof(val))) {156return 0;157}158return (val[0] << 8) | val[1];159}160161bool AP_Baro_BMP085::_read_prom(uint16_t *prom)162{163bool all_zero = true;164for (uint8_t i = 0; i < 11; i++) {165prom[i] = _read_prom_word(i);166if (prom[i] != 0) {167all_zero = false;168}169}170171if (all_zero) {172return false;173}174175return true;176}177178/*179This is a state machine. Accumulate a new sensor reading.180*/181void AP_Baro_BMP085::_timer(void)182{183if (!_data_ready()) {184return;185}186187if (_state == 0) {188_read_temp();189} else if (_read_pressure()) {190_calculate();191}192193_state++;194if (_state == 25) {195_state = 0;196_cmd_read_temp();197} else {198_cmd_read_pressure();199}200}201202/*203transfer data to the frontend204*/205void AP_Baro_BMP085::update(void)206{207WITH_SEMAPHORE(_sem);208209if (!_has_sample) {210return;211}212213float temperature = 0.1f * _temp;214float pressure = _pressure_filter.getf();215216_copy_to_frontend(_instance, pressure, temperature);217}218219// Send command to Read Pressure220void AP_Baro_BMP085::_cmd_read_pressure()221{222_dev->write_register(0xF4, 0x34 + (OVERSAMPLING << 6));223_last_press_read_command_time = AP_HAL::millis();224}225226// Read raw pressure values227bool AP_Baro_BMP085::_read_pressure()228{229uint8_t buf[3];230if (_dev->read_registers(0xF6, buf, sizeof(buf))) {231_raw_pressure = (((uint32_t)buf[0] << 16)232| ((uint32_t)buf[1] << 8)233| ((uint32_t)buf[2])) >> (8 - OVERSAMPLING);234return true;235}236237uint8_t xlsb;238if (_dev->read_registers(0xF6, buf, 2) && _dev->read_registers(0xF8, &xlsb, 1)) {239_raw_pressure = (((uint32_t)buf[0] << 16)240| ((uint32_t)buf[1] << 8)241| ((uint32_t)xlsb)) >> (8 - OVERSAMPLING);242return true;243}244245_last_press_read_command_time = AP_HAL::millis() + 1000;246_dev->set_speed(AP_HAL::Device::SPEED_LOW);247return false;248}249250// Send Command to Read Temperature251void AP_Baro_BMP085::_cmd_read_temp()252{253_dev->write_register(0xF4, 0x2E);254_last_temp_read_command_time = AP_HAL::millis();255}256257// Read raw temperature values258void AP_Baro_BMP085::_read_temp()259{260uint8_t buf[2];261int32_t _temp_sensor;262263if (!_dev->read_registers(0xF6, buf, sizeof(buf))) {264_dev->set_speed(AP_HAL::Device::SPEED_LOW);265return;266}267_temp_sensor = buf[0];268_temp_sensor = (_temp_sensor << 8) | buf[1];269270_raw_temp = _temp_sensor;271}272273// _calculate Temperature and Pressure in real units.274void AP_Baro_BMP085::_calculate()275{276int32_t x1, x2, x3, b3, b5, b6, p;277uint32_t b4, b7;278int32_t tmp;279280// See Datasheet page 13 for this formulas281// Based also on Jee Labs BMP085 example code. Thanks for share.282// Temperature calculations283x1 = ((int32_t)_raw_temp - ac6) * ac5 >> 15;284x2 = ((int32_t) mc << 11) / (x1 + md);285b5 = x1 + x2;286_temp = (b5 + 8) >> 4;287288// Pressure calculations289b6 = b5 - 4000;290x1 = (b2 * (b6 * b6 >> 12)) >> 11;291x2 = ac2 * b6 >> 11;292x3 = x1 + x2;293//b3 = (((int32_t) ac1 * 4 + x3)<<OVERSAMPLING + 2) >> 2; // BAD294//b3 = ((int32_t) ac1 * 4 + x3 + 2) >> 2; //OK for OVERSAMPLING=0295tmp = ac1;296tmp = (tmp*4 + x3)<<OVERSAMPLING;297b3 = (tmp+2)/4;298x1 = ac3 * b6 >> 13;299x2 = (b1 * (b6 * b6 >> 12)) >> 16;300x3 = ((x1 + x2) + 2) >> 2;301b4 = (ac4 * (uint32_t)(x3 + 32768)) >> 15;302b7 = ((uint32_t) _raw_pressure - b3) * (50000 >> OVERSAMPLING);303p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;304305x1 = (p >> 8) * (p >> 8);306x1 = (x1 * 3038) >> 16;307x2 = (-7357 * p) >> 16;308p += ((x1 + x2 + 3791) >> 4);309310if (!pressure_ok(p)) {311return;312}313314WITH_SEMAPHORE(_sem);315316_pressure_filter.apply(p);317_has_sample = true;318}319320bool AP_Baro_BMP085::_data_ready()321{322if (BMP085_EOC >= 0) {323return _eoc->read();324}325326// No EOC pin: use time from last read instead.327if (_state == 0) {328return AP_HAL::millis() - _last_temp_read_command_time > 5u;329}330331uint32_t conversion_time_msec;332333switch (OVERSAMPLING) {334case BMP085_OVERSAMPLING_ULTRALOWPOWER:335conversion_time_msec = 5;336break;337case BMP085_OVERSAMPLING_STANDARD:338conversion_time_msec = 8;339break;340case BMP085_OVERSAMPLING_HIGHRES:341conversion_time_msec = 14;342break;343case BMP085_OVERSAMPLING_ULTRAHIGHRES:344conversion_time_msec = 26;345break;346default:347break;348}349350return AP_HAL::millis() - _last_press_read_command_time > conversion_time_msec;351}352353#endif // AP_BARO_BMP085_ENABLED354355356