diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index d994ff9bc0..0a6c1ec7b5 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -109,9 +109,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. @@ -150,6 +147,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_INS_TYPE == CONFIG_INS_OILPAN || CONFIG_HAL_BOARD == HAL_BOARD_APM1 apm1_adc.Init(); // APM ADC library initialization #endif