aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-10-12 20:19:09 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-10-12 20:19:09 +0200
commit7d6a4ece6b1875bab62c4dbcb95fcc9fa5661674 (patch)
tree50f87eb2c5312282a59b8905fba0e8efe4abd4f9
parentc5b890e87d545328734a815d90ce16d396630048 (diff)
downloadpx4-firmware-7d6a4ece6b1875bab62c4dbcb95fcc9fa5661674.tar.gz
px4-firmware-7d6a4ece6b1875bab62c4dbcb95fcc9fa5661674.tar.bz2
px4-firmware-7d6a4ece6b1875bab62c4dbcb95fcc9fa5661674.zip
Added mixer test
-rw-r--r--src/systemcmds/tests/module.mk1
-rw-r--r--src/systemcmds/tests/test_mixer.cpp74
-rw-r--r--src/systemcmds/tests/tests.h5
-rw-r--r--src/systemcmds/tests/tests_main.c1
4 files changed, 81 insertions, 0 deletions
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 754d3a0da..6729ce4ae 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -23,6 +23,7 @@ SRCS = test_adc.c \
test_uart_console.c \
test_uart_loopback.c \
test_uart_send.c \
+ test_mixer.cpp \
tests_file.c \
tests_main.c \
tests_param.c
diff --git a/src/systemcmds/tests/test_mixer.cpp b/src/systemcmds/tests/test_mixer.cpp
new file mode 100644
index 000000000..acb7bd88f
--- /dev/null
+++ b/src/systemcmds/tests/test_mixer.cpp
@@ -0,0 +1,74 @@
+/****************************************************************************
+ *
+ * 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_mixer.hpp
+ *
+ * Mixer load test
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <time.h>
+
+#include <systemlib/err.h>
+#include <systemlib/mixer/mixer.h>
+
+#include "tests.h"
+
+int test_mixer(int argc, char *argv[])
+{
+ warnx("testing mixer");
+
+ char *filename = "/etc/mixers/IO_pass.mix";
+
+ if (argc > 1)
+ filename = argv[1];
+
+ warnx("loading: %s", filename);
+
+ char buf[2048];
+
+ load_mixer_file(filename, &buf[0]);
+
+ warnx("loaded: %s", &buf[0]);
+
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index c02ea6808..c483108cf 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -76,6 +76,8 @@
* Public Function Prototypes
****************************************************************************/
+__BEGIN_DECLS
+
extern int test_sensors(int argc, char *argv[]);
extern int test_gpio(int argc, char *argv[]);
extern int test_hrt(int argc, char *argv[]);
@@ -98,5 +100,8 @@ extern int test_jig_voltages(int argc, char *argv[]);
extern int test_param(int argc, char *argv[]);
extern int test_bson(int argc, char *argv[]);
extern int test_file(int argc, char *argv[]);
+extern int test_mixer(int argc, char *argv[]);
+
+__END_DECLS
#endif /* __APPS_PX4_TESTS_H */
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 9f8c5c9ea..9eb9c632e 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -110,6 +110,7 @@ const struct {
{"param", test_param, 0},
{"bson", test_bson, 0},
{"file", test_file, 0},
+ {"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{NULL, NULL, 0}
};