aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2014-01-10 16:23:51 +0100
committerAnton Babushkin <anton.babushkin@me.com>2014-01-10 16:23:51 +0100
commitf5501a050873a35b2b8bd751e192d6db859f42b6 (patch)
tree926e3547d0a662fb0e8e9a75bdae68e8733c6ef8
parentb5d56523bc100d7bf95a6dfbac95c1afc89e345e (diff)
parent6604d7b9479df29227797d47aee35db27e88865c (diff)
downloadpx4-firmware-f5501a050873a35b2b8bd751e192d6db859f42b6.tar.gz
px4-firmware-f5501a050873a35b2b8bd751e192d6db859f42b6.tar.bz2
px4-firmware-f5501a050873a35b2b8bd751e192d6db859f42b6.zip
Merge branch 'master' into autostart_cleanup
-rw-r--r--ROMFS/px4fmu_test/init.d/rcS67
-rw-r--r--makefiles/config_px4fmu-v1_test.mk48
-rw-r--r--makefiles/config_px4fmu-v2_test.mk7
-rw-r--r--src/drivers/boards/px4fmu-v2/px4fmu2_init.c15
-rw-r--r--src/drivers/hott/hott_sensors/hott_sensors.cpp2
-rw-r--r--src/drivers/hott/hott_telemetry/hott_telemetry.cpp2
-rw-r--r--src/systemcmds/nshterm/nshterm.c4
-rw-r--r--src/systemcmds/tests/module.mk3
-rw-r--r--src/systemcmds/tests/test_file.c111
-rw-r--r--src/systemcmds/tests/test_mount.c289
-rw-r--r--src/systemcmds/tests/tests.h1
-rw-r--r--src/systemcmds/tests/tests_main.c1
12 files changed, 452 insertions, 98 deletions
diff --git a/ROMFS/px4fmu_test/init.d/rcS b/ROMFS/px4fmu_test/init.d/rcS
index 6aa1d3d46..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
@@ -9,4 +10,68 @@ then
# Try to get an USB console
nshterm /dev/ttyACM0 &
-fi \ No newline at end of file
+fi
+
+#
+# Try to mount the microSD card.
+#
+echo "[init] looking for microSD..."
+if mount -t vfat /dev/mmcsd0 /fs/microsd
+then
+ echo "[init] card mounted at /fs/microsd"
+ # Start playing the startup tune
+ tone_alarm start
+else
+ echo "[init] no microSD card found"
+ # Play SOS
+ 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.txt ]
+then
+ tests mount
+fi
diff --git a/makefiles/config_px4fmu-v1_test.mk b/makefiles/config_px4fmu-v1_test.mk
new file mode 100644
index 000000000..41e8b95ff
--- /dev/null
+++ b/makefiles/config_px4fmu-v1_test.mk
@@ -0,0 +1,48 @@
+#
+# Makefile for the px4fmu_default configuration
+#
+
+#
+# Use the configuration's ROMFS.
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_test
+ROMFS_OPTIONAL_FILES = $(PX4_BASE)/Images/px4io-v1_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-v1
+MODULES += drivers/px4io
+MODULES += systemcmds/perf
+MODULES += systemcmds/reboot
+MODULES += systemcmds/tests
+MODULES += systemcmds/nshterm
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+MODULES += modules/systemlib/mixer
+MODULES += modules/uORB
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+# command priority stack entrypoint
+BUILTIN_COMMANDS := \
+ $(call _B, sercon, , 2048, sercon_main ) \
+ $(call _B, serdis, , 2048, serdis_main )
diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk
index 750c0e7c3..a1bb6c92b 100644
--- a/makefiles/config_px4fmu-v2_test.mk
+++ b/makefiles/config_px4fmu-v2_test.mk
@@ -6,22 +6,29 @@
# 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
+MODULES += systemcmds/nshterm
MODULES += systemcmds/hw_ver
#
# Library modules
#
MODULES += modules/systemlib
+MODULES += modules/systemlib/mixer
MODULES += modules/uORB
#
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;
}
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);
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);
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);
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_file.c b/src/systemcmds/tests/test_file.c
index cdb0b0337..7206b87d6 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 <lm@inf.ethz.ch>
*/
#include <sys/stat.h>
@@ -119,7 +121,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);
@@ -127,19 +128,18 @@ 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);
if (!check_user_abort())
return OK;
@@ -147,11 +147,6 @@ test_file(int argc, char *argv[])
}
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);
@@ -160,7 +155,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 */
@@ -175,7 +171,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;
}
if (!check_user_abort())
@@ -198,7 +195,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;
}
if (!check_user_abort())
@@ -220,7 +218,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 */
@@ -238,7 +237,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;
}
}
@@ -260,7 +260,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++) {
@@ -279,7 +280,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;
}
}
@@ -287,9 +289,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;
+ }
}
}
@@ -309,75 +312,9 @@ test_file(int argc, char *argv[])
} else {
/* failed opening dir */
- err(1, "FAILED LISTING MICROSD ROOT DIRECTORY");
- }
-
- 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");
+ warnx("FAILED LISTING MICROSD ROOT DIRECTORY");
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
new file mode 100644
index 000000000..44e34d9ef
--- /dev/null
+++ b/src/systemcmds/tests/test_mount.c
@@ -0,0 +1,289 @@
+/****************************************************************************
+ *
+ * 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 <lm@inf.ethz.ch>
+ */
+
+#include <sys/stat.h>
+#include <dirent.h>
+#include <stdio.h>
+#include <stddef.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/perf_counter.h>
+#include <string.h>
+
+#include <drivers/drv_hrt.h>
+
+#include "tests.h"
+
+const int fsync_tries = 1;
+const int abort_tries = 10;
+
+int
+test_mount(int argc, char *argv[])
+{
+ const unsigned iterations = 2000;
+ const unsigned alignments = 10;
+
+ const char* cmd_filename = "/fs/microsd/mount_test_cmds.txt";
+
+
+ /* check if microSD card is mounted */
+ struct stat buffer;
+ if (stat("/fs/microsd/", &buffer)) {
+ warnx("no microSD card mounted, aborting file test");
+ 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 */
+
+ /* initial values */
+ int it_left_fsync = fsync_tries;
+ int it_left_abort = abort_tries;
+
+ int cmd_fd;
+ if (stat(cmd_filename, &buffer) == OK) {
+
+ /* command file exists, read off state */
+ cmd_fd = open(cmd_filename, O_RDWR | O_NONBLOCK);
+ char buf[64];
+ int ret = read(cmd_fd, buf, sizeof(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) {
+
+ it_left_abort--;
+
+ /* 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];
+ 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[] = {32, 64, 128, 256, 512, 600, 1200};
+
+ 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++) {
+
+ printf(".");
+
+ 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;
+
+ int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
+
+ start = hrt_absolute_time();
+ for (unsigned i = 0; i < iterations; i++) {
+
+ 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)))
+ warnx("memory is unaligned, align shift: %d", a);
+
+ return 1;
+
+ }
+
+ if (it_left_fsync > 0) {
+ fsync(fd);
+ } else {
+ printf("#");
+ fsync(stdout);
+ fsync(stderr);
+ }
+ }
+
+ if (it_left_fsync > 0) {
+ printf("#");
+ }
+
+ printf(".");
+ fsync(stdout);
+ fsync(stderr);
+ usleep(200000);
+
+ end = hrt_absolute_time();
+
+ 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;
+ }
+
+ }
+ }
+
+ fsync(stdout);
+ fsync(stderr);
+ usleep(20000);
+
+
+
+ /* we always reboot for the next test if we get here */
+ warnx("Iteration done, rebooting..");
+ fsync(stdout);
+ fsync(stderr);
+ usleep(50000);
+ systemreset(false);
+
+ /* 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}
};