mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
bootloader: add bootloader version
This adds a new protocol extension which allows to get the bootloader version. The bootloader version is different from the bootloader protocol revision which has stabilized at 5 and is not easy to update unless a bootloader is actually breaking the protocol. The reason being that both the Python script as well as the uploader used in QGC will not attempt to load firmware if they don't know the bootloader version, so it could basically be considered a "breaking" protocol revision. Signed-off-by: Julian Oes <julian@oes.ch>
This commit is contained in:
parent
21e550fdba
commit
7c4507b6d6
@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2017 - 2024 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@ -132,7 +132,9 @@ list(GET VERSION_LIST 2 PX4_VERSION_PATCH)
|
||||
string(REPLACE "-" ";" PX4_VERSION_PATCH ${PX4_VERSION_PATCH})
|
||||
list(GET PX4_VERSION_PATCH 0 PX4_VERSION_PATCH)
|
||||
|
||||
message(STATUS "PX4 version: ${PX4_GIT_TAG} (${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH})")
|
||||
# # Capture only the hash part after 'g'
|
||||
string(REGEX MATCH "g([a-f0-9]+)$" GIT_HASH "${PX4_GIT_TAG}")
|
||||
set(PX4_GIT_HASH ${CMAKE_MATCH_1})
|
||||
|
||||
define_property(GLOBAL PROPERTY PX4_MODULE_LIBRARIES
|
||||
BRIEF_DOCS "PX4 module libs"
|
||||
|
||||
@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python3
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2012-2024 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@ -195,6 +195,7 @@ class uploader(object):
|
||||
GET_CHIP = b'\x2c' # rev5+ , get chip version
|
||||
SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
|
||||
GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII
|
||||
GET_VERSION = b'\x2f' # rev5+ , get chip description in ASCII
|
||||
CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+
|
||||
MAX_DES_LENGTH = 20
|
||||
|
||||
@ -206,6 +207,7 @@ class uploader(object):
|
||||
INFO_BOARD_ID = b'\x02' # board type
|
||||
INFO_BOARD_REV = b'\x03' # board revision
|
||||
INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes
|
||||
BL_VERSION = b'\x07' # get bootloader version, e.g. major.minor.patch.githash (up to 20 chars)
|
||||
|
||||
PROG_MULTI_MAX = 252 # protocol max is 255, must be multiple of 4
|
||||
READ_MULTI_MAX = 252 # protocol max is 255
|
||||
@ -412,6 +414,18 @@ class uploader(object):
|
||||
pieces = value.split(b",")
|
||||
return pieces
|
||||
|
||||
def __getVersion(self):
|
||||
self.__send(uploader.GET_VERSION + uploader.EOC)
|
||||
try:
|
||||
length = self.__recv_int()
|
||||
value = self.__recv(length)
|
||||
self.__getSync()
|
||||
except RuntimeError:
|
||||
# Bootloader doesn't support version call
|
||||
return "unknown"
|
||||
pieces = value.split(b".")
|
||||
return pieces
|
||||
|
||||
def __drawProgressBar(self, label, progress, maxVal):
|
||||
if maxVal < progress:
|
||||
progress = maxVal
|
||||
@ -594,6 +608,8 @@ class uploader(object):
|
||||
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
|
||||
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
|
||||
|
||||
self.version = self.__getVersion()
|
||||
|
||||
# upload the firmware
|
||||
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False):
|
||||
self.force_erase = force_erase
|
||||
@ -625,6 +641,8 @@ class uploader(object):
|
||||
print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%) " % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent))
|
||||
print()
|
||||
|
||||
print(f"Bootloader version: {self.version}")
|
||||
|
||||
# Make sure we are doing the right thing
|
||||
start = _time()
|
||||
if self.board_type != fw.property('board_id'):
|
||||
|
||||
@ -37,6 +37,10 @@ add_library(bootloader
|
||||
crypto.c
|
||||
)
|
||||
|
||||
target_compile_definitions(bootloader
|
||||
PRIVATE BOOTLOADER_VERSION="PX4BLv${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH}g${PX4_GIT_HASH}"
|
||||
)
|
||||
|
||||
target_link_libraries(bootloader
|
||||
PRIVATE
|
||||
arch_bootloader
|
||||
|
||||
@ -80,7 +80,7 @@
|
||||
// RESET finalise flash programming, reset chip and starts application
|
||||
//
|
||||
|
||||
#define BL_PROTOCOL_VERSION 5 // The revision of the bootloader protocol
|
||||
#define BL_PROTOCOL_REVISION 5 // The revision of the bootloader protocol
|
||||
//* Next revision needs to update
|
||||
|
||||
// protocol bytes
|
||||
@ -106,6 +106,7 @@
|
||||
#define PROTO_GET_CHIP 0x2c // read chip version (MCU IDCODE)
|
||||
#define PROTO_SET_DELAY 0x2d // set minimum boot delay
|
||||
#define PROTO_GET_CHIP_DES 0x2e // read chip version In ASCII
|
||||
#define PROTO_GET_VERSION 0x2f // read version
|
||||
#define PROTO_BOOT 0x30 // boot the application
|
||||
#define PROTO_DEBUG 0x31 // emit debug information - format not defined
|
||||
#define PROTO_SET_BAUD 0x33 // set baud rate on uart
|
||||
@ -143,7 +144,8 @@
|
||||
#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
|
||||
#define STATE_PROTO_GET_VERSION 0x200 // Have Seen get version
|
||||
#define STATE_PROTO_BOOT 0x400 // Have Seen boot the application
|
||||
|
||||
#if defined(TARGET_HW_PX4_PIO_V1)
|
||||
#define STATE_ALLOWS_ERASE (STATE_PROTO_GET_SYNC)
|
||||
@ -158,6 +160,18 @@
|
||||
static uint8_t bl_type;
|
||||
static uint8_t last_input;
|
||||
|
||||
int get_version(int n, uint8_t *version_str)
|
||||
{
|
||||
int len = strlen(BOOTLOADER_VERSION);
|
||||
|
||||
if (len > n) {
|
||||
len = n;
|
||||
}
|
||||
|
||||
strncpy((char *)version_str, BOOTLOADER_VERSION, n);
|
||||
return len;
|
||||
}
|
||||
|
||||
inline void cinit(void *config, uint8_t interface)
|
||||
{
|
||||
#if INTERFACE_USB
|
||||
@ -258,7 +272,7 @@ inline void cout(uint8_t *buf, unsigned len)
|
||||
|
||||
#endif
|
||||
|
||||
static const uint32_t bl_proto_rev = BL_PROTOCOL_VERSION; // value returned by PROTO_DEVICE_BL_REV
|
||||
static const uint32_t bl_proto_rev = BL_PROTOCOL_REVISION; // value returned by PROTO_DEVICE_BL_REV
|
||||
|
||||
static unsigned head, tail;
|
||||
static uint8_t rx_buf[256] USB_DATA_ALIGN;
|
||||
@ -973,7 +987,7 @@ bootloader(unsigned timeout)
|
||||
// read the chip description
|
||||
//
|
||||
// command: GET_CHIP_DES/EOC
|
||||
// reply: <value:4>/INSYNC/OK
|
||||
// reply: <length:4><buffer...>/INSYNC/OK
|
||||
case PROTO_GET_CHIP_DES: {
|
||||
uint8_t buffer[MAX_DES_LENGTH];
|
||||
unsigned len = MAX_DES_LENGTH;
|
||||
@ -990,6 +1004,25 @@ bootloader(unsigned timeout)
|
||||
}
|
||||
break;
|
||||
|
||||
// read the bootloader version (not to be confused with protocol revision)
|
||||
//
|
||||
// command: GET_VERSION/EOC
|
||||
// reply: <length:4><buffer...>/INSYNC/OK
|
||||
case PROTO_GET_VERSION: {
|
||||
uint8_t buffer[MAX_VERSION_LENGTH];
|
||||
|
||||
// expect EOC
|
||||
if (!wait_for_eoc(2)) {
|
||||
goto cmd_bad;
|
||||
}
|
||||
|
||||
int len = get_version(sizeof(buffer), buffer);
|
||||
cout_word(len);
|
||||
cout(buffer, len);
|
||||
SET_BL_STATE(STATE_PROTO_GET_VERSION);
|
||||
}
|
||||
break;
|
||||
|
||||
#ifdef BOOT_DELAY_ADDRESS
|
||||
|
||||
case PROTO_SET_DELAY: {
|
||||
@ -1107,4 +1140,4 @@ bad_silicon:
|
||||
continue;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
@ -96,6 +96,7 @@ extern int buf_get(void);
|
||||
#endif
|
||||
|
||||
#define MAX_DES_LENGTH 20
|
||||
#define MAX_VERSION_LENGTH 32
|
||||
|
||||
#define arraySize(a) (sizeof((a))/sizeof(((a)[0])))
|
||||
extern void led_on(unsigned led);
|
||||
@ -123,6 +124,8 @@ extern uint32_t get_mcu_id(void);
|
||||
int get_mcu_desc(int max, uint8_t *revstr);
|
||||
extern int check_silicon(void);
|
||||
|
||||
int get_version(int max, uint8_t *version_str);
|
||||
|
||||
/*****************************************************************************
|
||||
* Interface in/output.
|
||||
*/
|
||||
@ -135,4 +138,4 @@ extern void cout(uint8_t *buf, unsigned len);
|
||||
#if !defined(APP_VECTOR_OFFSET)
|
||||
# define APP_VECTOR_OFFSET 0
|
||||
#endif
|
||||
#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t))
|
||||
#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t))
|
||||
@ -83,4 +83,4 @@ add_subdirectory(srgbled)
|
||||
if (DEFINED PX4_CRYPTO)
|
||||
add_library(px4_random nuttx_random.c)
|
||||
target_link_libraries(px4_random PRIVATE nuttx_crypto)
|
||||
endif()
|
||||
endif()
|
||||
Loading…
x
Reference in New Issue
Block a user