AP_InertialSensor: fixes for HAL_GPIO_*

This commit is contained in:
Andrew Tridgell 2014-06-02 09:26:48 +10:00
parent 805d79debe
commit 4c43cd9775
2 changed files with 2 additions and 2 deletions

View File

@ -38,7 +38,7 @@ void setup(void)
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 #if CONFIG_HAL_BOARD == HAL_BOARD_APM2
// we need to stop the barometer from holding the SPI bus // we need to stop the barometer from holding the SPI bus
hal.gpio->pinMode(40, GPIO_OUTPUT); hal.gpio->pinMode(40, HAL_GPIO_OUTPUT);
hal.gpio->write(40, 1); hal.gpio->write(40, 1);
#endif #endif

View File

@ -42,7 +42,7 @@ void setup(void)
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 #if CONFIG_HAL_BOARD == HAL_BOARD_APM2
// we need to stop the barometer from holding the SPI bus // we need to stop the barometer from holding the SPI bus
hal.gpio->pinMode(40, GPIO_OUTPUT); hal.gpio->pinMode(40, HAL_GPIO_OUTPUT);
hal.gpio->write(40, 1); hal.gpio->write(40, 1);
#endif #endif