Skip to content

Commit

Permalink
tools/bootloader: add force-erase option
Browse files Browse the repository at this point in the history
If the STM32H7 fails to program or erase a full chunk of 256 bytes, the
ECC check will trigger a busfault when trying to read from it.

To speed up erasing and optimize wear, we read before erasing to check
if it actually needs erasing. That's when a busfault happens and the
erase time outs.

The workaround is to add an option to do a full erase without check.

Credit goes to:
ArduPilot/ardupilot#22090

And the protocol option added to the bootloader is the same as for
ArduPilot, so compatible.

Signed-off-by: Julian Oes <[email protected]>
  • Loading branch information
julianoes authored and chiara-septentrio committed Jul 3, 2024
1 parent f220533 commit 672844b
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 62 deletions.
100 changes: 44 additions & 56 deletions Tools/px_uploader.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#!/usr/bin/env python3
############################################################################
#
# Copyright (c) 2012-2024 PX4 Development Team. All rights reserved.
# Copyright (c) 2012-2017 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
Expand Down Expand Up @@ -50,6 +50,9 @@
# Currently only used for informational purposes.
#

# for python2.7 compatibility
from __future__ import print_function

import sys
import argparse
import binascii
Expand All @@ -67,32 +70,35 @@
try:
import serial
except ImportError as e:
print(f"Failed to import serial: {e}")
print("Failed to import serial: " + str(e))
print("")
print("You may need to install it using:")
print(" python -m pip install pyserial")
print(" pip3 install --user pyserial")
print("")
sys.exit(1)


# Define time to use time.time() by default
def _time():
return time.time()

# Detect python version
if sys.version_info[0] < 3:
raise RuntimeError("Python 2 is not supported. Please try again using Python 3.")
sys.exit(1)


# Use monotonic time where available
def _time():
try:
return time.monotonic()
except Exception:
return time.time()
runningPython3 = False
else:
runningPython3 = True
if sys.version_info[1] >=3:
# redefine to use monotonic time when available
def _time():
try:
return time.monotonic()
except Exception:
return time.time()

class FirmwareNotSuitableException(Exception):
def __init__(self, message):
super(FirmwareNotSuitableException, self).__init__(message)


class firmware(object):
'''Loads a firmware file'''

Expand Down Expand Up @@ -157,13 +163,13 @@ def __crc32(self, bytes, state):

def crc(self, padlen):
state = self.__crc32(self.image, int(0))
for _ in range(len(self.image), (padlen - 1), 4):
for i in range(len(self.image), (padlen - 1), 4):
state = self.__crc32(self.crcpad, state)
return state


class uploader:
'''Uploads a firmware file to the PX4 bootloader'''
class uploader(object):
'''Uploads a firmware file to the PX FMU bootloader'''

# protocol bytes
INSYNC = b'\x12'
Expand All @@ -189,7 +195,6 @@ class uploader:
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

Expand All @@ -201,7 +206,6 @@ class uploader:
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
Expand Down Expand Up @@ -355,22 +359,19 @@ def __determineInterface(self):
self.port.baudrate = self.baudrate_bootloader * 2.33
except NotImplementedError as e:
# This error can occur because pySerial on Windows does not support odd baudrates
print(f"{e} -> could not check for FTDI device, assuming USB connection")
print(str(e) + " -> could not check for FTDI device, assuming USB connection")
return

self.__send(uploader.GET_SYNC +
uploader.EOC)
try:
self.__getSync(False)
except RuntimeError:
except:
# if it fails we are on a real serial port - only leave this enabled on Windows
if sys.platform.startswith('win'):
self.ackWindowedMode = True
finally:
try:
self.port.baudrate = self.baudrate_bootloader
except Exception:
pass
self.port.baudrate = self.baudrate_bootloader

# send the GET_DEVICE command and wait for an info parameter
def __getInfo(self, param):
Expand Down Expand Up @@ -411,17 +412,6 @@ def __getCHIPDes(self):
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"
return value.decode()

def __drawProgressBar(self, label, progress, maxVal):
if maxVal < progress:
progress = maxVal
Expand All @@ -433,7 +423,7 @@ def __drawProgressBar(self, label, progress, maxVal):

# send the CHIP_ERASE command and wait for the bootloader to become ready
def __erase(self, label):
print(f"Windowed mode: {self.ackWindowedMode}")
print("Windowed mode: %s" % self.ackWindowedMode)
print("\n", end='')

