mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: update AP_Baro construtors and initializers
This commit is contained in:
parent
067724b4f1
commit
85b82e75f6
|
@ -137,7 +137,17 @@ static AP_ADC_ADS7844 adc;
|
|||
AP_Baro_BMP085_HIL barometer;
|
||||
AP_Compass_HIL compass;
|
||||
#else
|
||||
static AP_Baro_BMP085 barometer;
|
||||
|
||||
#if CONFIG_BARO == AP_BARO_BMP085
|
||||
# if CONFIG_HARDWARE == CONFIG_HARDWARE_APM2
|
||||
static AP_Baro_BMP085 barometer(true);
|
||||
# else
|
||||
static AP_Baro_BMP085 barometer(false);
|
||||
# endif
|
||||
#elif CONFIG_BARO == AP_BARO_MS5611
|
||||
static AP_Baro_MS5611 barometer;
|
||||
#endif
|
||||
|
||||
static AP_Compass_HMC5843 compass(Parameters::k_param_compass);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -177,11 +177,7 @@ static void init_ardupilot()
|
|||
|
||||
adc.Init(&timer_scheduler); // APM ADC library initialization
|
||||
|
||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
|
||||
barometer.Init(1, true);
|
||||
#else
|
||||
barometer.Init(1, false);
|
||||
#endif
|
||||
barometer.init(&timer_scheduler);
|
||||
|
||||
if (g.compass_enabled==true) {
|
||||
compass.set_orientation(MAG_ORIENTATION); // set compass's orientation on aircraft
|
||||
|
|
Loading…
Reference in New Issue