diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde
index b4a6a798b0d00f4fcc1894a90ac474bee9aa17a8..9663020463743ba40b4da68a6843664dc1bb3bcf 100644
--- a/ArduPlane/ArduPlane.pde
+++ b/ArduPlane/ArduPlane.pde
@@ -193,21 +193,7 @@ static AP_GPS 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;
 
 #if CONFIG_COMPASS == HAL_COMPASS_PX4
 static AP_Compass_PX4 compass;
@@ -1511,7 +1497,7 @@ static void set_flight_stage(AP_SpdHgtControl::FlightStage fs)
 
 static void update_alt()
 {
-    barometer.read();
+    barometer.update();
     if (should_log(MASK_LOG_IMU)) {
         Log_Write_Baro();
     }
diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde
index 7c4d9fbddb2e9eea6f2f50975972e603caaf6a94..d66cee6d23013c82fdb415408cc5bc0215dad53d 100644
--- a/ArduPlane/test.pde
+++ b/ArduPlane/test.pde
@@ -577,7 +577,7 @@ test_pressure(uint8_t argc, const Menu::arg *argv)
 
     while(1) {
         hal.scheduler->delay(100);
-        barometer.read();
+        barometer.update();
 
         if (!barometer.healthy()) {
             cliSerial->println_P(PSTR("not healthy"));