aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds/tests/test_dataman.c
diff options
context:
space:
mode:
Diffstat (limited to 'src/systemcmds/tests/test_dataman.c')
-rw-r--r--src/systemcmds/tests/test_dataman.c38
1 files changed, 31 insertions, 7 deletions
diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c
index 1f844a97d..c58e1a51e 100644
--- a/src/systemcmds/tests/test_dataman.c
+++ b/src/systemcmds/tests/test_dataman.c
@@ -70,19 +70,23 @@ task_main(int argc, char *argv[])
warnx("Starting dataman test task %s", argv[1]);
/* try to read an invalid item */
int my_id = atoi(argv[1]);
+
/* try to read an invalid item */
if (dm_read(DM_KEY_NUM_KEYS, 0, buffer, sizeof(buffer)) >= 0) {
warnx("%d read an invalid item failed", my_id);
goto fail;
}
+
/* try to read an invalid index */
if (dm_read(DM_KEY_SAFE_POINTS, DM_KEY_SAFE_POINTS_MAX, buffer, sizeof(buffer)) >= 0) {
warnx("%d read an invalid index failed", my_id);
goto fail;
}
+
srand(hrt_absolute_time() ^ my_id);
unsigned hit = 0, miss = 0;
wstart = hrt_absolute_time();
+
for (unsigned i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
memset(buffer, my_id, sizeof(buffer));
buffer[1] = i;
@@ -91,44 +95,53 @@ task_main(int argc, char *argv[])
int ret = dm_write(DM_KEY_WAYPOINTS_OFFBOARD_1, hash, DM_PERSIST_IN_FLIGHT_RESET, buffer, len);
warnx("ret: %d", ret);
+
if (ret != len) {
warnx("%d write failed, index %d, length %d", my_id, hash, len);
goto fail;
}
+
usleep(rand() & ((64 * 1024) - 1));
}
+
rstart = hrt_absolute_time();
wend = rstart;
for (unsigned i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
unsigned hash = i ^ my_id;
unsigned len2, len = (hash & 63) + 2;
+
if ((len2 = dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, hash, buffer, sizeof(buffer))) < 2) {
warnx("%d read failed length test, index %d", my_id, hash);
goto fail;
}
+
if (buffer[0] == my_id) {
hit++;
+
if (len2 != len) {
warnx("%d read failed length test, index %d, wanted %d, got %d", my_id, hash, len, len2);
goto fail;
}
+
if (buffer[1] != i) {
warnx("%d data verification failed, index %d, wanted %d, got %d", my_id, hash, my_id, buffer[1]);
goto fail;
}
- }
- else
+
+ } else {
miss++;
+ }
}
+
rend = hrt_absolute_time();
warnx("Test %d pass, hit %d, miss %d, io time read %llums. write %llums.",
- my_id, hit, miss, (rend - rstart) / NUM_MISSIONS_SUPPORTED / 1000, (wend - wstart) / NUM_MISSIONS_SUPPORTED / 1000);
+ my_id, hit, miss, (rend - rstart) / NUM_MISSIONS_SUPPORTED / 1000, (wend - wstart) / NUM_MISSIONS_SUPPORTED / 1000);
sem_post(sems + my_id);
return 0;
fail:
warnx("Test %d fail, buffer %02x %02x %02x %02x %02x %02x",
- my_id, buffer[0], buffer[1], buffer[2], buffer[3], buffer[4], buffer[5]);
+ my_id, buffer[0], buffer[1], buffer[2], buffer[3], buffer[4], buffer[5]);
sem_post(sems + my_id);
return -1;
}
@@ -138,11 +151,13 @@ int test_dataman(int argc, char *argv[])
int i, num_tasks = 4;
char buffer[DM_MAX_DATA_SIZE];
- if (argc > 1)
+ if (argc > 1) {
num_tasks = atoi(argv[1]);
-
+ }
+
sems = (sem_t *)malloc(num_tasks * sizeof(sem_t));
warnx("Running %d tasks", num_tasks);
+
for (i = 0; i < num_tasks; i++) {
int task;
char a[16];
@@ -151,32 +166,41 @@ int test_dataman(int argc, char *argv[])
av[0] = a;
av[1] = 0;
sem_init(sems + i, 1, 0);
+
/* start the task */
if ((task = task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, av)) <= 0) {
warn("task start failed");
}
}
+
for (i = 0; i < num_tasks; i++) {
sem_wait(sems + i);
sem_destroy(sems + i);
}
+
free(sems);
dm_restart(DM_INIT_REASON_IN_FLIGHT);
+
for (i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
- if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, i, buffer, sizeof(buffer)) != 0)
+ if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, i, buffer, sizeof(buffer)) != 0) {
break;
+ }
}
+
if (i >= NUM_MISSIONS_SUPPORTED) {
warnx("Restart in-flight failed");
return -1;
}
+
dm_restart(DM_INIT_REASON_POWER_ON);
+
for (i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, i, buffer, sizeof(buffer)) != 0) {
warnx("Restart power-on failed");
return -1;
}
}
+
return 0;
}