forked from Archive/PX4-Autopilot
Compare commits
2 Commits
main
...
pr-bootloa
Author | SHA1 | Date |
---|---|---|
Julian Oes | 7f3f8093f5 | |
Julian Oes | 6eef811db8 |
|
@ -195,13 +195,14 @@ 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
|
||||
CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+
|
||||
MAX_DES_LENGTH = 20
|
||||
|
||||
REBOOT = b'\x30'
|
||||
|
||||
INFO_BL_REV = b'\x01' # bootloader protocol revision
|
||||
BL_REV_MIN = 2 # minimum supported bootloader protocol
|
||||
BL_REV_MAX = 5 # maximum supported bootloader protocol
|
||||
BL_REV_MAX = 6 # maximum supported bootloader protocol
|
||||
INFO_BOARD_ID = b'\x02' # board type
|
||||
INFO_BOARD_REV = b'\x03' # board revision
|
||||
INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes
|
||||
|
@ -235,6 +236,7 @@ class uploader(object):
|
|||
self.baudrate_bootloader = baudrate_bootloader
|
||||
self.baudrate_flightstack = baudrate_flightstack
|
||||
self.baudrate_flightstack_idx = -1
|
||||
self.force_erase = False
|
||||
|
||||
def close(self):
|
||||
if self.port is not None:
|
||||
|
@ -423,8 +425,17 @@ class uploader(object):
|
|||
def __erase(self, label):
|
||||
print("Windowed mode: %s" % self.ackWindowedMode)
|
||||
print("\n", end='')
|
||||
self.__send(uploader.CHIP_ERASE +
|
||||
uploader.EOC)
|
||||
|
||||
if self.force_erase:
|
||||
if self.bl_rev < 6:
|
||||
raise RuntimeError("bootloader revision does not support force erase")
|
||||
|
||||
print("Force erasing full chip\n")
|
||||
self.__send(uploader.CHIP_FULL_ERASE +
|
||||
uploader.EOC)
|
||||
else:
|
||||
self.__send(uploader.CHIP_ERASE +
|
||||
uploader.EOC)
|
||||
|
||||
# erase is very slow, give it 30s
|
||||
deadline = _time() + 30.0
|
||||
|
@ -582,7 +593,8 @@ class uploader(object):
|
|||
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
|
||||
|
||||
# upload the firmware
|
||||
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False):
|
||||
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False):
|
||||
self.force_erase = force_erase
|
||||
# select correct binary
|
||||
found_suitable_firmware = False
|
||||
for file in fw_list:
|
||||
|
@ -790,6 +802,7 @@ def main():
|
|||
parser.add_argument('--baud-bootloader', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200) when communicating with bootloader, only required for true serial ports.")
|
||||
parser.add_argument('--baud-flightstack', action="store", default="57600", help="Comma-separated list of baud rate of the serial port (default is 57600) when communicating with flight stack (Mavlink or NSH), only required for true serial ports.")
|
||||
parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading')
|
||||
parser.add_argument('--force-erase', action="store_true", help="Do not perform the blank check, always erase every sector of the application space")
|
||||
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
|
||||
parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot')
|
||||
parser.add_argument('firmware', action="store", nargs='+', help="Firmware file(s)")
|
||||
|
@ -907,7 +920,7 @@ def main():
|
|||
|
||||
try:
|
||||
# ok, we have a bootloader, try flashing it
|
||||
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay)
|
||||
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay, force_erase=args.force_erase)
|
||||
|
||||
# if we made this far without raising exceptions, the upload was successful
|
||||
successful = True
|
||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -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_VERSION 6 // The revision of the bootloader protocol
|
||||
//* Next revision needs to update
|
||||
|
||||
// protocol bytes
|
||||
|
@ -114,6 +114,7 @@
|
|||
#define PROTO_RESERVED_0X37 0x37 // Reserved
|
||||
#define PROTO_RESERVED_0X38 0x38 // Reserved
|
||||
#define PROTO_RESERVED_0X39 0x39 // Reserved
|
||||
#define PROTO_CHIP_FULL_ERASE 0x40 // Full erase, without any flash wear optimization
|
||||
|
||||
#define PROTO_PROG_MULTI_MAX 64 // maximum PROG_MULTI size
|
||||
#define PROTO_READ_MULTI_MAX 255 // size of the size field
|
||||
|
@ -649,6 +650,8 @@ bootloader(unsigned timeout)
|
|||
|
||||
led_on(LED_ACTIVITY);
|
||||
|
||||
bool full_erase = false;
|
||||
|
||||
// handle the command byte
|
||||
switch (c) {
|
||||
|
||||
|
@ -728,6 +731,10 @@ bootloader(unsigned timeout)
|
|||
// success reply: INSYNC/OK
|
||||
// erase failure: INSYNC/FAILURE
|
||||
//
|
||||
case PROTO_CHIP_FULL_ERASE:
|
||||
full_erase = true;
|
||||
|
||||
// Fallthrough
|
||||
case PROTO_CHIP_ERASE:
|
||||
|
||||
/* expect EOC */
|
||||
|
@ -755,17 +762,18 @@ bootloader(unsigned timeout)
|
|||
arch_flash_unlock();
|
||||
|
||||
for (int i = 0; flash_func_sector_size(i) != 0; i++) {
|
||||
flash_func_erase_sector(i);
|
||||
flash_func_erase_sector(i, full_erase);
|
||||
}
|
||||
|
||||
// disable the LED while verifying the erase
|
||||
led_set(LED_OFF);
|
||||
|
||||
// verify the erase
|
||||
for (address = 0; address < board_info.fw_size; address += 4)
|
||||
for (address = 0; address < board_info.fw_size; address += 4) {
|
||||
if (flash_func_read_word(address) != 0xffffffff) {
|
||||
goto cmd_fail;
|
||||
}
|
||||
}
|
||||
|
||||
address = 0;
|
||||
SET_BL_STATE(STATE_PROTO_CHIP_ERASE);
|
||||
|
|
|
@ -39,6 +39,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
/*****************************************************************************
|
||||
* Generic bootloader functions.
|
||||
*/
|
||||
|
@ -105,7 +107,7 @@ extern void board_deinit(void);
|
|||
extern uint32_t board_get_devices(void);
|
||||
extern void clock_deinit(void);
|
||||
extern uint32_t flash_func_sector_size(unsigned sector);
|
||||
extern void flash_func_erase_sector(unsigned sector);
|
||||
extern void flash_func_erase_sector(unsigned sector, bool force);
|
||||
extern void flash_func_write_word(uintptr_t address, uint32_t word);
|
||||
extern uint32_t flash_func_read_word(uintptr_t address);
|
||||
extern uint32_t flash_func_read_otp(uintptr_t address);
|
||||
|
|
|
@ -395,6 +395,24 @@ flash_func_sector_size(unsigned sector)
|
|||
return 0;
|
||||
}
|
||||
|
||||
/* imxRT uses Flash lib, not up_progmem so let's stub it here */
|
||||
up_progmem_ispageerased(unsigned sector)
|
||||
{
|
||||
const uint32_t bytes_per_sector = flash_func_sector_size(sector);
|
||||
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));
|
||||
const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address);
|
||||
|
||||
int blank = 0; /* Assume it is Bank */
|
||||
|
||||
for (uint32_t i = 0; i < uint32_per_sector; i++) {
|
||||
if (address[i] != 0xffffffff) {
|
||||
blank = -1; /* It is not blank */
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return blank;
|
||||
}
|
||||
|
||||
/*!
|
||||
* @name Configuration Option
|
||||
|
@ -407,31 +425,15 @@ flash_func_sector_size(unsigned sector)
|
|||
* */
|
||||
locate_code(".ramfunc")
|
||||
void
|
||||
flash_func_erase_sector(unsigned sector)
|
||||
flash_func_erase_sector(unsigned sector, bool force)
|
||||
{
|
||||
|
||||
if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* blank-check the sector */
|
||||
const uint32_t bytes_per_sector = flash_func_sector_size(sector);
|
||||
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));
|
||||
const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address);
|
||||
bool blank = true;
|
||||
if (force || flash_func_is_sector_blank(sector) != 0) {
|
||||
struct flexspi_nor_config_s *pConfig = &g_bootConfig;
|
||||
|
||||
for (uint32_t i = 0; i < uint32_per_sector; i++) {
|
||||
if (address[i] != 0xffffffff) {
|
||||
blank = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
struct flexspi_nor_config_s *pConfig = &g_bootConfig;
|
||||
|
||||
/* erase the sector if it failed the blank check */
|
||||
if (!blank) {
|
||||
uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE;
|
||||
irqstate_t flags;
|
||||
flags = enter_critical_section();
|
||||
|
@ -439,8 +441,6 @@ flash_func_erase_sector(unsigned sector)
|
|||
leave_critical_section(flags);
|
||||
UNUSED(status);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void
|
||||
|
|
|
@ -458,18 +458,13 @@ flash_func_sector_size(unsigned sector)
|
|||
}
|
||||
|
||||
void
|
||||
flash_func_erase_sector(unsigned sector)
|
||||
flash_func_erase_sector(unsigned sector, bool force)
|
||||
{
|
||||
if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* blank-check the sector */
|
||||
|
||||
bool blank = up_progmem_ispageerased(sector) == 0;
|
||||
|
||||
/* erase the sector if it failed the blank check */
|
||||
if (!blank) {
|
||||
if (force || (up_progmem_ispageerased(sector) != 0)) {
|
||||
up_progmem_eraseblock(sector);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue