diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 07d7acaeb2..341f92f88e 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -160,11 +160,15 @@ static AP_Int8 *flight_modes = &g.flight_mode1; AP_Compass_HIL compass; #else - #if CONFIG_BARO == AP_BARO_BMP085 - AP_Baro_BMP085 barometer; - #elif CONFIG_BARO == AP_BARO_MS5611 +#if CONFIG_BARO == AP_BARO_BMP085 +# if CONFIG_HARDWARE == CONFIG_HARDWARE_APM2 + AP_Baro_BMP085 barometer(true); +# else + AP_Baro_BMP085 barometer(false); +# endif +#elif CONFIG_BARO == AP_BARO_MS5611 AP_Baro_MS5611 barometer; - #endif +#endif AP_Compass_HMC5843 compass(Parameters::k_param_compass); #endif diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 92b1e54f7d..283b2db44b 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -250,16 +250,7 @@ static void init_ardupilot() adc.Init(&timer_scheduler); // APM ADC library initialization #endif // CONFIG_ADC -#if CONFIG_BARO == AP_BARO_MS5611 - barometer.init(); -#elif CONFIG_BARO == AP_BARO_BMP085 -# if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 - #warning bmp085 for apm2 - barometer.init(1, true); -# else - barometer.init(1, false); -# endif // CONFIG_APM_HARDWARE -#endif // CONFIG_BARO + barometer.init(&timer_scheduler); #endif // HIL_MODE