if self.force_erase:
Expand Down Expand Up @@ -604,8 +594,6 @@ def identify(self):
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
Expand Down Expand Up @@ -637,8 +625,6 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_
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'):
Expand Down Expand Up @@ -668,14 +654,14 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_
self.otp_coa = self.otp[32:160]
# show user:
try:
print("Sn: ", end='')
print("sn: ", end='')
for byte in range(0, 12, 4):
x = self.__getSN(byte)
x = x[::-1] # reverse the bytes
self.sn = self.sn + x
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
print('')
print("Chip: %08x" % self.__getCHIP())
print("chip: %08x" % self.__getCHIP())

otp_id = self.otp_id.decode('Latin-1')
if ("PX4" in otp_id):
Expand All @@ -685,19 +671,17 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_
print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1'))
print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1'))

except Exception as e:
except Exception:
# ignore bad character encodings
print(f"Exception ignored: {e}")
pass

# Silicon errata check was added in v5
if (self.bl_rev >= 5):
des = self.__getCHIPDes()
if (len(des) == 2):
family, revision = des
print(f"Family: {family.decode()}")
print(f"Revision: {revision.decode()}")
print(f"Flash: {self.fw_maxsize} bytes")
print("family: %s" % des[0])
print("revision: %s" % des[1])
print("flash: %d bytes" % self.fw_maxsize)

# Prevent uploads where the maximum image size of the board config is smaller than the flash
# of the board. This is a hint the user chose the wrong config and will lack features
Expand All @@ -708,7 +692,8 @@ def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_
# https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144

if self.fw_maxsize > fw.property('image_maxsize') and not force:
raise RuntimeError(f"Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes). Please use the correct board configuration to avoid lacking critical functionality.")
raise RuntimeError("Board can accept larger flash images (%u bytes) than board config (%u bytes). Please use the correct board configuration to avoid lacking critical functionality."
% (self.fw_maxsize, fw.property('image_maxsize')))
else:
# If we're still on bootloader v4 on a Pixhawk, we don't know if we
# have the silicon errata and therefore need to flash px4_fmu-v2
Expand Down Expand Up @@ -809,6 +794,10 @@ def send_reboot(self, use_protocol_splitter_format=False):


def main():
# Python2 is EOL
if not runningPython3:
raise RuntimeError("Python 2 is not supported. Please try again using Python 3.")

# Parse commandline arguments
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
parser.add_argument('--port', action="store", required=True, help="Comma-separated list of serial port(s) to which the FMU may be attached")
Expand Down Expand Up @@ -893,10 +882,9 @@ def main():
# Windows, don't open POSIX ports
if "/" not in port:
up = uploader(port, args.baud_bootloader, baud_flightstack)
except Exception as e:
except Exception:
# open failed, rate-limit our attempts
time.sleep(0.05)
print(f"Exception ignored: {e}")

# and loop to the next port
continue
Expand All @@ -911,10 +899,10 @@ def main():
up.identify()
found_bootloader = True
print()
print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}")
print("Found board id: %s,%s bootloader version: %s on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
break

except (RuntimeError, serial.SerialException):
except Exception:

if not up.send_reboot(args.use_protocol_splitter_format):
break
Expand All @@ -939,9 +927,9 @@ def main():
# if we made this far without raising exceptions, the upload was successful
successful = True

except RuntimeError as e:
except RuntimeError as ex:
# print the error
print(f"\n\nError: {e}")
print("\nERROR: %s" % ex.args)

except FirmwareNotSuitableException:
unsuitable_board = True
Expand Down
8 changes: 2 additions & 6 deletions platforms/nuttx/src/bootloader/nxp/imxrt_common/main.c
Original file line number Diff line number Diff line change
Expand Up @@ -397,7 +397,7 @@ flash_func_sector_size(unsigned sector)
}

/* imxRT uses Flash lib, not up_progmem so let's stub it here */
ssize_t up_progmem_ispageerased(unsigned sector)
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));
Expand Down Expand Up @@ -432,13 +432,9 @@ flash_func_erase_sector(unsigned sector, bool force)
return;
}

if (force || up_progmem_ispageerased(sector) != 0) {

if (force || flash_func_is_sector_blank(sector) != 0) {
struct flexspi_nor_config_s *pConfig = &g_bootConfig;

const uint32_t bytes_per_sector = flash_func_sector_size(sector);
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));

uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE;
irqstate_t flags;
flags = enter_critical_section();
Expand Down

0 comments on commit 672844b

Please sign in to comment.