aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/modules/systemlib/mcu_version.c109
-rw-r--r--src/modules/systemlib/mcu_version.h52
-rw-r--r--src/modules/systemlib/module.mk4
-rw-r--r--src/systemcmds/ver/ver.c88
4 files changed, 179 insertions, 74 deletions
diff --git a/src/modules/systemlib/mcu_version.c b/src/modules/systemlib/mcu_version.c
new file mode 100644
index 000000000..4bcf95784
--- /dev/null
+++ b/src/modules/systemlib/mcu_version.c
@@ -0,0 +1,109 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mcu_version.c
+ *
+ * Read out the microcontroller version from the board
+ *
+ * @author Lorenz Meier <lorenz@px4.io>
+ *
+ */
+
+#include "mcu_version.h"
+
+#include <nuttx/config.h>
+
+#ifdef CONFIG_ARCH_CHIP_STM32
+#include <up_arch.h>
+
+#define DBGMCU_IDCODE 0xE0042000
+
+#define STM32F40x_41x 0x413
+#define STM32F42x_43x 0x419
+
+#define REVID_MASK 0xFFFF0000
+#define DEVID_MASK 0xFFF
+
+#endif
+
+
+
+int mcu_version(char* rev, char** revstr)
+{
+#ifdef CONFIG_ARCH_CHIP_STM32
+ uint32_t abc = getreg32(DBGMCU_IDCODE);
+
+ int32_t chip_version = abc & DEVID_MASK;
+ enum MCU_REV revid = (abc & REVID_MASK) >> 16;
+
+ switch (chip_version) {
+ case STM32F40x_41x:
+ *revstr = "STM32F40x";
+ break;
+ case STM32F42x_43x:
+ *revstr = "STM32F42x";
+ break;
+ default:
+ *revstr = "STM32F???";
+ break;
+ }
+
+ switch (revid) {
+
+ case MCU_REV_STM32F4_REV_A:
+ *rev = 'A';
+ break;
+ case MCU_REV_STM32F4_REV_Z:
+ *rev = 'Z';
+ break;
+ case MCU_REV_STM32F4_REV_Y:
+ *rev = 'Y';
+ break;
+ case MCU_REV_STM32F4_REV_1:
+ *rev = '1';
+ break;
+ case MCU_REV_STM32F4_REV_3:
+ *rev = '3';
+ break;
+ default:
+ *rev = '?';
+ revid = -1;
+ break;
+ }
+
+ return revid;
+#else
+ return -1;
+#endif
+}
diff --git a/src/modules/systemlib/mcu_version.h b/src/modules/systemlib/mcu_version.h
new file mode 100644
index 000000000..1b3d0aba9
--- /dev/null
+++ b/src/modules/systemlib/mcu_version.h
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+/* magic numbers from reference manual */
+enum MCU_REV {
+ MCU_REV_STM32F4_REV_A = 0x1000,
+ MCU_REV_STM32F4_REV_Z = 0x1001,
+ MCU_REV_STM32F4_REV_Y = 0x1003,
+ MCU_REV_STM32F4_REV_1 = 0x1007,
+ MCU_REV_STM32F4_REV_3 = 0x2001
+};
+
+/**
+ * Reports the microcontroller version of the main CPU.
+ *
+ * @param rev The silicon revision character
+ * @param revstr The full chip name string
+ * @return The silicon revision / version number as integer
+ */
+__EXPORT int mcu_version(char* rev, char** revstr);
diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk
index 147903aa0..233023e25 100644
--- a/src/modules/systemlib/module.mk
+++ b/src/modules/systemlib/module.mk
@@ -53,5 +53,5 @@ SRCS = err.c \
otp.c \
board_serial.c \
pwm_limit/pwm_limit.c \
- circuit_breaker.c
-
+ circuit_breaker.c \
+ mcu_version.c
diff --git a/src/systemcmds/ver/ver.c b/src/systemcmds/ver/ver.c
index 9d308bc3e..62a7a5b92 100644
--- a/src/systemcmds/ver/ver.c
+++ b/src/systemcmds/ver/ver.c
@@ -44,6 +44,7 @@
#include <string.h>
#include <version/version.h>
#include <systemlib/err.h>
+#include <systemlib/mcu_version.h>
// string constants for version commands
static const char sz_ver_hw_str[] = "hw";
@@ -52,32 +53,8 @@ static const char sz_ver_git_str[] = "git";
static const char sz_ver_bdate_str[] = "bdate";
static const char sz_ver_gcc_str[] = "gcc";
static const char sz_ver_all_str[] = "all";
-
-#ifdef CONFIG_ARCH_CHIP_STM32
-#include <up_arch.h>
-
static const char mcu_ver_str[] = "mcu";
-#define DBGMCU_IDCODE 0xE0042000
-
-#define STM32F40x_41x 0x413
-#define STM32F42x_43x 0x419
-
-#define REVID_MASK 0xFFFF0000
-#define DEVID_MASK 0xFFF
-
-/* magic numbers from reference manual */
-enum STM32F4_REV {
- STM32F4_REV_A = 0x1000,
- STM32F4_REV_Z = 0x1001,
- STM32F4_REV_Y = 0x1003,
- STM32F4_REV_1 = 0x1007,
- STM32F4_REV_3 = 0x2001
-};
-#else
-#error stm32
-#endif
-
static void usage(const char *reason)
{
if (reason != NULL) {
@@ -132,61 +109,28 @@ int ver_main(int argc, char *argv[])
printf("GCC toolchain: %s\n", __VERSION__);
ret = 0;
-#ifdef CONFIG_ARCH_CHIP_STM32
+
} else if (!strncmp(argv[1], mcu_ver_str, sizeof(mcu_ver_str))) {
- uint32_t abc = getreg32(DBGMCU_IDCODE);
-
- uint32_t chip_version = abc & DEVID_MASK;
- enum STM32F4_REV revid = (abc & REVID_MASK) >> 16;
-
- printf("CHIP TYPE: ");
-
- switch (revid) {
- case STM32F40x_41x:
- printf("STM32F40x");
- break;
- case STM32F42x_43x:
- printf("STM32F42x");
- break;
- default:
- printf("STM32F???");
- break;
- }
char rev;
+ char* revstr;
- switch (chip_version) {
-
- case STM32F4_REV_A:
- rev = 'A';
- break;
- case STM32F4_REV_Z:
- rev = 'Z';
- break;
- case STM32F4_REV_Y:
- rev = 'Y';
- break;
- case STM32F4_REV_1:
- rev = '1';
- break;
- case STM32F4_REV_3:
- rev = '3';
- break;
- default:
- rev = '?';
- break;
- }
+ int chip_version = mcu_version(&rev, &revstr);
+
+ if (chip_version < 0) {
+ printf("UNKNOWN MCU");
+ ret = 1;
- printf("\nHW REV: %c\n", rev);
+ } else {
+ printf("MCU: %s, rev. %c\n", revstr, rev);
- if (rev < STM32F4_REV_3) {
- printf("\n\nWARNING WARNING WARNING!\n"
- "Revision %c has a silicon errata\n"
- "This device can only utilize a maximum of 1MB flash safely!\n"
- "http://px4.io/help/errata\n", rev);
+ if (chip_version < MCU_REV_STM32F4_REV_3) {
+ printf("\n\nWARNING WARNING WARNING!\n"
+ "Revision %c has a silicon errata\n"
+ "This device can only utilize a maximum of 1MB flash safely!\n"
+ "http://px4.io/help/errata\n", rev);
+ }
}
- ret = 0;
-#endif
} else {
errx(1, "unknown command.\n");