PIXHAWK: Update to latest px_uploader.py

Updating px_uploader.py to the latest from ArduPilot

This is the latest px_uploader from the ArduPilot px4 submodule. It allows WiFi to function when the system is in bootloader.
This commit is contained in:
Matt 2017-08-03 05:25:59 -04:00
parent adbe6ebbf3
commit bed42fd01e

312
sololink/px_uploader/px_uploader.py Executable file → Normal file
View File

@ -1,7 +1,7 @@
#!/usr/bin/env python #!/usr/bin/env python
############################################################################ ############################################################################
# #
# Copyright (C) 2012-2015 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 # Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions # modification, are permitted provided that the following conditions
@ -67,6 +67,15 @@ import os
from sys import platform as _platform from sys import platform as _platform
# Detect python version
if sys.version_info[0] < 3:
runningPython3 = False
else:
runningPython3 = True
# list of tuples (bootloader boardID, firmware boardID, boardname)
# designating firmware builds compatible with multiple boardIDs
compatible_IDs = [(33, 9, 'AUAVX2.1')]
class firmware(object): class firmware(object):
'''Loads a firmware file''' '''Loads a firmware file'''
@ -148,6 +157,7 @@ class uploader(object):
OK = b'\x10' OK = b'\x10'
FAILED = b'\x11' FAILED = b'\x11'
INVALID = b'\x13' # rev3+ INVALID = b'\x13' # rev3+
BAD_SILICON_REV = b'\x14' # rev5+
# command bytes # command bytes
NOP = b'\x00' # guaranteed to be discarded by the bootloader NOP = b'\x00' # guaranteed to be discarded by the bootloader
@ -162,11 +172,15 @@ class uploader(object):
GET_SN = b'\x2b' # rev4+ , get a word from SN area GET_SN = b'\x2b' # rev4+ , get a word from SN area
GET_CHIP = b'\x2c' # rev5+ , get chip version GET_CHIP = b'\x2c' # rev5+ , get chip version
SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII
MAX_DES_LENGTH = 20
REBOOT = b'\x30' REBOOT = b'\x30'
SET_BAUD = b'\x33' # set baud
INFO_BL_REV = b'\x01' # bootloader protocol revision INFO_BL_REV = b'\x01' # bootloader protocol revision
BL_REV_MIN = 2 # minimum supported bootloader protocol BL_REV_MIN = 2 # minimum supported bootloader protocol
BL_REV_MAX = 4 # maximum supported bootloader protocol BL_REV_MAX = 5 # maximum supported bootloader protocol
INFO_BOARD_ID = b'\x02' # board type INFO_BOARD_ID = b'\x02' # board type
INFO_BOARD_REV = b'\x03' # board revision INFO_BOARD_REV = b'\x03' # board revision
INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes
@ -177,28 +191,59 @@ class uploader(object):
NSH_INIT = bytearray(b'\x0d\x0d\x0d') NSH_INIT = bytearray(b'\x0d\x0d\x0d')
NSH_REBOOT_BL = b"reboot -b\n" NSH_REBOOT_BL = b"reboot -b\n"
NSH_REBOOT = b"reboot\n" NSH_REBOOT = b"reboot\n"
MAVLINK_REBOOT_ID1 = bytearray(b'\xfe\x21\x72\xff\x00\x4c\x00\x00\x80\x3f\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\x48\xf0') 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')
MAVLINK_REBOOT_ID0 = bytearray(b'\xfe\x21\x45\xff\x00\x4c\x00\x00\x80\x3f\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\xd7\xac') 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): def __init__(self, portname, baudrate_bootloader, baudrate_flightstack, baudrate_bootloader_flash=None):
# open the port, keep the default timeout short so we can poll quickly # open the port, keep the default timeout short so we can poll quickly
self.port = serial.Serial(portname, baudrate, timeout=0.5) self.port = serial.Serial(portname, baudrate_bootloader, timeout=0.5)
self.otp = b'' self.otp = b''
self.sn = b'' self.sn = b''
self.baudrate_bootloader = baudrate_bootloader
if baudrate_bootloader_flash is not None:
self.baudrate_bootloader_flash = baudrate_bootloader_flash
else:
self.baudrate_bootloader_flash = self.baudrate_bootloader
self.baudrate_flightstack = baudrate_flightstack
self.baudrate_flightstack_idx = -1
def close(self): def close(self):
if self.port is not None: if self.port is not None:
self.port.close() self.port.close()
def open(self):
timeout = time.time() + 0.2
# Attempt to open the port while it exists and until timeout occurs
while self.port is not None:
portopen = True
try:
portopen = self.port.is_open
except AttributeError:
portopen = self.port.isOpen()
if not portopen and time.time() < timeout:
try:
self.port.open()
except OSError:
# wait for the port to be ready
time.sleep(0.04)
except serial.SerialException:
# if open fails, try again later
time.sleep(0.04)
else:
break
def __send(self, c): def __send(self, c):
# print("send " + binascii.hexlify(c)) # print("send " + binascii.hexlify(c))
self.port.write(c) self.port.write(c)
def __recv(self, count=1): def __recv(self, count=1):
c = self.port.read(count) c = self.port.read(count)
if len(c) < 1: if len(c) < 1:
raise RuntimeError("timeout waiting for data (%u bytes)" % count) raise RuntimeError("timeout waiting for data (%u bytes)" % count)
# print("recv " + binascii.hexlify(c)) # print("recv " + binascii.hexlify(c))
return c return c
def __recv_int(self): def __recv_int(self):
@ -223,26 +268,31 @@ class uploader(object):
def __sync(self): def __sync(self):
# send a stream of ignored bytes longer than the longest possible conversation # send a stream of ignored bytes longer than the longest possible conversation
# that we might still have in progress # that we might still have in progress
# self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2)) # self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2))
self.port.flushInput() self.port.flushInput()
self.__send(uploader.GET_SYNC self.__send(uploader.GET_SYNC +
+ uploader.EOC) uploader.EOC)
self.__getSync() self.__getSync()
def __trySync(self): def __trySync(self):
try: try:
self.port.flush() self.port.flush()
if (self.__recv() != self.INSYNC): if (self.__recv() != self.INSYNC):
#print("unexpected 0x%x instead of INSYNC" % ord(c)) # print("unexpected 0x%x instead of INSYNC" % ord(c))
return False; return False
c = self.__recv()
if (self.__recv() != self.OK): if (c == self.BAD_SILICON_REV):
#print("unexpected 0x%x instead of OK" % ord(c)) raise NotImplementedError()
if (c != self.OK):
# print("unexpected 0x%x instead of OK" % ord(c))
return False return False
return True return True
except NotImplementedError:
raise RuntimeError("Programing not supported for this version of silicon!\n"
"See https://pixhawk.org/help/errata")
except RuntimeError: except RuntimeError:
#timeout, no response yet # timeout, no response yet
return False return False
# send the GET_DEVICE command and wait for an info parameter # send the GET_DEVICE command and wait for an info parameter
@ -275,6 +325,15 @@ class uploader(object):
self.__getSync() self.__getSync()
return value return value
# send the GET_CHIP command
def __getCHIPDes(self):
self.__send(uploader.GET_CHIP_DES + uploader.EOC)
length = self.__recv_int()
value = self.__recv(length)
self.__getSync()
peices = value.split(",")
return peices
def __drawProgressBar(self, label, progress, maxVal): def __drawProgressBar(self, label, progress, maxVal):
if maxVal < progress: if maxVal < progress:
progress = maxVal progress = maxVal
@ -284,36 +343,35 @@ class uploader(object):
sys.stdout.write("\r%s: [%-20s] %.1f%%" % (label, '='*int(percent/5.0), percent)) sys.stdout.write("\r%s: [%-20s] %.1f%%" % (label, '='*int(percent/5.0), percent))
sys.stdout.flush() sys.stdout.flush()
# send the CHIP_ERASE command and wait for the bootloader to become ready # send the CHIP_ERASE command and wait for the bootloader to become ready
def __erase(self, label): def __erase(self, label):
print("\n", end='') print("\n", end='')
self.__send(uploader.CHIP_ERASE self.__send(uploader.CHIP_ERASE +
+ uploader.EOC) uploader.EOC)
# erase is very slow, give it 20s # erase is very slow, give it 30s
deadline = time.time() + 20.0 deadline = time.time() + 30.0
while time.time() < deadline: while time.time() < deadline:
#Draw progress bar (erase usually takes about 9 seconds to complete) # Draw progress bar (erase usually takes about 9 seconds to complete)
estimatedTimeRemaining = deadline-time.time() estimatedTimeRemaining = deadline-time.time()
if estimatedTimeRemaining >= 9.0: if estimatedTimeRemaining >= 9.0:
self.__drawProgressBar(label, 20.0-estimatedTimeRemaining, 9.0) self.__drawProgressBar(label, 30.0-estimatedTimeRemaining, 9.0)
else: else:
self.__drawProgressBar(label, 10.0, 10.0) self.__drawProgressBar(label, 10.0, 10.0)
sys.stdout.write(" (timeout: %d seconds) " % int(deadline-time.time()) ) sys.stdout.write(" (timeout: %d seconds) " % int(deadline-time.time()))
sys.stdout.flush() sys.stdout.flush()
if self.__trySync(): if self.__trySync():
self.__drawProgressBar(label, 10.0, 10.0) self.__drawProgressBar(label, 10.0, 10.0)
return; return
raise RuntimeError("timed out waiting for erase") raise RuntimeError("timed out waiting for erase")
# send a PROG_MULTI command to write a collection of bytes # send a PROG_MULTI command to write a collection of bytes
def __program_multi(self, data): def __program_multi(self, data):
if runningPython3 == True: if runningPython3:
length = len(data).to_bytes(1, byteorder='big') length = len(data).to_bytes(1, byteorder='big')
else: else:
length = chr(len(data)) length = chr(len(data))
@ -327,7 +385,7 @@ class uploader(object):
# verify multiple bytes in flash # verify multiple bytes in flash
def __verify_multi(self, data): def __verify_multi(self, data):
if runningPython3 == True: if runningPython3:
length = len(data).to_bytes(1, byteorder='big') length = len(data).to_bytes(1, byteorder='big')
else: else:
length = chr(len(data)) length = chr(len(data))
@ -346,8 +404,8 @@ class uploader(object):
# send the reboot command # send the reboot command
def __reboot(self): def __reboot(self):
self.__send(uploader.REBOOT self.__send(uploader.REBOOT +
+ uploader.EOC) uploader.EOC)
self.port.flush() self.port.flush()
# v3+ can report failure if the first word flash fails # v3+ can report failure if the first word flash fails
@ -368,7 +426,7 @@ class uploader(object):
for bytes in groups: for bytes in groups:
self.__program_multi(bytes) self.__program_multi(bytes)
#Print upload progress (throttled, so it does not delay upload progress) # Print upload progress (throttled, so it does not delay upload progress)
uploadProgress += 1 uploadProgress += 1
if uploadProgress % 256 == 0: if uploadProgress % 256 == 0:
self.__drawProgressBar(label, uploadProgress, len(groups)) self.__drawProgressBar(label, uploadProgress, len(groups))
@ -377,8 +435,8 @@ class uploader(object):
# verify code # verify code
def __verify_v2(self, label, fw): def __verify_v2(self, label, fw):
print("\n", end='') print("\n", end='')
self.__send(uploader.CHIP_VERIFY self.__send(uploader.CHIP_VERIFY +
+ uploader.EOC) uploader.EOC)
self.__getSync() self.__getSync()
code = fw.image code = fw.image
groups = self.__split_len(code, uploader.READ_MULTI_MAX) groups = self.__split_len(code, uploader.READ_MULTI_MAX)
@ -395,11 +453,10 @@ class uploader(object):
print("\n", end='') print("\n", end='')
self.__drawProgressBar(label, 1, 100) self.__drawProgressBar(label, 1, 100)
expect_crc = fw.crc(self.fw_maxsize) expect_crc = fw.crc(self.fw_maxsize)
self.__send(uploader.GET_CRC self.__send(uploader.GET_CRC +
+ uploader.EOC) uploader.EOC)
report_crc = self.__recv_int() report_crc = self.__recv_int()
self.__getSync() self.__getSync()
verifyProgress = 0
if report_crc != expect_crc: if report_crc != expect_crc:
print("Expected 0x%x" % expect_crc) print("Expected 0x%x" % expect_crc)
print("Got 0x%x" % report_crc) print("Got 0x%x" % report_crc)
@ -407,9 +464,15 @@ class uploader(object):
self.__drawProgressBar(label, 100, 100) self.__drawProgressBar(label, 100, 100)
def __set_boot_delay(self, boot_delay): def __set_boot_delay(self, boot_delay):
self.__send(uploader.SET_BOOT_DELAY self.__send(uploader.SET_BOOT_DELAY +
+ struct.pack("b", boot_delay) struct.pack("b", boot_delay) +
+ uploader.EOC) uploader.EOC)
self.__getSync()
def __setbaud(self, baud):
self.__send(uploader.SET_BAUD +
struct.pack("I", baud) +
uploader.EOC)
self.__getSync() self.__getSync()
# get basic data about the board # get basic data about the board
@ -428,13 +491,25 @@ class uploader(object):
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE) self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
# upload the firmware # upload the firmware
def upload(self, fw): def upload(self, fw, force=False, boot_delay=None):
# Make sure we are doing the right thing # Make sure we are doing the right thing
if self.board_type != fw.property('board_id'): if self.board_type != fw.property('board_id'):
# ID mismatch: check compatibility
incomp = True
for entry in compatible_IDs:
if (entry[0] == self.board_type) and (entry[1] == fw.property('board_id')):
msg = "Target %s (board_id: %d) is compatible with firmware for board_id=%u)" % (
entry[2], self.board_type, fw.property('board_id'))
print("INFO: %s" % msg)
incomp = False
break
if incomp:
msg = "Firmware not suitable for this board (board_type=%u board_id=%u)" % ( msg = "Firmware not suitable for this board (board_type=%u board_id=%u)" % (
self.board_type, fw.property('board_id')) self.board_type, fw.property('board_id'))
if args.force:
print("WARNING: %s" % msg) print("WARNING: %s" % msg)
if force:
print("FORCED WRITE, FLASHING ANYWAY!")
else: else:
raise IOError(msg) raise IOError(msg)
if self.fw_maxsize < fw.property('image_size'): if self.fw_maxsize < fw.property('image_size'):
@ -442,7 +517,7 @@ class uploader(object):
# OTP added in v4: # OTP added in v4:
if self.bl_rev > 3: if self.bl_rev > 3:
for byte in range(0,32*6,4): for byte in range(0, 32*6, 4):
x = self.__getOTP(byte) x = self.__getOTP(byte)
self.otp = self.otp + x self.otp = self.otp + x
print(binascii.hexlify(x).decode('Latin-1') + ' ', end='') print(binascii.hexlify(x).decode('Latin-1') + ' ', end='')
@ -457,20 +532,32 @@ class uploader(object):
print("type: " + self.otp_id.decode('Latin-1')) print("type: " + self.otp_id.decode('Latin-1'))
print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1')) print("idtype: " + binascii.b2a_qp(self.otp_idtype).decode('Latin-1'))
print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1')) print("vid: " + binascii.hexlify(self.otp_vid).decode('Latin-1'))
print("pid: "+ binascii.hexlify(self.otp_pid).decode('Latin-1')) print("pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1'))
print("coa: "+ binascii.b2a_base64(self.otp_coa).decode('Latin-1')) print("coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
print("sn: ", end='') print("sn: ", end='')
for byte in range(0,12,4): for byte in range(0, 12, 4):
x = self.__getSN(byte) x = self.__getSN(byte)
x = x[::-1] # reverse the bytes x = x[::-1] # reverse the bytes
self.sn = self.sn + x self.sn = self.sn + x
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
print('') print('')
print("chip: %08x" % self.__getCHIP()) print("chip: %08x" % self.__getCHIP())
if (self.bl_rev >= 5):
des = self.__getCHIPDes()
if (len(des) == 2):
print("family: %s" % des[0])
print("revision: %s" % des[1])
print("flash %d" % self.fw_maxsize)
except Exception: except Exception:
# ignore bad character encodings # ignore bad character encodings
pass pass
if self.baudrate_bootloader_flash != self.baudrate_bootloader:
print("Setting baudrate to %u" % self.baudrate_bootloader_flash)
self.__setbaud(self.baudrate_bootloader_flash)
self.port.baudrate = self.baudrate_bootloader_flash
self.__sync()
self.__erase("Erase ") self.__erase("Erase ")
self.__program("Program", fw) self.__program("Program", fw)
@ -479,55 +566,80 @@ class uploader(object):
else: else:
self.__verify_v3("Verify ", fw) self.__verify_v3("Verify ", fw)
if args.boot_delay is not None: if boot_delay is not None:
self.__set_boot_delay(args.boot_delay) self.__set_boot_delay(boot_delay)
print("\nRebooting.\n") print("\nRebooting.\n")
self.__reboot() self.__reboot()
self.port.close() self.port.close()
def send_reboot(self): def __next_baud_flightstack(self):
if self.baudrate_flightstack_idx + 1 >= len(self.baudrate_flightstack):
return False
try: try:
# try reboot via NSH first self.port.baudrate = self.baudrate_flightstack[self.baudrate_flightstack_idx + 1]
self.baudrate_flightstack_idx = self.baudrate_flightstack_idx + 1
except serial.SerialException:
# Sometimes _configure_port fails
time.sleep(0.04)
return True
def send_reboot(self):
if (not self.__next_baud_flightstack()):
return False
print("Attempting reboot on %s with baudrate=%d..." % (self.port.port, self.port.baudrate), file=sys.stderr)
print("If the board does not respond, unplug and re-plug the USB connector.", file=sys.stderr)
try:
# try MAVLINK command first
self.port.flush()
self.__send(uploader.MAVLINK_REBOOT_ID1)
self.__send(uploader.MAVLINK_REBOOT_ID0)
# then try reboot via NSH
self.__send(uploader.NSH_INIT) self.__send(uploader.NSH_INIT)
self.__send(uploader.NSH_REBOOT_BL) self.__send(uploader.NSH_REBOOT_BL)
self.__send(uploader.NSH_INIT) self.__send(uploader.NSH_INIT)
self.__send(uploader.NSH_REBOOT) self.__send(uploader.NSH_REBOOT)
# then try MAVLINK command self.port.flush()
self.__send(uploader.MAVLINK_REBOOT_ID1) self.port.baudrate = self.baudrate_bootloader
self.__send(uploader.MAVLINK_REBOOT_ID0)
except: except:
return try:
self.port.flush()
self.port.baudrate = self.baudrate_bootloader
except Exception:
pass
return True
# Detect python version def main():
if sys.version_info[0] < 3:
runningPython3 = False
else:
runningPython3 = True
# Parse commandline arguments # Parse commandline arguments
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.") parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
parser.add_argument('--port', action="store", required=True, help="Serial port(s) to which the FMU may be attached") parser.add_argument('--port', action="store", required=True, help="Comma-separated list of serial port(s) to which the FMU may be attached")
parser.add_argument('--baud', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200), only required for true serial ports.") 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('--force', action='store_true', default=False, help='Override board type check and continue loading') 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('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash') 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('firmware', action="store", help="Firmware file to be uploaded") parser.add_argument('--force', action='store_true', default=False, help='Override board type check and continue loading')
args = parser.parse_args() parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
parser.add_argument('firmware', action="store", help="Firmware file to be uploaded")
args = parser.parse_args()
# warn people about ModemManager which interferes badly with Pixhawk # warn people about ModemManager which interferes badly with Pixhawk
if os.path.exists("/usr/sbin/ModemManager"): if os.path.exists("/usr/sbin/ModemManager"):
print("==========================================================================================================") print("==========================================================================================================")
print("WARNING: You should uninstall ModemManager as it conflicts with any non-modem serial device (like Pixhawk)") print("WARNING: You should uninstall ModemManager as it conflicts with any non-modem serial device (like Pixhawk)")
print("==========================================================================================================") print("==========================================================================================================")
# Load the firmware file # Load the firmware file
fw = firmware(args.firmware) 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.") print("If the board does not respond within 1-2 seconds, unplug and re-plug the USB connector.")
# Spin waiting for a device to show up # Spin waiting for a device to show up
try: try:
while True: while True:
portlist = [] portlist = []
patterns = args.port.split(",") patterns = args.port.split(",")
@ -541,24 +653,26 @@ try:
else: else:
portlist = patterns portlist = patterns
baud_flightstack = [int(x) for x in args.baud_flightstack.split(',')]
for port in portlist: for port in portlist:
#print("Trying %s" % port) # print("Trying %s" % port)
# create an uploader attached to the port # create an uploader attached to the port
try: try:
if "linux" in _platform: if "linux" in _platform:
# Linux, don't open Mac OS and Win ports # Linux, don't open Mac OS and Win ports
if not "COM" in port and not "tty.usb" in port: if "COM" not in port and "tty.usb" not in port:
up = uploader(port, args.baud) up = uploader(port, args.baud_bootloader, baud_flightstack, args.baud_bootloader_flash)
elif "darwin" in _platform: elif "darwin" in _platform:
# OS X, don't open Windows and Linux ports # OS X, don't open Windows and Linux ports
if not "COM" in port and not "ACM" in port: if "COM" not in port and "ACM" not in port:
up = uploader(port, args.baud) up = uploader(port, args.baud_bootloader, baud_flightstack, args.baud_bootloader_flash)
elif "win" in _platform: elif "win" in _platform:
# Windows, don't open POSIX ports # Windows, don't open POSIX ports
if not "/" in port: if "/" not in port:
up = uploader(port, args.baud) up = uploader(port, args.baud_bootloader, baud_flightstack, args.baud_bootloader_flash)
except Exception: except Exception:
# open failed, rate-limit our attempts # open failed, rate-limit our attempts
time.sleep(0.05) time.sleep(0.05)
@ -566,35 +680,46 @@ try:
# and loop to the next port # and loop to the next port
continue continue
found_bootloader = False
while (True):
up.open()
# port is open, try talking to it # port is open, try talking to it
try: try:
# identify the bootloader # identify the bootloader
up.identify() up.identify()
found_bootloader = True
print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port)) print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
break
except Exception: except Exception:
# most probably a timeout talking to the port, no bootloader, try to reboot the board
print("attempting reboot on %s..." % port) if not up.send_reboot():
print("if the board does not respond, unplug and re-plug the USB connector.") break
up.send_reboot()
# wait for the reboot, without we might run into Serial I/O Error 5 # wait for the reboot, without we might run into Serial I/O Error 5
time.sleep(0.5) time.sleep(0.25)
# always close the port # always close the port
up.close() up.close()
# wait for the close, without we might run into Serial I/O Error 6
time.sleep(0.3)
if not found_bootloader:
# Go to the next port
continue continue
try: try:
# ok, we have a bootloader, try flashing it # ok, we have a bootloader, try flashing it
up.upload(fw) up.upload(fw, force=args.force, boot_delay=args.boot_delay)
except RuntimeError as ex: except RuntimeError as ex:
# print the error # print the error
print("\nERROR: %s" % ex.args) print("\nERROR: %s" % ex.args)
except IOError as e: except IOError:
up.close(); up.close()
continue continue
finally: finally:
@ -607,7 +732,12 @@ try:
# Delay retries to < 20 Hz to prevent spin-lock from hogging the CPU # Delay retries to < 20 Hz to prevent spin-lock from hogging the CPU
time.sleep(0.05) time.sleep(0.05)
# CTRL+C aborts the upload/spin-lock by interrupt mechanics # CTRL+C aborts the upload/spin-lock by interrupt mechanics
except KeyboardInterrupt: except KeyboardInterrupt:
print("\n Upload aborted by user.") print("\n Upload aborted by user.")
sys.exit(0) sys.exit(0)
if __name__ == '__main__':
main()
# vim: tabstop=4 expandtab shiftwidth=4 softtabstop=4