aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lorenz@px4.io>2015-03-15 12:50:32 +0100
committerLorenz Meier <lorenz@px4.io>2015-03-15 12:50:32 +0100
commitb73ea032448d5be5b403fd7fd767be1b75c5d1e0 (patch)
tree6ce3f9bbaac5fb16d4bf60e4fc8a4e4fc540ad4e
parent2d8908ad01cc75fd7fdcd3bc2c94c6d398322662 (diff)
parent9d8931328b1c4423f747c08d115aec1387d5e597 (diff)
downloadpx4-firmware-b73ea032448d5be5b403fd7fd767be1b75c5d1e0.tar.gz
px4-firmware-b73ea032448d5be5b403fd7fd767be1b75c5d1e0.tar.bz2
px4-firmware-b73ea032448d5be5b403fd7fd767be1b75c5d1e0.zip
Merge pull request #1917 from tridge/pullrequest-boot-delay
Pullrequest boot delay
-rwxr-xr-xTools/boot_now.py59
-rwxr-xr-xTools/px_uploader.py11
-rw-r--r--nuttx-configs/px4fmu-v2/scripts/ld.script8
3 files changed, 78 insertions, 0 deletions
diff --git a/Tools/boot_now.py b/Tools/boot_now.py
new file mode 100755
index 000000000..5a9e608da
--- /dev/null
+++ b/Tools/boot_now.py
@@ -0,0 +1,59 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2012-2015 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name PX4 nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# send BOOT command to a device
+
+import argparse
+import serial, sys
+
+from sys import platform as _platform
+
+# Parse commandline arguments
+parser = argparse.ArgumentParser(description="Send boot command to a device")
+parser.add_argument('--baud', action="store", type=int, default=115200, help="Baud rate of the serial port")
+parser.add_argument('port', action="store", help="Serial port(s) to which the FMU may be attached")
+args = parser.parse_args()
+
+REBOOT = b'\x30'
+EOC = b'\x20'
+
+print("Sending reboot to %s" % args.port)
+try:
+ port = serial.Serial(args.port, args.baud, timeout=0.5)
+except Exception:
+ print("Unable to open %s" % args.port)
+ sys.exit(1)
+port.write(REBOOT + EOC)
+port.close()
+sys.exit(0)
diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py
index 43a116745..3cdd9d1a6 100755
--- a/Tools/px_uploader.py
+++ b/Tools/px_uploader.py
@@ -161,6 +161,7 @@ class uploader(object):
GET_OTP = b'\x2a' # rev4+ , get a word from OTP area
GET_SN = b'\x2b' # rev4+ , get a word from SN area
GET_CHIP = b'\x2c' # rev5+ , get chip version
+ SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
REBOOT = b'\x30'
INFO_BL_REV = b'\x01' # bootloader protocol revision
@@ -405,6 +406,12 @@ class uploader(object):
raise RuntimeError("Program CRC failed")
self.__drawProgressBar(label, 100, 100)
+ def __set_boot_delay(self, boot_delay):
+ self.__send(uploader.SET_BOOT_DELAY
+ + struct.pack("b", boot_delay)
+ + uploader.EOC)
+ self.__getSync()
+
# get basic data about the board
def identify(self):
# make sure we are in sync before starting
@@ -472,6 +479,9 @@ class uploader(object):
else:
self.__verify_v3("Verify ", fw)
+ if args.boot_delay is not None:
+ self.__set_boot_delay(args.boot_delay)
+
print("\nRebooting.\n")
self.__reboot()
self.port.close()
@@ -501,6 +511,7 @@ parser = argparse.ArgumentParser(description="Firmware uploader for the PX autop
parser.add_argument('--port', action="store", required=True, help="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('--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('firmware', action="store", help="Firmware file to be uploaded")
args = parser.parse_args()
diff --git a/nuttx-configs/px4fmu-v2/scripts/ld.script b/nuttx-configs/px4fmu-v2/scripts/ld.script
index bec896d1c..b04ad89a6 100644
--- a/nuttx-configs/px4fmu-v2/scripts/ld.script
+++ b/nuttx-configs/px4fmu-v2/scripts/ld.script
@@ -66,12 +66,20 @@ EXTERN(_vectors) /* force the vectors to be included in the output */
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
+EXTERN(_bootdelay_signature)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
+ . = ALIGN(32);
+ /*
+ This signature provides the bootloader with a way to delay booting
+ */
+ _bootdelay_signature = ABSOLUTE(.);
+ FILL(0xffecc2925d7d05c5)
+ . += 8;
*(.text .text.*)
*(.fixup)
*(.gnu.warning)