aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds
diff options
context:
space:
mode:
Diffstat (limited to 'src/systemcmds')
-rw-r--r--src/systemcmds/mixer/mixer.cpp3
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c3
-rw-r--r--src/systemcmds/tests/module.mk1
-rw-r--r--src/systemcmds/tests/test_dataman.c182
-rw-r--r--src/systemcmds/tests/test_mathlib.cpp159
-rw-r--r--src/systemcmds/tests/tests.h1
-rw-r--r--src/systemcmds/tests/tests_main.c1
7 files changed, 347 insertions, 3 deletions
diff --git a/src/systemcmds/mixer/mixer.cpp b/src/systemcmds/mixer/mixer.cpp
index 6da39d371..2f5ed3265 100644
--- a/src/systemcmds/mixer/mixer.cpp
+++ b/src/systemcmds/mixer/mixer.cpp
@@ -102,7 +102,8 @@ load(const char *devname, const char *fname)
if (ioctl(dev, MIXERIOCRESET, 0))
err(1, "can't reset mixers on %s", devname);
- load_mixer_file(fname, &buf[0], sizeof(buf));
+ if (load_mixer_file(fname, &buf[0], sizeof(buf)) < 0)
+ err(1, "can't load mixer: %s", fname);
/* XXX pass the buffer to the device */
int ret = ioctl(dev, MIXERIOCLOADBUF, (unsigned long)buf);
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index 982b03782..86e4ff545 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -44,6 +44,7 @@
#include <string.h>
#include <fcntl.h>
#include <errno.h>
+#include <math.h>
#include <systemlib/err.h>
#include <systemlib/param/param.h>
@@ -87,9 +88,7 @@ int preflight_check_main(int argc, char *argv[])
/* give the system some time to sample the sensors in the background */
usleep(150000);
-
/* ---- MAG ---- */
- close(fd);
fd = open(MAG_DEVICE_PATH, 0);
if (fd < 0) {
warn("failed to open magnetometer - start with 'hmc5883 start' or 'lsm303d start'");
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index beb9ad13d..acf28c35b 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -24,6 +24,7 @@ SRCS = test_adc.c \
test_uart_loopback.c \
test_uart_send.c \
test_mixer.cpp \
+ test_mathlib.cpp \
test_file.c \
tests_main.c \
test_param.c \
diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c
new file mode 100644
index 000000000..1f844a97d
--- /dev/null
+++ b/src/systemcmds/tests/test_dataman.c
@@ -0,0 +1,182 @@
+/****************************************************************************
+ * px4/sensors/test_dataman.c
+ *
+ * Copyright (C) 2012 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 NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_led.h>
+#include <systemlib/systemlib.h>
+#include <drivers/drv_hrt.h>
+#include <semaphore.h>
+
+
+#include "tests.h"
+
+#include "dataman/dataman.h"
+
+static sem_t *sems;
+
+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]);
+ /* 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;
+ unsigned hash = i ^ my_id;
+ unsigned len = (hash & 63) + 2;
+
+ 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
+ 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);
+ 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]);
+ sem_post(sems + my_id);
+ return -1;
+}
+
+int test_dataman(int argc, char *argv[])
+{
+ int i, num_tasks = 4;
+ char buffer[DM_MAX_DATA_SIZE];
+
+ 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];
+ sprintf(a, "%d", i);
+ const char *av[2];
+ 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)
+ 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;
+}
diff --git a/src/systemcmds/tests/test_mathlib.cpp b/src/systemcmds/tests/test_mathlib.cpp
new file mode 100644
index 000000000..693a208ba
--- /dev/null
+++ b/src/systemcmds/tests/test_mathlib.cpp
@@ -0,0 +1,159 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 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_mathlib.cpp
+ *
+ * Mathlib test
+ */
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <time.h>
+#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+
+#include "tests.h"
+
+#define TEST_OP(_title, _op) { unsigned int n = 60000; hrt_abstime t0, t1; t0 = hrt_absolute_time(); for (unsigned int j = 0; j < n; j++) { _op; }; t1 = hrt_absolute_time(); warnx(_title ": %.6fus", (double)(t1 - t0) / n); }
+
+using namespace math;
+
+const char* formatResult(bool res) {
+ return res ? "OK" : "ERROR";
+}
+
+int test_mathlib(int argc, char *argv[])
+{
+ warnx("testing mathlib");
+
+ {
+ Vector<2> v;
+ Vector<2> v1(1.0f, 2.0f);
+ Vector<2> v2(1.0f, -1.0f);
+ float data[2] = {1.0f, 2.0f};
+ TEST_OP("Constructor Vector<2>()", Vector<2> v3);
+ TEST_OP("Constructor Vector<2>(Vector<2>)", Vector<2> v3(v1));
+ TEST_OP("Constructor Vector<2>(float[])", Vector<2> v3(data));
+ TEST_OP("Constructor Vector<2>(float, float)", Vector<2> v3(1.0f, 2.0f));
+ TEST_OP("Vector<2> = Vector<2>", v = v1);
+ TEST_OP("Vector<2> + Vector<2>", v + v1);
+ TEST_OP("Vector<2> - Vector<2>", v - v1);
+ TEST_OP("Vector<2> += Vector<2>", v += v1);
+ TEST_OP("Vector<2> -= Vector<2>", v -= v1);
+ TEST_OP("Vector<2> * Vector<2>", v * v1);
+ TEST_OP("Vector<2> %% Vector<2>", v1 % v2);
+ }
+
+ {
+ Vector<3> v;
+ Vector<3> v1(1.0f, 2.0f, 0.0f);
+ Vector<3> v2(1.0f, -1.0f, 2.0f);
+ float data[3] = {1.0f, 2.0f, 3.0f};
+ TEST_OP("Constructor Vector<3>()", Vector<3> v3);
+ TEST_OP("Constructor Vector<3>(Vector<3>)", Vector<3> v3(v1));
+ TEST_OP("Constructor Vector<3>(float[])", Vector<3> v3(data));
+ TEST_OP("Constructor Vector<3>(float, float, float)", Vector<3> v3(1.0f, 2.0f, 3.0f));
+ TEST_OP("Vector<3> = Vector<3>", v = v1);
+ TEST_OP("Vector<3> + Vector<3>", v + v1);
+ TEST_OP("Vector<3> - Vector<3>", v - v1);
+ TEST_OP("Vector<3> += Vector<3>", v += v1);
+ TEST_OP("Vector<3> -= Vector<3>", v -= v1);
+ TEST_OP("Vector<3> * float", v1 * 2.0f);
+ TEST_OP("Vector<3> / float", v1 / 2.0f);
+ TEST_OP("Vector<3> *= float", v1 *= 2.0f);
+ TEST_OP("Vector<3> /= float", v1 /= 2.0f);
+ TEST_OP("Vector<3> * Vector<3>", v * v1);
+ TEST_OP("Vector<3> %% Vector<3>", v1 % v2);
+ TEST_OP("Vector<3> length", v1.length());
+ TEST_OP("Vector<3> length squared", v1.length_squared());
+ TEST_OP("Vector<3> element read", volatile float a = v1(0));
+ TEST_OP("Vector<3> element read direct", volatile float a = v1.data[0]);
+ TEST_OP("Vector<3> element write", v1(0) = 1.0f);
+ TEST_OP("Vector<3> element write direct", v1.data[0] = 1.0f);
+ }
+
+ {
+ Vector<4> v;
+ Vector<4> v1(1.0f, 2.0f, 0.0f, -1.0f);
+ Vector<4> v2(1.0f, -1.0f, 2.0f, 0.0f);
+ float data[4] = {1.0f, 2.0f, 3.0f, 4.0f};
+ TEST_OP("Constructor Vector<4>()", Vector<4> v3);
+ TEST_OP("Constructor Vector<4>(Vector<4>)", Vector<4> v3(v1));
+ TEST_OP("Constructor Vector<4>(float[])", Vector<4> v3(data));
+ TEST_OP("Constructor Vector<4>(float, float, float, float)", Vector<4> v3(1.0f, 2.0f, 3.0f, 4.0f));
+ TEST_OP("Vector<4> = Vector<4>", v = v1);
+ TEST_OP("Vector<4> + Vector<4>", v + v1);
+ TEST_OP("Vector<4> - Vector<4>", v - v1);
+ TEST_OP("Vector<4> += Vector<4>", v += v1);
+ TEST_OP("Vector<4> -= Vector<4>", v -= v1);
+ TEST_OP("Vector<4> * Vector<4>", v * v1);
+ }
+
+ {
+ Vector<10> v1;
+ v1.zero();
+ float data[10];
+ TEST_OP("Constructor Vector<10>()", Vector<10> v3);
+ TEST_OP("Constructor Vector<10>(Vector<10>)", Vector<10> v3(v1));
+ TEST_OP("Constructor Vector<10>(float[])", Vector<10> v3(data));
+ }
+
+ {
+ Matrix<3, 3> m1;
+ m1.identity();
+ Matrix<3, 3> m2;
+ m2.identity();
+ Vector<3> v1(1.0f, 2.0f, 0.0f);
+ TEST_OP("Matrix<3, 3> * Vector<3>", m1 * v1);
+ TEST_OP("Matrix<3, 3> + Matrix<3, 3>", m1 + m2);
+ TEST_OP("Matrix<3, 3> * Matrix<3, 3>", m1 * m2);
+ }
+
+ {
+ Matrix<10, 10> m1;
+ m1.identity();
+ Matrix<10, 10> m2;
+ m2.identity();
+ Vector<10> v1;
+ v1.zero();
+ TEST_OP("Matrix<10, 10> * Vector<10>", m1 * v1);
+ TEST_OP("Matrix<10, 10> + Matrix<10, 10>", m1 + m2);
+ TEST_OP("Matrix<10, 10> * Matrix<10, 10>", m1 * m2);
+ }
+
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index 82de05dff..ac64ad33d 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -112,6 +112,7 @@ extern int test_rc(int argc, char *argv[]);
extern int test_conv(int argc, char *argv[]);
extern int test_mount(int argc, char *argv[]);
extern int test_mtd(int argc, char *argv[]);
+extern int test_mathlib(int argc, char *argv[]);
__END_DECLS
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 77a4df618..73827b7cf 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -109,6 +109,7 @@ const struct {
{"conv", test_conv, OPT_NOJIGTEST | OPT_NOALLTEST},
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
{"mtd", test_mtd, 0},
+ {"mathlib", test_mathlib, 0},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{NULL, NULL, 0}
};