diff options
Diffstat (limited to 'Tools/px_uploader.py')
-rwxr-xr-x | Tools/px_uploader.py | 137 |
1 files changed, 73 insertions, 64 deletions
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index 95a3d4046..8042ec34a 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -501,75 +501,84 @@ print("Loaded firmware for %x,%x, size: %d bytes, waiting for the bootloader..." 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 -while True: - portlist = [] - patterns = args.port.split(",") - # on unix-like platforms use glob to support wildcard ports. This allows - # the use of /dev/serial/by-id/usb-3D_Robotics on Linux, which prevents the upload from - # causing modem hangups etc - if "linux" in _platform or "darwin" in _platform: - import glob - for pattern in patterns: - portlist += glob.glob(pattern) - else: - portlist = patterns - - for port in portlist: - - #print("Trying %s" % port) - - # create an uploader attached to the port - try: - if "linux" in _platform: - # Linux, don't open Mac OS and Win ports - if not "COM" in port and not "tty.usb" in port: - up = uploader(port, args.baud) - elif "darwin" in _platform: - # OS X, don't open Windows and Linux ports - if not "COM" in port and not "ACM" in port: - up = uploader(port, args.baud) - elif "win" in _platform: - # Windows, don't open POSIX ports - if not "/" in port: - up = uploader(port, args.baud) - except Exception: - # open failed, rate-limit our attempts - time.sleep(0.05) - - # and loop to the next port - continue - - # port is open, try talking to it - try: - # identify the bootloader - up.identify() - print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port)) +try: + while True: + portlist = [] + patterns = args.port.split(",") + # on unix-like platforms use glob to support wildcard ports. This allows + # the use of /dev/serial/by-id/usb-3D_Robotics on Linux, which prevents the upload from + # causing modem hangups etc + if "linux" in _platform or "darwin" in _platform: + import glob + for pattern in patterns: + portlist += glob.glob(pattern) + else: + portlist = patterns + + for port in portlist: + + #print("Trying %s" % port) + + # create an uploader attached to the port + try: + if "linux" in _platform: + # Linux, don't open Mac OS and Win ports + if not "COM" in port and not "tty.usb" in port: + up = uploader(port, args.baud) + elif "darwin" in _platform: + # OS X, don't open Windows and Linux ports + if not "COM" in port and not "ACM" in port: + up = uploader(port, args.baud) + elif "win" in _platform: + # Windows, don't open POSIX ports + if not "/" in port: + up = uploader(port, args.baud) + except Exception: + # open failed, rate-limit our attempts + time.sleep(0.05) + + # and loop to the next port + continue + + # port is open, try talking to it + try: + # identify the bootloader + up.identify() + print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port)) - except Exception: - # most probably a timeout talking to the port, no bootloader, try to reboot the board - print("attempting reboot on %s..." % port) - print("if the board does not respond, unplug and re-plug the USB connector.") - up.send_reboot() + except Exception: + # most probably a timeout talking to the port, no bootloader, try to reboot the board + print("attempting reboot on %s..." % port) + print("if the board does not respond, unplug and re-plug the USB connector.") + up.send_reboot() - # wait for the reboot, without we might run into Serial I/O Error 5 - time.sleep(0.5) + # wait for the reboot, without we might run into Serial I/O Error 5 + time.sleep(0.5) - # always close the port - up.close() - continue + # always close the port + up.close() + continue - try: - # ok, we have a bootloader, try flashing it - up.upload(fw) + try: + # ok, we have a bootloader, try flashing it + up.upload(fw) + + except RuntimeError as ex: + + # print the error + print("\nERROR: %s" % ex.args) - except RuntimeError as ex: + finally: + # always close the port + up.close() - # print the error - print("\nERROR: %s" % ex.args) + # we could loop here if we wanted to wait for more boards... + sys.exit(0) - finally: - # always close the port - up.close() + #Rate-limit retries to prevent spin-lock from hogging the CPU + time.sleep(0.5) - # we could loop here if we wanted to wait for more boards... - sys.exit(0) +#CTRL+C aborts the upload/spin-lock by interrupt mechanics +except KeyboardInterrupt: + print("\n Upload aborted by user.") + sys.exit(0)
\ No newline at end of file |