mirror of https://github.com/ArduPilot/ardupilot
HAL_F4Light: print() is a function in modern Python
This commit is contained in:
parent
aafede65f7
commit
094e284737
|
@ -1,4 +1,5 @@
|
|||
#!/usr/bin/env python
|
||||
from __future__ import print_function
|
||||
|
||||
import serial
|
||||
import os
|
||||
|
@ -7,13 +8,19 @@ import sys
|
|||
import time
|
||||
from struct import pack
|
||||
|
||||
try:
|
||||
raw_input # Python 2
|
||||
except NameError:
|
||||
raw_input = input # Python 3
|
||||
|
||||
|
||||
def unix_get_maple_path(file_prefix):
|
||||
"""Try to find the device file for the Maple on *nix; assuming
|
||||
that it looks like /dev/<file_prefix>*. If there are multiple
|
||||
possibilities, ask the user what to do. If the user chooses not
|
||||
to say, returns None."""
|
||||
possible_paths = [os.path.join('/dev', x) for x in os.listdir('/dev') \
|
||||
if x.startswith(file_prefix)]
|
||||
possible_paths = [os.path.join('/dev', x) for x in os.listdir('/dev')
|
||||
if x.startswith(file_prefix)]
|
||||
return choose_path(possible_paths)
|
||||
|
||||
def windows_get_maple_path():
|
||||
|
@ -37,12 +44,12 @@ def choose_path(possible_paths):
|
|||
elif len(possible_paths) == 1:
|
||||
return possible_paths[0]
|
||||
else:
|
||||
print 'Found multiple candidates for the Maple device:'
|
||||
print('Found multiple candidates for the Maple device:')
|
||||
return choose_among_options(possible_paths)
|
||||
|
||||
def choose_among_options(options):
|
||||
for (i,p) in enumerate(options):
|
||||
print '\t%d. %s' % (i+1, p)
|
||||
print('\t%d. %s' % (i+1, p))
|
||||
|
||||
prompt = 'Enter a number to select one, or q to quit: '
|
||||
while True:
|
||||
|
@ -63,12 +70,12 @@ plat_sys = platform.system()
|
|||
plat_bits = platform.architecture()[0]
|
||||
if plat_sys == 'Linux':
|
||||
if plat_bits == '64bit':
|
||||
print 'You appear to be using 64-bit Linux. Let us know if this works.'
|
||||
print('You appear to be using 64-bit Linux. Let us know if this works.')
|
||||
maple_path = unix_get_maple_path('ttyACM')
|
||||
# fall back on /dev/maple if that doesn't work
|
||||
if maple_path is None:
|
||||
maple_path = '/dev/maple'
|
||||
print 'Could not find Maple serial port; defaulting to /dev/maple.'
|
||||
print('Could not find Maple serial port; defaulting to /dev/maple.')
|
||||
elif plat_sys == 'Darwin':
|
||||
maple_path = unix_get_maple_path('tty.usbmodem')
|
||||
elif plat_sys == 'Windows':
|
||||
|
@ -78,17 +85,17 @@ else:
|
|||
"the path to the Maple's serial port device file:")
|
||||
|
||||
if maple_path is None:
|
||||
print 'Could not find the Maple serial port for reset.', \
|
||||
'Perhaps this is your first upload, or the board is already', \
|
||||
'in bootloader mode.'
|
||||
print
|
||||
print "If your sketch doesn't upload, try putting your Maple", \
|
||||
'into bootloader mode manually by pressing the RESET button', \
|
||||
'then letting it go and quickly pressing button BUT', \
|
||||
'(hold for several seconds).'
|
||||
print('Could not find the Maple serial port for reset. '
|
||||
'Perhaps this is your first upload, or the board is already '
|
||||
'in bootloader mode.')
|
||||
print()
|
||||
print("If your sketch doesn't upload, try putting your Maple "
|
||||
"into bootloader mode manually by pressing the RESET button "
|
||||
"then letting it go and quickly pressing button BUT "
|
||||
"(hold for several seconds).")
|
||||
sys.exit()
|
||||
|
||||
print 'Using %s as Maple serial port' % maple_path
|
||||
print('Using %s as Maple serial port' % maple_path)
|
||||
|
||||
try:
|
||||
ser = serial.Serial(maple_path, baudrate=115200, xonxoff=1)
|
||||
|
@ -119,6 +126,5 @@ try:
|
|||
ser.close()
|
||||
|
||||
except Exception as e:
|
||||
print 'Failed to open serial port %s for reset' % maple_path
|
||||
print('Failed to open serial port %s for reset' % maple_path)
|
||||
sys.exit()
|
||||
|
||||
|
|
|
@ -22,11 +22,13 @@
|
|||
# along with stm32loader; see the file COPYING3. If not see
|
||||
# <http://www.gnu.org/licenses/>.
|
||||
|
||||
import sys, getopt
|
||||
from __future__ import print_function
|
||||
|
||||
import sys
|
||||
import getopt
|
||||
import serial
|
||||
import time
|
||||
import glob
|
||||
import time
|
||||
import tempfile
|
||||
import os
|
||||
import subprocess
|
||||
|
@ -37,12 +39,17 @@ try:
|
|||
except:
|
||||
usepbar = 0
|
||||
|
||||
try:
|
||||
xrange # Python 2
|
||||
except NameError:
|
||||
xrange = range # Python 3
|
||||
|
||||
# Verbose level
|
||||
QUIET = 20
|
||||
|
||||
def mdebug(level, message):
|
||||
if(QUIET >= level):
|
||||
print >> sys.stderr , message
|
||||
if QUIET >= level:
|
||||
print(message, file=sys.stderr)
|
||||
|
||||
|
||||
class CmdException(Exception):
|
||||
|
@ -321,7 +328,7 @@ class CommandInterface:
|
|||
|
||||
|
||||
def usage():
|
||||
print """Usage: %s [-hqVewvr] [-l length] [-p port] [-b baud] [-a addr] [file.bin]
|
||||
print("""Usage: %s [-hqVewvr] [-l length] [-p port] [-b baud] [-a addr] [file.bin]
|
||||
-h This help
|
||||
-q Quiet
|
||||
-V Verbose
|
||||
|
@ -336,7 +343,7 @@ def usage():
|
|||
|
||||
./stm32loader.py -e -w -v example/main.bin
|
||||
|
||||
""" % sys.argv[0]
|
||||
""" % sys.argv[0])
|
||||
|
||||
def read(filename):
|
||||
"""Read the file to be programmed and turn it into a binary"""
|
||||
|
@ -373,7 +380,7 @@ if __name__ == "__main__":
|
|||
try:
|
||||
import psyco
|
||||
psyco.full()
|
||||
print "Using Psyco..."
|
||||
print("Using Psyco...")
|
||||
except ImportError:
|
||||
pass
|
||||
|
||||
|
@ -393,9 +400,9 @@ if __name__ == "__main__":
|
|||
|
||||
try:
|
||||
opts, args = getopt.getopt(sys.argv[1:], "hqVewvrp:b:a:l:")
|
||||
except getopt.GetoptError, err:
|
||||
except getopt.GetoptError as err:
|
||||
# print help information and exit:
|
||||
print str(err) # will print something like "option -a not recognized"
|
||||
print(str(err)) # will print something like "option -a not recognized"
|
||||
usage()
|
||||
sys.exit(2)
|
||||
|
||||
|
@ -456,7 +463,7 @@ if __name__ == "__main__":
|
|||
try:
|
||||
cmd.initChip()
|
||||
except CmdException:
|
||||
print "Can't init. Ensure that BOOT0 is enabled and reset device"
|
||||
print("Can't init. Ensure that BOOT0 is enabled and reset device")
|
||||
|
||||
bootversion = cmd.cmdGet()
|
||||
|
||||
|
@ -486,20 +493,19 @@ if __name__ == "__main__":
|
|||
if conf['verify']:
|
||||
verify = cmd.readMemory(conf['address'], len(data))
|
||||
if(data == verify):
|
||||
print "Verification OK"
|
||||
print("Verification OK")
|
||||
else:
|
||||
print "Verification FAILED"
|
||||
print str(len(data)) + ' vs ' + str(len(verify))
|
||||
print("Verification FAILED")
|
||||
print('{} vs {}'.format(len(data), len(verify)))
|
||||
for i in xrange(0, len(data)):
|
||||
if data[i] != verify[i]:
|
||||
print hex(i) + ': ' + hex(data[i]) + ' vs ' + hex(verify[i])
|
||||
print(hex(i) + ': ' + hex(data[i]) + ' vs ' + hex(verify[i]))
|
||||
|
||||
if not conf['write'] and conf['read']:
|
||||
rdata = cmd.readMemory(conf['address'], conf['len'])
|
||||
# file(conf['fname'], 'wb').write(rdata)
|
||||
file(args[0], 'wb').write(''.join(map(chr,rdata)))
|
||||
open(args[0], 'wb').write(''.join(map(chr, rdata)))
|
||||
|
||||
# cmd.cmdGo(addr + 0x04)
|
||||
finally:
|
||||
cmd.releaseChip()
|
||||
|
||||
|
|
Loading…
Reference in New Issue