ardupilot 主函数之任务列表
发布时间
阅读量:
阅读量
目录
文章目录
-
目录
-
- @[toc]
-
摘要
-
核心功能模块
-
底层驱动程序
-
运行主循环过程
-
系统如何从外部导入并启动任务管理机制
-
系统在什么情况下开始处理任务列表
摘要
本节主要分析ardupilot的主函数之间运行关系。
1.main函数

从这里可以看出最终执行的函数是:
int main(int argc, char* const argv[])
{
hal.run(argc, argv, &callbacks);
return 0;
}
AI助手
该main()函数将在之前的Ardupilot启动篇章中的启动流程中被调用。
2.hal.run函数
基于不同飞行控制板层次的最终操作将分别调用不同的设备运行函数来实现。我们在这里主要采用了Chibios系统,并且可以直接定位到AP_HAL_Chibios文件夹以找到相应的运行函数实现。
系统进行初始化过程中会启动Chibios HAL服务,并完成对设备驱动模块的配置以及特殊板层的初始化操作。在内核启动阶段后,main()函数将被指定为主线程并被激活以处理后续任务。
void HAL_ChibiOS::run(int argc, char * const argv[], Callbacks* callbacks) const
{
/* * 系统初始化
* Chibios HAL初始化,也初始化配置设备驱动和执行特殊板层初始化,内核初始化,main()函数成为一个主线程和激活线程。
* System initializations.
* - ChibiOS HAL initialization, this also initializes the configured device drivers
* and performs the board-specific initializations.
* - Kernel initialization, the main() function becomes a thread and the
* RTOS is active.
*/
#ifdef HAL_USB_PRODUCT_ID //初始化USB
setup_usb_strings();
#endif
#ifdef HAL_STDOUT_SERIAL //配置串口标准输出
//STDOUT Initialistion
SerialConfig stdoutcfg =
{
HAL_STDOUT_BAUDRATE,
0,
USART_CR2_STOP1_BITS,
0
};
sdStart((SerialDriver*)&HAL_STDOUT_SERIAL, &stdoutcfg);
#endif
assert(callbacks); //宣布回调函数
g_callbacks = callbacks; //赋值回调函数
//声明主工作线程
void *main_thread_wa = hal.util->malloc_type(THD_WORKING_AREA_SIZE(APM_MAIN_THREAD_STACK_SIZE), AP_HAL::Util::MEM_FAST);
chThdCreateStatic(main_thread_wa,
APM_MAIN_THREAD_STACK_SIZE,
APM_MAIN_PRIORITY, /* 初始化优先级---Initial priority. */
main_loop, /*线程函数-----Thread function. */
nullptr); /*线程参数----- Thread parameter. */
chThdExit(0);
}
AI助手
3.执行main_loop函数
该段代码展示了如何在C语言中对一个名为THD_FUNCTION的功能进行定义。具体而言,
其功能等效于通过 static void main_loop(void *arg) 函数来实现。
static AP_HAL::HAL::Callbacks* g_callbacks;
static THD_FUNCTION(main_loop,arg)
{
daemon_task = chThdGetSelfX();
#ifdef HAL_I2C_CLEAR_BUS
// Clear all I2C Buses. This can be needed on some boards which
// can get a stuck I2C peripheral on boot
//清除所有I2C总线。这可能需要在一些板上
//启动时会出现I2C外设卡滞
ChibiOS::I2CBus::clear_all();
#endif
//DMA配置
ChibiOS::Shared_DMA::init();
//power使能
peripheral_power_enable();
//使能USB
hal.uartA->begin(115200);
#ifdef HAL_SPI_CHECK_CLOCK_FREQ
// optional test of SPI clock frequencies
//SPI时钟频率的可选测试
ChibiOS::SPIDevice::test_clock_freq();
#endif
hal.uartB->begin(115200); //GPS1波特率设置
hal.uartC->begin(115200); //修改波特率57600为115200
hal.uartG->begin(115200); //修改波特率57600为115200
hal.uartH->begin(57600); //修改波特率57600为115200
hal.analogin->init(); //模拟端口初始化
hal.scheduler->init(); //任务调度初始化
/***************************************************************** * 以低优先级运行setup()以确保CLI不会挂起系统,并允许初始传感器读取回路运行
* run setup() at low priority to ensure CLI doesn't hang the
* system, and to allow initial sensor read loops to run
******************************************************************/
hal_chibios_set_priority(APM_STARTUP_PRIORITY);
//初始化hal
schedulerInstance.hal_initialized();
//回调setup函数
g_callbacks->setup();
//系统初始化
hal.scheduler->system_initialized();
thread_running = true;
chRegSetThreadName(SKETCHNAME);
/*********************************************************** * 切换到主回路的高优先级
* switch to high priority for main loop
***********************************************************/
chThdSetPriority(APM_MAIN_PRIORITY);
while (true)
{
//调用loop()函数,主循环任务开始
g_callbacks->loop();
/*
give up 250 microseconds of time if the INS loop hasn't
called delay_microseconds_boost(), to ensure low priority
drivers get a chance to run. Calling
delay_microseconds_boost() means we have already given up
time from the main loop, so we don't need to do it again
here
如果INS循环周期没有调用delay_microseconds_boost延迟函数,放弃250us时间,确保低优先级的驱动能
正常运转,号召delay_microseconds_boost意味着我们已经放弃主循环时间,因此我们不需要在做。
*/
if (!schedulerInstance.check_called_boost())
{
hal.scheduler->delay_microseconds(250);
}
}
thread_running = false;
}
AI助手
其中涉及的函数包括调用g_callbacks->setup()和g_callbacks->loop()这两个关键函数。已经在之前的代码中进行了详细记录,在这里我们主要关注另一个重要的初始化步骤:hal.scheduler->init()的任务调度初始化过程。
void Scheduler::init()
{
//创建定时器信号量
chBSemObjectInit(&_timer_semaphore, false);
//io信号亮
chBSemObjectInit(&_io_semaphore, false);
// setup the timer thread - this will call tasks at 1kHz
//设置计时器线程-这将调用1kHz的任务
_timer_thread_ctx = chThdCreateStatic(_timer_thread_wa,
sizeof(_timer_thread_wa),
APM_TIMER_PRIORITY, /* Initial priority. */
_timer_thread, /* Thread function. */
this); /* Thread parameter. */
// setup the uavcan thread - this will call tasks at 1kHz
//设置uavcan线程-这将调用1kHz的任务
#if HAL_WITH_UAVCAN
_uavcan_thread_ctx = chThdCreateStatic(_uavcan_thread_wa,
sizeof(_uavcan_thread_wa),
APM_UAVCAN_PRIORITY, /* Initial priority. */
_uavcan_thread, /* Thread function. */
this); /* Thread parameter. */
#endif
// setup the RCIN thread - this will call tasks at 1kHz
//设置RCIN线程-这将调用1kHz的任务
_rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa,
sizeof(_rcin_thread_wa),
APM_RCIN_PRIORITY, /* Initial priority. */
_rcin_thread, /* Thread function. */
this); /* Thread parameter. */
// the IO thread runs at lower priority
//IO线程以较低优先级运行
_io_thread_ctx = chThdCreateStatic(_io_thread_wa,
sizeof(_io_thread_wa),
APM_IO_PRIORITY, /* Initial priority. */
_io_thread, /* Thread function. */
this); /* Thread parameter. */
// the storage thread runs at just above IO priority
//存储线程以略高于IO优先级的方式运行
_storage_thread_ctx = chThdCreateStatic(_storage_thread_wa,
sizeof(_storage_thread_wa),
APM_STORAGE_PRIORITY, /* Initial priority. */
_storage_thread, /* Thread function. */
this); /* Thread parameter. */
}
AI助手
这里创建了定时器,信号量,任务等等。
4.任务列表如何被加载执行
scheduler.init(&scheduler_tasks[0], ARRAY_SIZE(scheduler_tasks), MASK_LOG_PM);
AI助手
其中:scheduler_tasks[]数组就是我们的任务列表

