Tool: uploader.py: flake8-clean

This commit is contained in:
Peter Barker 2021-06-22 12:16:37 +10:00 committed by Peter Barker
parent b35a586447
commit 4ea8c32c61

View File

@ -50,6 +50,8 @@
# Currently only used for informational purposes.
#
# AP_FLAKE8_CLEAN
# for python2.7 compatibility
from __future__ import print_function
@ -132,6 +134,7 @@ crctab = array.array('I', [
0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d])
def crc32(bytes, state=0):
'''crc32 exposed for use by chibios.py'''
for byte in bytes:
@ -139,6 +142,7 @@ def crc32(bytes, state=0):
state = crctab[index] ^ (state >> 8)
return state
class firmware(object):
'''Loads a firmware file'''
@ -215,9 +219,17 @@ class uploader(object):
NSH_REBOOT_BL = b"reboot -b\n"
NSH_REBOOT = b"reboot\n"
def __init__(self, portname, baudrate_bootloader, baudrate_flightstack, baudrate_bootloader_flash=None, target_system=None, target_component=None, source_system=None, source_component=None):
self.MAVLINK_REBOOT_ID1 = bytearray(b'\xfe\x21\x72\xff\x00\x4c\x00\x00\x40\x40\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x01\x00\x00\x53\x6b')
self.MAVLINK_REBOOT_ID0 = bytearray(b'\xfe\x21\x45\xff\x00\x4c\x00\x00\x40\x40\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x00\x00\x00\xcc\x37')
def __init__(self,
portname,
baudrate_bootloader,
baudrate_flightstack,
baudrate_bootloader_flash=None,
target_system=None,
target_component=None,
source_system=None,
source_component=None):
self.MAVLINK_REBOOT_ID1 = bytearray(b'\xfe\x21\x72\xff\x00\x4c\x00\x00\x40\x40\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x01\x00\x00\x53\x6b') # NOQA
self.MAVLINK_REBOOT_ID0 = bytearray(b'\xfe\x21\x45\xff\x00\x4c\x00\x00\x40\x40\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\x00\xf6\x00\x00\x00\x00\xcc\x37') # NOQA
if target_component is None:
target_component = 1
if source_system is None:
@ -638,7 +650,6 @@ class uploader(object):
}
family = mcu_id & 0xfff
chip_s = "%x [unknown family/revision]" % (chip)
if family in F4_IDS:
mcu = F4_IDS[family]
@ -659,7 +670,8 @@ class uploader(object):
if rev in revs:
(label, flawed) = revs[rev]
if flawed and family == 0x419:
print(" %x %s rev%s (flawed; 1M limit, see STM32F42XX Errata sheet sec. 2.1.10)" % (chip, mcu, label,))
print(" %x %s rev%s (flawed; 1M limit, see STM32F42XX Errata sheet sec. 2.1.10)" %
(chip, mcu, label,))
elif family == 0x419:
print(" %x %s rev%s (no 1M flaw)" % (chip, mcu, label,))
else:
@ -699,7 +711,7 @@ class uploader(object):
# uploader.py is swiped into other places, so if the dir
# doesn't exist then fail silently
if os.path.exists(hwdef_dir):
dirs = [x if (x not in ["scripts","common","STM32CubeConf"] and os.path.isdir(os.path.join(hwdef_dir, x))) else None for x in os.listdir(hwdef_dir)]
dirs = [x if (x not in ["scripts", "common", "STM32CubeConf"] and os.path.isdir(os.path.join(hwdef_dir, x))) else None for x in os.listdir(hwdef_dir)] # NOQA
for adir in dirs:
if adir is None:
continue
@ -708,11 +720,10 @@ class uploader(object):
continue
fh = open(filepath)
if fh is None:
# print("Failed to open (%s)" % filepath)
continue
text = fh.readlines()
for line in text:
m = re.match("^\s*APJ_BOARD_ID\s+(\d+)\s*$", line)
m = re.match(r"^\s*APJ_BOARD_ID\s+(\d+)\s*$", line)
if m is None:
continue
if int(m.group(1)) == board_id:
@ -735,7 +746,7 @@ class uploader(object):
board_name = compatible_IDs[self.board_type][1]
if comp_fw_id == fw.property('board_id'):
msg = "Target %s (board_id: %d) is compatible with firmware for board_id=%u)" % (
board_name, self.board_type, fw.property('board_id'))
board_name, self.board_type, fw.property('board_id'))
print("INFO: %s" % msg)
incomp = False
if incomp:
@ -830,6 +841,7 @@ class uploader(object):
self.__download("Download", fw)
self.port.close()
def ports_to_try(args):
portlist = []
if args.port is None:
@ -860,6 +872,7 @@ def ports_to_try(args):
return portlist
def modemmanager_check():
if os.path.exists("/usr/sbin/ModemManager"):
print("""
@ -868,6 +881,7 @@ WARNING: You should uninstall ModemManager as it conflicts with any non-modem se
==========================================================================================================
""")
def find_bootloader(up, port):
while (True):
up.open()
@ -879,7 +893,7 @@ def find_bootloader(up, port):
print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
return True
except Exception as e:
except Exception:
pass
reboot_sent = up.send_reboot()
@ -901,17 +915,50 @@ def main():
# Parse commandline arguments
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
parser.add_argument('--port', action="store", help="Comma-separated list of serial port(s) to which the FMU may be attached",
default=None)
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-bootloader-flash', action="store", type=int, default=None, help="Attempt to negotiate this baudrate with bootloader for flashing.")
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(
'--port',
action="store",
help="Comma-separated list of serial port(s) to which the FMU may be attached",
default=None
)
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." # NOQA
)
parser.add_argument(
'--baud-bootloader-flash',
action="store",
type=int,
default=None,
help="Attempt to negotiate this baudrate with bootloader for flashing."
)
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." # NOQA
)
parser.add_argument('--force', action='store_true', default=False, help='Override board type check and continue loading')
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
parser.add_argument('--target-system', type=int, action="store", help="System ID to update")
parser.add_argument('--target-component', type=int, action="store", help="Component ID to update")
parser.add_argument('--source-system', type=int, action="store", help="Source system to send reboot mavlink packets from", default=255)
parser.add_argument('--source-component', type=int, action="store", help="Source component to send reboot mavlink packets from", default=0)
parser.add_argument(
'--source-system',
type=int,
action="store",
help="Source system to send reboot mavlink packets from",
default=255
)
parser.add_argument(
'--source-component',
type=int,
action="store",
help="Source component to send reboot mavlink packets from",
default=0
)
parser.add_argument('--download', action='store_true', default=False, help='download firmware from board')
parser.add_argument('--identify', action="store_true", help="Do not flash firmware; simply dump information about board")
parser.add_argument('firmware', nargs="?", action="store", default=None, help="Firmware file to be uploaded")
@ -927,7 +974,8 @@ def main():
# Load the firmware file
if not args.download and not args.identify:
fw = firmware(args.firmware)
print("Loaded firmware for %x,%x, size: %d bytes, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size')))
print("Loaded firmware for %x,%x, size: %d bytes, waiting for the bootloader..." %
(fw.property('board_id'), fw.property('board_revision'), fw.property('image_size')))
print("If the board does not respond within 1-2 seconds, unplug and re-plug the USB connector.")
baud_flightstack = [int(x) for x in args.baud_flightstack.split(',')]
@ -996,6 +1044,7 @@ def main():
print("\n Upload aborted by user.")
sys.exit(0)
if __name__ == '__main__':
main()