px4协处理器bootloader

PX4 bootloader工程架构

从 https://github.com/PX4/PX4-Bootloader 工程中获取代码之后,更新子模块,多运行几次更新子模块的命令,之后使用 make 命令来编译工程,编译成功,则代码没有什么问题:

git submodule sync --recursive
git submodule update --init --recursive
make

需要注意:如果是高版本的px4硬件,则bootloader的代码也会包含在 px4 的主工程中,而不是此 bootloader 工程。

工程目录下一些重要的文件与目录如下:

libopencm3 是 github 上的一个针对 M3 核芯片的一个开源底层库,也包含 stm32 的内容,PX4 的 bootloader 底层便是调用的这个开源库的底层。

Makefile文件:包含 Makefile,Makefile.f1,Makefile.f3,Makefile.f4,Makefile.f7 五个文件,分别对应系统总的编译流程以及各系列芯片的编译流程

bootloader通用函数库:包含 bl.c 与 bl.h 两个文件,提供了 bootloader 需要调用的上层通用函数(与硬件底层剥离的应用层函数),其中包含了 flash 操作相关的函数,led 操作,以及跳转 APP 等,升级过程中各状态机的定义,以及各个升级命令的宏定义

调试函数库:包含串口调试使用的 uart.h和uart.c 以及 USB 调试使用的 cdcacm.h和cdcacm.c,其中两个头文件位于工程根目录下,两个源文件位于 PX4-Bootloader/stm32 目录下

主流程文件:main_f1.c,main_f3.c,main_f4.c,main_f7.c 等文件分别对应各系列芯片的主流程程序

硬件配置文件:hw_config.h,此文件中包含所有系列的 bootloader 的硬件配置宏

Makefile文件

主编译文件 Makefile

主编译文件 Makefile 文件增加了部分注释,删减了一些不必要内容,如下:

