diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 9a5226a16d..14a47404e5 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -259,21 +259,8 @@ static GPS_Glitch gps_glitch(gps); // flight modes convenience array static AP_Int8 *flight_modes = &g.flight_mode1; -#if CONFIG_BARO == HAL_BARO_BMP085 -static AP_Baro_BMP085 barometer; -#elif CONFIG_BARO == HAL_BARO_PX4 -static AP_Baro_PX4 barometer; -#elif CONFIG_BARO == HAL_BARO_VRBRAIN -static AP_Baro_VRBRAIN barometer; -#elif CONFIG_BARO == HAL_BARO_HIL -static AP_Baro_HIL barometer; -#elif CONFIG_BARO == HAL_BARO_MS5611 -static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::i2c); -#elif CONFIG_BARO == HAL_BARO_MS5611_SPI -static AP_Baro_MS5611 barometer(&AP_Baro_MS5611::spi); -#else - #error Unrecognized CONFIG_BARO setting -#endif +static AP_Baro barometer; + static Baro_Glitch baro_glitch(barometer); #if CONFIG_COMPASS == HAL_COMPASS_PX4 diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 3a88aed867..8ec3998855 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -16,7 +16,7 @@ static void init_barometer(bool full_calibration) // return barometric altitude in centimeters static void read_barometer(void) { - barometer.read(); + barometer.update(); if (should_log(MASK_LOG_IMU)) { Log_Write_Baro(); }