AP_Baro: BMP085: use DigitalSource interface in BMP085

Use the DigitalSource interface rather than going through the "static"
interface hal.gpio provides
This commit is contained in:
Lucas De Marchi 2015-07-11 17:00:57 -03:00
parent 56fa1b6214
commit e40b88aa70
2 changed files with 5 additions and 3 deletions

View File

@ -48,9 +48,9 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice>
AP_HAL::panic("BMP085: unable to get semaphore");
}
// End Of Conversion (PC7) input
if (BMP085_EOC >= 0) {
hal.gpio->pinMode(BMP085_EOC, HAL_GPIO_INPUT);
_eoc = hal.gpio->channel(BMP085_EOC);
_eoc->mode(HAL_GPIO_INPUT);
}
// We read the calibration data registers
@ -233,7 +233,7 @@ void AP_Baro_BMP085::_calculate()
bool AP_Baro_BMP085::_data_ready()
{
if (BMP085_EOC >= 0) {
return hal.gpio->read(BMP085_EOC);
return _eoc->read();
}
// No EOC pin: use time from last read instead.

View File

@ -1,6 +1,7 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#pragma once
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/utility/OwnPtr.h>
@ -24,6 +25,7 @@ private:
bool _data_ready();
AP_HAL::OwnPtr<AP_HAL::I2CDevice> _dev;
AP_HAL::DigitalSource *_eoc;
uint8_t _instance;
float _temp_sum;