Browse Source

ArduCopter: instantiate correct AP_Baro object based on CONFIG_BARO

mission-4.1.18
Pat Hickey 13 years ago
parent
commit
b055aa6f81
  1. 8
      ArduCopter/ArduCopter.pde

8
ArduCopter/ArduCopter.pde

@ -159,7 +159,13 @@ static AP_Int8 *flight_modes = &g.flight_mode1; @@ -159,7 +159,13 @@ static AP_Int8 *flight_modes = &g.flight_mode1;
AP_Baro_BMP085_HIL barometer;
AP_Compass_HIL compass;
#else
AP_Baro_BMP085 barometer;
#if CONFIG_BARO == AP_BARO_BMP085
AP_Baro_BMP085 barometer;
#elif CONFIG_BARO == AP_BARO_MS5611
AP_Baro_MS5611 barometer;
#endif
AP_Compass_HMC5843 compass(Parameters::k_param_compass);
#endif

Loading…
Cancel
Save