1 引言
半年前入手了Pixhawk V2全套硬件,编译好的开源固件也下了,四轴也飞了,一直想对这套开源飞控进行一个系统地解析,由于工作原因一直没时间。最近翻开了PX4飞控源代码,它基于NUTTX操作系统,在github上更新十分迅速。为了能够全面地掌握这套软硬件设计思想,同时对硬件系统有全面的认识,我决定对PX4 Bootloader进行详细解析。凡涉及到硬件相关的部分,本文以Pixhawk V2的主控STM32F427和IO协处理器STM32F100为基础进行解析,其他硬件可参照此方法进行类比,基本结构都是相似的。
感谢韦东山老师u-boot视频,我用同样的方法对PX4 Bootloader采用类似的方法进行了分析。针对我解析中存在的问题,希望同行和前辈们能够不吝赐教,谢谢。
2 PX4 Bootloader系统架构
从github上下载之后,打开Bootloader文件夹,可以看到libopencm3和Tools共2个文件夹和一共30个文件。
libopencm3和Tools这两个文件夹的主要功能如下:
- Tools文件夹主要用于coding style和git submodule的检查,不需要太注意。
- libopencm3是github上针对STM32系列芯片的开源库,Bootloader使用其中的库函数对相应型号的芯片进行操作,用到的地方将对库函数功能作简要说明,这里并不展开讨论。
其余30个文件主要功能如下:
- 工程文件:包括Bootloader.sublime-project共1个文件,为sublime编辑器的工程文件。
- Readme:包括Readme.md文件共1个,自己看,都能看懂。
- License:包括LISENCE.md文件1个,权限文件,自己看。
- Makefile文件:包括Makefile、Makefile.f1、Makefile.f2、Makefile.f3、Makefile.f4、Makefile.f7共5个文件,为系统的编译过程提供了依据。
- Jtag配置文件:以.cfg结尾,包括jig_px4fmu.cfg、stm32f1x.cfg、stm32f3x.cfg、stm32f4x.cfg、stm32f102.cfg共5个文件,分别对应不同的Jtag烧写器、不同芯片使用openocd进行烧写时的配置。根据原理图可知,PX4 Bootloader可以使用Jtag接口进行程序烧写,某宝上买的Pixhawk V2拆开后在板上可以看到两个Jtag接口(分别对应主控STM32F427和协处理STM32F100),但是没有焊接出来,如需烧写bootloader程序可自行焊接。
- 硬件配置头函数:包括hw_config.h共1个文件,规定了各类可运行PX4开源飞控程序的硬件配置,可与原理图对应查看。
- 通用bootloader调用函数集:包括bl.h和bl.c共2个文件。提供了bootloader的main函数中需要调用的通用函数,这些函数与具体硬件无关,属顶层调用函数。
- USB调试接口函数集:包括cdcacm.h和cdcacm.c共2个文件。提供了bootloader程序基于USB接口进行调试时所需的输入输出函数。
- 串口调试接口集:包括usart.h和usart.c共2个文件。提供了bootloader程序基于串口进行调试时所需的输入输出函数。
- main函数:包括main_f1.c、main_f3.c、main_f4.c、main_f7.c共4个文件。分别对应STM32F1、STM32F3、STM32F4和STM32F7芯片上运行的Bootloader的主函数。
- 链接文件:以.ld结尾,包括stm32f1.ld、stm32f3.ld、stm32f4.ld、stm32f7.ld共4个文件。分别对应STM32F1、STM32F3、STM32F4和STM32F7芯片上Bootloader程序的链接方式。
- PX固件生成脚本:包括px_mkfw.py共1个文件。根据文件说明,PX4固件为基于JSON编码的python对象,此脚本用于生成包含额外编码域的压缩文件固件,类似于u-boot中mkimage程序,生成的固件上传前需要用此脚本进行打包。PX4的固件本身已经具有这项功能,这个脚本应该不再需要了,应该很快会被丢弃。
- PX固件上传脚本:包括px_uploader.py共1个文件。根据说明,此文件不再使用,已被固件中的上传脚本取代。
综上所述,这里需要重点分析的文件包括Makefile文件,链接文件,main函数文件,硬件配置头文件(hw_config.h),通用bootloader调用函数集文件(bl.h和bl.c),USB虚拟串口函数集文件(cdcacm.h和cdcacm.c),串口函数集文件(包括usart.h和usart.c)。
3 Makefile文件解析
PX4 Bootloader工程包含5个Makefile文件。其中Makefile是make命令的入口文件,将根据不同的编译对象,调用不同的Makefile.*文件。为了更清晰地了解Bootloader的编译过程,本节将对工程的Makefile进行详细注释。
3.1 主Makefile文件注释
Bootloader编译的make命令入口为根目录下的Makefile,这是所有编译命令开始的文件。
Makefile
#
# Paths to common dependencies
#
export BL_BASE ?= $(wildcard .) #获取Bootloader本地工程所在目录,并赋给变量BL_BASE
export LIBOPENCM3 ?= $(wildcard libopencm3) #获取开源库libopencm3所在目录,并赋给变量LIBOPENCM3
#
# Tools
#
export CC = arm-none-eabi-gcc #定义交叉编译工具链变量CC
export OBJCOPY = arm-none-eabi-objcopy #定义二进制生成工具链变量OBJCOPY
#
# Common configuration
#
export FLAGS = -std=gnu99 \ #使用GNU99的优化C语言标准
-Os \ #专门针对生成目标文件大小进行
-g \ #生成调试信息
-Wundef \ #当没有定义的符号出现在#if中时警告
-Wall \ #打开一些有用的警告选项
-fno-builtin \ #不接受没有__buildin__前缀的函数作为内建函数
-I$(LIBOPENCM3)/include \ #包含开源库libopencm3的头文件
-ffunction-sections \ #要求编译器为每个function分配独立的section
-nostartfiles \ #链接时不使用标准的启动文件
-lnosys \ #链接libnosys.a文件
-Wl,-gc-sections \ #传递-gc-sections给连接器,删除没有使用的section
-Wl,-g \ #传递-g选项给链接器,兼容其他工具
-Werror #把警告当错误,出现警告就放弃编译
export COMMON_SRCS = bl.c cdcacm.c usart.c #定义通用源文件变量COMMON_SRCS
#
# Bootloaders to build
#
TARGETS = \ #定义编译目标
aerofcv1_bl \
auavx2v1_bl \
crazyflie_bl \
mindpxv2_bl \
px4aerocore_bl \
px4discovery_bl \
px4flow_bl \
px4fmu_bl \
px4fmuv2_bl \
px4fmuv4_bl \
px4fmuv4pro_bl \
px4fmuv5_bl \
px4io_bl \
px4iov3_bl \
tapv1_bl
all: $(TARGETS) #编译目标all=$(TARGETS)
clean: #定义清理工程的操作(即make clean)
cd libopencm3 && make --no-print-directory clean && cd .. # 从Bootloader本地工程目录进入libopencm3文件夹,执行make clean清理命令,然后回到上一级目录。
rm -f *.elf *.bin #删除.efl和.bin文件
#
# Specific bootloader targets.
# 各编译目标的具体操作,主要规定了编译需要使用的Makefile文件,硬件目标TARGET_HW,链接脚本LINKER_FILE,编译目标TARGET_FILE_NAME
#
auavx2v1_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=AUAV_X2V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
px4fmu_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_FMU_V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
px4fmuv2_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_FMU_V2 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
px4fmuv4_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_FMU_V4 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
px4fmuv4pro_bl:$(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_FMU_V4_PRO LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@ EXTRAFLAGS=-DSTM32F469
px4fmuv5_bl:$(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f7 TARGET_HW=PX4_FMU_V5 LINKER_FILE=stm32f7.ld TARGET_FILE_NAME=$@
mindpxv2_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=MINDPX_V2 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
px4discovery_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_DISCOVERY_V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
px4flow_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_FLOW_V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
px4aerocore_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_AEROCORE_V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
crazyflie_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=CRAZYFLIE LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
# Default bootloader delay is *very* short, just long enough to catch
# the board for recovery but not so long as to make restarting after a
# brownout problematic.
#
px4io_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f1 TARGET_HW=PX4_PIO_V1 LINKER_FILE=stm32f1.ld TARGET_FILE_NAME=$@
px4iov3_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f3 TARGET_HW=PX4_PIO_V3 LINKER_FILE=stm32f3.ld TARGET_FILE_NAME=$@
tapv1_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=TAP_V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
aerofcv1_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=AEROFC_V1 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
#
# Binary management
# 二进制文件压缩操作:deploy命令
#
.PHONY: deploy
deploy:
zip Bootloader.zip *.bin
#
# Submodule management
# 子模块libopencm3操作与管理,进行的操作如下:
# 1. 更新git子工程libopencm3。
# 2. 调用Tools/check_submodules.sh检查当前libopencm3的版本信息是否正确。
# 3. 编译libopencm3工程,生成库文件,供bootloader使用。
#
$(LIBOPENCM3): checksubmodules
make -C $(LIBOPENCM3) lib
.PHONY: checksubmodules
checksubmodules: updatesubmodules
$(Q) ($(BL_BASE)/Tools/check_submodules.sh)
.PHONY: updatesubmodules
updatesubmodules:
$(Q) (git submodule init)
$(Q) (git submodule update)
3.2 主控Makefile.f4文件注释
由主Makefile中目标生成语句可以看出,Pixhawk V2硬件系统的主控stm32f427对应的bootloader调用了如下语句:
Makefile
px4fmuv2_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f4 TARGET_HW=PX4_FMU_V2 LINKER_FILE=stm32f4.ld TARGET_FILE_NAME=$@
因此,目标px4fmuv2_bl生成的Makefile脚本为Makefile.f4,同时,它还定义了如下变量
- 硬件目标:$(TARGET_HW)=PX4_FMU_V2
- 链接文件:$(LINKER_FILE)=stm32f4.ld
- 目标名称:$(TARGET_FILE_NAME)=$@=px4fmuv2_bl
同时,在主Makefile中规定的全局变量BL_BASE、LIBOPENCM3、CC、OBJCOPY、FLAGS、COMMON_SRCS在Makefile.f4中同样有效。下面将对Makefile.f4进行详细注释。
Makefile.f4
OPENOCD ?= openocd #定义OPENOCD命令
JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg #定义openocd对应的jtag烧写器配置文件
#JTAGCONFIG ?= interface/jtagkey-tiny.cfg
# 5 seconds / 5000 ms default delay
PX4_BOOTLOADER_DELAY ?= 5000 #定义启动变量PX4_BOOTLOADER_DELAY为5000ms
SRCS = $(COMMON_SRCS) main_f4.c #定义编译源文件为bl.c cdcacm.c usart.c和main_f4.c
FLAGS += -mthumb\ #使用thumb指令集
-mcpu=cortex-m4\ #使用cortex m4对应的CPU指令
-mfloat-abi=hard\ #浮点为硬件浮点运算
-mfpu=fpv4-sp-d16 \ #浮点运算协处理器为fpv4-sp-d16
-DTARGET_HW_$(TARGET_HW) \ #定义变量TARGET_HW_PX4_FMU_V2为1
-DSTM32F4 \ #定义变量STM32F4为1
-T$(LINKER_FILE) \ #使用链接文件stm32f4.ld
-L$(LIBOPENCM3)/lib \ #添加库文件搜索目录libopencm3/lib
-lopencm3_stm32f4 \ #链接库文件libopencm3_stm32f4.a
$(EXTRAFLAGS)
ELF = $(TARGET_FILE_NAME).elf #定义目标变量ELF=px4fmuv2_bl.elf
BINARY = $(TARGET_FILE_NAME).bin #定义目标二进制变量BINARY=px4fmuv2_bl.bin
all: $(ELF) $(BINARY) #定义目标all,为px4fmuv2_bl.elf和px4fmuv2_bl.bin
#px4fmuv2_bl.elf的生成规则:
#px4fmuv2_bl.elf: bl.c cdcacm.c usart.c main_f4.c Makefile
# arm-none-eabi-gcc -o px4fmuv2_bl.elf bl.c cdcacm.c usart.c main_f4.c $(FLAGS)
$(ELF): $(SRCS) $(MAKEFILE_LIST)
$(CC) -o $@ $(SRCS) $(FLAGS)
#px4fmuv2_bl.bin的生成规则:
#px4fmuv2_bl.bin: px4fmuv2_bl.elf
# arm-none-eabi-objcopy -O binary px4fmuv2_bl.elf px4fmuv2_bl.bin
$(BINARY): $(ELF)
$(OBJCOPY) -O binary $(ELF) $(BINARY)
#upload: all flash flash-bootloader
#定义upload目标,依赖于all flash-bootloader
upload: all flash-bootloader
#定义flash-bootloader目标的命令规则
#执行openocd命令,查找与本工程目录平行的px4_bootloader目录中interface/olimex-jtag-tiny.cfg文件作为jtag烧写器的配置文件,以stm32f4x.cfg作为主控stm32f427的SOC配置文件。然后在openocd环境下依次执行init, reset halt, flash write_image erase px4fmuv2_bl.bin 0x08000000, reset run, shutdown命令进行烧写。
flash-bootloader:
$(OPENOCD) --search ../px4_bootloader -f $(JTAGCONFIG) -f stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase $(BINARY) 0x08000000" -c "reset run" -c shutdown
# Use to upload to a stm32f4-discovery devboard, requires the latest version of openocd (from git)
# build openocd with "cd openocd; ./bootstrap; ./configure --enable-maintainer-mode --enable-stlink"
#定义upload-discovery目标的命令规则
#执行openocd命令,默认使用stlink烧写器及其配置文件,查找board/stm32f4discovery.cfg配置文件,在openocd环境下依次执行init, reset halt, flash probe 0, stm32f2x mass_erase 0, flash write_image erase px4fmuv2_bl.bin 0x08000000, reset, shutdown命令进行烧写。
upload-discovery:
$(OPENOCD) --search ../px4_bootloader -f board/stm32f4discovery.cfg -c init -c "reset halt" -c "flash probe 0" -c "stm32f2x mass_erase 0" -c "flash write_image erase $(BINARY) 0x08000000" -c "reset" -c shutdown
3.3 IO协处理器Makefile.f1文件注释
由主Makefile中目标生成语句可以看出,Pixhawk V2硬件系统的IO协处理器stm32f100对应的bootloader调用了如下语句:
Makefile
px4io_bl: $(MAKEFILE_LIST) $(LIBOPENCM3)
make -f Makefile.f1 TARGET_HW=PX4_PIO_V1 LINKER_FILE=stm32f1.ld TARGET_FILE_NAME=$@
因此,目标px4io_bl生成的Makefile脚本为Makefile.f1,同时,它还定义了如下变量
- 硬件目标:$(TARGET_HW)=PX4_PIO_V1
- 链接文件:$(LINKER_FILE)=stm32f1.ld
- 目标名称:$(TARGET_FILE_NAME)=$@=px4io_bl
同理,在主Makefile中规定的全局变量BL_BASE、LIBOPENCM3、CC、OBJCOPY、FLAGS、COMMON_SRCS在Makefile.f1中同样有效。下面将对Makefile.f1进行详细注释。
Makefile.f1
OPENOCD ?= ../../sat/bin/openocd #定义openocd命令变量
JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg #定义Jtag烧写器配置文件
#JTAGCONFIG ?= interface/jtagkey-tiny.cfg
# 3 seconds / 3000 ms default delay
PX4_BOOTLOADER_DELAY ?= 3000 #定义bootloader延时3000ms
SRCS = $(COMMON_SRCS) main_f1.c #定义源文件为bl.c cdcacm.c usart.c和main_f1.c
FLAGS += -mthumb\ #使用thumb指令集
-mcpu=cortex-m3\ #使用cortex m3指令集
-DTARGET_HW_$(TARGET_HW) \ #定义TARGET_HW_PX4_PIO_V1变量为1
-DSTM32F1 \ #定义STM32F1变量为1
-T$(LINKER_FILE) \ #使用链接脚本stm32f1.ld
-L$(LIBOPENCM3)/lib \ #增加库文件搜索目录libopencm3/lib
-lopencm3_stm32f1 #链接库文件libopencm3_stm32f1.a
ELF = $(TARGET_FILE_NAME).elf #定义ELF目标变量px4io_bl.elf
BINARY = $(TARGET_FILE_NAME).bin #定义BINARY目标变量px4io_bl.bin
all: $(ELF) $(BINARY) #定义目标all为px4io_bl.elf和px4io_bl.bin
#px4io_bl.elf生成规则
#px4io_bl.elf: bl.c cdcacm.c usart.c main_f1.c Makefile
# arm-none-eabi-gcc -o px4io_bl.elf bl.c cdcacm.c usart.c main_f1.c $(FLAGS)
$(ELF): $(SRCS) $(MAKEFILE_LIST)
$(CC) -o $@ $(SRCS) $(FLAGS)
#px4io_bl.bin生成规则
#px4io_bl.bin: px4io_bl.elf
# arm-none-eabi-objcopy -O binary px4io_bl.elf px4io_bl.bin
$(BINARY): $(ELF)
$(OBJCOPY) -O binary $(ELF) $(BINARY)
#upload: all flash flash-bootloader
#定义upload目标,依赖于all flash-bootloader
upload: all flash-bootloader
#flash-bootloader目标生成命令
#执行openocd命令,查找与本工程目录平行的px4_bootloader目录中interface/olimex-jtag-tiny.cfg文件作为jtag烧写器的配置文件,以stm32f1.cfg作为IO协处理器stm32f100的SOC配置文件。然后在openocd环境下依次执行init, reset halt, flash write_image erase px4io_bl.bin, reset run, shutdown命令进行烧写。
flash-bootloader:
$(OPENOCD) --search ../px4_bootloader -f $(JTAGCONFIG) -f stm32f1.cfg -c init -c "reset halt" -c "flash write_image erase $(BINARY)" -c "reset run" -c shutdown
4 链接文件解析
PX4 Bootloader中包含4个链接文件stm32f1.ld、stm32f3.ld、stm32f4.ld和stm32f7.ld。与pixhawk V2硬件相关的为主控stm32f4.ld和IO协处理器stm32f1.ld两个链接脚本,它们将作为本文的分析重点。
PX4 Bootloader的链接文件可分为如下4个部分:
- 声明可使用存储结构变量
- 声明向量表名称
- 定义段区
- 定义栈顶地址变量值
4.1 主控链接脚本stm32f4.ld解析
链接脚本stm32f4.ld和libopencm3/lib/cm3/vector.c文件之间的关系十分密切。stm32f4.ld中定义了一系列在vector.c文件中使用的变量,包括_data_loadaddr,_data,_edata,_ebss,_stack,__preinit_array_start,__preinit_array_end,__init_array_start,__init_array_end,__fini_array_start,__fini_array_end,这些变量被用于Cortex M4的向量表初始化,主要是第一项的堆栈指针初始化和第二项的reset_handler函数的初始化。链接脚本stm32f4.ld中声明的向量表变量vector_table的定义在vector.c文件中。
与其它常见的链接脚本不同,stm32f4.ld中没有关键字ENTRY来规定程序的入口地址,在这种情况下程序就是从代码段(text)开始的。代码段最开始位置的是向量表,且ST公司的Cortex M4内核默认入口首地址(0x0)为堆栈指针(SP寄存器)的值;第二字为入口地址,因此reset_handler函数被调用为程序入口地址。
stm32f4.ld
/* Define memory regions. */
/* 声明存储区域,分为rom和ram两部分 */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 16K /* 定义rom区,即片内flash的部分区域,权限可读可执行,起始于flash起始地址0x08000000,使用前16K(即Section 0) */
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K /* 定义ram区,即片内SRAM的部分区域,权限可读可写可执行,起始于SRAM1起始地址0x20000000,包含SRAM1和SRAM2的全部区域(128K) */
}
/* Enforce emmission of the vector table. */
/* 声明外部定义的vector_table变量,此变量被定义在libopencm3/lib/cm3/vector.c中 */
EXTERN (vector_table)
/* Define sections. */
SECTIONS /* 定义段 */
{
. = ORIGIN(rom); /* 链接器指针定位于rom区起始地址 */
.text : { /* 定义代码段text */
*(.vectors) /* Vector table 中断向量表,定义于libopencm3/lib/cm3/vector.c文件中,仅包含vector_table变量 */
*(.text*) /* Program code 程序代码段 */
. = ALIGN(4); /* 4字节对齐 */
*(.rodata*) /* Read-only data 程序只读数据段 */
. = ALIGN(4); /* 4字节对齐 */
_etext = .; /* 定义变量_etext为当前地址 */
} >rom /* 代码段text的程序地址位于rom中 */
/* C++ Static constructors/destructors, also used for __attribute__
* ((constructor)) and the likes */
.preinit_array : { /* 定义C++构造函数段preinit_array */
. = ALIGN(4); /* 4字节对齐 */
__preinit_array_start = .; /* 定义变量__preinit_array_start为当前地址 */
KEEP (*(.preinit_array)) /* 强制链接器保留preinit_array段 */
__preinit_array_end = .; /* 定义变量__preinit_array_end为当前地址 */
} >rom /* C++构造函数段preinit_array的程序地址位于rom中 */
.init_array : { /* 定义C++构造函数段init_array */
. = ALIGN(4); /* 4字节对齐 */
__init_array_start = .; /* 定义变量__init_array_start为当前地址 */
KEEP (*(SORT(.init_array.*))) /* 强制链接器保留init_array.* 段,并对满足字符串模式的内容进行升序排列 */
KEEP (*(.init_array)) /* 强制链接器保留init_array段 */
__init_array_end = .; /* 定义变量__init_array_end为当前地址 */
} >rom /* C++构造函数段init_array的程序地址位于rom中 */
.fini_array : { /* 定义C++析构函数段fini_array */
. = ALIGN(4); /* 4字节对齐 */
__fini_array_start = .; /* 定义变量__fini_array_start为当前地址 */
KEEP (*(.fini_array)) /* 强制链接器保留fini_array段 */
KEEP (*(SORT(.fini_array.*))) /* 强制链接器保留fini_array.*段,并对满足字符串模式的内容进行排序 */
__fini_array_end = .; /* 定义变量__fini_array_end为当前地址 */
} >rom /* C++析构函数段fini_array的程序地址位于rom中 */
. = ORIGIN(ram); /* 链接器指针定位于ram区起始地址 */
.data : AT(_etext) { /* 定义数据段data,加载地址位于变量_etext定义的位置 */
_data = .; /* 定义变量_data为当前地址 */
*(.data*) /* Read-write initialized data,程序数据段 */
. = ALIGN(4); /* 4字节对齐 */
_edata = .; /* 定义变量_edata为当前地址 */
} >ram /* 数据段data的程序地址位于ram中 */
_data_loadaddr = LOADADDR(.data); /* 定义变量_data_loadaddr为数据段加载地址的起始位置 */
.bss : { /* 定义bss段 */
*(.bss*) /* Read-write zero initialized data,程序bss段 */
*(COMMON) /* COMMON段 */
. = ALIGN(4); /* 4字节对齐 */
_ebss = .; /* 定义变量_ebss为当前地址 */
} >ram AT >rom /* bss段的程序地址位于ram中,加载地址位于rom中 */
/*
* The .eh_frame section appears to be used for C++ exception handling.
* You may need to fix this if you're using C++.
*/
/DISCARD/ : { *(.eh_frame) } /* 被丢弃段eh_frame不会出现在输出文件中 */
. = ALIGN(4); /* 4字节对齐 */
end = .; /* 定义变量end为当前地址 */
}
PROVIDE(_stack = 0x20020000); /* 定义变量_stack,仅在被使用时生效,堆栈指针指向ram区最高地址 */
4.2 IO协处理器链接脚本stm32f1.ld解析
链接脚本stm32f1.ld与stm32f4.ld情况十分相近,不再复述,这里仅对其进行注释。
stm32f1.ld
/* Define memory regions. */
/* 声明存储区域,分为rom和ram两部分 */
MEMORY
{
rom (rx) : ORIGIN = 0x08000000, LENGTH = 4K /* 定义rom区,即片内flash的部分区域,权限可读可执行,起始于flash起始地址0x08000000,使用前4K(即Page 0~3) */
ram (rwx) : ORIGIN = 0x20000000, LENGTH = 8K /* 定义ram区,即片内SRAM的部分区域,权限可读可写可执行,起始于SRAM1起始地址0x20000000,使用全部8K(注意F100系列片内RAM最高为8K) */
}
/* Enforce emmission of the vector table. */
/* 声明外部定义的vector_table变量,此变量被定义在libopencm3/lib/cm3/vector.c中 */
EXTERN (vector_table)
/* Define sections. */
SECTIONS /* 定义段 */
{
. = ORIGIN(rom); /* 链接器指针定位于rom区起始地址 */
.text : { /* 定义代码段text */
*(.vectors) /* Vector table 中断向量表,定义于libopencm3/lib/cm3/vector.c文件中,仅包含vector_table变量 */
*(.text*) /* Program code 程序代码段 */
. = ALIGN(4); /* 4字节对齐 */
*(.rodata*) /* Read-only data 程序只读数据段 */
. = ALIGN(4); /* 4字节对齐 */
_etext = .; /* 定义变量_etext为当前地址 */
} >rom /* 代码段text的程序地址位于rom中 */
/* C++ Static constructors/destructors, also used for __attribute__
* ((constructor)) and the likes */
.preinit_array : { /* 定义C++构造函数段preinit_array */
. = ALIGN(4); /* 4字节对齐 */
__preinit_array_start = .; /* 定义变量__preinit_array_start为当前地址 */
KEEP (*(.preinit_array)) /* 强制链接器保留preinit_array段 */
__preinit_array_end = .; /* 定义变量__preinit_array_end为当前地址 */
} >rom /* C++构造函数段preinit_array的程序地址位于rom中 */
.init_array : { /* 定义C++构造函数段init_array */
. = ALIGN(4); /* 4字节对齐 */
__init_array_start = .; /* 定义变量__init_array_start为当前地址 */
KEEP (*(SORT(.init_array.*))) /* 强制链接器保留init_array.* 段,并对满足字符串模式的内容进行升序排列 */
KEEP (*(.init_array)) /* 强制链接器保留init_array段 */
__init_array_end = .; /* 定义变量__init_array_end为当前地址 */
} >rom /* C++构造函数段init_array的程序地址位于rom中 */
.fini_array : { /* 定义C++析构函数段fini_array */
. = ALIGN(4); /* 4字节对齐 */
__fini_array_start = .; /* 定义变量__fini_array_start为当前地址 */
KEEP (*(.fini_array)) /* 强制链接器保留fini_array段 */
KEEP (*(SORT(.fini_array.*))) /* 强制链接器保留fini_array.* 段,并对满足字符串模式的内容进行升序排列 */
__fini_array_end = .; /* 定义变量__fini_array_end为当前地址 */
} >rom /* C++析构函数段fini_array的程序地址位于rom中 */
. = ORIGIN(ram); /* 链接器指针定位于ram区起始地址 */
.data : AT(_etext) { /* 定义数据段data,加载地址位于变量_etext定义的位置 */
_data = .; /* 定义变量_data为当前地址 */
*(.data*) /* Read-write initialized data 程序数据段 */
. = ALIGN(4); /* 4字节对齐 */
_edata = .; /* 定义变量_edata为当前地址 */
} >ram /* 数据段data的程序地址位于ram中 */
_data_loadaddr = LOADADDR(.data); /* 定义变量_data_loadaddr为数据段加载地址的起始位置 */
.bss : { /* 定义bss段 */
*(.bss*) /* Read-write zero initialized data 程序bss段 */
*(COMMON) /* COMMON段 */
. = ALIGN(4); /* 4字节对齐 */
_ebss = .; /* 定义变量_ebss为当前地址 */
} >ram AT >rom /* bss段的程序地址位于ram中,加载地址位于rom中 */
/*
* The .eh_frame section appears to be used for C++ exception handling.
* You may need to fix this if you're using C++.
*/
/DISCARD/ : { *(.eh_frame) } /* 被丢弃段eh_frame不会出现在输出文件中 */
. = ALIGN(4); /* 4字节对齐 */
end = .; /* 定义变量end为当前地址 */
}
PROVIDE(_stack = 0x20002000); /* 定义变量_stack,仅在被使用时生效,堆栈指针指向ram区最高地址 */
5 硬件配置头文件
PX4 Bootloader的硬件配置头文件仅有一个,hw_config.h。这套代码支持的所有硬件板配置均可在这里找到。它的结构很简单,针对不同的硬件配置使用#if-#elif-#end宏条件编译语句进行配置。针对Pixhawk V2这套硬件,仅涉及其中TARGET_HW_PX4_FMU_V2和TARGET_HW_PX4_PIO_V1两个条件编译块中的内容。由于本节将涉及具体的硬件信息,将结合芯片手册和原理图对这两部分内容进行详细解析。
5.1 主控宏TARGET_HW_PX4_FMU_V2对应的配置
在Makefile.f4的FLAGS变量中定义了TARGET_HW_PX4_FMU_V2和STM32F4两个变量,这两个变量主要用于宏条件编译分支的判断上,对硬件板载配置的时候起到了决定性的作用。
Makefile.f4
FLAGS += -mthumb\ #使用thumb指令集
-mcpu=cortex-m4\ #使用cortex m4对应的CPU指令
-mfloat-abi=hard\ #浮点为硬件浮点运算
-mfpu=fpv4-sp-d16 \ #浮点运算协处理器为fpv4-sp-d16
-DTARGET_HW_$(TARGET_HW) \ #定义变量TARGET_HW_PX4_FMU_V2为1
-DSTM32F4 \ #定义变量STM32F4为1
-T$(LINKER_FILE) \ #使用链接文件stm32f4.ld
-L$(LIBOPENCM3)/lib \ #添加库文件搜索目录libopencm3/lib
-lopencm3_stm32f4 \ #链接库文件libopencm3_stm32f4.a
$(EXTRAFLAGS)
hw_config.h文件中对应主控宏TARGET_HW_PX4_FMU_V2的代码如下:
hw_config.h
#elif defined(TARGET_HW_PX4_FMU_V2) /* 若TARGET_HW_PX4_FMU_V2为真,下面的宏定义有效 */
# define APP_LOAD_ADDRESS 0x08004000 /* APP_LOAD_ADDRESS,为Bootloader初始化完成后的飞控固件跳转地址(实际入口地址在0x08004004,这一点在bl.c文件的源代码中可以看到,0x08004000被用于标识后面的代码是否有效) */
# define BOOTLOADER_DELAY 5000 /* BOOTLOADER_DELAY,为Bootloader初始化完毕到跳转到飞控固件需等待的时间 */
# define BOARD_FMUV2 /* BOARD_FMUV2,在全部代码中没有用到 */
# define INTERFACE_USB 1 /* INTERFACE_USB,表示Bootloader可采用USB口与上位机通信 */
# define INTERFACE_USART 1 /* INTERFACE_USART,表示Bootloader可采用串口与上位机通信 */
# define USBDEVICESTRING "PX4 BL FMU v2.x" /* USBDEVICESTRING,表示对应USB ID的字符串 */
# define USBPRODUCTID 0x0011 /* USBPRODUCTID,USB接口的PID */
# define BOOT_DELAY_ADDRESS 0x000001a0 /* BOOT_DELAY_ADDRESS,flash上对应存放Bootloader等待时间的内存地址 */
# define BOARD_TYPE 9 /* BOARD_TYPE,对应不同硬件配置板子上处理器的编号,每个不同的处理器对应不同的值 */
# define _FLASH_KBYTES (*(uint16_t *)0x1fff7a22) /* _FLASH_KBYTES,程序运行期间flash以KB计的大小的存储地址(为何位于Reserved地址?) */
# define BOARD_FLASH_SECTORS ((_FLASH_KBYTES == 0x400) ? 11 : 23) /* BOARD_FLASH_SECTORS,STM32F4芯片若片内flash为1M,则Sector数量为11;若不为1M(2M),则Sector数量为23,详见芯片手册 */
# define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024) /* BOARD_FLASH_SIZE,flash总大小 */
# define OSC_FREQ 24 /* OSC_FREQ,外部晶振频率24kHz */
/* 主控FMU指示灯在板上一共有2个,FMU的PWR和B/E;PWR(LED704)为绿色常亮,上电即亮,B/E(LED701)由FMU的GPIOE12控制,为闪烁红色 */
# define BOARD_PIN_LED_ACTIVITY 0 // no activity LED,无命令处理显示LED灯
# define BOARD_PIN_LED_BOOTLOADER GPIO12 /* BOARD_PIN_LED_BOOTLOADER,主控Bootloader的LED指示灯为GPIOE12 */
# define BOARD_PORT_LEDS GPIOE /* BOARD_PORT_LEDS,主控FMU的LED指示灯控制引脚在GPIO Port E */
# define BOARD_CLOCK_LEDS RCC_AHB1ENR_IOPEEN /* BOARD_CLOCK_LEDS,RCC_AHB1ENR_IOPEEN被libopencm3/include/libopencm3/stm32/f4/rcc.h定义为(1<<4),对应RCC_AHB1ENR寄存器的第4位,GPIOE的时钟使能位 */
# define BOARD_LED_ON gpio_clear /* BOARD_LED_ON,gpio_clear函数定义在libopencm3/lib/stm32/common/gpio_common_all.c中,实际为GPIO pin清零功能 */
# define BOARD_LED_OFF gpio_set /* BOARD_LED_OFF,gpio_set函数定义在libopencm3/lib/stm32/common/gpio_common_all.c中,实际为GPIO pin置1功能 */
# define BOARD_USART USART2 /* BOARD_USART,通信串口,USART2被libopencm3/include/libopencm3/stm32/common/usart_common_all.h定义为USART2_BASE(0x40004400) */
# define BOARD_USART_CLOCK_REGISTER RCC_APB1ENR /* BOARD_USART_CLOCK_REGISTER,被定义为RCC_APB1ENR寄存器,用于使能USART2的时钟 */
# define BOARD_USART_CLOCK_BIT RCC_APB1ENR_USART2EN /* BOARD_USART_CLOCK_BIT,RCC_APB1ENR_USART2EN被libopencm3/include/libopencm3/stm32/f4/rcc.h定义为(1<<17),对应RCC_APB1ENR的17位,用于使能USART2的时钟 */
# define BOARD_PORT_USART GPIOD /* BOARD_PORT_USART,USART2的引脚位于GPIO Port D */
# define BOARD_PORT_USART_AF GPIO_AF7 /* BOARD_PORT_USART_AF,GPIO_AF7被libopencm3/include/libopencm3/stm32/common/gpio_common_f234.h定义为0x7,对应AF7的alternative function功能为USART1~3 */
# define BOARD_PIN_TX GPIO5 /* BOARD_PIN_TX,USART2的发送引脚为GPIOD5 */
# define BOARD_PIN_RX GPIO6 /* BOARD_PIN_RX,USART2的接收引脚为GPIOD6 */
# define BOARD_USART_PIN_CLOCK_REGISTER RCC_AHB1ENR /* BOARD_USART_PIN_CLOCK_REGISTER,被定义为RCC_AHB1ENR寄存器,用于使能USART2引脚的时钟 */
# define BOARD_USART_PIN_CLOCK_BIT RCC_AHB1ENR_IOPDEN /* BOARD_USART_PIN_CLOCK_BIT,RCC_AHB1ENR_IOPDEN被libopencm3/include/libopencm3/stm32/f4/rcc.h定义为(1<<3),对应RCC_AHB1ENR寄存器的第3位,用于使能GPIOD的时钟 */
5.2 IO协处理器宏TARGET_HW_PX4_PIO_V1对应的配置
在Makefile.f1的FLAGS变量中定义了TARGET_HW_PX4_PIO_V1和STM32F1两个变量,这两个变量主要用于宏条件编译分支的判断上,对硬件板载配置的时候起到了决定性的作用。
Makefile.f1
FLAGS += -mthumb\ #使用thumb指令集
-mcpu=cortex-m3\ #使用cortex m3指令集
-DTARGET_HW_$(TARGET_HW) \ #定义TARGET_HW_PX4_PIO_V1变量为1
-DSTM32F1 \ #定义STM32F1变量为1
-T$(LINKER_FILE) \ #使用链接脚本stm32f1.ld
-L$(LIBOPENCM3)/lib \ #增加库文件搜索目录libopencm3/lib
-lopencm3_stm32f1 #链接库文件libopencm3_stm32f1.a
hw_config.h文件中对应主控宏TARGET_HW_PX4_PIO_V1的代码如下:
hw_config.h
#elif defined(TARGET_HW_PX4_PIO_V1) || defined(TARGET_HW_PX4_PIO_V2) /* 若TARGET_HW_PX4_FMU_V2为真,下面的宏定义有效 */
# define APP_LOAD_ADDRESS 0x08001000 /* APP_LOAD_ADDRESS,为bootloader初始化完成后的飞控固件跳转地址(实际入口地址在0x08001004,这一点在bl.c文件的源代码中可以看到,0x08001000被用于标识后面的代码是否有效) */
# define APP_SIZE_MAX 0xf000 /* APP_SIZE_MAX,板载系统程序(Bootloader)大小上限 */
# define BOOTLOADER_DELAY 200 /* BOOTLOADER_DELAY,为Bootloader初始化完毕到跳转到飞控固件需等待的时间 */
# define BOARD_PIO /* 未见引用 */
# define INTERFACE_USB 0 /* INTERFACE_USB,表示Bootloader不能用USB与上位机通信 */
# define INTERFACE_USART 1 /* INTERFACE_USART,表示Bootloader可以用串口与上位机通信 */
# define USBDEVICESTRING "" /* USBDEVICESTRING,因INTERFACE_USB为0,不使用USB与上位机通信,故USB ID的字符串设置为空 */
# define USBPRODUCTID -1 /* USBPRODUCTID,因INTERFACE_USB为0,不使用USB与上位机通信,故USB设备ID设为非法值 */
# define OSC_FREQ 24 /* OSC_FREQ,外部晶振频率24kHz */
/* IO协处理器指示灯在板上一共有3个,IO的PWR、B/E和ACT;PWR(LED702)为绿色常亮,上电即亮,B/E(LED703)由IO协处理器的GPIOB15控制,为闪烁红色,ACT(LED705)由IO协处理器的GPIOB14控制,为闪烁蓝色 */
# define BOARD_PIN_LED_ACTIVITY GPIO14 /* BOARD_PIN_LED_ACTIVITY,Bootloader有命令要处理时亮起,由IO协处理器的GPIOB14控制 */
# define BOARD_PIN_LED_BOOTLOADER GPIO15 /* BOARD_PIN_LED_BOOTLOADER,IO协处理器Bootloader的LED指示灯为GPIOB15 */
# define BOARD_PORT_LEDS GPIOB /* BOARD_PORT_LEDS,IO协处理器的LED指示灯控制引脚在GPIO Port B */
# define BOARD_CLOCK_LEDS_REGISTER RCC_APB2ENR /* BOARD_CLOCK_LEDS_REGISTER,被定义为RCC_APB2ENR寄存器,用于使能LED时钟 */
# define BOARD_CLOCK_LEDS RCC_APB2ENR_IOPBEN /* BOARD_CLOCK_LEDS,RCC_APB2ENR_IOPBEN被libopencm3/include/libopencm3/stm32/f1/rcc.h定义为(1<<3),对应RCC_APB2ENR寄存器的第3,GPIOB的时钟使能位 */
# define BOARD_LED_ON gpio_clear /* BOARD_LED_ON,gpio_clear函数定义在libopencm3/lib/stm32/common/gpio_common_all.c中,实际为GPIO pin清零功能 */
# define BOARD_LED_OFF gpio_set /* BOARD_LED_OFF,gpio_set函数定义在libopencm3/lib/stm32/common/gpio_common_all.c中,实际为GPIO pin置1功能 */
/* IO协处理器的通信串口为USART2,与主控FMU的USART6通信 */
# define BOARD_USART USART2 /* BOARD_USART,通信串口,USART2被libopencm3/include/libopencm3/stm32/common/usart_common_all.h定义为USART2_BASE(0x40004400) */
# define BOARD_USART_CLOCK_REGISTER RCC_APB1ENR /* BOARD_USART_CLOCK_REGISTER,被定义为RCC_APB1ENR寄存器,用于使能USART2的时钟 */
# define BOARD_USART_CLOCK_BIT RCC_APB1ENR_USART2EN /* BOARD_USART_CLOCK_BIT,RCC_APB1ENR_USART2EN被libopencm3/include/libopencm3/stm32/f1/rcc.h定义为(1<<17),对应RCC_APB1ENR的17位,用于使能USART2的时钟 */
# define BOARD_PORT_USART GPIOA /* BOARD_PORT_USART,USART2的引脚位于GPIO Port A */
# define BOARD_PIN_TX GPIO_USART2_TX /* BOARD_PIN_TX,GPIO_USART2_TX被libopencm3/include/libopencm3/stm32/f1/gpio.h中定义为GPIO2,PA2 */
# define BOARD_PIN_RX GPIO_USART2_RX /* BOARD_PIN_RX,GPIO_USART2_RX被libopencm3/include/libopencm3/stm32/f1/gpio.h中定义为GPIO3,PA3 */
# define BOARD_USART_PIN_CLOCK_REGISTER RCC_APB2ENR /* BOARD_USART_PIN_CLOCK_REGISTER,被定义为寄存器RCC_APB2ENR,用于使能USART2引脚的时钟 */
# define BOARD_USART_PIN_CLOCK_BIT RCC_APB2ENR_IOPAEN /* BOARD_USART_PIN_CLOCK_BIT,RCC_APB2ENR_IOPAEN被libopencm3/include/libopencm3/stm32/f1/rcc.h定义为(1<<2),对应RCC_APB2ENR的第2位,用于使能GPIOA的时钟 */
/* IO协处理器的GPIOB5接J702安全开关 */
# define BOARD_FORCE_BL_PIN GPIO5 /* BOARD_FORCE_BL_PIN,板载强制Bootloader引脚为GPIOB5 */
# define BOARD_FORCE_BL_PORT GPIOB /* BOARD_FORCE_BL_PIN,板载强制Bootloader引脚在GPIOB中 */
# define BOARD_FORCE_BL_CLOCK_REGISTER RCC_APB2ENR /* BOARD_FORCE_BL_CLOCK_REGISTER,被定义为RCC_APB2ENR,用于使能GPIOB5的时钟 */
# define BOARD_FORCE_BL_CLOCK_BIT RCC_APB2ENR_IOPBEN /* BOARD_FORCE_BL_CLOCK_BIT,RCC_APB2ENR_IOPBEN被libopencm3/include/libopencm3/stm32/f1/rcc.h定义为(1<<3),对应RCC_APB2ENR寄存器的第3,GPIOB的时钟使能位 */
# define BOARD_FORCE_BL_PULL GPIO_CNF_INPUT_FLOAT // depend on external pull BOARD_FORCE_BL_PULL,GPIO_CNF_INPUT_FLOAT被libopencm3/include/libopencm3/stm32/f1/gpio.h定义为0x01,根据芯片手册表示GPIOB5为浮动输入状态,其值取决于外部硬件输入,即安全开关的状态
# define BOARD_FORCE_BL_VALUE BOARD_FORCE_BL_PIN /* BOARD_FORCE_BL_VALUE,BOARD_FORCE_BL_PIN为GPIO5的值,用于判定IO协处理器是否永远进入Bootloader的循环状态 */
# define BOARD_FLASH_SECTORS 60 /* BOARD_FLASH_SECTORS,STM32F1片内flash页数,Bootloader认为片内flash的前60页有效 */
# define BOARD_TYPE 10 /* BOARD_TYPE,对应不同硬件配置板子上处理器的编号,每个不同的处理器对应不同的值 */
# define FLASH_SECTOR_SIZE 0x400 /* FLASH_SECTOR_SIZE,STM32F1片内flash每页大小为1KB */
6 核心数据结构
与u-boot类似,PX4 Bootloader运行时需要一些核心数据结构的支持。这些数据结构一般是全局变量,它们的值能够充分反映整个程序运行的状态。Pixhawk V2板上有两个处理器分别跑着各自的Bootloader,因此各自维持这自己的核心数据结构。无论主控FMU还是IO协处理器的Bootloader程序都是从向量表开始的,而且PX4 Bootloader对所有处理器的向量表处理方式完全相同,因此本节将向量表数据结构单独拿出来分析。
6.1 向量表vector_table_t
STM32的Cortex M核心启动时均需要中断向量表支持,因此这个数据结构对程序的启动至关重要。这个数据结构在库文件libopencm3/include/libopencm3/cm3/vector.h中定义,宏NVIC_IRQ_COUNT在libopencm3/include/libopencm3/dispatch/nvic.h中被定义为0,故一般中断向量irq数量为0,可理解为不启用一般中断。
vector.h
typedef void (*vector_table_entry_t)(void); /* 定义向量表函数指针类型 */
typedef struct {
unsigned int *initial_sp_value; /* 初始堆栈指针地址 */
vector_table_entry_t reset; /* 重启reset向量函数指针 */
vector_table_entry_t nmi; /* 不可屏蔽中断NMI向量函数指针 */
vector_table_entry_t hard_fault; /* 硬件错误hard_fault向量函数指针 */
vector_table_entry_t memory_manage_fault; /* 内存管理错误memory_manage_fault向量函数指针,Cortex M0核心不含此项 */
vector_table_entry_t bus_fault; /* 总线错误bus_fault向量函数指针,Cortex M0核心不含此项 */
vector_table_entry_t usage_fault; /* 指令使用错误usage_fault向量函数指针,Cortex M0核心不含此项 */
vector_table_entry_t reserved_x001c[4]; /* 预留 */
vector_table_entry_t sv_call; /* 管理模式sv_call向量函数指针 */
vector_table_entry_t debug_monitor; /* 调试监控debug_monitor向量函数指针,Cortex M0核心不含此项(手册显示M4和M3也没有) */
vector_table_entry_t reserved_x0034; /* 预留 */
vector_table_entry_t pend_sv; /* pend_sv向量函数指针 */
vector_table_entry_t systick; /* 系统时钟systick向量函数指针 */
vector_table_entry_t irq[NVIC_IRQ_COUNT]; /* 一般中断irq向量函数指针数组,宏NVIC_IRQ_COUNT被定义为0 */
} vector_table_t;
vector_table_t数据结构在文件libopencm3/lib/cm3/vector.c中实体化为变量vector_table并被初始化,单独构成vectors段,被链接脚本规定放在代码段最开始位置。初始化的重点时栈指针initial_sp_value和重启reset向量函数reset_handler,其余或者被初始化为什么都不做的null_handler,或者被初始化为死循环函数blocking_handler。null_handler和blocking_handler的定义均在vector.c文件中。宏IRQ_HANDLERS在文件libopencm3/lib/dispatch/vector_nvic.c中被定义为空,说明Bootloader不含中断处理函数。
vector.c中,向量函数的初始化函数均被定义为弱属性(weak),表示若外部没有同名函数定义,则用此弱属性函数;若有其他定义,则采用其他定义的函数。从这一点也可看到,对Bootloader的向量函数进行重写时十分方便,不需要修改软件框架。由于reset_handeler作为入口函数,因此还增加了裸属性(naked)。
vector.c
__attribute__ ((section(".vectors"))) /* 变量vector_table属于vectors段 *
vector_table_t vector_table = {
.initial_sp_value = &_stack, /* 栈指针指向的地址,_stack在链接脚本中被定义为ram区最高地址 */
.reset = reset_handler, /* 重启reset向量函数,reset_handler被定义在vector.c中 */
.nmi = nmi_handler, /* 不可屏蔽中断nmi向量函数,nmi_handeler在vector.c中被定义为什么都不做的函数null_handler */
.hard_fault = hard_fault_handler, /* 硬件错误hard_fault向量函数,hard_fault_handler在vector.c中被定义为死循环函数blocking_handler */
/* Those are defined only on CM3 or CM4 */
#if defined(__ARM_ARCH_7M__) || defined(__ARM_ARCH_7EM__) /* 若为CM3和CM4 */
.memory_manage_fault = mem_manage_handler, /* 内存管理错误memory_manage_fault向量函数,mem_manage_handler在vector.c中被定义为死循环函数blocking_handler */
.bus_fault = bus_fault_handler, /* 总线错误bus_fault向量函数,bus_fault_handler在vector.c中被定义为死循环函数blocking_handler */
.usage_fault = usage_fault_handler, /* 指令使用错误usage_fault向量函数,usage_fault_handler在vector.c中被定义为死循环函数blocking_handler */
.debug_monitor = debug_monitor_handler, /* 调试监控debug_monitor向量函数,debug_monitor_handler在vector.c中被定义为什么都不做的函数null_handler */
#endif
.sv_call = sv_call_handler, /* 调试监控debug_monitor向量函数,sv_call_handler在vector.c中被定义为什么都不做的函数null_handler */
.pend_sv = pend_sv_handler, /* pend_sv向量函数,pend_sv_handler在vector.c中被定义为什么都不做的函数null_handler */
.systick = sys_tick_handler, /* 系统时钟systick向量函数,sys_tick_handler在vector.c中被定义为什么都不做的函数null_handler */
/* 由于sys_tick_handler被vector.c定义为弱属性(weak),该函数在bl.c中被重新定义,实际定义在bl.c中。 */
.irq = {
IRQ_HANDLERS /* IRQ_HANDLERS,在vector_nvic.c中被定义为空 */
}
};
6.2 主控FMU核心数据结构
除向量表vector外,主控FMU的核心数据结构包括boardinfo,flash_sector,mcu_des_t和mcu_rev_t,它们均为全局变量,表示板载FMU的基本配置情况。