diff --git a/libraries/AP_Baro/AP_Baro_BMP085.cpp b/libraries/AP_Baro/AP_Baro_BMP085.cpp index 72bc3caea2..36a6b96d3b 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP085.cpp @@ -85,7 +85,7 @@ bool AP_Baro_BMP085::init() if (!i2c_sem->take(HAL_SEMAPHORE_BLOCK_FOREVER)) 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 if (hal.i2c->readRegisters(BMP085_ADDRESS, 0xAA, 22, buff) != 0) { diff --git a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde index 3abf274fb4..fc2a70961c 100644 --- a/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde +++ b/libraries/AP_Baro/examples/AP_Baro_MS5611_test/AP_Baro_MS5611_test.pde @@ -23,7 +23,7 @@ void setup() hal.scheduler->delay(1000); /* What's this for? */ - hal.gpio->pinMode(63, GPIO_OUTPUT); + hal.gpio->pinMode(63, HAL_GPIO_OUTPUT); hal.gpio->write(63, 1); baro.init();