Plane: move delay callback setup to after compass and airspeed config

this ensure parameters sent on startup include compass settings and
airspeed offset
This commit is contained in:
Andrew Tridgell 2014-11-08 15:29:25 +11:00
parent 9e12b01569
commit 0a318d3a68
1 changed files with 4 additions and 4 deletions

View File

@ -152,10 +152,6 @@ 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
apm1_adc.Init(); // APM ADC library initialization
#endif
@ -172,6 +168,10 @@ static void init_ardupilot()
}
}
// 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);
// give AHRS the airspeed sensor
ahrs.set_airspeed(&airspeed);