手头资源紧张(只有一架完整的模型飞机),但是又想切换ArduPilot飞行(后续打算将wfb-ng挂上,将图像加密(直接/中转)传输回来)。
尽管前期使用Kakute F7 AIO做了F450的试飞,但是当时存在几个问题:
【1】ArduPilot飞控之DIY-F450计划
【2】QGroundControl之安装调试
【3】ArduPilot Kakute F7 AIO DIYF450 之GPS配置
【4】ArduPilot Kakute F7 AIO DIYF450 without GPS配置
【5】ArduPilot之posHold&RTL实测
【6】Betaflight BN880 GPS 简单测试
鉴于目前手头的飞控板尚未得到ArduPilot官方支持,在做厂家“小白鼠”之前,尽量知道所以然,在上手飞,对于仅有的模型来说,损失概率可以大大降低。
因此,首先有必要分析和研究下AOCODARC H7DUAL这块飞控的相关配置信息,从源由确保配置信息是正确的(这里得益于ArduPilot切换ChibiOS之后的架构设计,目前飞控板配置在OS这层就已经解耦)。
APM-AOCODARCH7DUAL.rar
./AOCODARC-H7DUAL/
├── defaults.parm
├── hwdef-bl.dat
└── hwdef.dat
注:这个H7Dual厂家有两款,一款是BMI270 x 2,另一款是MPU6000 + BMI270。笔者手上这块是BMI270x2。
这里主要有三个配置文件组成:
当前review最新代码
# git log -n 1
commit 1359b43742922008e43c178423f9e0cbeaafcd67 (HEAD -> master, origin/master, origin/HEAD)
Author: Peter Barker <[email protected]>
Date: Tue May 23 23:33:21 2023 +1000
Tools: build_binaries.py: avoid exception while handling exception
From the build server:
File "./build_binaries.py", line 570, in get_exception_stacktrace
ret = "%s\n" % e
File "/usr/lib/python3.8/subprocess.py", line 113, in __str__
if self.returncode and self.returncode < 0:
唯一的差异就是增加了原厂提供的配置文件
# git status
On branch master
Your branch is up to date with 'origin/master'.
Untracked files:
(use "git add ..." to include in what will be committed)
libraries/AP_HAL_ChibiOS/hwdef/AOCODARC-H7DUAL/
nothing added to commit but untracked files present (use "git add" to track)
# cat AOCODARC-H7DUAL/defaults.parm
# logging
LOG_BACKEND_TYPE 4
LOG_FILE_BUFSIZE 4
从目前最新代码库上情况看,使用这个defaults.parm文件来做配置的板子不多。
# grep "LOG_FILE_BUFSIZE" -rn .
./skyviper-journey/defaults.parm:310:LOG_FILE_BUFSIZE 1
./AOCODARC-H7DUAL/defaults.parm:3:LOG_FILE_BUFSIZE 4
# grep "LOG_BACKEND_TYPE" -rn .
./skyviper-journey/defaults.parm:309:LOG_BACKEND_TYPE 2
./AOCODARC-H7DUAL/defaults.parm:2:LOG_BACKEND_TYPE 4
该文件在编译过程中被脚本自动调用执行。
# grep "defaults.parm" -rn .
./scripts/chibios_hwdef.py:2744: # see if board has a defaults.parm file or a --default-parameters file was specified
./scripts/chibios_hwdef.py:2745: defaults_filename = os.path.join(os.path.dirname(args.hwdef[0]), 'defaults.parm')
./HolybroG4_GPS/hwdef.dat:136:# we setup a small defaults.parm
./f405-MatekGPS/hwdef.dat:56:# we setup a small defaults.parm
./HolybroGPS/hwdef.dat:148:# we setup a small defaults.parm
./C-RTK2-HP/hwdef.dat:101:# we setup a small defaults.parm
./rGNSS/hwdef.dat:117:# we setup a small defaults.parm
./Sierra-F412/hwdef.dat:126:# we setup a small defaults.parm
./HolybroG4_Compass/hwdef.dat:100:# we setup a small defaults.parm
./FreeflyRTK/hwdef.dat:125:# we setup a small defaults.parm
./CubeOrangePlus-bdshot/hwdef.dat:14:env DEFAULT_PARAMETERS libraries/AP_HAL_ChibiOS/hwdef/CubeOrangePlus/defaults.parm
./skyviper-v2450/hwdef.dat:66:env DEFAULT_PARAMETERS 'Tools/Frame_params/SkyViper-2450GPS/defaults.parm'
./AeroFox-PMU/hwdef.inc:47:# setup a small defaults.parm
./AeroFox-GNSS_F9P/hwdef.dat:42:# we setup a small defaults.parm
./Sierra-F405/hwdef.dat:47:# we setup a small defaults.parm
./CubeOrange-bdshot/hwdef.dat:14:env DEFAULT_PARAMETERS libraries/AP_HAL_ChibiOS/hwdef/CubeOrange/defaults.parm
./CUAV_GPS/hwdef.dat:138:# we setup a small defaults.parm
./Sierra-F9P/hwdef.dat:117:# we setup a small defaults.parm
./MatekL431/hwdef.inc:47:# we setup a small defaults.parm
libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py给出信息表明,该文件主要是配置一些编译时的环境变量。
def write_env_py(self, filename):
'''write out env.py for environment variables to control the build process'''
# see if board has a defaults.parm file or a --default-parameters file was specified
defaults_filename = os.path.join(os.path.dirname(args.hwdef[0]), 'defaults.parm')
defaults_path = os.path.join(os.path.dirname(args.hwdef[0]), args.params)
if not args.bootloader:
if os.path.exists(defaults_path):
self.env_vars['DEFAULT_PARAMETERS'] = os.path.abspath(self.default_params_filepath)
print("Default parameters path from command line: %s" % self.default_params_filepath)
elif os.path.exists(defaults_filename):
self.env_vars['DEFAULT_PARAMETERS'] = os.path.abspath(defaults_filename)
print("Default parameters path from hwdef: %s" % defaults_filename)
else:
print("No default parameter file found")
# CHIBIOS_BUILD_FLAGS is passed to the ChibiOS makefile
self.env_vars['CHIBIOS_BUILD_FLAGS'] = ' '.join(self.build_flags)
pickle.dump(self.env_vars, open(filename, "wb"))
libraries/AP_Logger/AP_Logger.给出LOG_BACKEND_TYPE 4
块设备外部Flash定义。
enum class Backend_Type : uint8_t {
NONE = 0,
FILESYSTEM = (1<<0),
MAVLINK = (1<<1),
BLOCK = (1<<2),
};
LOG_FILE_BUFSIZE 4
可能之文件缓存使用4KB,工程里面没有找到对应的定义。
# grep "LOG_FILE_BUFSIZE" -rn .
./libraries/SITL/examples/SilentWings/Params/Rolladen-Schneider-LS8b.param:307:LOG_FILE_BUFSIZE,16
./libraries/SITL/examples/SilentWings/Params/Schleicher-ASW27B.param:310:LOG_FILE_BUFSIZE,16
./libraries/AP_Logger/AP_Logger.cpp:100: // @Description: If LOG_REPLAY is set to 1 then the EKF2 and EKF3 state estimators will log detailed information needed for diagnosing problems with the Kalman filter. LOG_DISARMED must be set to 1 or 2 or else the log will not contain the pre-flight data required for replay testing of the EKF's. It is suggested that you also raise LOG_FILE_BUFSIZE to give more buffer space for logging and use a high quality microSD card to ensure no sensor data is lost.
./libraries/AP_Logger/AP_Logger.cpp:194: // convert from 8 bit to 16 bit LOG_FILE_BUFSIZE
./libraries/AP_HAL_ChibiOS/hwdef/skyviper-journey/defaults.parm:310:LOG_FILE_BUFSIZE 1
./libraries/AP_HAL_ChibiOS/hwdef/AOCODARC-H7DUAL/defaults.parm:3:LOG_FILE_BUFSIZE 4
./Tools/Frame_params/Solo_Copter-4.param:95:LOG_FILE_BUFSIZE,8
./Tools/Frame_params/Sub/bluerov2-heavy-4_0_0.params:325:LOG_FILE_BUFSIZE,16
./Tools/Frame_params/Sub/bluerov2-heavy-3_5_2.params:282:LOG_FILE_BUFSIZE,16
./Tools/Frame_params/Sub/bluerov2-3_5_4.params:278:LOG_FILE_BUFSIZE,16
./Tools/Frame_params/Sub/bluerov2-3_5.params:285:LOG_FILE_BUFSIZE,16
./Tools/Frame_params/Sub/bluerov2-4_0_0.params:325:LOG_FILE_BUFSIZE,16
./Tools/Frame_params/Sub/bluerov2-3_5_2.params:282:LOG_FILE_BUFSIZE,16
./Tools/Frame_params/Sub/bluerov2-heavy-3_5_4.params:278:LOG_FILE_BUFSIZE,16
./Tools/Frame_params/Solo_Copter-3.6_GreenCube.param:80:LOG_FILE_BUFSIZE,8
./Tools/Frame_params/Solo_Copter-3.5_GreenCube.param:74:LOG_FILE_BUFSIZE,32
./Tools/Frame_params/Solo_Copter-4_GreenCube.param:94:LOG_FILE_BUFSIZE,8
./Tools/Frame_params/SkyViper-2450GPS/defaults.parm:187:LOG_FILE_BUFSIZE 1
./Tools/Replay/LR_MsgHandler.cpp:304: "LOG_FILE_BUFSIZE",
./Tools/autotest/default_params/vee-gull 005.param:345:LOG_FILE_BUFSIZE,16
Binary file ./modules/mavlink/pymavlink/tests/test.BIN matches
./modules/mavlink/pymavlink/tests/test.BIN.py3.dumped:682:2017-10-29 12:47:13.02: PARM {TimeUS : 81877832, Name : LOG_FILE_BUFSIZE, Value : 16.0}
./modules/mavlink/pymavlink/tests/test.BIN.dumped:682:2017-10-29 12:47:13.02: PARM {TimeUS : 81877832, Name : LOG_FILE_BUFSIZE, Value : 16.0}
./ArduPlane/ReleaseNotes.txt:2018: - raise default LOG_FILE_BUFSIZE on boards with more memory
注:逐行增加注释方式研读。
# hw definition file for processing by chibios_pins.py
#
# MCU class and specific type
MCU STM32H7xx STM32H743xx //STM32H7系列,型号H743
# board ID for firmware load
APJ_BOARD_ID 99 //ID:99,要确保bootloader和飞控配置一致
# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000 //晶振频率
FLASH_SIZE_KB 2048 //芯片存储容量 2MB
# bootloader starts at zero offset
FLASH_RESERVE_START_KB 0 //bootloader位置,通常0地址
# use last 2 pages for flash storage
# H743 has 16 pages of 128k each
STORAGE_FLASH_PAGE 14 //bootloader和application使用一共14 pages,2 pages用于参数保存
# the location where the bootloader will put the firmware
# the H743 has 128k sectors
FLASH_BOOTLOADER_LOAD_KB 128 //application起始位置
# order of UARTs (and USB). Allow bootloading on USB and telem1
SERIAL_ORDER OTG1 #UART7 //这里定义了一个USB串口
# UART7 (telem1)
#PE7 UART7_RX UART7 NODMA
#PE8 UART7_TX UART7 NODMA
# PA10 IO-debug-console //OTG USB+/-信号定义
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD //JTAG引脚定义
PA14 JTCK-SWCLK SWD
PE3 LED_BOOTLOADER OUTPUT LOW //其中一个PE03作为指示灯,并且低电平点亮
define HAL_LED_ON 0
# Add CS pins to ensure they are high in bootloader //芯片的一些CS引脚,感觉bootloader不用检查这些外设(也可以节省代码空间),毕竟应用会进行初始化。
PC15 IMU1_CS CS
PB12 MAX7456_CS CS
PE11 IMU2_CS CS
PD3 FLASH_CS CS
注:逐行增加注释方式研读。
# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32H7xx STM32H743xx //STM32H7系列,型号H743
# board ID for firmware load
APJ_BOARD_ID 99 //ID:99,要确保bootloader和飞控配置一致
# crystal frequency, setup to use external oscillator
OSCILLATOR_HZ 8000000 //晶振频率
FLASH_SIZE_KB 2048 //芯片存储容量 2MB
env OPTIMIZE -Os //size 优化,这个可以根据具体情况选择,详见gcc参考资料
# bootloader takes first sector
FLASH_RESERVE_START_KB 128 //application起始位置
# ChibiOS system timer
STM32_ST_USE_TIMER 12 //使用定时器12作为系统脉搏
define CH_CFG_ST_RESOLUTION 16 //定时器精度 16bit
# USB
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD
# SPI1 for IMU1 (MPU6000)
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PD7 SPI1_MOSI SPI1
PC15 IMU1_CS CS
# SPI2 for MAX7456 OSD
PB12 MAX7456_CS CS
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# SPI3 - external //板载Flash W25N01G
PB3 SPI3_SCK SPI3
PB4 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3
PD3 FLASH_CS CS
# external CS pins
PD4 EXT_CS1 CS //问题1:Betaflight配置文件也没有对应的描述,该引脚用于什么用途?
PE2 EXT_CS2 CS //OTG USB Detect
# SPI4 for IMU2 (BMI270)
PE11 IMU2_CS CS
PE12 SPI4_SCK SPI4
PE13 SPI4_MISO SPI4
PE14 SPI4_MOSI SPI4
# two I2C bus
I2C_ORDER I2C2 I2C1
# I2C1 //磁力计
PB6 I2C1_SCL I2C1
PB7 I2C1_SDA I2C1
# I2C2 //气压计
PB10 I2C2_SCL I2C2
PB11 I2C2_SDA I2C2
# ADC
PC0 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC1 BATT_CURRENT_SENS ADC1 SCALE(1)
PA4 BATT2_VOLTAGE_SENS ADC1 SCALE(1) //问题2:引脚Betaflight配置文件中未见,这里貌似MatekH743的双电调供电,需要原理图确认?
PA7 BATT2_CURRENT_SENS ADC1 SCALE(1) //问题3:引脚Betaflight配置文件中未见,这里貌似MatekH743的双电调供电,需要原理图确认?
define HAL_BATT_MONITOR_DEFAULT 4 //电源配置参数
define HAL_BATT_VOLT_PIN 10
define HAL_BATT_CURR_PIN 11
define HAL_BATT2_VOLT_PIN 18
define HAL_BATT2_CURR_PIN 7
define HAL_BATT_VOLT_SCALE 11.0
define HAL_BATT_CURR_SCALE 40.0
define HAL_BATT2_VOLT_SCALE 11.0
PC4 PRESSURE_SENS ADC1 SCALE(2) //空速计
define HAL_DEFAULT_AIRSPEED_PIN 4
PC5 RSSI_ADC ADC1 //模拟RSSI ADC输入
define BOARD_RSSI_ANA_PIN 8
# LED
# green LED1 marked as B/E
# blue LED0 marked as ACT
PE3 LED0 OUTPUT LOW GPIO(90) # blue
PE4 LED1 OUTPUT LOW GPIO(91) # orange
define HAL_GPIO_A_LED_PIN 91
define HAL_GPIO_B_LED_PIN 90
define HAL_GPIO_LED_OFF 1
# order of UARTs (and USB) //含USB 一共7个串口(串口5未定义),问题4:为什么不定义串口5?
SERIAL_ORDER OTG1 UART4 UART8 USART2 USART3 USART6 UART7 USART1
# USART1 (RC input), SERIAL7
PA9 USART1_TX USART1
PA10 TIM1_CH3 TIM1 RCININT PULLDOWN LOW
# USART2 (GPS1), SERIAL3
PD5 USART2_TX USART2
PD6 USART2_RX USART2
# USART3 (GPS2), SERIAL4
PD8 USART3_TX USART3
PD9 USART3_RX USART3
# UART4 (telem1), SERIAL1
PB8 UART4_RX UART4
PB9 UART4_TX UART4
# USART6 (spare)
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# UART7 (spare)
PE7 UART7_RX UART7
PE8 UART7_TX UART7
# UART8 (telem2), SERIAL2
PE0 UART8_RX UART8
PE1 UART8_TX UART8
# CAN bus //没有CanBus
#PD0 CAN1_RX CAN1
#PD1 CAN1_TX CAN1
#PD3 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW GPIO(70)
# Motors
PB0 TIM8_CH2N TIM8 PWM(1) GPIO(50)
PB1 TIM8_CH3N TIM8 PWM(2) GPIO(51)
PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52)
PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53)
PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54)
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55)
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56)
PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57)
PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) NODMA //问题5:没有DMA dshot协议还能支持吗,目前ArduPilot支持bitbang方式使用dshot吗?
PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) NODMA
PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA
PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA
#PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED this will be affects RC input //问题6:是什么原因引起LED灯带不能使用,DMA,timer不够;灯带GPIO有定义,还能使用吗?
# Beeper
PA15 TIM2_CH1 TIM2 GPIO(80) ALARM
#use LED-STRIP output as general purpose GPIO
PA8 GP_GPIO OUTPUT LOW GPIO(70)
# microSD support
#PC8 SDMMC1_D0 SDMMC1
#PC9 SDMMC1_D1 SDMMC1
#PC10 SDMMC1_D2 SDMMC1
#PC11 SDMMC1_D3 SDMMC1
#PC12 SDMMC1_CK SDMMC1
#PD2 SDMMC1_CMD SDMMC1
# GPIOs
PD10 PINIO1 OUTPUT GPIO(81) LOW
PD11 PINIO2 OUTPUT GPIO(82) LOW
DMA_PRIORITY S* TIM3* TIM2*
DMA_NOSHARE SPI1* SPI4* TIM3* TIM2*
define HAL_STORAGE_SIZE 16384 //问题7:不是有2个pages用于storage,为什么这里只用了16KB?
# use last 2 pages for flash storage
# H743 has 16 pages of 128k each
STORAGE_FLASH_PAGE 14
#STORAGE_FLASH_PAGE 1
# spi devices
SPIDEV mpu6000 SPI1 DEVID1 IMU1_CS MODE3 1*MHZ 4*MHZ //一个型号是MPU6000 + BMI270
SPIDEV bmi270_1 SPI1 DEVID1 IMU1_CS MODE3 10*MHZ 10*MHZ //一个型号是BMI270 + BMI270
SPIDEV bmi270_2 SPI4 DEVID1 IMU2_CS MODE3 10*MHZ 10*MHZ
#SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE0 32*MHZ 32*MHZ
SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 104*MHZ 104*MHZ
SPIDEV osd SPI2 DEVID4 MAX7456_CS MODE0 10*MHZ 10*MHZ
//问题8:为什么不做DMA_NOSHARE SPI1* SPI4*?
# SPI3 external connections
#SPIDEV pixartflow SPI3 DEVID1 EXT_CS1 MODE3 2*MHZ 2*MHZ
# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# two IMUs
IMU Invensense SPI:mpu6000 ROTATION_YAW_270
IMU BMI270 SPI:bmi270_1 ROTATION_ROLL_180_YAW_90
IMU BMI270 SPI:bmi270_2 ROTATION_ROLL_180_YAW_270
# DPS310 integrated on I2C2 bus, multiple possible choices for external barometer
BARO MS56XX I2C:0:0x77
BARO DPS310 I2C:0:0x76
BARO BMP280 I2C:0:0x76
#define HAL_OS_FATFS_IO 1
#define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
#define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
# setup for OSD
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
# enable logging to dataflash
define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25N01GV
【1】wfb-ng 开源工程结构&代码框架简明介绍
【2】BetaFlight统一硬件AOCODARC H7DUAL配置文件讨论
【3】ArduPilot飞控AOCODARC-H7DUAL固件编译
【4】Using Tabula to Parse PDF Tables
【5】gcc - Options That Control Optimization
ArduPilot on Chibios
注:上述问题已经反馈厂家,不过板子尚未得到ArduPilot官方支持。因此后续要使用,可能需要仔细的调整。
答:PE2用在OTG USB Detect引脚上;PD4 在Matek H743板子上用在光流计上,AOCODARC可能原理图上没有用到这个pin脚。
# external CS pins
PD4 EXT_CS1 CS
PE2 EXT_CS2 CS
PA4 BATT2_VOLTAGE_SENS ADC1 SCALE(1)
PA7 BATT2_CURRENT_SENS ADC1 SCALE(1)
# order of UARTs (and USB)
SERIAL_ORDER OTG1 UART4 UART8 USART2 USART3 USART6 UART7 USART1
# Motors
PB0 TIM8_CH2N TIM8 PWM(1) GPIO(50)
PB1 TIM8_CH3N TIM8 PWM(2) GPIO(51)
PA0 TIM5_CH1 TIM5 PWM(3) GPIO(52)
PA1 TIM5_CH2 TIM5 PWM(4) GPIO(53)
PA2 TIM5_CH3 TIM5 PWM(5) GPIO(54)
PA3 TIM5_CH4 TIM5 PWM(6) GPIO(55)
PD12 TIM4_CH1 TIM4 PWM(7) GPIO(56)
PD13 TIM4_CH2 TIM4 PWM(8) GPIO(57)
PD14 TIM4_CH3 TIM4 PWM(9) GPIO(58) NODMA
PD15 TIM4_CH4 TIM4 PWM(10) GPIO(59) NODMA
PE5 TIM15_CH1 TIM15 PWM(11) GPIO(60) NODMA
PE6 TIM15_CH2 TIM15 PWM(12) GPIO(61) NODMA
#PA8 TIM1_CH1 TIM1 PWM(13) GPIO(62) # for WS2812 LED this will be affects RC input
#use LED-STRIP output as general purpose GPIO
PA8 GP_GPIO OUTPUT LOW GPIO(70)
define HAL_STORAGE_SIZE 16384
TIM2(Beeper)这个优先级需要特别之处吗?
TIM3用于那个外设?
MatekH743
DMA_PRIORITY S*
DMA_NOSHARE SPI1* SPI4*
AOCODARC H743
DMA_PRIORITY S* TIM3* TIM2*
DMA_NOSHARE SPI1* SPI4* TIM3* TIM2*
答:Matek H743也有类似RcInput定义,这里进行了引脚重新规划。
# USART6 (RC input), SERIAL7
PC7 TIM3_CH2 TIM3 RCININT PULLDOWN LOW
PC6 USART6_TX USART6 NODMA
【1】ArduPilot开源飞控系统之简单介绍
MatekH743定义与功能规格书一致。
# USART1 (telem2)
PA10 USART1_RX USART1
PA9 USART1_TX USART1
AOCODARC H743定义与功能规格书有差异。
# USART1 (RC input)
PA9 USART1_TX USART1
PA10 TIM1_CH3 TIM1 RCININT PULLDOWN LOW