diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index f4c604887d..4f14fc1ac4 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -117,6 +117,9 @@ static void init_ardupilot() // used to detect in-flight resets g.num_resets.set_and_save(g.num_resets+1); + // init baro before we start the GCS, so that the CLI baro test works + barometer.init(); + // init the GCS gcs0.init(hal.uartA); // Register mavlink_delay_cb, which will run anytime you have @@ -157,8 +160,6 @@ static void init_ardupilot() adc.Init(); // APM ADC library initialization #endif - barometer.init(); - if (g.compass_enabled==true) { if (!compass.init() || !compass.read()) { cliSerial->println_P(PSTR("Compass initialisation failed!"));