Plane: move baro init earlier in startup

this ensures it is initialised when CLI takeover by MP happens

Thanks to Prof Avi Levi for reporting this bug
This commit is contained in:
Andrew Tridgell 2013-05-06 10:57:57 +10:00
parent 0cf49308af
commit fdd509a7c1

View File

@ -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!"));