Rover: initialise scheduler callback after logging

prevents possible log corruption
This commit is contained in:
Andrew Tridgell 2013-12-28 10:25:45 +11:00
parent 7ffbed24cc
commit e926f11ec3

View File

@ -116,10 +116,6 @@ static void init_ardupilot()
// init the GCS
gcs[0].init(hal.uartA);
// Register mavlink_delay_cb, which will run anytime you have
// more than 5ms remaining in your call to hal.scheduler->delay
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
// we start by assuming USB connected, as we initialed the serial
// port with SERIAL0_BAUD. check_usb_mux() fixes this if need be.
usb_connected = true;
@ -153,6 +149,10 @@ static void init_ardupilot()
}
#endif
// Register mavlink_delay_cb, which will run anytime you have
// more than 5ms remaining in your call to hal.scheduler->delay
hal.scheduler->register_delay_callback(mavlink_delay_cb, 5);
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
adc.Init(); // APM ADC library initialization
#endif