|
在上一篇文章中,我们分享了两大开源飞控ArduPilot与PX4,这一篇我们开始分享ArduPilot的一些知识。
与PX4系列的分享一样,ArduPilot的分享也会从系统到模块的架构和原理上分享,在细节上不做更多的展开,它们的细节的确太多丰富,大家在实际应用中再具体研究。
ArduPilot由几部分组成:
Vehicle应用层,如多旋翼(ArduCopter)、固定翼(ArduPlane)、小车(Rover)等
库:如硬件抽象层(AP_HAL)、传感器驱动(AP_InertialSensor)、传感器融合(AP_NavEKF/2/3)、电机混控输出(AP_Motors)、日志库(AP_Logger)等
第三方模块:RTOS(ChibiOS)、CAN协议层(DroneCAN)、mavlink、DDS库(Micro-XRCE-DDS-Client)、构建工具(waf)等
对于ArduCopter应用,应用与库的调用关系如下图所示:
ArduPilot采用的是将功能模块封装成类,再由具体的应用实例化需要的功能模块类,完成具体的功能。模块间的数据传递依靠函数传参和类指针完成。这样的方式非常灵活,可以比较方便的完成复杂的操作。当然也有一定的缺点,功能的耦合性和模块间的依赖很强,可以发现ArduPilot的应用和库源码中存在大量的宏定义,用于启用和关闭一些功能和模块。
PX4在功能解耦上做的会更好一些,相对而言也带来一些缺点,就是模块间的数据传递不是很灵活,模块间的时序、同步等操作不如ArduPilot方便。
回到ArduPilot这个话题,ArduPilot原本是基于Arduino开发的UAV项目,沿用了Arduino的基本框架,其最为直观的是应用的setup()和loop()接口。
setup()完成应用的初始化,loop()则是应用的循环执行函数。
ArduPilot将这两个接口封装在AP_Vehicle这个类中,所有的应用类都继承这个类,以实现初始化和定时循环任务的接口。
那么setup()和loop()又是怎么被调用的呢,我们以ChibiOS系统举例,在libraries/AP_HAL/AP_HAL_Main.h 中定义了系统的main函数
#define AP_HAL_MAIN_CALLBACKS(CALLBACKS) extern "C" { \
int AP_MAIN(int argc, char* const argv[]); \
int AP_MAIN(int argc, char* const argv[]) { \
hal.run(argc, argv, CALLBACKS); \
return 0; \
} \
}
这里调用了硬件抽线层的run函数,在libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp中则是ChibiOS Hal对run函数的实现,在run函数中完成底层初始化,线程初始化以及应用层setup()和loop()接口的调用
static void main_loop()
{
hal.scheduler->init();
g_callbacks->setup();
while (true) {
g_callbacks->loop();
}
}
loop()接口中主要实现应用层调度器的运行,而应用层调度器是定义在应用层cpp中一个非常直观的任务列表,如在ArduCopter/Copter.cpp中,
const AP_Scheduler::Task Copter::scheduler_tasks[] = {
// update INS immediately to get current gyro data populated
FAST_TASK_CLASS(AP_InertialSensor, &copter.ins, update),
// run low level rate controllers that only require IMU data
FAST_TASK(run_rate_controller),
// send outputs to the motors library immediately
FAST_TASK(motors_output),
// run EKF state estimator (expensive)
FAST_TASK(read_AHRS),
// Inertial Nav
FAST_TASK(read_inertia),
SCHED_TASK(rc_loop, 250, 130, 3),
SCHED_TASK(throttle_loop, 50, 75, 6),
SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9),
};
这些任务实际上是运行在一个线程中的通过AP_Scheduler调度器调度的分时任务队列,这样的设计非常便于增加自定义的任务。
除了应用层的setup()和loop(),在main_loop()也完成了对底层线程的初始化,如:
void Scheduler::init()
{
chBSemObjectInit(&_timer_semaphore, false);
chBSemObjectInit(&_io_semaphore, false);
#ifndef HAL_NO_MONITOR_THREAD
// setup the monitor thread - this is used to detect software lockups
_monitor_thread_ctx = chThdCreateStatic(_monitor_thread_wa,
sizeof(_monitor_thread_wa),
APM_MONITOR_PRIORITY, /* Initial priority. */
_monitor_thread, /* Thread function. */
this); /* Thread parameter. */
#endif
#ifndef HAL_NO_TIMER_THREAD
// setup the timer thread - this will call tasks at 1kHz
_timer_thread_ctx = chThdCreateStatic(_timer_thread_wa,
sizeof(_timer_thread_wa),
APM_TIMER_PRIORITY, /* Initial priority. */
_timer_thread, /* Thread function. */
this); /* Thread parameter. */
#endif
#ifndef HAL_NO_RCOUT_THREAD
// setup the RCOUT thread - this will call tasks at 1kHz
_rcout_thread_ctx = chThdCreateStatic(_rcout_thread_wa,
sizeof(_rcout_thread_wa),
APM_RCOUT_PRIORITY, /* Initial priority. */
_rcout_thread, /* Thread function. */
this); /* Thread parameter. */
#endif
#ifndef HAL_NO_RCIN_THREAD
// setup the RCIN thread - this will call tasks at 1kHz
_rcin_thread_ctx = chThdCreateStatic(_rcin_thread_wa,
sizeof(_rcin_thread_wa),
APM_RCIN_PRIORITY, /* Initial priority. */
_rcin_thread, /* Thread function. */
this); /* Thread parameter. */
#endif
#ifndef HAL_USE_EMPTY_IO
// the IO thread runs at lower priority
_io_thread_ctx = chThdCreateStatic(_io_thread_wa,
sizeof(_io_thread_wa),
APM_IO_PRIORITY, /* Initial priority. */
_io_thread, /* Thread function. */
this); /* Thread parameter. */
#endif
#ifndef HAL_USE_EMPTY_STORAGE
// the storage thread runs at just above IO priority
_storage_thread_ctx = chThdCreateStatic(_storage_thread_wa,
sizeof(_storage_thread_wa),
APM_STORAGE_PRIORITY, /* Initial priority. */
_storage_thread, /* Thread function. */
this); /* Thread parameter. */
#endif
}
/*
initialise UART TX_thread
*/
void UARTDriver::thread_init(void)
{
if (uart_thread_ctx == nullptr) {
hal.util->snprintf(uart_thread_name, sizeof(uart_thread_name), sdef.is_usb ? "OTG%1u" : "UART%1u", sdef.instance);
uart_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(HAL_UART_STACK_SIZE),
uart_thread_name,
unbuffered_writes ? APM_UART_UNBUFFERED_PRIORITY : APM_UART_PRIORITY,
uart_thread_trampoline,
this);
if (uart_thread_ctx == nullptr) {
AP_HAL::panic("Could not create UART TX thread\n");
}
}
}
这些底层任务线程主要完成串口发送、存储器读写、定时器操作等任务,这些任务比较耗时,因此在独立的线程中运行。
后面我们将对ArduPilot的各个模块进行一些分享。
往期分享:
AcmeGCS-21-集群多窗口显示
ArduPilot-1-ArduPilot还是PX4?
AcmeGCS-21-原生ROS2支持
PX4-19-MicroDDS
这里会不定期更新一些我整理的无人机相关知识,如果对您有帮助,欢迎关注转发分享。 |
|