aboutsummaryrefslogtreecommitdiff
path: root/Tools
diff options
context:
space:
mode:
Diffstat (limited to 'Tools')
-rwxr-xr-x[-rw-r--r--]Tools/px_generate_xml.sh0
-rwxr-xr-xTools/px_mkfw.py5
-rwxr-xr-x[-rw-r--r--]Tools/px_update_wiki.sh0
-rwxr-xr-xTools/px_uploader.py12
-rwxr-xr-xTools/upload.sh28
-rw-r--r--Tools/usb_serialload.py55
6 files changed, 96 insertions, 4 deletions
diff --git a/Tools/px_generate_xml.sh b/Tools/px_generate_xml.sh
index 65f0c95da..65f0c95da 100644..100755
--- a/Tools/px_generate_xml.sh
+++ b/Tools/px_generate_xml.sh
diff --git a/Tools/px_mkfw.py b/Tools/px_mkfw.py
index b598a65a1..c2da8a203 100755
--- a/Tools/px_mkfw.py
+++ b/Tools/px_mkfw.py
@@ -73,6 +73,7 @@ parser.add_argument("--version", action="store", help="set a version string")
parser.add_argument("--summary", action="store", help="set a brief description")
parser.add_argument("--description", action="store", help="set a longer description")
parser.add_argument("--git_identity", action="store", help="the working directory to check for git identity")
+parser.add_argument("--parameter_xml", action="store", help="the parameters.xml file")
parser.add_argument("--image", action="store", help="the firmware image")
args = parser.parse_args()
@@ -101,6 +102,10 @@ if args.git_identity != None:
p = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE).stdout
desc['git_identity'] = str(p.read().strip())
p.close()
+if args.parameter_xml != None:
+ f = open(args.parameter_xml, "rb")
+ bytes = f.read()
+ desc['parameter_xml'] = base64.b64encode(zlib.compress(bytes,9)).decode('utf-8')
if args.image != None:
f = open(args.image, "rb")
bytes = f.read()
diff --git a/Tools/px_update_wiki.sh b/Tools/px_update_wiki.sh
index d66bb9e10..d66bb9e10 100644..100755
--- a/Tools/px_update_wiki.sh
+++ b/Tools/px_update_wiki.sh
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index b46db00b5..3a4540ac0 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -178,9 +178,9 @@ class uploader(object):
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_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')
- def __init__(self, portname, baudrate, interCharTimeout=0.001, timeout=0.5):
+ def __init__(self, portname, baudrate):
# open the port, keep the default timeout short so we can poll quickly
- self.port = serial.Serial(portname, baudrate)
+ self.port = serial.Serial(portname, baudrate, timeout=0.5)
self.otp = b''
self.sn = b''
@@ -195,7 +195,7 @@ class uploader(object):
def __recv(self, count=1):
c = self.port.read(count)
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))
return c
@@ -458,7 +458,8 @@ if os.path.exists("/usr/sbin/ModemManager"):
# Load the firmware file
fw = firmware(args.firmware)
-print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision')))
+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.")
# Spin waiting for a device to show up
while True:
@@ -508,9 +509,12 @@ while True:
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)
+ # always close the port
+ up.close()
continue
try:
diff --git a/Tools/upload.sh b/Tools/upload.sh
new file mode 100755
index 000000000..c0dd65eba
--- /dev/null
+++ b/Tools/upload.sh
@@ -0,0 +1,28 @@
+#!/bin/bash
+
+EXEDIR=`pwd`
+BASEDIR=$(dirname $0)
+
+SYSTYPE=`uname -s`
+
+#
+# Serial port defaults.
+#
+# XXX The uploader should be smarter than this.
+#
+if [ $SYSTYPE = "Darwin" ];
+then
+SERIAL_PORTS="/dev/tty.usbmodemPX*,/dev/tty.usbmodem*"
+fi
+
+if [ $SYSTYPE = "Linux" ];
+then
+SERIAL_PORTS="/dev/serial/by-id/usb-3D_Robotics*"
+fi
+
+if [ $SYSTYPE = "" ];
+then
+SERIAL_PORTS="COM32,COM31,COM30,COM29,COM28,COM27,COM26,COM25,COM24,COM23,COM22,COM21,COM20,COM19,COM18,COM17,COM16,COM15,COM14,COM13,COM12,COM11,COM10,COM9,COM8,COM7,COM6,COM5,COM4,COM3,COM2,COM1,COM0"
+fi
+
+python $BASEDIR/px_uploader.py --port $SERIAL_PORTS $1 \ No newline at end of file
diff --git a/Tools/usb_serialload.py b/Tools/usb_serialload.py
new file mode 100644
index 000000000..5c864532f
--- /dev/null
+++ b/Tools/usb_serialload.py
@@ -0,0 +1,55 @@
+import serial, time
+
+
+port = serial.Serial('/dev/ttyACM0', baudrate=57600, timeout=2)
+
+data = '01234567890123456789012345678901234567890123456789'
+#data = 'hellohello'
+outLine = 'echo %s\n' % data
+
+port.write('\n\n\n')
+port.write('free\n')
+line = port.readline(80)
+while line != '':
+ print(line)
+ line = port.readline(80)
+
+
+i = 0
+bytesOut = 0
+bytesIn = 0
+
+startTime = time.time()
+lastPrint = startTime
+while True:
+ bytesOut += port.write(outLine)
+ line = port.readline(80)
+ bytesIn += len(line)
+ # check command line echo
+ if (data not in line):
+ print('command error %d: %s' % (i,line))
+ #break
+ # read echo output
+ line = port.readline(80)
+ if (data not in line):
+ print('echo output error %d: %s' % (i,line))
+ #break
+ bytesIn += len(line)
+ #print('%d: %s' % (i,line))
+ #print('%d: bytesOut: %d, bytesIn: %d' % (i, bytesOut, bytesIn))
+
+ elapsedT = time.time() - lastPrint
+ if (time.time() - lastPrint >= 5):
+ outRate = bytesOut / elapsedT
+ inRate = bytesIn / elapsedT
+ usbRate = (bytesOut + bytesIn) / elapsedT
+ lastPrint = time.time()
+ print('elapsed time: %f' % (time.time() - startTime))
+ print('data rates (bytes/sec): out: %f, in: %f, total: %f' % (outRate, inRate, usbRate))
+
+ bytesOut = 0
+ bytesIn = 0
+
+ i += 1
+ #if (i > 2): break
+