// initialise the main loop scheduler
//AP调度器的初始化,包含用户任务和通用任务,用户任务数组定义在ArduSub.cpp中,由函数get_scheduler_tasks获取
const AP_Scheduler::Task *tasks;
uint8_t task_count;
uint32_t log_bit;
get_scheduler_tasks(tasks, task_count, log_bit);
AP::scheduler().init(tasks, task_count, log_bit);
// time per loop - this gets updated in the main loop() based on
// actual loop rate
G_Dt = scheduler.get_loop_period_s();
// this is here for Plane; its failsafe_check method requires the
// RC channels to be set as early as possible for maximum
// survivability.
set_control_channels();
// initialise serial manager as early as sensible to get
// diagnostic output during boot process. We have to initialise
// the GCS singleton first as it sets the global mavlink system ID
// which may get used very early on.
gcs().init();
// initialise serial ports
serial_manager.init();
gcs().setup_console();
// Register scheduler_delay_cb, which will run anytime you have
// more than 5ms remaining in your call to hal.scheduler->delay
//在HAL调度器中注册delay callback,在每次调用delay函数时会调用这个callback,用于与地面站的通信
hal.scheduler->register_delay_callback(scheduler_delay_callback, 5);
// init_ardupilot is where the vehicle does most of its initialisation.
//板级资源的初始化
init_ardupilot();
// gyro FFT needs to be initialized really late
#if HAL_GYROFFT_ENABLED
gyro_fft.init(AP::scheduler().get_loop_period_us());
#endif
#if HAL_RUNCAM_ENABLED
runcam.init();
#endif
#if HAL_HOTT_TELEM_ENABLED
hott_telem.init();
#endif
#if HAL_VISUALODOM_ENABLED
// init library used for visual position estimation
visual_odom.init();
#endif
vtx.init();