diff --git a/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde b/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde index b7de303c6f..7779747c86 100644 --- a/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde +++ b/libraries/AP_InertialNav/examples/AP_InertialNav_test/AP_InertialNav_test.pde @@ -35,13 +35,13 @@ const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; AP_InertialSensor ins; -#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 -AP_Baro_MS5611 baro(&AP_Baro_MS5611::spi); -#else + +#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 AP_ADC_ADS7844 adc; -AP_Baro_BMP085 baro; #endif +AP_Baro baro; + AP_GPS gps; GPS_Glitch gps_glitch(gps); Baro_Glitch baro_glitch(baro);