Browse Source

AP_Baro: fix for HAL_GPIO_*

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
3705c90b8e
  1. 2
      libraries/AP_Baro/AP_Baro_BMP085.cpp
  2. 2
      libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde

2
libraries/AP_Baro/AP_Baro_BMP085.cpp

@ -85,7 +85,7 @@ bool AP_Baro_BMP085::init()
if (!i2c_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) if (!i2c_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER))
return false; return false;
hal.gpio->pinMode(BMP085_EOC, GPIO_INPUT);// End Of Conversion (PC7) input hal.gpio->pinMode(BMP085_EOC, HAL_GPIO_INPUT);// End Of Conversion (PC7) input
// We read the calibration data registers // We read the calibration data registers
if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) { if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) {

2
libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde

@ -23,7 +23,7 @@ void setup()
hal.scheduler->delay(1000); hal.scheduler->delay(1000);
/* What's this for? */ /* What's this for? */
hal.gpio->pinMode(63, GPIO_OUTPUT); hal.gpio->pinMode(63, HAL_GPIO_OUTPUT);
hal.gpio->write(63, 1); hal.gpio->write(63, 1);
baro.init(); baro.init();

Loading…
Cancel
Save