export BUILD_DIR_ROOT ?= build
export BL_BASE      ?= $(wildcard .)          #获取PX4-Bootloader工程根目录,复制给 BL_BASE
export LIBOPENCM3   ?= $(wildcard libopencm3) #获取stm32底层开源库目录
export LIBKINETIS   ?= $(wildcard lib/kinetis/NXP_Kinetis_Bootloader_2_0_0)
MKFLAGS=--no-print-directory
SRC_DIR := $(shell dirname $(realpath $(lastword $(MAKEFILE_LIST))))
COLOR_BLUE = \033[0;94m
NO_COLOR   = \033[m
define colorecho
+@echo -e '${COLOR_BLUE}${1} ${NO_COLOR}'
endef
#
# Tools
#
export CC        = arm-none-eabi-gcc         #定义交叉编译工具链变量
export OBJCOPY       = arm-none-eabi-objcopy #定义二进制生成工具链变量
#
# Common configuration
#
export FLAGS         = -std=gnu99 \                 #使用gnu99的C语言标准
               -Os \                                
               -g \                                 #生成调试信息
               -Wundef \                            #当没有定义的符号出现在#if中时警告
               -Wall \
               -fno-builtin \
               -I$(BL_BASE)/$(LIBOPENCM3)/include \ #包含开源库libopencm3的头文件
               -I$(BL_BASE)/. \
               -ffunction-sections \
               -nostartfiles \
               -lnosys \
               -Wl,-gc-sections \
               -Wl,-g \
               -Werror                               #把警告当错误,出现警告就放弃编译
ifneq ($(CRYPTO_HAL),)
include crypto_hal/$(CRYPTO_HAL)/Makefile.include
endif
export COMMON_SRCS   = bl.c $(CRYPTO_SRCS)
export ARCH_SRCS     = cdcacm.c  usart.c
#
# Bootloaders to build
# Note: px4fmuv3_bl is the same as px4fmuv2_bl except for a different USB device
# string
# 定义编译目标
TARGETS = \  
    aerofcv1_bl \
    auavx2v1_bl \
    ...
    px4fmuv2_bl \
    px4fmuv3_bl \
    px4fmuv4_bl \
    ...
    px4io_bl \
    px4iov3_bl \
    ...
all:    $(TARGETS) sizes
clean:    #定义清理编译信息的操作
    cd libopencm3 && make --no-print-directory clean && cd ..
    rm -f *.elf *.bin *.map # Remove any elf or bin files contained directly in the Bootloader directory
    rm -rf build # Remove build directories
#
# Specific bootloader targets.
# 各个系列芯片的具体编译操作
fmuk66v3_bl: $(MAKEFILE_LIST) $(LIBKINETIS)
    ${MAKE} ${MKFLAGS} -f  Makefile.k66 TARGET_HW=FMUK66_V3  LINKER_FILE=kinetisk66.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} ${MKFLAGS} -f  Makefile.f1 TARGET_HW=PX4_PIO_V1 LINKER_FILE=stm32f1.ld TARGET_FILE_NAME=$@
...
#
# Show sizes
#
.PHONY: sizes
sizes:
    @-find build/*/ -name '*.elf' -type f | xargs size 2> /dev/null || :
#
# Binary management
#  二进制文件压缩
.PHONY: deploy
deploy:
    zip -j Bootloader.zip build/*/*.bin
...

在主 Makefile 文件中,定义了编译目标,以及调用了子编译文件,例如协处理器使用的是 f1 芯片。

协处理器编译文件 Makefile.f1

在主 Makefile 文件中,调用 Makefile.f1 使用了如下命令:

传入的参数包含如下变量:

硬件目标:$(TARGET_HW)=PX4_PIO_V1

链接文件:$(LINKER_FILE)=stm32f1.ld

目标名称:$(TARGET_FILE_NAME)=$@ 在这里 $@ 表示的就是目标名称,即为 px4io_bl

Makefile.f1 文件中的内容笔记少,容易理解。

硬件配置文件

PX4 Bootloader 的硬件配置头文件仅有一个:hw_config.h。这套代码支持的所有硬件板配置均可在这里找到。它的结构很简单,针对不同的硬件配置使用 #if --- #elif --- #end 宏条件编译语句进行配置。

我们分析协处理器的话,上面 makefile 调用命令中的变量 $(TARGET_HW)=PX4_PIO_V1 ,那么对应的就是 TARGET_HW_PX4_PIO_V1 宏中的内容:

#elif  defined(TARGET_HW_PX4_PIO_V1) ||  defined(TARGET_HW_PX4_PIO_V2)
# define APP_LOAD_ADDRESS               0x08001000
# define APP_SIZE_MAX                   0xf000
# define BOOTLOADER_DELAY               200
# define BOARD_PIO
# define INTERFACE_USB                  0
# define INTERFACE_USART                1
# define USBDEVICESTRING                ""
# define USBPRODUCTID                   -1
# define OSC_FREQ                       24
# define BOARD_PIN_LED_ACTIVITY         GPIO14
# define BOARD_PIN_LED_BOOTLOADER       GPIO15
# define BOARD_PORT_LEDS                GPIOB
# define BOARD_CLOCK_LEDS_REGISTER      RCC_APB2ENR
# define BOARD_CLOCK_LEDS               RCC_APB2ENR_IOPBEN
# define BOARD_LED_ON                   gpio_clear
# define BOARD_LED_OFF                  gpio_set
# define BOARD_USART                    USART2
# define BOARD_USART_CLOCK_REGISTER     RCC_APB1ENR
# define BOARD_USART_CLOCK_BIT          RCC_APB1ENR_USART2EN
# define BOARD_PORT_USART               GPIOA
# define BOARD_PIN_TX                   GPIO_USART2_TX
# define BOARD_PIN_RX                   GPIO_USART2_RX
# define BOARD_USART_PIN_CLOCK_REGISTER RCC_APB2ENR
# define BOARD_USART_PIN_CLOCK_BIT      RCC_APB2ENR_IOPAEN
# define BOARD_FORCE_BL_PIN             GPIO5
# define BOARD_FORCE_BL_PORT            GPIOB
# define BOARD_FORCE_BL_CLOCK_REGISTER  RCC_APB2ENR
# define BOARD_FORCE_BL_CLOCK_BIT       RCC_APB2ENR_IOPBEN
# define BOARD_FORCE_BL_PULL            GPIO_CNF_INPUT_FLOAT // depend on external pull
# define BOARD_FORCE_BL_VALUE           BOARD_FORCE_BL_PIN
# define BOARD_FLASH_SECTORS            60
# define BOARD_TYPE                     10
# define FLASH_SECTOR_SIZE              0x400
# define NO_OTP_SN_CHIP                 1

其中,比较重要的信息是:

# define APP_LOAD_ADDRESS               0x08001000     //偏移地址
# define APP_SIZE_MAX                   0xf000    //协处理器固件的最大文件大小  60kb
# define BOARD_USART                    USART2   //与主处理器通信的串口号

偏移地址在后续的升级中,虽然不会经常改动,但是是一个非常重要的定义。

固件文件大小的值与所选的芯片内存大小有关,根据选型修改。

主函数文件

IO协处理器的主线程序的核心是main函数,它被入口函数reset_handler调用。

IO协处理器的main函数流程如下:

  1. 调用board_init函数初始化,包括 LED 脚、强制 Bootloader 救砖引脚 GPIOB5、设置 RTC 备份寄存器、配置串口2引脚(串口 2 与飞控通信)
  2. 若 RTC 备份寄存器 BKP_DR1 中存储了预定值 BL_WAIT_MAGIC或者串口或 usb 连接到了板子,则 timeout 会被赋值为 200ms,之后程序会停留在 bootloader
  3. 若 GPIO5 为高电平,则 timeout 赋值为 0xffffffff,相当于一直停留在 bootloader 中,此为救砖操作,GPIO5 连接安全开关,有必要时,可以使用安全开关来强制救砖
  4. 若超时时间为0(未赋值),则调用 jump_to_app 跳转到 app 固件地址
  5. 初始化串口与时钟
  6. 调用 bootloader 函数与飞控通信,接收固件文件
  7. 接收完成后,调用函数jump_to_app启动 app 固件
int
main(void)
{
    unsigned timeout = 0; /* bootloader初始化完毕后跳转到飞控固件入口地址时,所需等待的时间,以ms计算。 */
    /* 调用board_init函数,此函数在main_f1.c中被定义,功能如下 */
    /* 1. 初始化LED控制并点亮LED灯 */
    /* 2. 设置强制Bootloader引脚GPIOB5为浮动输入模式,方便采集安全开关的状态 */
    /* 3. 使能能源接口时钟和备份接口时钟,准备RTC备份寄存器 */
    /* 4. 设置USART2-TX引脚GPIOA2,对应原理图SERIAL_IO_TO_FMU,用于IO协处理器发送信息到主控FMU */   
    board_init();
#if defined(INTERFACE_USART) || defined (INTERFACE_USB)
    //根据串口或usb是否连接来决定是否在boot中停留(如果连接的话,会创建实例)
    timeout = BOOTLOADER_DELAY; 
#endif
#ifdef INTERFACE_I2C
# error I2C bootloader detection logic not implemented
#endif
    /* 若RTC备份寄存器BKP_DR1中存储了预定值,则timeout赋值为200ms */
    /* should_wait:判定RTC备份寄存器BKP_DR1中是否存储了预定值。若存储了返回真,未存储则返回假 */
    /* BOOTLOADER_DELAY:值200,表示200ms,hw_config.h */
    if (should_wait()) {
        timeout = BOOTLOADER_DELAY;
    }
#ifdef BOARD_FORCE_BL_PIN
    /* 宏BOARD_FORCE_BL_PIN定义为GPIO5,代码有效,hw_config.h */
    /* 若GPIO5为高电平,则timeout赋值为0xffffffff,永久停留在bootloader中 */
    /* BOARD_FORCE_BL_VALUE:被定义为GPIO5(1<<5),hw_config.h */
    /* BOARD_FORCE_BL_PORT:被定义为GPIOB(GPIOB的首寄存器),hw_config.h */
    /* BOARD_FORCE_BL_PIN:被定义为GPIO5(1<<5),hw_config.h */
    /* gpio_get:获取某GPIO组的值,定义在libopencm3/lib/stm32/common/gpio_common_all.c */  
    if (BOARD_FORCE_BL_VALUE == gpio_get(BOARD_FORCE_BL_PORT, BOARD_FORCE_BL_PIN)) {
        timeout = 0xffffffff;
    }
#endif
    /* 若timeout为0,则调用jump_to_app立即启动飞控固件。 */
    /* 若jump_to_app函数返回,则timeout赋值为0 */ 
    if (timeout == 0) {
        jump_to_app();
        timeout = 0;
    }
    /* 初始化系统时钟为PLL(使用HSI) */
    /* clock_init:使用HSI将MCU的系统时钟为PLL,频率48MHz,定义在main_f1.c */    
    clock_init();
    /* 函数初始化串口USART2 */
    /* BOARD_INTERFACE_CONFIG:定义为BOARD_USART(USART2),main_f1.c */
    /* USART:值1,枚举型,定义在bl.h中 */ 
    cinit(BOARD_INTERFACE_CONFIG, USART);
    while (1) {
        /*进行升级流程,升级完成新的固件,或者超时时间到则函数返回*/
        bootloader(timeout);
        /*跳转到app固件地址*/
        jump_to_app();
        timeout = 0;
    }
}

升级流程

升级命令有一个命令表格

#define PROTO_GET_SYNC              0x21    // 获取同步命令
#define PROTO_GET_DEVICE            0x22    // 获取设备ID
#define PROTO_CHIP_ERASE            0x23    // 擦除flash准备烧写固件
#define PROTO_PROG_MULTI            0x27    // 烧写flash
#define PROTO_GET_CRC               0x29    // 计算crc校验
#define PROTO_GET_OTP               0x2a    // 读取OTP区域某地址的1字节
#define PROTO_GET_SN                0x2b    // 读取MCU的UDID
#define PROTO_GET_CHIP              0x2c    // 读取芯片ID和版本
#define PROTO_SET_DELAY             0x2d    // 设置飞控固件启动等待时间
#define PROTO_GET_CHIP_DES          0x2e    // 读取芯片描述信息
#define PROTO_BOOT                  0x30    // 完成升级启动app固件
#define PROTO_DEBUG                 0x31    // 输出调试信息
#define PROTO_SET_BAUD              0x33    // 设置串口波特率

上述表格中的命令,需要与其他的分隔命令配置使用:

// protocol bytes
#define PROTO_INSYNC                0x12    // 同步字节
#define PROTO_EOC                   0x20    // 命令结束符

而升级过程的状态机,基本也是跟命令是相对应的,比较容易看懂:

// State
#define STATE_PROTO_GET_SYNC      0x1     // Have Seen NOP for re-establishing sync
#define STATE_PROTO_GET_DEVICE    0x2     // Have Seen get device ID bytes
#define STATE_PROTO_CHIP_ERASE    0x4     // Have Seen erase program area and reset program address
#define STATE_PROTO_PROG_MULTI    0x8     // Have Seen write bytes at program address and increment
#define STATE_PROTO_GET_CRC       0x10    // Have Seen compute & return a CRC
#define STATE_PROTO_GET_OTP       0x20    // Have Seen read a byte from OTP at the given address
#define STATE_PROTO_GET_SN        0x40    // Have Seen read a word from UDID area ( Serial)  at the given address
#define STATE_PROTO_GET_CHIP      0x80    // Have Seen read chip version (MCU IDCODE)
#define STATE_PROTO_GET_CHIP_DES  0x100   // Have Seen read chip version In ASCII
#define STATE_PROTO_BOOT          0x200   // Have Seen boot the application

命令发送格式

发送命令

PX4 使用了特定的发送格式来识别这么多的命令,命令发送的格式为:

命令类型数据(可省略)命令终止符(PROTO_EOC)

也就是说,每个命令发送后都需要跟一个命令终止符 PROTO_EOC

例如同步命令:

send(PROTO_GET_SYNC);
send(PROTO_EOC);

如果中间有数据的话,则夹杂一个数据,例如获取设备ID命令:

send(PROTO_GET_DEVICE);
send(param);
send(PROTO_EOC);

bootloader 中,根据命令头与终止符来解析命令,并且设置了错误状态 cmd_bad 来处理那些跟命令头相同的数据,避免误触发一些命令。

回复命令

当飞控给协处理器 boot 发送了命令之后,boot 解析到命令,就会回复一个同步成功消息

// send the sync response for this command
/*每接收到一次命令之后,都会回复一个同步成功消息*/
sync_response();

同步成功消息用来告诉飞控,已经接收到了它发送过来的指令。同步消息也是只有两条:

static void
sync_response(void)
{
    uint8_t data[] = {
        PROTO_INSYNC,   // "in sync"
        PROTO_OK    // "OK"
    };
    cout(data, sizeof(data));
}

回复消息的格式:

PROTO_INSYNCPROTO_OK

例如,飞控发送了擦除 flash 命令之后,就会等待 boot 回复同步成功的消息:

而等待回复消息中,也是等待的这两个命令关键字 PROTO_INSYNC 与 PROTO_OK:

固件发送流程

命令非常的多,不过按照正常的固件升级流程,起到主要作用的是以下流程图中几个:

需要注意的是,每发送一个命令,都会等待 boot 回复同步成功消息,上图的流程图将等待回复省略了。

需要重点注意的是 PROTO_PROG_MULTI,在此命令下,是上位机发送固件,boot 接收固件并写入 flash 的重点步骤,在此,单独拿出来解析。

发送固件时上位机端

此时上位机以飞控为例,发送固件时,对应的函数 program:

PX4IO_Uploader::program(size_t fw_size)

在此函数中,获取固件描述符,在发送的循环中,先是计算剩余多少字节,之后规定每次读取文件的字节数 n,规定了最大读取字节数 PROG_MULTI_MAX:

/* get more bytes to program */
//获取剩余字节数   总字节数减去已经发送的字节数
size_t n = fw_size - sent;
if (n > PROG_MULTI_MAX) {
        n = PROG_MULTI_MAX;
}

每次读取不超过 248 字节的内容:

//读取文件字节,每次最多读取 PROG_MULTI_MAX 248 字节(必须是4的倍数),
//读到的字节数返回到 count 变量中,字节内容返回到 file_buf
count = read_with_retry(_fw_fd, file_buf, n);

在此读取函数内容可以看出,每次读取了不超过 248 字节的内容,并且规定了读取时的重试次数:

之后,计算已经发送的字节数,并且发送响应的命令与数据,数据中第一个是本次发送的字节数,之后才是跟上文件内容:

sent += count;  //计算已经发送的字节数
send(PROTO_PROG_MULTI);  //发送固件内容命令
send(count);    //发送本次字节数
send(file_buf, count);   //发送本次数据
send(PROTO_EOC);   //发送命令终止符
ret = get_sync(1000);  //等待回复
接收固件时boot端

boot端定义了一个共用体,共享内存,以此来更方便的控制读取数据与写入数据:

//存储固件的存储空间使用共用体,共享内存,
//就可以使用c数组来读取,w数组来写入
static union {
    uint8_t     c[256];
    uint32_t    w[64];
} flash_buffer;   

在收到命令之后,接收到的第一个字节对应的是本次发送的字节总数 count:

case PROTO_PROG_MULTI:      // program bytes
    // expect count
    arg = cin_wait(50);  //接收到的第一个字节是此次发送的字节总数

在接收到首字节---字节总数后,将后续的数据记录在数组c中:

/*根据第一个字节---字节总数,接收接下来的数据,存储在 flash_buffer.c[i]*/
for (int i = 0; i < arg; i++) {
    c = cin_wait(1000);
    if (c < 0) {
        goto cmd_bad;
    }
    flash_buffer.c[i] = c;  //记录数据
}

之后,按照4个字节为单位,使用 w 数组将数据写入 flash 中,由于flash_buffer.c 与 flash_buffer.w 是同一个共用体的,因此内存共享:

超时时间的含义与实现方法

超时时间含义

此设置的超时时间主要是用来进行上电进入 boot 后到首次接收数据的时间是否超时判断的。也就是说,设置的 200ms,如果在进入 bootloader 后,200ms之内,没有接收到数据,则判断超出时间,则跳转到 app 偏移地址中,如果 200ms 之内,接收到了数据,则停止计时,开始进入接收数据状态。

实现方法

1.在 px4 中,定义了一个 timer 数组,实际上是为了功能复用,四组数据分别用于四种计时:

/* generic timers */
#define NTIMERS     4
#define TIMER_BL_WAIT   0 //超时时间计时
#define TIMER_CIN   1     //输入计时
#define TIMER_LED   2     //LED翻转计时
#define TIMER_DELAY 3     //延迟计时
extern volatile unsigned timer[NTIMERS];    /* each timer decrements every millisecond if > 0 */

其中 0 通道用于超时时间的计时,其他的功能可以以此类推。

2.在 boot 的时钟初始化中,初始化了系统时钟,并且使能了系统时钟的中断,每 1ms 就会进入一次中断,在中断中,时间自减:

3.在 boot 的循环中,会先进行超时时间的赋值,之后当超时时间为 0或超过超过超时时间时,会直接 return:

4.当有数据接收到时,c 不为 -1,则程序会继续往下执行,之后会执行到一句程序,将超时时间清零:

//上面已经获取到数据,即在超时时间内已经收到数据,将超时时间清零,避免重复判断        
timeout = 0;   

当清零时,其实也表示已经接收到了数据,之后,程序在下一次循环时,变不会再进行 do...while...中的 if 超时判断了,也就实现了超时判断的功能。

烧录boot

先在工程目录下运行 make 指令,编译工程,之后就可以看到在 build 目录下已经生成了相应的文件:

烧录使用 bin 文件即可。

烧录 boot 需要借助下载器,使用 STLink 就可以,需要下载工具软件 STLinkUtility ,下载完成后,打开软件,如下所示:

飞控中,连接 px4io 板的调试口:

线接好后,电机 STLink 工具软件中的 Target->Connect 来连接 STLink,之后选择 File->Open file 来选择刚刚生成的 px4io_bl.bin 文件。

之后选择 Target -> Program & Verify ,运行 start 即可:

评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值