aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorAndrew Tridgell <tridge@samba.org>2013-12-13 12:44:11 +1100
committerLorenz Meier <lm@inf.ethz.ch>2013-12-13 11:22:14 +0100
commit5b7d1af5d83554d3119e3e0669d6429fc1aef262 (patch)
treee037d7a7db1d4646a7c2c6463b378550327a6c4f /src/modules
parent6016fbe55d3fd402012168b5a704a550bcfc4d28 (diff)
downloadpx4-firmware-5b7d1af5d83554d3119e3e0669d6429fc1aef262.tar.gz
px4-firmware-5b7d1af5d83554d3119e3e0669d6429fc1aef262.tar.bz2
px4-firmware-5b7d1af5d83554d3119e3e0669d6429fc1aef262.zip
Merged crccheck command
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/px4iofirmware/protocol.h2
-rw-r--r--src/modules/px4iofirmware/px4io.c20
-rw-r--r--src/modules/px4iofirmware/registers.c1
3 files changed, 23 insertions, 0 deletions
diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h
index 2856bdea4..cffabbb45 100644
--- a/src/modules/px4iofirmware/protocol.h
+++ b/src/modules/px4iofirmware/protocol.h
@@ -189,6 +189,8 @@ enum { /* DSM bind states */
#define PX4IO_P_SETUP_REBOOT_BL 10 /* reboot IO into bootloader */
#define PX4IO_REBOOT_BL_MAGIC 14662 /* required argument for reboot (random) */
+#define PX4IO_P_SETUP_CRC 11 /* get CRC of IO firmware */
+
/* autopilot control values, -10000..10000 */
#define PX4IO_PAGE_CONTROLS 51 /* 0..CONFIG_CONTROL_COUNT */
diff --git a/src/modules/px4iofirmware/px4io.c b/src/modules/px4iofirmware/px4io.c
index cd9bd197b..745bd5705 100644
--- a/src/modules/px4iofirmware/px4io.c
+++ b/src/modules/px4iofirmware/px4io.c
@@ -45,6 +45,7 @@
#include <string.h>
#include <poll.h>
#include <signal.h>
+#include <crc32.h>
#include <drivers/drv_pwm_output.h>
#include <drivers/drv_hrt.h>
@@ -124,6 +125,22 @@ heartbeat_blink(void)
LED_BLUE(heartbeat = !heartbeat);
}
+
+static void
+calculate_fw_crc(void)
+{
+#define APP_SIZE_MAX 0xf000
+#define APP_LOAD_ADDRESS 0x08001000
+ // compute CRC of the current firmware
+ uint32_t sum = 0;
+ for (unsigned p = 0; p < APP_SIZE_MAX; p += 4) {
+ uint32_t bytes = *(uint32_t *)(p + APP_LOAD_ADDRESS);
+ sum = crc32part((uint8_t *)&bytes, sizeof(bytes), sum);
+ }
+ r_page_setup[PX4IO_P_SETUP_CRC] = sum & 0xFFFF;
+ r_page_setup[PX4IO_P_SETUP_CRC+1] = sum >> 16;
+}
+
int
user_start(int argc, char *argv[])
{
@@ -136,6 +153,9 @@ user_start(int argc, char *argv[])
/* configure the high-resolution time/callout interface */
hrt_init();
+ /* calculate our fw CRC so FMU can decide if we need to update */
+ calculate_fw_crc();
+
/*
* Poll at 1ms intervals for received bytes that have not triggered
* a DMA event.
diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c
index 6785e5366..1a8519aec 100644
--- a/src/modules/px4iofirmware/registers.c
+++ b/src/modules/px4iofirmware/registers.c
@@ -157,6 +157,7 @@ volatile uint16_t r_page_setup[] =
#endif
[PX4IO_P_SETUP_SET_DEBUG] = 0,
[PX4IO_P_SETUP_REBOOT_BL] = 0,
+ [PX4IO_P_SETUP_CRC ... (PX4IO_P_SETUP_CRC+1)] = 0,
};
#define PX4IO_P_SETUP_FEATURES_VALID (0)