mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_Baro: fix for HAL_GPIO_*
This commit is contained in:
parent
d70bee9249
commit
3705c90b8e
@ -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) {
|
||||
|
@ -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();
|
||||
|
Loading…
Reference in New Issue
Block a user