aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAndrew Tridgell <tridge@samba.org>2013-12-13 11:30:07 +1100
committerLorenz Meier <lm@inf.ethz.ch>2013-12-13 11:21:00 +0100
commit6016fbe55d3fd402012168b5a704a550bcfc4d28 (patch)
tree66434a0cec21b472b0aa9792e2e49cec8ef52335 /src/modules
parent8f90efa312b4bccbacb9e9173e2cba7d7b4bc193 (diff)
downloadpx4-firmware-6016fbe55d3fd402012168b5a704a550bcfc4d28.tar.gz
px4-firmware-6016fbe55d3fd402012168b5a704a550bcfc4d28.tar.bz2
px4-firmware-6016fbe55d3fd402012168b5a704a550bcfc4d28.zip
Merged PX4IO crc checks and force update
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/px4iofirmware/protocol.h3
-rw-r--r--src/modules/px4iofirmware/registers.c26
2 files changed, 29 insertions, 0 deletions
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 5e5396782..2856bdea4 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -186,6 +186,9 @@ enum { /* DSM bind states */
/* 8 */
#define PX4IO_P_SETUP_SET_DEBUG 9 /* debug level for IO board */
+#define PX4IO_P_SETUP_REBOOT_BL 10 /* reboot IO into bootloader */
+#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
+
/* autopilot control values, -10000..10000 */
#define PX4IO_PAGE_CONTROLS 51 /* 0..CONFIG_CONTROL_COUNT */
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 86a40bc22..6785e5366 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -45,6 +45,8 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_pwm_output.h>
+#include <systemlib/systemlib.h>
+#include <stm32_pwr.h>
#include "px4io.h"
#include "protocol.h"
@@ -154,6 +156,7 @@ volatile uint16_t r_page_setup[] =
[PX4IO_P_SETUP_VBATT_SCALE] = 10000,
#endif
[PX4IO_P_SETUP_SET_DEBUG] = 0,
+ [PX4IO_P_SETUP_REBOOT_BL] = 0,
};
#define PX4IO_P_SETUP_FEATURES_VALID (0)
@@ -501,6 +504,29 @@ registers_set_one(uint8_t page, uint8_t offset, uint16_t value)
isr_debug(0, "set debug %u\n", (unsigned)r_page_setup[PX4IO_P_SETUP_SET_DEBUG]);
break;
+ case PX4IO_P_SETUP_REBOOT_BL:
+ if ((r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) ||
+ (r_status_flags & PX4IO_P_STATUS_FLAGS_OVERRIDE) ||
+ (r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)) {
+ // don't allow reboot while armed
+ break;
+ }
+
+ // check the magic value
+ if (value != PX4IO_REBOOT_BL_MAGIC)
+ break;
+
+ // note that we don't set BL_WAIT_MAGIC in
+ // BKP_DR1 as that is not necessary given the
+ // timing of the forceupdate command. The
+ // bootloader on px4io waits for enough time
+ // anyway, and this method works with older
+ // bootloader versions (tested with both
+ // revision 3 and revision 4).
+
+ up_systemreset();
+ break;
+
case PX4IO_P_SETUP_DSM:
dsm_bind(value & 0x0f, (value >> 4) & 7);
break;