AP_Baro: ran BMP085 driver through code formatter

This commit is contained in:
Andrew Tridgell 2018-02-05 11:33:00 +11:00
parent 2c043b822b
commit 83d1e71cb2
2 changed files with 28 additions and 25 deletions

View File

@ -38,7 +38,7 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev
, _dev(std::move(dev))
{ }
AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev)
{
if (!dev) {
@ -51,7 +51,7 @@ AP_Baro_Backend * AP_Baro_BMP085::probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::De
return nullptr;
}
return sensor;
}
bool AP_Baro_BMP085::_init()
@ -76,13 +76,15 @@ bool AP_Baro_BMP085::_init()
uint8_t id;
if (!_dev->read_registers(0xD0, &id, 1)) {
sem->give();
return false;
}
if(id!=0x55) return false; // not BMP180
if (id!=0x55) {
return false; // not BMP180
}
_dev->read_registers(0xD1, &_vers, 1);
@ -93,16 +95,16 @@ bool AP_Baro_BMP085::_init()
// We read the calibration data registers
if (_dev->read_registers(0xAA, bb.buff, sizeof(bb.buff))) {
prom_ok=true;
}
if(!prom_ok){
if(_read_prom((uint16_t *)&bb.wb[0])) { // BMP180 requires reads by 2 bytes
if (!prom_ok) {
if (_read_prom((uint16_t *)&bb.wb[0])) { // BMP180 requires reads by 2 bytes
prom_ok=true;
_type=1;
}
}
if(!prom_ok){
}
if (!prom_ok) {
sem->give();
return false;
}
@ -118,13 +120,15 @@ bool AP_Baro_BMP085::_init()
mb = ((int16_t)bb.buff[16] << 8) | bb.buff[17];
mc = ((int16_t)bb.buff[18] << 8) | bb.buff[19];
md = ((int16_t)bb.buff[20] << 8) | bb.buff[21];
if( (ac1==0 || ac1==-1) ||
if ((ac1==0 || ac1==-1) ||
(ac2==0 || ac2==-1) ||
(ac3==0 || ac3==-1) ||
(ac4==0 || ac4==0xFFFF) ||
(ac5==0 || ac5==0xFFFF) ||
(ac6==0 || ac6==0xFFFF) ) return false;
(ac6==0 || ac6==0xFFFF)) {
return false;
}
_last_press_read_command_time = 0;
_last_temp_read_command_time = 0;
@ -161,7 +165,7 @@ bool AP_Baro_BMP085::_read_prom(uint16_t *prom)
all_zero = false;
}
}
if (all_zero) {
return false;
}
@ -231,10 +235,10 @@ bool AP_Baro_BMP085::_read_pressure()
}
uint8_t xlsb;
if (_dev->read_registers(0xF6, buf, 2) && _dev->read_registers(0xF8, &xlsb, 1) ) {
if (_dev->read_registers(0xF6, buf, 2) && _dev->read_registers(0xF8, &xlsb, 1)) {
_raw_pressure = (((uint32_t)buf[0] << 16)
| ((uint32_t)buf[1] << 8)
| ((uint32_t)xlsb)) >> (8 - OVERSAMPLING);
| ((uint32_t)buf[1] << 8)
| ((uint32_t)xlsb)) >> (8 - OVERSAMPLING);
return true;
}
@ -294,7 +298,7 @@ void AP_Baro_BMP085::_calculate()
x1 = ac3 * b6 >> 13;
x2 = (b1 * (b6 * b6 >> 12)) >> 16;
x3 = ((x1 + x2) + 2) >> 2;
b4 = (ac4 * (uint32_t) (x3 + 32768)) >> 15;
b4 = (ac4 * (uint32_t)(x3 + 32768)) >> 15;
b7 = ((uint32_t) _raw_pressure - b3) * (50000 >> OVERSAMPLING);
p = b7 < 0x80000000 ? (b7 * 2) / b4 : (b7 / b4) * 2;

View File

@ -8,19 +8,18 @@
#include "AP_Baro_Backend.h"
#ifndef HAL_BARO_BMP085_I2C_ADDR
#define HAL_BARO_BMP085_I2C_ADDR (0x77)
#define HAL_BARO_BMP085_I2C_ADDR (0x77)
#endif
class AP_Baro_BMP085 : public AP_Baro_Backend
{
class AP_Baro_BMP085 : public AP_Baro_Backend {
public:
AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
/* AP_Baro public interface: */
void update();
static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::Device> dev);
private:
bool _init();
@ -59,7 +58,7 @@ private:
int32_t _raw_temp;
int32_t _temp;
AverageIntegralFilter<int32_t, int32_t, 10> _pressure_filter;
uint8_t _vers;
uint8_t _type;
uint8_t _type;
};