AP_Baro: remove checks for HAL_BOARD_APM2 and HAL_BOARD_APM1

This commit is contained in:
Lucas De Marchi 2015-11-03 11:46:29 -02:00 committed by Andrew Tridgell
parent 221d822573
commit 4bd8b2ae35
3 changed files with 13 additions and 23 deletions

View File

@ -28,20 +28,16 @@
extern const AP_HAL::HAL& hal;
#define BMP085_ADDRESS 0x77 //(0xEE >> 1)
#define BMP085_EOC 30 // End of conversion pin PC7 on APM1
// the apm2 hardware needs to check the state of the
// chip using a direct IO port
// On APM2 prerelease hw, the data ready port is hooked up to PE7, which
// is not available to the arduino digitalRead function.
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
#define BMP_DATA_READY() hal.gpio->read(BMP085_EOC)
#else
#ifndef BMP085_EOC
// No EOC connection from Baro
// Use times instead.
// Temp conversion time is 4.5ms
// Pressure conversion time is 25.5ms (for OVERSAMPLING=3)
#define BMP085_EOC -1
#define BMP_DATA_READY() (BMP085_State == 0 ? hal.scheduler->millis() > (_last_temp_read_command_time + 5) : hal.scheduler->millis() > (_last_press_read_command_time + 26))
#else
#define BMP_DATA_READY() hal.gpio->read(BMP085_EOC)
#endif
// oversampling 3 gives 26ms conversion time. We then average
@ -72,7 +68,9 @@ AP_Baro_BMP085::AP_Baro_BMP085(AP_Baro &baro) :
}
// End Of Conversion (PC7) input
if (BMP085_EOC >= 0) {
hal.gpio->pinMode(BMP085_EOC, HAL_GPIO_INPUT);
}
// We read the calibration data registers
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) {

View File

@ -384,10 +384,9 @@ void AP_Baro_MS5611::_calculate()
// Formulas from manufacturer datasheet
// sub -15c temperature compensation is not included
// we do the calculations using floating point
// as this is much faster on an AVR2560, and also allows
// us to take advantage of the averaging of D1 and D1 over
// multiple samples, giving us more precision
// we do the calculations using floating point allows us to take advantage
// of the averaging of D1 and D1 over multiple samples, giving us more
// precision
dT = _D2-(((uint32_t)_C5)<<8);
TEMP = (dT * _C6)/8388608;
OFF = _C2 * 65536.0f + (_C4 * dT) / 128;
@ -424,10 +423,9 @@ void AP_Baro_MS5607::_calculate()
// Formulas from manufacturer datasheet
// sub -15c temperature compensation is not included
// we do the calculations using floating point
// as this is much faster on an AVR2560, and also allows
// us to take advantage of the averaging of D1 and D1 over
// multiple samples, giving us more precision
// we do the calculations using floating point allows us to take advantage
// of the averaging of D1 and D1 over multiple samples, giving us more
// precision
dT = _D2-(((uint32_t)_C5)<<8);
TEMP = (dT * _C6)/8388608;
OFF = _C2 * 131072.0f + (_C4 * dT) / 64;

View File

@ -18,12 +18,6 @@ void setup()
hal.scheduler->delay(1000);
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
// disable CS on MPU6000
hal.gpio->pinMode(63, HAL_GPIO_OUTPUT);
hal.gpio->write(63, 1);
#endif
barometer.init();
barometer.calibrate();