From e7c1e8e94b082a0ba5b22b2f449844ee9a76a50a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 4 Jan 2014 13:53:59 +0100 Subject: Added tests for mount / fsync / reboot --- src/systemcmds/tests/module.mk | 3 +- src/systemcmds/tests/test_mount.c | 232 ++++++++++++++++++++++++++++++++++++++ src/systemcmds/tests/tests.h | 1 + src/systemcmds/tests/tests_main.c | 1 + 4 files changed, 236 insertions(+), 1 deletion(-) create mode 100644 src/systemcmds/tests/test_mount.c (limited to 'src') diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk index 68a080c77..28e214a6c 100644 --- a/src/systemcmds/tests/module.mk +++ b/src/systemcmds/tests/module.mk @@ -28,4 +28,5 @@ SRCS = test_adc.c \ tests_main.c \ test_param.c \ test_ppm_loopback.c \ - test_rc.c + test_rc.c \ + test_mount.c diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c new file mode 100644 index 000000000..bef953d11 --- /dev/null +++ b/src/systemcmds/tests/test_mount.c @@ -0,0 +1,232 @@ +/**************************************************************************** + * + * 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 + * 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 test_mount.c + * + * Device mount / unmount stress test + * + * @author Lorenz Meier + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include "tests.h" + +int +test_mount(int argc, char *argv[]) +{ + const unsigned iterations = 100; + const unsigned alignments = 65; + + /* check if microSD card is mounted */ + struct stat buffer; + if (stat("/fs/microsd/", &buffer)) { + warnx("no microSD card mounted, aborting file test"); + return 1; + } + + /* read current test status from file, write test instructions for next round */ + const char* cmd_filename = "/fs/microsd/mount_test_cmds"; + + /* initial values */ + int it_left_fsync = 100; + int it_left_abort = 100; + + int cmd_fd; + if (stat(cmd_filename, &buffer)) { + + /* command file exists, read off state */ + cmd_fd = open(cmd_filename, O_RDWR); + char buf[64]; + int ret = read(cmd_fd, buf, sizeof(buf)); + if (ret > 0) + ret = sscanf("%d %d", &it_left_fsync, &it_left_abort); + + warnx("Iterations left: #%d / #%d\n(%s)", it_left_fsync, it_left_abort, buf); + + /* now write again what to do next */ + if (it_left_fsync > 0) + it_left_fsync--; + if (it_left_fsync == 0 && it_left_abort > 0) + it_left_abort--; + + if (it_left_abort == 0) + (void)unlink(cmd_filename); + return 0; + + } else { + + /* this must be the first iteration, do something */ + cmd_fd = open(cmd_filename, O_TRUNC | O_WRONLY | O_CREAT); + } + + char buf[64]; + sprintf(buf, "%d %d", it_left_fsync, it_left_abort); + write(cmd_fd, buf, strlen(buf) + 1); + + /* perform tests for a range of chunk sizes */ + unsigned chunk_sizes[] = {1, 5, 8, 13, 16, 32}; + + for (unsigned c = 0; c < (sizeof(chunk_sizes) / sizeof(chunk_sizes[0])); c++) { + + printf("\n====== FILE TEST: %u bytes chunks ======\n", chunk_sizes[c]); + + for (unsigned a = 0; a < alignments; a++) { + + printf("\n"); + warnx("----- alignment test: %u bytes -----", a); + + uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); + + /* fill write buffer with known values */ + for (int i = 0; i < sizeof(write_buf); i++) { + /* this will wrap, but we just need a known value with spacing */ + write_buf[i] = i+11; + } + + uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); + hrt_abstime start, end; + //perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes (aligned)"); + + int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); + + warnx("testing unaligned writes - please wait.."); + + start = hrt_absolute_time(); + for (unsigned i = 0; i < iterations; i++) { + //perf_begin(wperf); + int wret = write(fd, write_buf + a, chunk_sizes[c]); + + if (wret != chunk_sizes[c]) { + warn("WRITE ERROR!"); + + if ((0x3 & (uintptr_t)(write_buf + a))) + errx(1, "memory is unaligned, align shift: %d", a); + + } + + if (it_left_fsync > 0) { + fsync(fd); + } else { + if (it_left_abort % chunk_sizes[c] == 0) { + systemreset(); + } + } + //perf_end(wperf); + + } + end = hrt_absolute_time(); + + //warnx("%dKiB in %llu microseconds", iterations / 2, end - start); + + //perf_print_counter(wperf); + //perf_free(wperf); + + close(fd); + fd = open("/fs/microsd/testfile", O_RDONLY); + + /* read back data for validation */ + for (unsigned i = 0; i < iterations; i++) { + int rret = read(fd, read_buf, chunk_sizes[c]); + + if (rret != chunk_sizes[c]) { + warnx("READ ERROR!"); + return 1; + } + + /* compare value */ + bool compare_ok = true; + + for (int j = 0; j < chunk_sizes[c]; j++) { + if (read_buf[j] != write_buf[j + a]) { + warnx("COMPARISON ERROR: byte %d, align shift: %d", j, a); + compare_ok = false; + break; + } + } + + if (!compare_ok) { + warnx("ABORTING FURTHER COMPARISON DUE TO ERROR"); + return 1; + } + + } + + int ret = unlink("/fs/microsd/testfile"); + close(fd); + + if (ret) { + warnx("UNLINKING FILE FAILED"); + return 1; + } + + } + } + + /* list directory */ + DIR *d; + struct dirent *dir; + d = opendir("/fs/microsd"); + if (d) { + + while ((dir = readdir(d)) != NULL) { + //printf("%s\n", dir->d_name); + } + + closedir(d); + + warnx("directory listing ok (FS mounted and readable)"); + + } else { + /* failed opening dir */ + warnx("FAILED LISTING MICROSD ROOT DIRECTORY"); + return 1; + } + + /* we always reboot for the next test if we get here */ + systemreset(); + + /* never going to get here */ + return 0; +} diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h index a57d04be3..bec13bd30 100644 --- a/src/systemcmds/tests/tests.h +++ b/src/systemcmds/tests/tests.h @@ -109,6 +109,7 @@ extern int test_bson(int argc, char *argv[]); extern int test_file(int argc, char *argv[]); extern int test_mixer(int argc, char *argv[]); extern int test_rc(int argc, char *argv[]); +extern int test_mount(int argc, char *argv[]); __END_DECLS diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c index 1088a4407..84535126f 100644 --- a/src/systemcmds/tests/tests_main.c +++ b/src/systemcmds/tests/tests_main.c @@ -106,6 +106,7 @@ const struct { {"file", test_file, 0}, {"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST}, {"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST}, + {"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST}, {"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST}, {NULL, NULL, 0} }; -- cgit v1.2.3 From 7590d91cf24d7fdd9bc0167958eba16cf584c67c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 4 Jan 2014 17:05:52 +0100 Subject: Improved mount test --- ROMFS/px4fmu_test/init.d/rcS | 44 ++++++++++- makefiles/config_px4fmu-v2_test.mk | 4 + src/systemcmds/tests/test_file.c | 71 +----------------- src/systemcmds/tests/test_mount.c | 148 +++++++++++++++++++++++++------------ 4 files changed, 149 insertions(+), 118 deletions(-) (limited to 'src') diff --git a/ROMFS/px4fmu_test/init.d/rcS b/ROMFS/px4fmu_test/init.d/rcS index d8ed71f12..56482d140 100644 --- a/ROMFS/px4fmu_test/init.d/rcS +++ b/ROMFS/px4fmu_test/init.d/rcS @@ -2,6 +2,7 @@ # # PX4FMU startup script for test hackery. # +uorb start if sercon then @@ -26,10 +27,51 @@ else tone_alarm error fi +# +# Start a minimal system +# + +if [ -f /etc/extras/px4io-v2_default.bin ] +then + set io_file /etc/extras/px4io-v2_default.bin +else + set io_file /etc/extras/px4io-v1_default.bin +fi + +if px4io start +then + echo "PX4IO OK" +fi + +if px4io checkcrc $io_file +then + echo "PX4IO CRC OK" +else + echo "PX4IO CRC failure" + tone_alarm MBABGP + if px4io forceupdate 14662 $io_file + then + usleep 500000 + if px4io start + then + echo "PX4IO restart OK" + tone_alarm MSPAA + else + echo "PX4IO restart failed" + tone_alarm MNGGG + sleep 5 + reboot + fi + else + echo "PX4IO update failed" + tone_alarm MNGGG + fi +fi + # # The presence of this file suggests we're running a mount stress test # -if [ -f /fs/microsd/mount_test_cmds ] +if [ -f /fs/microsd/mount_test_cmds.txt ] then tests mount fi diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk index 3139a0db4..6faef7e0a 100644 --- a/makefiles/config_px4fmu-v2_test.mk +++ b/makefiles/config_px4fmu-v2_test.mk @@ -6,14 +6,18 @@ # Use the configuration's ROMFS. # ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test +ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v2_default.bin # # Board support modules # MODULES += drivers/device MODULES += drivers/stm32 +MODULES += drivers/stm32/adc +MODULES += drivers/stm32/tone_alarm MODULES += drivers/led MODULES += drivers/boards/px4fmu-v2 +MODULES += drivers/px4io MODULES += systemcmds/perf MODULES += systemcmds/reboot MODULES += systemcmds/tests diff --git a/src/systemcmds/tests/test_file.c b/src/systemcmds/tests/test_file.c index 798724cf1..4ca84f276 100644 --- a/src/systemcmds/tests/test_file.c +++ b/src/systemcmds/tests/test_file.c @@ -103,6 +103,7 @@ test_file(int argc, char *argv[]) if ((0x3 & (uintptr_t)(write_buf + a))) errx(1, "memory is unaligned, align shift: %d", a); + return 1; } fsync(fd); @@ -139,7 +140,8 @@ test_file(int argc, char *argv[]) } if (!compare_ok) { - errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR"); + warnx("ABORTING FURTHER COMPARISON DUE TO ERROR"); + return 1; } } @@ -266,70 +268,3 @@ test_file(int argc, char *argv[]) return 0; } -#if 0 -int -test_file(int argc, char *argv[]) -{ - const iterations = 1024; - - /* check if microSD card is mounted */ - struct stat buffer; - if (stat("/fs/microsd/", &buffer)) { - warnx("no microSD card mounted, aborting file test"); - return 1; - } - - uint8_t buf[512]; - hrt_abstime start, end; - perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes"); - - int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); - memset(buf, 0, sizeof(buf)); - - start = hrt_absolute_time(); - for (unsigned i = 0; i < iterations; i++) { - perf_begin(wperf); - write(fd, buf, sizeof(buf)); - perf_end(wperf); - } - end = hrt_absolute_time(); - - close(fd); - - unlink("/fs/microsd/testfile"); - - warnx("%dKiB in %llu microseconds", iterations / 2, end - start); - perf_print_counter(wperf); - perf_free(wperf); - - warnx("running unlink test"); - - /* ensure that common commands do not run against file count limits */ - for (unsigned i = 0; i < 64; i++) { - - warnx("unlink iteration #%u", i); - - int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); - if (fd < 0) - errx(1, "failed opening test file before unlink()"); - int ret = write(fd, buf, sizeof(buf)); - if (ret < 0) - errx(1, "failed writing test file before unlink()"); - close(fd); - - ret = unlink("/fs/microsd/testfile"); - if (ret != OK) - errx(1, "failed unlinking test file"); - - fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); - if (fd < 0) - errx(1, "failed opening test file after unlink()"); - ret = write(fd, buf, sizeof(buf)); - if (ret < 0) - errx(1, "failed writing test file after unlink()"); - close(fd); - } - - return 0; -} -#endif diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c index bef953d11..2f3a0d99e 100644 --- a/src/systemcmds/tests/test_mount.c +++ b/src/systemcmds/tests/test_mount.c @@ -46,6 +46,7 @@ #include #include #include +#include #include #include @@ -53,11 +54,17 @@ #include "tests.h" +const int fsync_tries = 50; +const int abort_tries = 200; + int test_mount(int argc, char *argv[]) { - const unsigned iterations = 100; - const unsigned alignments = 65; + const unsigned iterations = 10; + const unsigned alignments = 4; + + const char* cmd_filename = "/fs/microsd/mount_test_cmds.txt"; + /* check if microSD card is mounted */ struct stat buffer; @@ -66,56 +73,114 @@ test_mount(int argc, char *argv[]) return 1; } + /* list directory */ + DIR *d; + struct dirent *dir; + d = opendir("/fs/microsd"); + if (d) { + + while ((dir = readdir(d)) != NULL) { + //printf("%s\n", dir->d_name); + } + + closedir(d); + + warnx("directory listing ok (FS mounted and readable)"); + + } else { + /* failed opening dir */ + warnx("FAILED LISTING MICROSD ROOT DIRECTORY"); + + if (stat(cmd_filename, &buffer) == OK) { + (void)unlink(cmd_filename); + } + + return 1; + } + /* read current test status from file, write test instructions for next round */ - const char* cmd_filename = "/fs/microsd/mount_test_cmds"; /* initial values */ - int it_left_fsync = 100; - int it_left_abort = 100; + int it_left_fsync = fsync_tries; + int it_left_abort = abort_tries; int cmd_fd; - if (stat(cmd_filename, &buffer)) { + if (stat(cmd_filename, &buffer) == OK) { /* command file exists, read off state */ - cmd_fd = open(cmd_filename, O_RDWR); + cmd_fd = open(cmd_filename, O_RDWR | O_NONBLOCK); char buf[64]; int ret = read(cmd_fd, buf, sizeof(buf)); - if (ret > 0) - ret = sscanf("%d %d", &it_left_fsync, &it_left_abort); - warnx("Iterations left: #%d / #%d\n(%s)", it_left_fsync, it_left_abort, buf); + if (ret > 0) { + int count = 0; + ret = sscanf(buf, "TEST: %u %u %n", &it_left_fsync, &it_left_abort, &count); + } else { + buf[0] = '\0'; + } + + if (it_left_fsync > fsync_tries) + it_left_fsync = fsync_tries; + + if (it_left_abort > abort_tries) + it_left_abort = abort_tries; + + warnx("Iterations left: #%d / #%d of %d / %d\n(%s)", it_left_fsync, it_left_abort, + fsync_tries, abort_tries, buf); + + int it_left_fsync_prev = it_left_fsync; /* now write again what to do next */ if (it_left_fsync > 0) it_left_fsync--; - if (it_left_fsync == 0 && it_left_abort > 0) + + if (it_left_fsync == 0 && it_left_abort > 0) { + it_left_abort--; - if (it_left_abort == 0) + /* announce mode switch */ + if (it_left_fsync_prev != it_left_fsync && it_left_fsync == 0) { + warnx("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC"); + fsync(stdout); + fsync(stderr); + usleep(20000); + } + + } + + if (it_left_abort == 0) { (void)unlink(cmd_filename); return 0; + } } else { /* this must be the first iteration, do something */ cmd_fd = open(cmd_filename, O_TRUNC | O_WRONLY | O_CREAT); + + warnx("First iteration of file test\n"); } char buf[64]; - sprintf(buf, "%d %d", it_left_fsync, it_left_abort); - write(cmd_fd, buf, strlen(buf) + 1); + int wret = sprintf(buf, "TEST: %d %d ", it_left_fsync, it_left_abort); + lseek(cmd_fd, 0, SEEK_SET); + write(cmd_fd, buf, strlen(buf) + 1); + fsync(cmd_fd); /* perform tests for a range of chunk sizes */ - unsigned chunk_sizes[] = {1, 5, 8, 13, 16, 32}; + unsigned chunk_sizes[] = {32, 64, 128, 256, 512, 600, 1200}; for (unsigned c = 0; c < (sizeof(chunk_sizes) / sizeof(chunk_sizes[0])); c++) { - printf("\n====== FILE TEST: %u bytes chunks ======\n", chunk_sizes[c]); + printf("\n\n====== FILE TEST: %u bytes chunks (%s) ======\n", chunk_sizes[c], (it_left_fsync > 0) ? "FSYNC" : "NO FSYNC"); + fsync(stdout); + fsync(stderr); + usleep(50000); for (unsigned a = 0; a < alignments; a++) { - printf("\n"); - warnx("----- alignment test: %u bytes -----", a); + // warnx("----- alignment test: %u bytes -----", a); + printf("."); uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); @@ -127,15 +192,12 @@ test_mount(int argc, char *argv[]) uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); hrt_abstime start, end; - //perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes (aligned)"); int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); - warnx("testing unaligned writes - please wait.."); - start = hrt_absolute_time(); for (unsigned i = 0; i < iterations; i++) { - //perf_begin(wperf); + int wret = write(fd, write_buf + a, chunk_sizes[c]); if (wret != chunk_sizes[c]) { @@ -144,25 +206,23 @@ test_mount(int argc, char *argv[]) if ((0x3 & (uintptr_t)(write_buf + a))) errx(1, "memory is unaligned, align shift: %d", a); + return 1; + } if (it_left_fsync > 0) { fsync(fd); } else { - if (it_left_abort % chunk_sizes[c] == 0) { - systemreset(); + if (it_left_abort % 5 == 0) { + systemreset(false); + } else { + fsync(stdout); + fsync(stderr); } } - //perf_end(wperf); - } end = hrt_absolute_time(); - //warnx("%dKiB in %llu microseconds", iterations / 2, end - start); - - //perf_print_counter(wperf); - //perf_free(wperf); - close(fd); fd = open("/fs/microsd/testfile", O_RDONLY); @@ -204,28 +264,18 @@ test_mount(int argc, char *argv[]) } } - /* list directory */ - DIR *d; - struct dirent *dir; - d = opendir("/fs/microsd"); - if (d) { - - while ((dir = readdir(d)) != NULL) { - //printf("%s\n", dir->d_name); - } - - closedir(d); + fsync(stdout); + fsync(stderr); + usleep(20000); - warnx("directory listing ok (FS mounted and readable)"); - } else { - /* failed opening dir */ - warnx("FAILED LISTING MICROSD ROOT DIRECTORY"); - return 1; - } /* we always reboot for the next test if we get here */ - systemreset(); + warnx("Iteration done, rebooting.."); + fsync(stdout); + fsync(stderr); + usleep(50000); + systemreset(false); /* never going to get here */ return 0; -- cgit v1.2.3 From 9886a384ff284722b65f61a6622669f86f1aa68f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 08:02:47 +0100 Subject: Fixed error handling logic, we want to return, not exit --- src/systemcmds/tests/test_file.c | 42 +++++++++++++++++++++------------------- 1 file changed, 22 insertions(+), 20 deletions(-) (limited to 'src') diff --git a/src/systemcmds/tests/test_file.c b/src/systemcmds/tests/test_file.c index 4ca84f276..419e8d5e9 100644 --- a/src/systemcmds/tests/test_file.c +++ b/src/systemcmds/tests/test_file.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 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 @@ -35,6 +35,8 @@ * @file test_file.c * * File write test. + * + * @author Lorenz Meier */ #include @@ -86,7 +88,6 @@ test_file(int argc, char *argv[]) uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); hrt_abstime start, end; - //perf_counter_t wperf = perf_alloc(PC_ELAPSED, "SD writes (aligned)"); int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); @@ -94,29 +95,22 @@ test_file(int argc, char *argv[]) start = hrt_absolute_time(); for (unsigned i = 0; i < iterations; i++) { - //perf_begin(wperf); int wret = write(fd, write_buf + a, chunk_sizes[c]); if (wret != chunk_sizes[c]) { warn("WRITE ERROR!"); if ((0x3 & (uintptr_t)(write_buf + a))) - errx(1, "memory is unaligned, align shift: %d", a); + warnx("memory is unaligned, align shift: %d", a); return 1; } fsync(fd); - //perf_end(wperf); } end = hrt_absolute_time(); - //warnx("%dKiB in %llu microseconds", iterations / 2, end - start); - - //perf_print_counter(wperf); - //perf_free(wperf); - close(fd); fd = open("/fs/microsd/testfile", O_RDONLY); @@ -125,7 +119,8 @@ test_file(int argc, char *argv[]) int rret = read(fd, read_buf, chunk_sizes[c]); if (rret != chunk_sizes[c]) { - errx(1, "READ ERROR!"); + warnx("READ ERROR!"); + return 1; } /* compare value */ @@ -161,7 +156,8 @@ test_file(int argc, char *argv[]) int wret = write(fd, write_buf, chunk_sizes[c]); if (wret != chunk_sizes[c]) { - err(1, "WRITE ERROR!"); + warnx("WRITE ERROR!"); + return 1; } } @@ -180,7 +176,8 @@ test_file(int argc, char *argv[]) int rret = read(fd, read_buf, chunk_sizes[c]); if (rret != chunk_sizes[c]) { - err(1, "READ ERROR!"); + warnx("READ ERROR!"); + return 1; } /* compare value */ @@ -195,7 +192,8 @@ test_file(int argc, char *argv[]) } if (!align_read_ok) { - errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR"); + warnx("ABORTING FURTHER COMPARISON DUE TO ERROR"); + return 1; } } @@ -217,7 +215,8 @@ test_file(int argc, char *argv[]) int rret = read(fd, read_buf + a, chunk_sizes[c]); if (rret != chunk_sizes[c]) { - err(1, "READ ERROR!"); + warnx("READ ERROR!"); + return 1; } for (int j = 0; j < chunk_sizes[c]; j++) { @@ -233,7 +232,8 @@ test_file(int argc, char *argv[]) } if (!unalign_read_ok) { - errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR"); + warnx("ABORTING FURTHER COMPARISON DUE TO ERROR"); + return 1; } } @@ -241,9 +241,10 @@ test_file(int argc, char *argv[]) ret = unlink("/fs/microsd/testfile"); close(fd); - if (ret) - err(1, "UNLINKING FILE FAILED"); - + if (ret) { + warnx("UNLINKING FILE FAILED"); + return 1; + } } } @@ -263,7 +264,8 @@ test_file(int argc, char *argv[]) } else { /* failed opening dir */ - err(1, "FAILED LISTING MICROSD ROOT DIRECTORY"); + warnx("FAILED LISTING MICROSD ROOT DIRECTORY"); + return 1; } return 0; -- cgit v1.2.3 From f35e6efbcaa5f9770ee4f6ef7686752b40c6a9ce Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 08:37:06 +0100 Subject: Check 30 seconds for USB port --- src/systemcmds/nshterm/nshterm.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) (limited to 'src') diff --git a/src/systemcmds/nshterm/nshterm.c b/src/systemcmds/nshterm/nshterm.c index 458bb2259..7d9484d3e 100644 --- a/src/systemcmds/nshterm/nshterm.c +++ b/src/systemcmds/nshterm/nshterm.c @@ -62,7 +62,9 @@ nshterm_main(int argc, char *argv[]) } uint8_t retries = 0; int fd = -1; - while (retries < 50) { + + /* try the first 30 seconds */ + while (retries < 300) { /* the retries are to cope with the behaviour of /dev/ttyACM0 */ /* which may not be ready immediately. */ fd = open(argv[1], O_RDWR); -- cgit v1.2.3 From 138b2890c4a874a82aff33df8e5ea37bd3a74e35 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 08:37:34 +0100 Subject: Better mount test, still not reproducing failure very well --- src/systemcmds/tests/test_mount.c | 31 +++++++++++++++++++------------ 1 file changed, 19 insertions(+), 12 deletions(-) (limited to 'src') diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c index 2f3a0d99e..db4ddeed9 100644 --- a/src/systemcmds/tests/test_mount.c +++ b/src/systemcmds/tests/test_mount.c @@ -54,14 +54,14 @@ #include "tests.h" -const int fsync_tries = 50; -const int abort_tries = 200; +const int fsync_tries = 1; +const int abort_tries = 10; int test_mount(int argc, char *argv[]) { - const unsigned iterations = 10; - const unsigned alignments = 4; + const unsigned iterations = 2000; + const unsigned alignments = 10; const char* cmd_filename = "/fs/microsd/mount_test_cmds.txt"; @@ -173,13 +173,13 @@ test_mount(int argc, char *argv[]) for (unsigned c = 0; c < (sizeof(chunk_sizes) / sizeof(chunk_sizes[0])); c++) { printf("\n\n====== FILE TEST: %u bytes chunks (%s) ======\n", chunk_sizes[c], (it_left_fsync > 0) ? "FSYNC" : "NO FSYNC"); + printf("unpower the system immediately (within 0.5s) when the hash (#) sign appears\n"); fsync(stdout); fsync(stderr); usleep(50000); for (unsigned a = 0; a < alignments; a++) { - // warnx("----- alignment test: %u bytes -----", a); printf("."); uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64))); @@ -204,7 +204,7 @@ test_mount(int argc, char *argv[]) warn("WRITE ERROR!"); if ((0x3 & (uintptr_t)(write_buf + a))) - errx(1, "memory is unaligned, align shift: %d", a); + warnx("memory is unaligned, align shift: %d", a); return 1; @@ -213,14 +213,21 @@ test_mount(int argc, char *argv[]) if (it_left_fsync > 0) { fsync(fd); } else { - if (it_left_abort % 5 == 0) { - systemreset(false); - } else { - fsync(stdout); - fsync(stderr); - } + printf("#"); + fsync(stdout); + fsync(stderr); } } + + if (it_left_fsync > 0) { + printf("#"); + } + + printf("\n"); + fsync(stdout); + fsync(stderr); + usleep(1000000); + end = hrt_absolute_time(); close(fd); -- cgit v1.2.3 From 4ef7817d965ec77c04acd4e4173bb6051e7d6836 Mon Sep 17 00:00:00 2001 From: Buzz Date: Fri, 27 Sep 2013 15:10:37 +1000 Subject: added otp library --- src/modules/systemlib/module.mk | 4 +- src/modules/systemlib/otp.c | 191 ++++++++++++++++++++++++++++++++++++++++ src/modules/systemlib/otp.h | 156 ++++++++++++++++++++++++++++++++ 3 files changed, 350 insertions(+), 1 deletion(-) create mode 100644 src/modules/systemlib/otp.c create mode 100644 src/modules/systemlib/otp.h (limited to 'src') diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk index 843cda722..1749ec9c7 100644 --- a/src/modules/systemlib/module.mk +++ b/src/modules/systemlib/module.mk @@ -49,4 +49,6 @@ SRCS = err.c \ airspeed.c \ system_params.c \ mavlink_log.c \ - rc_check.c + rc_check.c \ + otp.c + diff --git a/src/modules/systemlib/otp.c b/src/modules/systemlib/otp.c new file mode 100644 index 000000000..7968637de --- /dev/null +++ b/src/modules/systemlib/otp.c @@ -0,0 +1,191 @@ +/**************************************************************************** + * + * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. + * Authors: + * Lorenz Meier + * David "Buzz" Bussenschutt + * + * 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 otp.c + * otp estimation + * + * @author Lorenz Meier + * @author David "Buzz" Bussenschutt + * + */ + +#include +#include +#include +#include // memset +#include "conversions.h" +#include "otp.h" +#include "err.h" // warnx +#include + + +int val_read(void* dest, volatile const void* src, int bytes) +{ + + int i; + for (i = 0; i < bytes / 4; i++) { + *(((volatile uint32_t *)dest) + i) = *(((volatile uint32_t *)src) + i); + } + return i*4; +} + + +int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char* signature) +{ + + warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n",id_type, vid, pid); + + // descriptor + F_write_byte( ADDR_OTP_START, 'P'); // write the 'P' from PX4. to first byte in OTP + F_write_byte( ADDR_OTP_START+1, 'X'); // write the 'P' from PX4. to first byte in OTP + F_write_byte( ADDR_OTP_START+2, '4'); + F_write_byte( ADDR_OTP_START+3, '\0'); + //id_type + F_write_byte( ADDR_OTP_START+4, id_type); + // vid and pid are 4 bytes each + F_write_word( ADDR_OTP_START+5, vid); + F_write_word( ADDR_OTP_START+9, pid); + // leave some 19 bytes of space, and go to the next block... + // then the auth sig starts + for ( int i = 0 ; i < 128 ; i++ ) { + F_write_byte( ADDR_OTP_START+32+i, signature[i]); + } + + +} + +int lock_otp(void) +{ + //determine the required locking size - can only write full lock bytes */ +// int size = sizeof(struct otp) / 32; +// +// struct otp_lock otp_lock_mem; +// +// memset(&otp_lock_mem, OTP_LOCK_UNLOCKED, sizeof(otp_lock_mem)); +// for (int i = 0; i < sizeof(otp_lock_mem) / sizeof(otp_lock_mem.lock_bytes[0]); i++) +// otp_lock_mem.lock_bytes[i] = OTP_LOCK_LOCKED; + //XXX add the actual call here to write the OTP_LOCK bytes only at final stage + // val_copy(lock_ptr, &otp_lock_mem, sizeof(otp_lock_mem)); + + int locksize = 5; + // or just realise it's exctly 5x 32byte blocks we need to lock. 1 block for ID,type,vid,pid, and 4 blocks for certificate, which is 128 bytes. + for ( int i = 0 ; i < locksize ; i++ ) { + F_write_byte( ADDR_OTP_LOCK_START+i, OTP_LOCK_LOCKED); + } + +} + + + +// COMPLETE, BUSY, or other flash error? +uint8_t F_GetStatus(void) { + uint8_t fs = F_COMPLETE; + if((FLASH->status & F_BSY) == F_BSY) { fs = F_BUSY; } else { + if((FLASH->status & F_WRPERR) != (uint32_t)0x00) { fs = F_ERROR_WRP; } else { + if((FLASH->status & (uint32_t)0xEF) != (uint32_t)0x00) { fs = F_ERROR_PROGRAM; } else { + if((FLASH->status & F_OPERR) != (uint32_t)0x00) { fs = F_ERROR_OPERATION; } else { + fs = F_COMPLETE; } } } } + return fs; +} + + +// enable FLASH Registers +void F_unlock(void) +{ + if((FLASH->control & F_CR_LOCK) != 0) + { + FLASH->key = F_KEY1; + FLASH->key = F_KEY2; + } +} + +// lock the FLASH Registers +void F_lock(void) +{ + FLASH->control |= F_CR_LOCK; +} + +// flash write word. +uint8_t F_write_word(uint32_t Address, uint32_t Data) +{ + unsigned char octet[4] = {0,0,0,0}; + for (int i=0; i<4; i++) + { + octet[i] = ( Data >> (i*8) ) & 0xFF; + F_write_byte(Address+i,octet[i]); + } + + } + +// flash write byte +uint8_t F_write_byte(uint32_t Address, uint8_t Data) +{ + volatile uint8_t status = F_COMPLETE; + + //warnx("F_write_byte: %08X %02d", Address , Data ) ; + + //Check the parameters + assert(IS_F_ADDRESS(Address)); + + //Wait for FLASH operation to complete by polling on BUSY flag. + status = F_GetStatus(); + while(status == F_BUSY){ status = F_GetStatus();} + + if(status == F_COMPLETE) + { + //if the previous operation is completed, proceed to program the new data + FLASH->control &= CR_PSIZE_MASK; + FLASH->control |= F_PSIZE_BYTE; + FLASH->control |= F_CR_PG; + + *(volatile uint8_t*)Address = Data; + + //Wait for FLASH operation to complete by polling on BUSY flag. + status = F_GetStatus(); + while(status == F_BUSY){ status = F_GetStatus();} + + //if the program operation is completed, disable the PG Bit + FLASH->control &= (~F_CR_PG); + } + + //Return the Program Status + return status; +} + + + + \ No newline at end of file diff --git a/src/modules/systemlib/otp.h b/src/modules/systemlib/otp.h new file mode 100644 index 000000000..e80ca9afb --- /dev/null +++ b/src/modules/systemlib/otp.h @@ -0,0 +1,156 @@ +/**************************************************************************** + * + * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. + * Authors: + * Lorenz Meier + * David "Buzz" Bussenschutt + * + * 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 otp.h + * One TIme Programmable ( OTP ) Flash routine/s. + * + * @author Lorenz Meier + * @author David "Buzz" Bussenschutt + * + */ + +#ifndef OTP_H_ +#define OTP_H_ + + __BEGIN_DECLS + +#define ADDR_OTP_START 0x1FFF7800 +#define ADDR_OTP_LOCK_START 0x1FFF7A00 + +#define OTP_LOCK_LOCKED 0x00 +#define OTP_LOCK_UNLOCKED 0xFF + + + +#include +#include + +// possible flash statuses +#define F_BUSY 1 +#define F_ERROR_WRP 2 +#define F_ERROR_PROGRAM 3 +#define F_ERROR_OPERATION 4 +#define F_COMPLETE 5 + +typedef struct +{ + volatile uint32_t accesscontrol; // 0x00 + volatile uint32_t key; // 0x04 + volatile uint32_t optionkey; // 0x08 + volatile uint32_t status; // 0x0C + volatile uint32_t control; // 0x10 + volatile uint32_t optioncontrol; //0x14 +} flash_registers; + +#define PERIPH_BASE ((uint32_t)0x40000000) //Peripheral base address +#define AHB1PERIPH_BASE (PERIPH_BASE + 0x00020000) +#define F_R_BASE (AHB1PERIPH_BASE + 0x3C00) +#define FLASH ((flash_registers *) F_R_BASE) + +#define F_BSY ((uint32_t)0x00010000) //FLASH Busy flag bit +#define F_OPERR ((uint32_t)0x00000002) //FLASH operation Error flag bit +#define F_WRPERR ((uint32_t)0x00000010) //FLASH Write protected error flag bit +#define CR_PSIZE_MASK ((uint32_t)0xFFFFFCFF) +#define F_PSIZE_WORD ((uint32_t)0x00000200) +#define F_PSIZE_BYTE ((uint32_t)0x00000000) +#define F_CR_PG ((uint32_t)0x00000001) // a bit in the F_CR register +#define F_CR_LOCK ((uint32_t)0x80000000) // also another bit. + +#define F_KEY1 ((uint32_t)0x45670123) +#define F_KEY2 ((uint32_t)0xCDEF89AB) +#define IS_F_ADDRESS(ADDRESS) ((((ADDRESS) >= 0x08000000) && ((ADDRESS) < 0x080FFFFF)) || (((ADDRESS) >= 0x1FFF7800) && ((ADDRESS) < 0x1FFF7A0F))) + + + + #pragma pack(push, 1) + +/* + * The OTP area is divided into 16 OTP data blocks of 32 bytes and one lock OTP block of 16 bytes. + * The OTP data and lock blocks cannot be erased. The lock block contains 16 bytes LOCKBi (0 ≤ i ≤ 15) + * to lock the corresponding OTP data block (blocks 0 to 15). Each OTP data block can be programmed + * until the value 0x00 is programmed in the corresponding OTP lock byte. The lock bytes must only + * contain 0x00 and 0xFF values, otherwise the OTP bytes might not be taken into account correctly. + */ + + struct otp { + // first 32 bytes = the '0' Block + char id[4]; ///4 bytes < 'P' 'X' '4' '\n' + uint8_t id_type; ///1 byte < 0 for USB VID, 1 for generic VID + uint32_t vid; ///4 bytes + uint32_t pid; ///4 bytes + char unused[19]; ///19 bytes + // Cert-of-Auth is next 4 blocks ie 1-4 ( where zero is first block ) + char signature[128]; + // insert extras here + uint32_t lock_bytes[4]; + }; + + struct otp_lock { + uint8_t lock_bytes[16]; + }; +#pragma pack(pop) + +#define UDID_START 0x1FFF7A10 +#define ADDR_F_SIZE 0x1FFF7A22 + +#pragma pack(push, 1) + union udid { + uint32_t serial[3]; + char data[12]; + }; +#pragma pack(pop) + + + /** + * s + */ + //__EXPORT float calc_indicated_airspeed(float differential_pressure); + + __EXPORT void F_unlock(void); + __EXPORT void F_lock(void); + __EXPORT int val_read(void* dest, volatile const void* src, int bytes); + __EXPORT int val_write(volatile void* dest, const void* src, int bytes); + __EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char* signature); + __EXPORT int lock_otp(void); + + + __EXPORT uint8_t F_write_byte(uint32_t Address, uint8_t Data); + __EXPORT uint8_t F_write_word(uint32_t Address, uint32_t Data); + +__END_DECLS + +#endif -- cgit v1.2.3 From 0ef85c133b387f5d5aab26e00985922c9f05c7e0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 21:41:07 +0100 Subject: OTP return value cleanup --- src/modules/systemlib/otp.c | 223 +++++++++++++++++++++++++------------------- src/modules/systemlib/otp.h | 107 ++++++++++----------- 2 files changed, 179 insertions(+), 151 deletions(-) (limited to 'src') diff --git a/src/modules/systemlib/otp.c b/src/modules/systemlib/otp.c index 7968637de..695574fdc 100644 --- a/src/modules/systemlib/otp.c +++ b/src/modules/systemlib/otp.c @@ -1,9 +1,9 @@ /**************************************************************************** * * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. - * Authors: + * Authors: * Lorenz Meier - * David "Buzz" Bussenschutt + * David "Buzz" Bussenschutt * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -43,6 +43,8 @@ * */ +#include +#include #include #include #include @@ -53,139 +55,170 @@ #include -int val_read(void* dest, volatile const void* src, int bytes) +int val_read(void *dest, volatile const void *src, int bytes) { - + int i; + for (i = 0; i < bytes / 4; i++) { - *(((volatile uint32_t *)dest) + i) = *(((volatile uint32_t *)src) + i); + *(((volatile unsigned *)dest) + i) = *(((volatile unsigned *)src) + i); } - return i*4; + + return i * 4; } -int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char* signature) +int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature) { - - warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n",id_type, vid, pid); - - // descriptor - F_write_byte( ADDR_OTP_START, 'P'); // write the 'P' from PX4. to first byte in OTP - F_write_byte( ADDR_OTP_START+1, 'X'); // write the 'P' from PX4. to first byte in OTP - F_write_byte( ADDR_OTP_START+2, '4'); - F_write_byte( ADDR_OTP_START+3, '\0'); - //id_type - F_write_byte( ADDR_OTP_START+4, id_type); - // vid and pid are 4 bytes each - F_write_word( ADDR_OTP_START+5, vid); - F_write_word( ADDR_OTP_START+9, pid); - // leave some 19 bytes of space, and go to the next block... - // then the auth sig starts - for ( int i = 0 ; i < 128 ; i++ ) { - F_write_byte( ADDR_OTP_START+32+i, signature[i]); - } - - + + warnx("write_otp: PX4 / %02X / %02X / %02X / ... etc \n", id_type, vid, pid); + + int errors = 0; + + // descriptor + if (F_write_byte(ADDR_OTP_START, 'P')) + errors++; + // write the 'P' from PX4. to first byte in OTP + if (F_write_byte(ADDR_OTP_START + 1, 'X')) + errors++; // write the 'P' from PX4. to first byte in OTP + if (F_write_byte(ADDR_OTP_START + 2, '4')) + errors++; + if (F_write_byte(ADDR_OTP_START + 3, '\0')) + errors++; + //id_type + if (F_write_byte(ADDR_OTP_START + 4, id_type)) + errors++; + // vid and pid are 4 bytes each + if (F_write_word(ADDR_OTP_START + 5, vid)) + errors++; + if (F_write_word(ADDR_OTP_START + 9, pid)) + errors++; + + // leave some 19 bytes of space, and go to the next block... + // then the auth sig starts + for (int i = 0 ; i < 128 ; i++) { + if (F_write_byte(ADDR_OTP_START + 32 + i, signature[i])) + errors++; + } + + return errors; } int lock_otp(void) { //determine the required locking size - can only write full lock bytes */ // int size = sizeof(struct otp) / 32; -// +// // struct otp_lock otp_lock_mem; // // memset(&otp_lock_mem, OTP_LOCK_UNLOCKED, sizeof(otp_lock_mem)); // for (int i = 0; i < sizeof(otp_lock_mem) / sizeof(otp_lock_mem.lock_bytes[0]); i++) // otp_lock_mem.lock_bytes[i] = OTP_LOCK_LOCKED; - //XXX add the actual call here to write the OTP_LOCK bytes only at final stage + //XXX add the actual call here to write the OTP_LOCK bytes only at final stage // val_copy(lock_ptr, &otp_lock_mem, sizeof(otp_lock_mem)); - - int locksize = 5; - // or just realise it's exctly 5x 32byte blocks we need to lock. 1 block for ID,type,vid,pid, and 4 blocks for certificate, which is 128 bytes. - for ( int i = 0 ; i < locksize ; i++ ) { - F_write_byte( ADDR_OTP_LOCK_START+i, OTP_LOCK_LOCKED); - } + int locksize = 5; + + int errors = 0; + + // or just realise it's exctly 5x 32byte blocks we need to lock. 1 block for ID,type,vid,pid, and 4 blocks for certificate, which is 128 bytes. + for (int i = 0 ; i < locksize ; i++) { + if (F_write_byte(ADDR_OTP_LOCK_START + i, OTP_LOCK_LOCKED)) + errors++; + } + + return errors; } -// COMPLETE, BUSY, or other flash error? -uint8_t F_GetStatus(void) { - uint8_t fs = F_COMPLETE; - if((FLASH->status & F_BSY) == F_BSY) { fs = F_BUSY; } else { - if((FLASH->status & F_WRPERR) != (uint32_t)0x00) { fs = F_ERROR_WRP; } else { - if((FLASH->status & (uint32_t)0xEF) != (uint32_t)0x00) { fs = F_ERROR_PROGRAM; } else { - if((FLASH->status & F_OPERR) != (uint32_t)0x00) { fs = F_ERROR_OPERATION; } else { - fs = F_COMPLETE; } } } } - return fs; -} +// COMPLETE, BUSY, or other flash error? +int F_GetStatus(void) +{ + int fs = F_COMPLETE; + + if ((FLASH->status & F_BSY) == F_BSY) { fs = F_BUSY; } else { + + if ((FLASH->status & F_WRPERR) != (uint32_t)0x00) { fs = F_ERROR_WRP; } else { + + if ((FLASH->status & (uint32_t)0xEF) != (uint32_t)0x00) { fs = F_ERROR_PROGRAM; } else { + + if ((FLASH->status & F_OPERR) != (uint32_t)0x00) { fs = F_ERROR_OPERATION; } else { + fs = F_COMPLETE; + } + } + } + } + + return fs; +} -// enable FLASH Registers +// enable FLASH Registers void F_unlock(void) { - if((FLASH->control & F_CR_LOCK) != 0) - { - FLASH->key = F_KEY1; - FLASH->key = F_KEY2; - } + if ((FLASH->control & F_CR_LOCK) != 0) { + FLASH->key = F_KEY1; + FLASH->key = F_KEY2; + } } -// lock the FLASH Registers +// lock the FLASH Registers void F_lock(void) { - FLASH->control |= F_CR_LOCK; + FLASH->control |= F_CR_LOCK; } -// flash write word. -uint8_t F_write_word(uint32_t Address, uint32_t Data) +// flash write word. +int F_write_word(uint32_t Address, uint32_t Data) { - unsigned char octet[4] = {0,0,0,0}; - for (int i=0; i<4; i++) - { - octet[i] = ( Data >> (i*8) ) & 0xFF; - F_write_byte(Address+i,octet[i]); - } - - } + unsigned char octet[4] = {0, 0, 0, 0}; + + int ret = 0; + + for (int i = 0; i < 4; i++) { + octet[i] = (Data >> (i * 8)) & 0xFF; + ret = F_write_byte(Address + i, octet[i]); + } + + return ret; +} // flash write byte -uint8_t F_write_byte(uint32_t Address, uint8_t Data) +int F_write_byte(uint32_t Address, uint8_t Data) { - volatile uint8_t status = F_COMPLETE; - - //warnx("F_write_byte: %08X %02d", Address , Data ) ; - - //Check the parameters - assert(IS_F_ADDRESS(Address)); - - //Wait for FLASH operation to complete by polling on BUSY flag. - status = F_GetStatus(); - while(status == F_BUSY){ status = F_GetStatus();} - - if(status == F_COMPLETE) - { - //if the previous operation is completed, proceed to program the new data - FLASH->control &= CR_PSIZE_MASK; - FLASH->control |= F_PSIZE_BYTE; - FLASH->control |= F_CR_PG; - - *(volatile uint8_t*)Address = Data; - - //Wait for FLASH operation to complete by polling on BUSY flag. - status = F_GetStatus(); - while(status == F_BUSY){ status = F_GetStatus();} - - //if the program operation is completed, disable the PG Bit - FLASH->control &= (~F_CR_PG); - } - - //Return the Program Status - return status; + volatile int status = F_COMPLETE; + + //warnx("F_write_byte: %08X %02d", Address , Data ) ; + + //Check the parameters + assert(IS_F_ADDRESS(Address)); + + //Wait for FLASH operation to complete by polling on BUSY flag. + status = F_GetStatus(); + + while (status == F_BUSY) { status = F_GetStatus();} + + if (status == F_COMPLETE) { + //if the previous operation is completed, proceed to program the new data + FLASH->control &= CR_PSIZE_MASK; + FLASH->control |= F_PSIZE_BYTE; + FLASH->control |= F_CR_PG; + + *(volatile uint8_t *)Address = Data; + + //Wait for FLASH operation to complete by polling on BUSY flag. + status = F_GetStatus(); + + while (status == F_BUSY) { status = F_GetStatus();} + + //if the program operation is completed, disable the PG Bit + FLASH->control &= (~F_CR_PG); + } + + //Return the Program Status + return !(status == F_COMPLETE); } - \ No newline at end of file diff --git a/src/modules/systemlib/otp.h b/src/modules/systemlib/otp.h index e80ca9afb..f10e129d8 100644 --- a/src/modules/systemlib/otp.h +++ b/src/modules/systemlib/otp.h @@ -1,9 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved. - * Authors: - * Lorenz Meier - * David "Buzz" Bussenschutt + * 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 @@ -36,7 +33,7 @@ /** * @file otp.h - * One TIme Programmable ( OTP ) Flash routine/s. + * One TIme Programmable ( OTP ) Flash routine/s. * * @author Lorenz Meier * @author David "Buzz" Bussenschutt @@ -46,8 +43,8 @@ #ifndef OTP_H_ #define OTP_H_ - __BEGIN_DECLS - +__BEGIN_DECLS + #define ADDR_OTP_START 0x1FFF7800 #define ADDR_OTP_LOCK_START 0x1FFF7A00 @@ -58,22 +55,21 @@ #include #include - -// possible flash statuses + +// possible flash statuses #define F_BUSY 1 #define F_ERROR_WRP 2 #define F_ERROR_PROGRAM 3 #define F_ERROR_OPERATION 4 #define F_COMPLETE 5 -typedef struct -{ - volatile uint32_t accesscontrol; // 0x00 - volatile uint32_t key; // 0x04 - volatile uint32_t optionkey; // 0x08 - volatile uint32_t status; // 0x0C - volatile uint32_t control; // 0x10 - volatile uint32_t optioncontrol; //0x14 +typedef struct { + volatile uint32_t accesscontrol; // 0x00 + volatile uint32_t key; // 0x04 + volatile uint32_t optionkey; // 0x08 + volatile uint32_t status; // 0x0C + volatile uint32_t control; // 0x10 + volatile uint32_t optioncontrol; //0x14 } flash_registers; #define PERIPH_BASE ((uint32_t)0x40000000) //Peripheral base address @@ -96,7 +92,7 @@ typedef struct - #pragma pack(push, 1) +#pragma pack(push, 1) /* * The OTP area is divided into 16 OTP data blocks of 32 bytes and one lock OTP block of 16 bytes. @@ -106,51 +102,50 @@ typedef struct * contain 0x00 and 0xFF values, otherwise the OTP bytes might not be taken into account correctly. */ - struct otp { - // first 32 bytes = the '0' Block - char id[4]; ///4 bytes < 'P' 'X' '4' '\n' - uint8_t id_type; ///1 byte < 0 for USB VID, 1 for generic VID - uint32_t vid; ///4 bytes - uint32_t pid; ///4 bytes - char unused[19]; ///19 bytes - // Cert-of-Auth is next 4 blocks ie 1-4 ( where zero is first block ) - char signature[128]; - // insert extras here - uint32_t lock_bytes[4]; - }; - - struct otp_lock { - uint8_t lock_bytes[16]; - }; +struct otp { + // first 32 bytes = the '0' Block + char id[4]; ///4 bytes < 'P' 'X' '4' '\n' + uint8_t id_type; ///1 byte < 0 for USB VID, 1 for generic VID + uint32_t vid; ///4 bytes + uint32_t pid; ///4 bytes + char unused[19]; ///19 bytes + // Cert-of-Auth is next 4 blocks ie 1-4 ( where zero is first block ) + char signature[128]; + // insert extras here + uint32_t lock_bytes[4]; +}; + +struct otp_lock { + uint8_t lock_bytes[16]; +}; #pragma pack(pop) -#define UDID_START 0x1FFF7A10 #define ADDR_F_SIZE 0x1FFF7A22 #pragma pack(push, 1) - union udid { - uint32_t serial[3]; - char data[12]; - }; +union udid { + uint32_t serial[3]; + char data[12]; +}; #pragma pack(pop) - - /** - * s - */ - //__EXPORT float calc_indicated_airspeed(float differential_pressure); - - __EXPORT void F_unlock(void); - __EXPORT void F_lock(void); - __EXPORT int val_read(void* dest, volatile const void* src, int bytes); - __EXPORT int val_write(volatile void* dest, const void* src, int bytes); - __EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char* signature); - __EXPORT int lock_otp(void); - - - __EXPORT uint8_t F_write_byte(uint32_t Address, uint8_t Data); - __EXPORT uint8_t F_write_word(uint32_t Address, uint32_t Data); - + +/** + * s + */ +//__EXPORT float calc_indicated_airspeed(float differential_pressure); + +__EXPORT void F_unlock(void); +__EXPORT void F_lock(void); +__EXPORT int val_read(void *dest, volatile const void *src, int bytes); +__EXPORT int val_write(volatile void *dest, const void *src, int bytes); +__EXPORT int write_otp(uint8_t id_type, uint32_t vid, uint32_t pid, char *signature); +__EXPORT int lock_otp(void); + + +__EXPORT int F_write_byte(uint32_t Address, uint8_t Data); +__EXPORT int F_write_word(uint32_t Address, uint32_t Data); + __END_DECLS #endif -- cgit v1.2.3 From ea4552a53d5bced405b83e455ded691d62bc7fb3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 21:41:54 +0100 Subject: Added functionality to read serial --- src/modules/systemlib/board_serial.c | 60 ++++++++++++++++++++++++++++++++++++ src/modules/systemlib/board_serial.h | 49 +++++++++++++++++++++++++++++ 2 files changed, 109 insertions(+) create mode 100644 src/modules/systemlib/board_serial.c create mode 100644 src/modules/systemlib/board_serial.h (limited to 'src') diff --git a/src/modules/systemlib/board_serial.c b/src/modules/systemlib/board_serial.c new file mode 100644 index 000000000..ad8c2bf83 --- /dev/null +++ b/src/modules/systemlib/board_serial.c @@ -0,0 +1,60 @@ +/**************************************************************************** + * + * 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 + * 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 board_serial.h + * Read off the board serial + * + * @author Lorenz Meier + * @author David "Buzz" Bussenschutt + * + */ + +#include "otp.h" +#include "board_config.h" +#include "board_serial.h" + +int get_board_serial(char *serialid) +{ + const volatile unsigned *udid_ptr = (const unsigned *)UDID_START; + union udid id; + val_read((unsigned *)&id, udid_ptr, sizeof(id)); + + + /* Copy the serial from the chips non-write memory and swap endianess */ + serialid[0] = id.data[3]; serialid[1] = id.data[2]; serialid[2] = id.data[1]; serialid[3] = id.data[0]; + serialid[4] = id.data[7]; serialid[5] = id.data[6]; serialid[6] = id.data[5]; serialid[7] = id.data[4]; + serialid[8] = id.data[11]; serialid[9] = id.data[10]; serialid[10] = id.data[9]; serialid[11] = id.data[8]; + + return 0; +} \ No newline at end of file diff --git a/src/modules/systemlib/board_serial.h b/src/modules/systemlib/board_serial.h new file mode 100644 index 000000000..b14bb4376 --- /dev/null +++ b/src/modules/systemlib/board_serial.h @@ -0,0 +1,49 @@ +/**************************************************************************** + * + * 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 + * 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 board_serial.h + * Read off the board serial + * + * @author Lorenz Meier + * @author David "Buzz" Bussenschutt + * + */ + +#pragma once + +__BEGIN_DECLS + +__EXPORT int get_board_serial(char *serialid); + +__END_DECLS -- cgit v1.2.3 From 72b9d3a0b1084e8ae9216edf95055ae5e0cb5fb7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 21:42:17 +0100 Subject: Added unique ID location --- src/drivers/boards/px4fmu-v1/board_config.h | 1 + src/drivers/boards/px4fmu-v2/board_config.h | 2 ++ 2 files changed, 3 insertions(+) (limited to 'src') diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h index 6f7166284..02c26b5c0 100644 --- a/src/drivers/boards/px4fmu-v1/board_config.h +++ b/src/drivers/boards/px4fmu-v1/board_config.h @@ -60,6 +60,7 @@ __BEGIN_DECLS /* PX4IO connection configuration */ #define PX4IO_SERIAL_DEVICE "/dev/ttyS2" +#define UDID_START 0x1FFF7A10 //#ifdef CONFIG_STM32_SPI2 //# error "SPI2 is not supported on this board" diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h index a19ed9d24..4972e6914 100644 --- a/src/drivers/boards/px4fmu-v2/board_config.h +++ b/src/drivers/boards/px4fmu-v2/board_config.h @@ -52,6 +52,8 @@ __BEGIN_DECLS /* these headers are not C++ safe */ #include #include + +#define UDID_START 0x1FFF7A10 /**************************************************************************************************** * Definitions -- cgit v1.2.3 From 1834a884b2abab0b38612c8d69f15156d0ef9d14 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 21:42:39 +0100 Subject: Added FMU command to read serial --- src/drivers/px4fmu/fmu.cpp | 29 ++++++++++++++++++++--------- 1 file changed, 20 insertions(+), 9 deletions(-) (limited to 'src') diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index b878d29bc..b28d318d7 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -65,6 +65,7 @@ #include #include #include +#include #include #include @@ -224,10 +225,10 @@ PX4FMU::PX4FMU() : _armed(false), _pwm_on(false), _mixers(nullptr), - _failsafe_pwm( {0}), - _disarmed_pwm( {0}), - _num_failsafe_set(0), - _num_disarmed_set(0) + _failsafe_pwm({0}), + _disarmed_pwm({0}), + _num_failsafe_set(0), + _num_disarmed_set(0) { for (unsigned i = 0; i < _max_actuators; i++) { _min_pwm[i] = PWM_DEFAULT_MIN; @@ -575,7 +576,7 @@ PX4FMU::task_main() if (i >= outputs.noutputs || !isfinite(outputs.output[i]) || outputs.output[i] < -1.0f || - outputs.output[i] > 1.0f) { + outputs.output[i] > 1.0f) { /* * Value is NaN, INF or out of band - set to the minimum value. * This will be clearly visible on the servo status and will limit the risk of accidentally @@ -933,7 +934,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) break; } - /* FALLTHROUGH */ + /* FALLTHROUGH */ case PWM_SERVO_SET(3): case PWM_SERVO_SET(2): if (_mode < MODE_4PWM) { @@ -941,7 +942,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) break; } - /* FALLTHROUGH */ + /* FALLTHROUGH */ case PWM_SERVO_SET(1): case PWM_SERVO_SET(0): if (arg <= 2100) { @@ -960,7 +961,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) break; } - /* FALLTHROUGH */ + /* FALLTHROUGH */ case PWM_SERVO_GET(3): case PWM_SERVO_GET(2): if (_mode < MODE_4PWM) { @@ -968,7 +969,7 @@ PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) break; } - /* FALLTHROUGH */ + /* FALLTHROUGH */ case PWM_SERVO_GET(1): case PWM_SERVO_GET(0): *(servo_position_t *)arg = up_pwm_servo_get(cmd - PWM_SERVO_GET(0)); @@ -1591,6 +1592,15 @@ fmu_main(int argc, char *argv[]) errx(0, "FMU driver stopped"); } + if (!strcmp(verb, "id")) { + char id[12]; + (void)get_board_serial(id); + + errx(0, "Board serial:\n %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X", + (unsigned)id[0], (unsigned)id[1], (unsigned)id[2], (unsigned)id[3], (unsigned)id[4], (unsigned)id[5], + (unsigned)id[6], (unsigned)id[7], (unsigned)id[8], (unsigned)id[9], (unsigned)id[10], (unsigned)id[11]); + } + if (fmu_start() != OK) errx(1, "failed to start the FMU driver"); @@ -1647,6 +1657,7 @@ fmu_main(int argc, char *argv[]) sensor_reset(0); warnx("resettet default time"); } + exit(0); } -- cgit v1.2.3 From c463fde0b95eb07a5f2792032d24fbda8626b808 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 7 Jan 2014 21:42:51 +0100 Subject: Compiling in new functions --- src/modules/systemlib/module.mk | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) (limited to 'src') diff --git a/src/modules/systemlib/module.mk b/src/modules/systemlib/module.mk index 1749ec9c7..8c6c300d6 100644 --- a/src/modules/systemlib/module.mk +++ b/src/modules/systemlib/module.mk @@ -50,5 +50,6 @@ SRCS = err.c \ system_params.c \ mavlink_log.c \ rc_check.c \ - otp.c + otp.c \ + board_serial.c -- cgit v1.2.3 From fed5a2daae3298ba097b4e7b406168928fc7816b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 8 Jan 2014 08:41:50 +0100 Subject: Better settings for the mount test --- src/systemcmds/tests/test_mount.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) (limited to 'src') diff --git a/src/systemcmds/tests/test_mount.c b/src/systemcmds/tests/test_mount.c index db4ddeed9..44e34d9ef 100644 --- a/src/systemcmds/tests/test_mount.c +++ b/src/systemcmds/tests/test_mount.c @@ -223,10 +223,10 @@ test_mount(int argc, char *argv[]) printf("#"); } - printf("\n"); + printf("."); fsync(stdout); fsync(stderr); - usleep(1000000); + usleep(200000); end = hrt_absolute_time(); -- cgit v1.2.3 From 184f4a29eb010413a27cabedbcbc348ef1af7100 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 8 Jan 2014 18:06:30 +0100 Subject: Improved file test, allowed abortion --- src/systemcmds/tests/test_file.c | 50 +++++++++++++++++++++++++++++++++++++++- 1 file changed, 49 insertions(+), 1 deletion(-) (limited to 'src') diff --git a/src/systemcmds/tests/test_file.c b/src/systemcmds/tests/test_file.c index 798724cf1..cdb0b0337 100644 --- a/src/systemcmds/tests/test_file.c +++ b/src/systemcmds/tests/test_file.c @@ -38,6 +38,7 @@ */ #include +#include #include #include #include @@ -51,6 +52,38 @@ #include "tests.h" +int check_user_abort(); + +int check_user_abort() { + /* check if user wants to abort */ + char c; + + struct pollfd fds; + int ret; + fds.fd = 0; /* stdin */ + fds.events = POLLIN; + ret = poll(&fds, 1, 0); + + if (ret > 0) { + + read(0, &c, 1); + + switch (c) { + case 0x03: // ctrl-c + case 0x1b: // esc + case 'c': + case 'q': + { + warnx("Test aborted."); + return OK; + /* not reached */ + } + } + } + + return 1; +} + int test_file(int argc, char *argv[]) { @@ -108,6 +141,9 @@ test_file(int argc, char *argv[]) fsync(fd); //perf_end(wperf); + if (!check_user_abort()) + return OK; + } end = hrt_absolute_time(); @@ -142,6 +178,9 @@ test_file(int argc, char *argv[]) errx(1, "ABORTING FURTHER COMPARISON DUE TO ERROR"); } + if (!check_user_abort()) + return OK; + } /* @@ -152,7 +191,7 @@ test_file(int argc, char *argv[]) int ret = unlink("/fs/microsd/testfile"); fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT); - warnx("testing aligned writes - please wait.."); + warnx("testing aligned writes - please wait.. (CTRL^C to abort)"); start = hrt_absolute_time(); for (unsigned i = 0; i < iterations; i++) { @@ -162,6 +201,9 @@ test_file(int argc, char *argv[]) err(1, "WRITE ERROR!"); } + if (!check_user_abort()) + return OK; + } fsync(fd); @@ -190,6 +232,9 @@ test_file(int argc, char *argv[]) align_read_ok = false; break; } + + if (!check_user_abort()) + return OK; } if (!align_read_ok) { @@ -228,6 +273,9 @@ test_file(int argc, char *argv[]) if (unalign_read_err_count > 10) break; } + + if (!check_user_abort()) + return OK; } if (!unalign_read_ok) { -- cgit v1.2.3 From f5dfc241977e5095f4821d9f325a4d702905cb04 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 Jan 2014 08:44:57 +0100 Subject: Allow to check IO CRC independent of the IO start status (retains the interface status, startet or unstarted --- src/drivers/px4io/px4io.cpp | 116 +++++++++++++++++++++++++++----------------- 1 file changed, 71 insertions(+), 45 deletions(-) (limited to 'src') diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index cbdd5acc4..0ca35d2f2 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -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 @@ -35,7 +35,7 @@ * @file px4io.cpp * Driver for the PX4IO board. * - * PX4IO is connected via I2C. + * PX4IO is connected via I2C or DMA enabled high-speed UART. */ #include @@ -1690,6 +1690,9 @@ PX4IO::mixer_send(const char *buf, unsigned buflen, unsigned retries) int ret = io_reg_set(PX4IO_PAGE_MIXERLOAD, 0, (uint16_t *)frame, (sizeof(px4io_mixdata) + 2) / 2); + if (ret) + return ret; + retries--; log("mixer sent"); @@ -2419,6 +2422,69 @@ detect(int argc, char *argv[]) } } +void +checkcrc(int argc, char *argv[]) +{ + bool keep_running = false; + + if (g_dev == nullptr) { + /* allocate the interface */ + device::Device *interface = get_interface(); + + /* create the driver - it will set g_dev */ + (void)new PX4IO(interface); + + if (g_dev == nullptr) + errx(1, "driver alloc failed"); + } else { + /* its already running, don't kill the driver */ + keep_running = true; + } + + /* + check IO CRC against CRC of a file + */ + if (argc < 2) { + printf("usage: px4io checkcrc filename\n"); + exit(1); + } + int fd = open(argv[1], O_RDONLY); + if (fd == -1) { + printf("open of %s failed - %d\n", argv[1], errno); + exit(1); + } + const uint32_t app_size_max = 0xf000; + uint32_t fw_crc = 0; + uint32_t nbytes = 0; + while (true) { + uint8_t buf[16]; + int n = read(fd, buf, sizeof(buf)); + if (n <= 0) break; + fw_crc = crc32part(buf, n, fw_crc); + nbytes += n; + } + close(fd); + while (nbytes < app_size_max) { + uint8_t b = 0xff; + fw_crc = crc32part(&b, 1, fw_crc); + nbytes++; + } + + int ret = g_dev->ioctl(nullptr, PX4IO_CHECK_CRC, fw_crc); + + if (!keep_running) { + delete g_dev; + g_dev = nullptr; + } + + if (ret != OK) { + printf("check CRC failed - %d\n", ret); + exit(1); + } + printf("CRCs match\n"); + exit(0); +} + void bind(int argc, char *argv[]) { @@ -2613,6 +2679,9 @@ px4io_main(int argc, char *argv[]) if (!strcmp(argv[1], "detect")) detect(argc - 1, argv + 1); + if (!strcmp(argv[1], "checkcrc")) + checkcrc(argc - 1, argv + 1); + if (!strcmp(argv[1], "update")) { if (g_dev != nullptr) { @@ -2798,49 +2867,6 @@ px4io_main(int argc, char *argv[]) exit(0); } - if (!strcmp(argv[1], "checkcrc")) { - /* - check IO CRC against CRC of a file - */ - if (argc <= 2) { - printf("usage: px4io checkcrc filename\n"); - exit(1); - } - if (g_dev == nullptr) { - printf("px4io is not started\n"); - exit(1); - } - int fd = open(argv[2], O_RDONLY); - if (fd == -1) { - printf("open of %s failed - %d\n", argv[2], errno); - exit(1); - } - const uint32_t app_size_max = 0xf000; - uint32_t fw_crc = 0; - uint32_t nbytes = 0; - while (true) { - uint8_t buf[16]; - int n = read(fd, buf, sizeof(buf)); - if (n <= 0) break; - fw_crc = crc32part(buf, n, fw_crc); - nbytes += n; - } - close(fd); - while (nbytes < app_size_max) { - uint8_t b = 0xff; - fw_crc = crc32part(&b, 1, fw_crc); - nbytes++; - } - - int ret = g_dev->ioctl(nullptr, PX4IO_CHECK_CRC, fw_crc); - if (ret != OK) { - printf("check CRC failed - %d\n", ret); - exit(1); - } - printf("CRCs match\n"); - exit(0); - } - if (!strcmp(argv[1], "rx_dsm") || !strcmp(argv[1], "rx_dsm_10bit") || !strcmp(argv[1], "rx_dsm_11bit") || -- cgit v1.2.3 From 4fcbe806cef61aa3b8a749602b65da0e5c8d48a4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 9 Jan 2014 18:05:17 +0100 Subject: Cleaned up init config and picked a safe bet on FRAM clock speed --- src/drivers/boards/px4fmu-v2/px4fmu2_init.c | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) (limited to 'src') diff --git a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c index 269ec238e..71414d62c 100644 --- a/src/drivers/boards/px4fmu-v2/px4fmu2_init.c +++ b/src/drivers/boards/px4fmu-v2/px4fmu2_init.c @@ -282,7 +282,7 @@ __EXPORT int nsh_archinitialize(void) SPI_SELECT(spi1, PX4_SPIDEV_MPU, false); up_udelay(20); - message("[boot] Successfully initialized SPI port 1\n"); + message("[boot] Initialized SPI port 1 (SENSORS)\n"); /* Get the SPI port for the FRAM */ @@ -294,20 +294,23 @@ __EXPORT int nsh_archinitialize(void) return -ENODEV; } - /* Default SPI2 to 37.5 MHz (F4 max) and de-assert the known chip selects. */ - SPI_SETFREQUENCY(spi2, 375000000); + /* Default SPI2 to 37.5 MHz (40 MHz rounded to nearest valid divider, F4 max) + * and de-assert the known chip selects. */ + + // XXX start with 10.4 MHz in FRAM usage and go up to 37.5 once validated + SPI_SETFREQUENCY(spi2, 12 * 1000 * 1000); SPI_SETBITS(spi2, 8); SPI_SETMODE(spi2, SPIDEV_MODE3); SPI_SELECT(spi2, SPIDEV_FLASH, false); - message("[boot] Successfully initialized SPI port 2\n"); + message("[boot] Initialized SPI port 2 (RAMTRON FRAM)\n"); #ifdef CONFIG_MMCSD /* First, get an instance of the SDIO interface */ sdio = sdio_initialize(CONFIG_NSH_MMCSDSLOTNO); if (!sdio) { - message("nsh_archinitialize: Failed to initialize SDIO slot %d\n", + message("[boot] Failed to initialize SDIO slot %d\n", CONFIG_NSH_MMCSDSLOTNO); return -ENODEV; } @@ -315,7 +318,7 @@ __EXPORT int nsh_archinitialize(void) /* Now bind the SDIO interface to the MMC/SD driver */ int ret = mmcsd_slotinitialize(CONFIG_NSH_MMCSDMINOR, sdio); if (ret != OK) { - message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret); + message("[boot] Failed to bind SDIO to the MMC/SD driver: %d\n", ret); return ret; } -- cgit v1.2.3 From a303175c4c24f33b15b787b99be47be5ddafae3b Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 10 Jan 2014 07:51:47 +0100 Subject: Reduce the scheduler priority to a more acceptable value --- src/drivers/hott/hott_telemetry/hott_telemetry.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src') diff --git a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp index 042d9f816..d293f9954 100644 --- a/src/drivers/hott/hott_telemetry/hott_telemetry.cpp +++ b/src/drivers/hott/hott_telemetry/hott_telemetry.cpp @@ -237,7 +237,7 @@ hott_telemetry_main(int argc, char *argv[]) thread_should_exit = false; deamon_task = task_spawn_cmd(daemon_name, SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 40, + SCHED_PRIORITY_DEFAULT, 2048, hott_telemetry_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); -- cgit v1.2.3 From 7265006f3f6d3da7d5fd7010dc9da92a22cae6d8 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 10 Jan 2014 08:03:54 +0100 Subject: Adjust the HoTT sensor scheduler priority as well --- src/drivers/hott/hott_sensors/hott_sensors.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src') diff --git a/src/drivers/hott/hott_sensors/hott_sensors.cpp b/src/drivers/hott/hott_sensors/hott_sensors.cpp index e322c6349..a3d3a3933 100644 --- a/src/drivers/hott/hott_sensors/hott_sensors.cpp +++ b/src/drivers/hott/hott_sensors/hott_sensors.cpp @@ -211,7 +211,7 @@ hott_sensors_main(int argc, char *argv[]) thread_should_exit = false; deamon_task = task_spawn_cmd(daemon_name, SCHED_DEFAULT, - SCHED_PRIORITY_MAX - 40, + SCHED_PRIORITY_DEFAULT, 1024, hott_sensors_thread_main, (argv) ? (const char **)&argv[2] : (const char **)NULL); -- cgit v1.2.3 From ac7787e2a2a2439a5fa47755dda3f775568330dd Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 11 Jan 2014 00:09:10 +0100 Subject: launchdetection: send warning to qgc every 4s --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) (limited to 'src') diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 04caf0bbc..c90b0313a 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -175,7 +175,6 @@ private: /* takeoff/launch states */ bool launch_detected; bool usePreTakeoffThrust; - bool launch_detection_message_sent; /* Landingslope object */ Landingslope landingslope; @@ -397,8 +396,7 @@ FixedwingPositionControl::FixedwingPositionControl() : _mavlink_fd(-1), launchDetector(), launch_detected(false), - usePreTakeoffThrust(false), - launch_detection_message_sent(false) + usePreTakeoffThrust(false) { /* safely initialize structs */ vehicle_attitude_s _att = {0}; @@ -985,10 +983,11 @@ FixedwingPositionControl::control_position(const math::Vector2f ¤t_positio // warnx("Launch detection running"); if(!launch_detected) { //do not do further checks once a launch was detected if (launchDetector.launchDetectionEnabled()) { -// warnx("Launch detection enabled"); - if(!launch_detection_message_sent) { + static hrt_abstime last_sent = 0; + if(hrt_absolute_time() - last_sent > 4e6) { +// warnx("Launch detection running"); mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running"); - launch_detection_message_sent = true; + last_sent = hrt_absolute_time(); } launchDetector.update(_sensor_combined.accelerometer_m_s2[0]); if (launchDetector.getLaunchDetected()) { @@ -1057,7 +1056,6 @@ FixedwingPositionControl::control_position(const math::Vector2f ¤t_positio if (mission_item_triplet.current.nav_cmd != NAV_CMD_TAKEOFF) { launch_detected = false; usePreTakeoffThrust = false; - launch_detection_message_sent = false; } if (was_circle_mode && !_l1_control.circle_mode()) { -- cgit v1.2.3