ArduPilot开源代码之AP_IOMCU
1. 源由
之前我们讨论了FMU + IMU的硬件架构,该设计主要是由于STM32外设IO、MCU计算资源不够应付外设的情况下,采用的一种折中的方案。
-ArduPilot开源代码之FMU+IOMCU设计
-Ardupilot开源飞控之IOMCU设计细节
随着技术的日益发展,更高效,更多的IO资源的MCU芯片已经具备。当然在特殊应用领域或者方案,仍然可以考虑采用这一方案。
为此,我们研究下AP_IOMCU
应用类:FMU与IOMCU通信实现。
注:参考Pixhawk4硬件飞控板。
2. 框架设计
hwdef.h
头文件定义FMU端通信端口UART8
.
#define HAL_UART_IOMCU_IDX 8
#define HAL_UART_IO_DRIVER ChibiOS::UARTDriver uart_io(HAL_UART_IOMCU_IDX)
libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp初始化FMU串口实例.
#if HAL_WITH_IO_MCU
HAL_UART_IO_DRIVER;
#include <AP_IOMCU/AP_IOMCU.h>
AP_IOMCU iomcu(uart_io);
#endif
2.1 启动代码
AP_Vehicle::setup
└──> AP_BoardConfig::init
└──> AP_BoardConfig::board_setup
└──> hal.rcout->init();
└──> AP_IOMCU::init
└──> !hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void)
2.2 初始化
采用1.5Mbps,默认(测试)确保,当前连接在无CTS/RTS的方式下进行通信无异常。
void AP_IOMCU::init(void)
{
// uart runs at 1.5MBit, 不知道为何,因为后面`thread_main`里面仍然要初始化一遍。难道是为了`check_crc`
uart.begin(1500*1000, 128, 128);
uart.set_unbuffered_writes(true);
#if IOMCU_DEBUG_ENABLE
crc_is_ok = true;
#else
AP_BoardConfig *boardconfig = AP_BoardConfig::get_singleton();
if ((!boardconfig || boardconfig->io_enabled() == 1) && !hal.util->was_watchdog_reset()) {
check_crc();
} else {
crc_is_ok = true;
}
#endif
if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_IOMCU::thread_main, void), "IOMCU",
1024, AP_HAL::Scheduler::PRIORITY_BOOST, 1)) {
AP_HAL::panic("Unable to allocate IOMCU thread");
}
initialised = true;
}
2.3 动态过程
AP_IOMCU::thread_main(void)
|
|-- 初始化部分
| |-- thread_ctx = chThdGetSelfX()
| |-- chEvtSignal(thread_ctx, initial_event_mask)
| |-- uart.begin(1500*1000, 128, 128)
| |-- uart.set_unbuffered_writes(true)
|
|-- 条件编译(DSHOT 相关配置)
| |-- HAL_WITH_IO_MCU_BIDIR_DSHOT
| |-- erpm_period_ms = 10
| |-- HAVE_AP_BLHELI_SUPPORT
| |-- blh = AP_BLHeli::get_singleton()
| |-- erpm_period_ms = constrain_int16(1000 / blh->get_telemetry_rate(), 1, 1000)
|
|-- 触发初始化事件
| |-- trigger_event(IOEVENT_INIT)
|
|-- 主循环
|
|-- 检查与 IOMCU 的通信
| |-- now_ms = AP_HAL::millis()
| |-- last_reg_access_ms 检查
| |-- INTERNAL_ERROR(AP_InternalError::error_t::iomcu_reset)
|
|-- 等待事件
| |-- mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(10))
|
|-- 处理各类 IO 事件
|
|-- IOEVENT_SEND_PWM_OUT
| |-- send_servo_out()
|
|-- IOEVENT_INIT
| |-- 读取协议版本
| |-- read_registers()
| |-- is_chibios_backend 赋值
| |-- DEV_PRINTF
| |-- modify_register()
| |-- AP_IOMCU_FORCE_ENABLE_HEATER
| |-- modify_register()
|
|-- IOEVENT_MIXING
| |-- write_registers(PAGE_MIXING, ...)
|
|-- IOEVENT_FORCE_S