从scheduler.init()可以看出scheduler属于AP_Scheduler的一个对象
AP_Scheduler scheduler{FUNCTOR_BIND_MEMBER(&Copter::fast_loop, void)};
AI助手
void AP_Scheduler::init(const AP_Scheduler::Task *tasks, uint8_t num_tasks,
uint32_t log_performance_bit)
{
//任务指针
_tasks = tasks;
//总共的任务数
_num_tasks = num_tasks;
_last_run = new uint16_t[_num_tasks];
//最后运行赋值0
memset(_last_run, 0, sizeof(_last_run[0]) * _num_tasks);
_tick_counter = 0;
//初始化执行计数------ setup initial performance counters
//运行周期是400hz
perf_info.set_loop_rate(get_loop_rate_hz());
perf_info.reset();
//log执行位
_log_performance_bit = log_performance_bit;
}
AI助手
5.任务列表何时被执行
执行 g_callbacks- >loop();运行下面函数
void Copter::loop()
{
scheduler.loop();
G_Dt = scheduler.get_last_loop_time_s();
}
AI助手
void AP_Scheduler::loop()
{
//等候INS采样数据------ wait for an INS sample
AP::ins().wait_for_sample();
//获取采样时间
const uint32_t sample_time_us = AP_HAL::micros();
//循环计数开始时间等于多少us
if (_loop_timer_start_us == 0)
{
_loop_timer_start_us = sample_time_us;
_last_loop_time_s = get_loop_period_s();
} else
{
//两次时间差
_last_loop_time_s = (sample_time_us - _loop_timer_start_us) * 1.0e-6;
}
//执行快速循环任务------ Execute the fast loop
// ---------------------
if (_fastloop_fn)
{
_fastloop_fn(); //执行快速循环函数
}
//告诉任务调度去一个时钟节拍已经过去------ tell the scheduler one tick has passed
tick();
// run all the tasks that are due to run. Note that we only
// have to call this once per loop, as the tasks are scheduled
// in multiples of the main loop tick. So if they don't run on
// the first call to the scheduler they won't run on a later
// call until scheduler.tick() is called again
//运行所有要运行的任务。请注意,我们只
//每次循环必须调用一次,因为任务是计划好的
//以主循环的倍数滴答作响。所以如果他们不继续
//对调度程序的第一次调用他们以后不会运行
//号召到调度程序.tick()被再次调用
const uint32_t loop_us = get_loop_period_us(); //获取循环时间
//总时间减掉到这里的时间,就是剩余的有效可以使用的时间
const uint32_t time_available = (sample_time_us + loop_us) - AP_HAL::micros();
//如果有效时间大于我们的周期循环时间loop_us,则直接传递0
run(time_available > loop_us ? 0u : time_available);
//执行仿真
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// move result of AP_HAL::micros() forward:
hal.scheduler->delay_microseconds(1);
#endif
//检查loop运行时间----- check loop time
perf_info.check_loop_time(sample_time_us - _loop_timer_start_us);
//记录到执行这里的时间
_loop_timer_start_us = sample_time_us;
}
AI助手
void AP_Scheduler::run(uint32_t time_available) //time_available=0或者有效时间
{
//记录开始运行时间是多少us
uint32_t run_started_usec = AP_HAL::micros();
//把数据传递过去赋值给now
uint32_t now = run_started_usec;
//执行调试代码
if (_debug > 1 && _perf_counters == nullptr)
{
_perf_counters = new AP_HAL::Util::perf_counter_t[_num_tasks];
if (_perf_counters != nullptr)
{
for (uint8_t i=0; i<_num_tasks; i++)
{
_perf_counters[i] = hal.util->perf_alloc(AP_HAL::Util::PC_ELAPSED, _tasks[i].name);
}
}
}
//循环执行任务
for (uint8_t i=0; i<_num_tasks; i++)
{
//获取单个任务的时间
uint16_t dt = _tick_counter - _last_run[i];
//间隔时间,主循环时间/任务时间一定要大于1
uint16_t interval_ticks = _loop_rate_hz / _tasks[i].rate_hz;
//小于1被限制等于1
if (interval_ticks < 1)
{
interval_ticks = 1;
}
//一般不会存在
if (dt < interval_ticks)
{
// this task is not yet scheduled to run again
//此任务尚未计划再次运行,主要是超过了主循环时间
continue;
}
// this task is due to run. Do we have enough time to run it?
//此任务将运行。我们有足够的时间跑吗?
_task_time_allowed = _tasks[i].max_time_micros;
if (dt >= interval_ticks*2) //时间不应该超过这个值
{
// we've slipped a whole run of this task!
//我们把这项任务搞砸了!
debug(2, "Scheduler slip task[%u-%s] (%u/%u/%u)\n",
(unsigned)i,
_tasks[i].name,
(unsigned)dt,
(unsigned)interval_ticks,
(unsigned)_task_time_allowed);
}
//可能还有其他的任务可以满足,因此for循环还是会继续
if (_task_time_allowed > time_available)
{
// not enough time to run this task. Continue loop -
// maybe another task will fit into time remaining
//没有足够的时间运行此任务。继续循环-
//也许剩下的时间里会有另一项任务
continue;
}
//开始运行他---- run it
_task_time_started = now;
//当前运行的是哪个任务
current_task = i;
//调试信息
if (_debug > 1 && _perf_counters && _perf_counters[i])
{
hal.util->perf_begin(_perf_counters[i]);
}
//执行任务函数
_tasks[i].function();
//是否执行调试信息
if (_debug > 1 && _perf_counters && _perf_counters[i])
{
hal.util->perf_end(_perf_counters[i]);
}
//当前任务赋值-1
current_task = -1;
// record the tick counter when we ran. This drives
// when we next run the event
//我们跑的时候记录下滴答计数器。这个驱动器
//当我们下一次运行活动时
_last_run[i] = _tick_counter;
// work out how long the event actually took
//算出这件事实际花了多长时间
now = AP_HAL::micros();
//计算两次时间差
uint32_t time_taken = now - _task_time_started;
//判断是否超时
if (time_taken > _task_time_allowed)
{
// the event overran!
debug(3, "Scheduler overrun task[%u-%s] (%u/%u)\n",
(unsigned)i,
_tasks[i].name,
(unsigned)time_taken,
(unsigned)_task_time_allowed);
}
//如果超时了,记录现在可以使用的时间是0
if (time_taken >= time_available)
{
time_available = 0;
break;
}
//否则就把有效时间继续减少
time_available -= time_taken;
}
// update number of spare microseconds
//更新备用微秒数
_spare_micros += time_available;
_spare_ticks++;
if (_spare_ticks == 32)
{
_spare_ticks /= 2;
_spare_micros /= 2;
}
}
AI助手
全部评论 (0)
还没有任何评论哟~
