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 29d8b50b1e..b8f1a70e1b 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 @@ -7,6 +7,7 @@ #include #include #include +#include <../../../AP_HAL_Linux/GPIO.h> #include #include @@ -24,9 +25,14 @@ void setup() hal.scheduler->delay(1000); #if CONFIG_HAL_BOARD == HAL_BOARD_APM2 - hal.gpio->pinMode(63, GPIO_OUTPUT); + hal.gpio->pinMode(63, HAL_GPIO_OUTPUT); hal.gpio->write(63, 1); #endif + +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_ERLE + hal.gpio->pinMode(BBB_P9_28, HAL_GPIO_OUTPUT); + hal.gpio->write(BBB_P9_28, 1); +#endif baro.init(); baro.calibrate();