|
|
|
|
@@ -61,61 +61,64 @@
|
|
|
|
|
static px4_sem_t *sems;
|
|
|
|
|
int test_dataman(int argc, char *argv[]);
|
|
|
|
|
|
|
|
|
|
#define NUM_MISSIONS_TEST 50
|
|
|
|
|
|
|
|
|
|
static int
|
|
|
|
|
task_main(int argc, char *argv[])
|
|
|
|
|
{
|
|
|
|
|
char buffer[DM_MAX_DATA_SIZE];
|
|
|
|
|
hrt_abstime wstart, wend, rstart, rend;
|
|
|
|
|
|
|
|
|
|
warnx("Starting dataman test task %s", argv[1]);
|
|
|
|
|
PX4_INFO("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);
|
|
|
|
|
PX4_ERR("%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);
|
|
|
|
|
PX4_ERR("%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();
|
|
|
|
|
hrt_abstime wstart = hrt_absolute_time();
|
|
|
|
|
|
|
|
|
|
for (unsigned i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
|
|
|
|
|
for (unsigned i = 0; i < NUM_MISSIONS_TEST; i++) {
|
|
|
|
|
memset(buffer, my_id, sizeof(buffer));
|
|
|
|
|
buffer[1] = i;
|
|
|
|
|
unsigned hash = i ^ my_id;
|
|
|
|
|
unsigned len = (hash % (DM_MAX_DATA_SIZE / 2)) + 2;
|
|
|
|
|
|
|
|
|
|
int ret = dm_write(DM_KEY_WAYPOINTS_OFFBOARD_1, hash, DM_PERSIST_IN_FLIGHT_RESET, buffer, len);
|
|
|
|
|
warnx("ret: %d", ret);
|
|
|
|
|
//PX4_INFO("ret: %d", ret);
|
|
|
|
|
|
|
|
|
|
if (ret != len) {
|
|
|
|
|
warnx("%d write failed, index %d, length %d", my_id, hash, len);
|
|
|
|
|
PX4_WARN("task %d: write failed, index %d, length %d", my_id, hash, len);
|
|
|
|
|
goto fail;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (i % (NUM_MISSIONS_TEST / 10) == 0) {
|
|
|
|
|
PX4_INFO("task %d: %.0f%%", my_id, (double)i * 100.0f / NUM_MISSIONS_TEST);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
usleep(rand() & ((64 * 1024) - 1));
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
rstart = hrt_absolute_time();
|
|
|
|
|
wend = rstart;
|
|
|
|
|
hrt_abstime rstart = hrt_absolute_time();
|
|
|
|
|
hrt_abstime wend = rstart;
|
|
|
|
|
|
|
|
|
|
for (unsigned i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
|
|
|
|
|
for (unsigned i = 0; i < NUM_MISSIONS_TEST; i++) {
|
|
|
|
|
unsigned hash = i ^ my_id;
|
|
|
|
|
unsigned len2;
|
|
|
|
|
unsigned len = (hash % (DM_MAX_DATA_SIZE / 2)) + 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);
|
|
|
|
|
PX4_WARN("task %d: read failed length test, index %d", my_id, hash);
|
|
|
|
|
goto fail;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@@ -123,12 +126,12 @@ task_main(int argc, char *argv[])
|
|
|
|
|
hit++;
|
|
|
|
|
|
|
|
|
|
if (len2 != len) {
|
|
|
|
|
warnx("%d read failed length test, index %d, wanted %d, got %d", my_id, hash, len, len2);
|
|
|
|
|
PX4_WARN("task %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]);
|
|
|
|
|
PX4_WARN("task %d: data verification failed, index %d, wanted %d, got %d", my_id, hash, my_id, buffer[1]);
|
|
|
|
|
goto fail;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@@ -137,21 +140,23 @@ task_main(int argc, char *argv[])
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
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);
|
|
|
|
|
hrt_abstime rend = hrt_absolute_time();
|
|
|
|
|
PX4_INFO("task %d pass, hit %d, miss %d, io time read %llums. write %llums.",
|
|
|
|
|
my_id, hit, miss, (rend - rstart) / NUM_MISSIONS_TEST / 1000, (wend - wstart) / NUM_MISSIONS_TEST / 1000);
|
|
|
|
|
px4_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]);
|
|
|
|
|
PX4_ERR("test_dataman FAILED: task %d, buffer %02x %02x %02x %02x %02x %02x",
|
|
|
|
|
my_id, buffer[0], buffer[1], buffer[2], buffer[3], buffer[4], buffer[5]);
|
|
|
|
|
px4_sem_post(sems + my_id);
|
|
|
|
|
return -1;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
int test_dataman(int argc, char *argv[])
|
|
|
|
|
{
|
|
|
|
|
int i, num_tasks = 4;
|
|
|
|
|
int i = 0;
|
|
|
|
|
unsigned num_tasks = 4;
|
|
|
|
|
char buffer[DM_MAX_DATA_SIZE];
|
|
|
|
|
|
|
|
|
|
if (argc > 1) {
|
|
|
|
|
@@ -159,22 +164,23 @@ int test_dataman(int argc, char *argv[])
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
sems = (px4_sem_t *)malloc(num_tasks * sizeof(px4_sem_t));
|
|
|
|
|
warnx("Running %d tasks", num_tasks);
|
|
|
|
|
PX4_INFO("Running %d tasks", num_tasks);
|
|
|
|
|
|
|
|
|
|
for (i = 0; i < num_tasks; i++) {
|
|
|
|
|
int task;
|
|
|
|
|
|
|
|
|
|
char a[16];
|
|
|
|
|
sprintf(a, "%d", i);
|
|
|
|
|
const char *av[2];
|
|
|
|
|
av[0] = a;
|
|
|
|
|
av[1] = 0;
|
|
|
|
|
snprintf(a, 16, "%d", i);
|
|
|
|
|
|
|
|
|
|
char *av[] = {"tests_dataman", a, NULL};
|
|
|
|
|
|
|
|
|
|
px4_sem_init(sems + i, 1, 0);
|
|
|
|
|
/* sems use case is a signal */
|
|
|
|
|
px4_sem_setprotocol(&sems, SEM_PRIO_NONE);
|
|
|
|
|
px4_sem_setprotocol(sems, SEM_PRIO_NONE);
|
|
|
|
|
|
|
|
|
|
/* start the task */
|
|
|
|
|
if ((task = px4_task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, (void *)av)) <= 0) {
|
|
|
|
|
warn("task start failed");
|
|
|
|
|
if ((task = px4_task_spawn_cmd("dataman", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, 2048, task_main, av)) <= 0) {
|
|
|
|
|
PX4_ERR("task start failed");
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
@@ -186,23 +192,23 @@ int test_dataman(int argc, char *argv[])
|
|
|
|
|
free(sems);
|
|
|
|
|
dm_restart(DM_INIT_REASON_IN_FLIGHT);
|
|
|
|
|
|
|
|
|
|
for (i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
|
|
|
|
|
for (i = 0; i < NUM_MISSIONS_TEST; i++) {
|
|
|
|
|
if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, i, buffer, sizeof(buffer)) != 0) {
|
|
|
|
|
break;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
if (i >= NUM_MISSIONS_SUPPORTED) {
|
|
|
|
|
warnx("Restart in-flight failed");
|
|
|
|
|
if (i >= NUM_MISSIONS_TEST) {
|
|
|
|
|
PX4_ERR("Restart in-flight failed");
|
|
|
|
|
return -1;
|
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
dm_restart(DM_INIT_REASON_POWER_ON);
|
|
|
|
|
|
|
|
|
|
for (i = 0; i < NUM_MISSIONS_SUPPORTED; i++) {
|
|
|
|
|
for (i = 0; i < NUM_MISSIONS_TEST; i++) {
|
|
|
|
|
if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD_1, i, buffer, sizeof(buffer)) != 0) {
|
|
|
|
|
warnx("Restart power-on failed");
|
|
|
|
|
PX4_ERR("Restart power-on failed");
|
|
|
|
|
return -1;
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|