ArduCopter Init: different call to barometer.init based on CONFIG_BARO

* BMP085 has two arguments, second varying on apm1/apm2
* ms5611 has no arguments
This commit is contained in:
Pat Hickey 2011-11-29 20:36:07 -08:00
parent 82b8f4d7b7
commit bd00b629e7

View File

@ -244,11 +244,16 @@ 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
barometer.Init(1, true);
#warning bmp085 for apm2
barometer.init(1, true);
# else
barometer.Init(1, false);
barometer.init(1, false);
# endif // CONFIG_APM_HARDWARE
#endif // CONFIG_BARO
#endif // HIL_MODE