aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds
diff options
context:
space:
mode:
Diffstat (limited to 'src/systemcmds')
-rw-r--r--src/systemcmds/hw_ver/hw_ver.c73
-rw-r--r--src/systemcmds/hw_ver/module.mk43
-rw-r--r--src/systemcmds/tests/test_mtd.c35
-rw-r--r--src/systemcmds/tests/test_rc.c2
-rw-r--r--src/systemcmds/tests/tests.h2
5 files changed, 147 insertions, 8 deletions
diff --git a/src/systemcmds/hw_ver/hw_ver.c b/src/systemcmds/hw_ver/hw_ver.c
new file mode 100644
index 000000000..4b84523cc
--- /dev/null
+++ b/src/systemcmds/hw_ver/hw_ver.c
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * 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 hw_ver.c
+ *
+ * Show and test hardware version.
+ */
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <string.h>
+#include <errno.h>
+#include <version/version.h>
+
+__EXPORT int hw_ver_main(int argc, char *argv[]);
+
+int
+hw_ver_main(int argc, char *argv[])
+{
+ if (argc >= 2) {
+ if (!strcmp(argv[1], "show")) {
+ printf(HW_ARCH "\n");
+ exit(0);
+ }
+
+ if (!strcmp(argv[1], "compare")) {
+ if (argc >= 3) {
+ int ret = strcmp(HW_ARCH, argv[2]) != 0;
+ if (ret == 0) {
+ printf("hw_ver match: %s\n", HW_ARCH);
+ }
+ exit(ret);
+
+ } else {
+ errx(1, "not enough arguments, try 'compare PX4FMU_1'");
+ }
+ }
+ }
+
+ errx(1, "expected a command, try 'show' or 'compare'");
+}
diff --git a/src/systemcmds/hw_ver/module.mk b/src/systemcmds/hw_ver/module.mk
new file mode 100644
index 000000000..3cc08b6a1
--- /dev/null
+++ b/src/systemcmds/hw_ver/module.mk
@@ -0,0 +1,43 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# Show and test hardware version
+#
+
+MODULE_COMMAND = hw_ver
+SRCS = hw_ver.c
+
+MODULE_STACKSIZE = 1024
+
+MAXOPTIMIZATION = -Os
diff --git a/src/systemcmds/tests/test_mtd.c b/src/systemcmds/tests/test_mtd.c
index 8a626b65c..bac9efbdb 100644
--- a/src/systemcmds/tests/test_mtd.c
+++ b/src/systemcmds/tests/test_mtd.c
@@ -90,6 +90,16 @@ int check_user_abort(int fd) {
return 1;
}
+void print_fail()
+{
+ printf("<[T]: MTD: FAIL>\n");
+}
+
+void print_success()
+{
+ printf("<[T]: MTD: OK>\n");
+}
+
int
test_mtd(int argc, char *argv[])
{
@@ -99,6 +109,7 @@ test_mtd(int argc, char *argv[])
struct stat buffer;
if (stat(PARAM_FILE_NAME, &buffer)) {
warnx("file %s not found, aborting MTD test", PARAM_FILE_NAME);
+ print_fail();
return 1;
}
@@ -123,9 +134,17 @@ test_mtd(int argc, char *argv[])
uint8_t read_buf[chunk_sizes[c]] __attribute__((aligned(64)));
hrt_abstime start, end;
- int fd = open(PARAM_FILE_NAME, O_WRONLY);
+ int fd = open(PARAM_FILE_NAME, O_RDONLY);
+ int rret = read(fd, read_buf, chunk_sizes[c]);
+ close(fd);
- warnx("testing unaligned writes - please wait..");
+ fd = open(PARAM_FILE_NAME, O_WRONLY);
+
+ printf("printing 2 percent of the first chunk:\n");
+ for (int i = 0; i < sizeof(read_buf) / 50; i++) {
+ printf("%02X", read_buf[i]);
+ }
+ printf("\n");
iterations = file_size / chunk_sizes[c];
@@ -133,9 +152,9 @@ test_mtd(int argc, char *argv[])
for (unsigned i = 0; i < iterations; i++) {
int wret = write(fd, write_buf, chunk_sizes[c]);
- if (wret != chunk_sizes[c]) {
+ if (wret != (int)chunk_sizes[c]) {
warn("WRITE ERROR!");
-
+ print_fail();
return 1;
}
@@ -156,6 +175,7 @@ test_mtd(int argc, char *argv[])
if (rret != chunk_sizes[c]) {
warnx("READ ERROR!");
+ print_fail();
return 1;
}
@@ -165,6 +185,7 @@ test_mtd(int argc, char *argv[])
for (int j = 0; j < chunk_sizes[c]; j++) {
if (read_buf[j] != write_buf[j]) {
warnx("COMPARISON ERROR: byte %d", j);
+ print_fail();
compare_ok = false;
break;
}
@@ -172,6 +193,7 @@ test_mtd(int argc, char *argv[])
if (!compare_ok) {
warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
+ print_fail();
return 1;
}
@@ -183,7 +205,6 @@ test_mtd(int argc, char *argv[])
close(fd);
- printf("RESULT: OK! No readback errors.\n\n");
}
/* fill the file with 0xFF to make it look new again */
@@ -193,14 +214,16 @@ test_mtd(int argc, char *argv[])
for (int i = 0; i < file_size / sizeof(ffbuf); i++) {
int ret = write(fd, ffbuf, sizeof(ffbuf));
- if (ret) {
+ if (ret != sizeof(ffbuf)) {
warnx("ERROR! Could not fill file with 0xFF");
close(fd);
+ print_fail();
return 1;
}
}
(void)close(fd);
+ print_success();
return 0;
}
diff --git a/src/systemcmds/tests/test_rc.c b/src/systemcmds/tests/test_rc.c
index 6a602ecfc..57c0e7f4c 100644
--- a/src/systemcmds/tests/test_rc.c
+++ b/src/systemcmds/tests/test_rc.c
@@ -121,7 +121,7 @@ int test_rc(int argc, char *argv[])
return ERROR;
}
- if (hrt_absolute_time() - rc_input.timestamp > 100000) {
+ if (hrt_absolute_time() - rc_input.timestamp_last_signal > 100000) {
warnx("TIMEOUT, less than 10 Hz updates");
(void)close(_rc_sub);
return ERROR;
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index 223edc14a..82de05dff 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+ * Copyright (c) 2012-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