aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds/tests
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2013-12-23 11:13:42 +0100
committerThomas Gubler <thomasgubler@gmail.com>2013-12-23 11:13:42 +0100
commit68d8230e78b9116da794e93a0a5edcce4d1d8ee4 (patch)
treee0c86a748a5604e042f1e56c464df117d4eb3030 /src/systemcmds/tests
parent23d0c6f8dd1a0b9aa64dafe26cfd56e43637c5ee (diff)
parentf6176890947dd33f6b26fb2cad53263882fb8e3b (diff)
downloadpx4-firmware-68d8230e78b9116da794e93a0a5edcce4d1d8ee4.tar.gz
px4-firmware-68d8230e78b9116da794e93a0a5edcce4d1d8ee4.tar.bz2
px4-firmware-68d8230e78b9116da794e93a0a5edcce4d1d8ee4.zip
Merge remote-tracking branch 'upstream/control_groups' into fw_autoland_att_tecs_navigator_termination_controlgroups
Conflicts: src/systemcmds/tests/module.mk src/systemcmds/tests/tests.h
Diffstat (limited to 'src/systemcmds/tests')
-rw-r--r--src/systemcmds/tests/module.mk6
-rw-r--r--src/systemcmds/tests/test_rc.c146
-rw-r--r--src/systemcmds/tests/test_sensors.c67
-rw-r--r--src/systemcmds/tests/tests.h2
-rw-r--r--src/systemcmds/tests/tests_main.c1
5 files changed, 191 insertions, 31 deletions
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index c1f8074ea..68a080c77 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -24,10 +24,8 @@ SRCS = test_adc.c \
test_uart_loopback.c \
test_uart_send.c \
test_mixer.cpp \
- test_dataman.c \
test_file.c \
tests_main.c \
test_param.c \
- test_ppm_loopback.c
-
-INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+ test_ppm_loopback.c \
+ test_rc.c
diff --git a/src/systemcmds/tests/test_rc.c b/src/systemcmds/tests/test_rc.c
new file mode 100644
index 000000000..72619fc8b
--- /dev/null
+++ b/src/systemcmds/tests/test_rc.c
@@ -0,0 +1,146 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2012, 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_ppm_loopback.c
+ * Tests the PWM outputs and PPM input
+ *
+ */
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+
+#include <stdio.h>
+#include <poll.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+#include <drivers/drv_pwm_output.h>
+#include <drivers/drv_rc_input.h>
+#include <systemlib/err.h>
+
+#include "tests.h"
+
+#include <math.h>
+#include <float.h>
+
+int test_rc(int argc, char *argv[])
+{
+
+ int _rc_sub = orb_subscribe(ORB_ID(input_rc));
+
+ /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
+ struct rc_input_values rc_input;
+ struct rc_input_values rc_last;
+ orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
+ usleep(100000);
+
+ /* open PPM input and expect values close to the output values */
+
+ bool rc_updated;
+ orb_check(_rc_sub, &rc_updated);
+
+ warnx("Reading PPM values - press any key to abort");
+ warnx("This test guarantees: 10 Hz update rates, no glitches (channel values), no channel count changes.");
+
+ if (rc_updated) {
+
+ /* copy initial set */
+ for (unsigned i = 0; i < rc_input.channel_count; i++) {
+ rc_last.values[i] = rc_input.values[i];
+ }
+
+ rc_last.channel_count = rc_input.channel_count;
+
+ /* poll descriptor */
+ struct pollfd fds[2];
+ fds[0].fd = _rc_sub;
+ fds[0].events = POLLIN;
+ fds[1].fd = 0;
+ fds[1].events = POLLIN;
+
+ while (true) {
+
+ int ret = poll(fds, 2, 200);
+
+ if (ret > 0) {
+
+ if (fds[0].revents & POLLIN) {
+
+ orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
+
+ /* go and check values */
+ for (unsigned i = 0; i < rc_input.channel_count; i++) {
+ if (fabsf(rc_input.values[i] - rc_last.values[i]) > 20) {
+ warnx("comparison fail: RC: %d, expected: %d", rc_input.values[i], rc_last.values[i]);
+ (void)close(_rc_sub);
+ return ERROR;
+ }
+
+ rc_last.values[i] = rc_input.values[i];
+ }
+
+ if (rc_last.channel_count != rc_input.channel_count) {
+ warnx("channel count mismatch: last: %d, now: %d", rc_last.channel_count, rc_input.channel_count);
+ (void)close(_rc_sub);
+ return ERROR;
+ }
+
+ if (hrt_absolute_time() - rc_input.timestamp > 100000) {
+ warnx("TIMEOUT, less than 10 Hz updates");
+ (void)close(_rc_sub);
+ return ERROR;
+ }
+
+ } else {
+ /* key pressed, bye bye */
+ return 0;
+ }
+
+ }
+ }
+
+ } else {
+ warnx("failed reading RC input data");
+ return ERROR;
+ }
+
+ warnx("PPM CONTINUITY TEST PASSED SUCCESSFULLY!");
+
+ return 0;
+}
diff --git a/src/systemcmds/tests/test_sensors.c b/src/systemcmds/tests/test_sensors.c
index f6415b72f..096106ff3 100644
--- a/src/systemcmds/tests/test_sensors.c
+++ b/src/systemcmds/tests/test_sensors.c
@@ -78,7 +78,8 @@ static int accel(int argc, char *argv[]);
static int gyro(int argc, char *argv[]);
static int mag(int argc, char *argv[]);
static int baro(int argc, char *argv[]);
-static int mpu6k(int argc, char *argv[]);
+static int accel1(int argc, char *argv[]);
+static int gyro1(int argc, char *argv[]);
/****************************************************************************
* Private Data
@@ -93,7 +94,8 @@ struct {
{"gyro", "/dev/gyro", gyro},
{"mag", "/dev/mag", mag},
{"baro", "/dev/baro", baro},
- {"mpu6k", "/dev/mpu6k", mpu6k},
+ {"accel1", "/dev/accel1", accel1},
+ {"gyro1", "/dev/gyro1", gyro1},
{NULL, NULL, NULL}
};
@@ -137,7 +139,7 @@ accel(int argc, char *argv[])
}
if (fabsf(buf.x) > 30.0f || fabsf(buf.y) > 30.0f || fabsf(buf.z) > 30.0f) {
- warnx("MPU6K acceleration values out of range!");
+ warnx("ACCEL1 acceleration values out of range!");
return ERROR;
}
@@ -149,20 +151,19 @@ accel(int argc, char *argv[])
}
static int
-mpu6k(int argc, char *argv[])
+accel1(int argc, char *argv[])
{
- printf("\tMPU6K: test start\n");
+ printf("\tACCEL1: test start\n");
fflush(stdout);
int fd;
struct accel_report buf;
- struct gyro_report gyro_buf;
int ret;
- fd = open("/dev/accel_mpu6k", O_RDONLY);
+ fd = open("/dev/accel1", O_RDONLY);
if (fd < 0) {
- printf("\tMPU6K: open fail, run <mpu6000 start> first.\n");
+ printf("\tACCEL1: open fail, run <mpu6000 start> or <lsm303d start> first.\n");
return ERROR;
}
@@ -173,26 +174,40 @@ mpu6k(int argc, char *argv[])
ret = read(fd, &buf, sizeof(buf));
if (ret != sizeof(buf)) {
- printf("\tMPU6K: read1 fail (%d)\n", ret);
+ printf("\tACCEL1: read1 fail (%d)\n", ret);
return ERROR;
} else {
- printf("\tMPU6K accel: x:%8.4f\ty:%8.4f\tz:%8.4f m/s^2\n", (double)buf.x, (double)buf.y, (double)buf.z);
+ printf("\tACCEL1 accel: x:%8.4f\ty:%8.4f\tz:%8.4f m/s^2\n", (double)buf.x, (double)buf.y, (double)buf.z);
}
if (fabsf(buf.x) > 30.0f || fabsf(buf.y) > 30.0f || fabsf(buf.z) > 30.0f) {
- warnx("MPU6K acceleration values out of range!");
+ warnx("ACCEL1 acceleration values out of range!");
return ERROR;
}
/* Let user know everything is ok */
- printf("\tOK: MPU6K ACCEL passed all tests successfully\n");
+ printf("\tOK: ACCEL1 passed all tests successfully\n");
close(fd);
- fd = open("/dev/gyro_mpu6k", O_RDONLY);
+
+ return OK;
+}
+
+static int
+gyro(int argc, char *argv[])
+{
+ printf("\tGYRO: test start\n");
+ fflush(stdout);
+
+ int fd;
+ struct gyro_report buf;
+ int ret;
+
+ fd = open("/dev/gyro", O_RDONLY);
if (fd < 0) {
- printf("\tMPU6K GYRO: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
+ printf("\tGYRO: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
return ERROR;
}
@@ -200,37 +215,37 @@ mpu6k(int argc, char *argv[])
usleep(5000);
/* read data - expect samples */
- ret = read(fd, &gyro_buf, sizeof(gyro_buf));
+ ret = read(fd, &buf, sizeof(buf));
- if (ret != sizeof(gyro_buf)) {
- printf("\tMPU6K GYRO: read fail (%d)\n", ret);
+ if (ret != sizeof(buf)) {
+ printf("\tGYRO: read fail (%d)\n", ret);
return ERROR;
} else {
- printf("\tMPU6K GYRO rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)gyro_buf.x, (double)gyro_buf.y, (double)gyro_buf.z);
+ printf("\tGYRO rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)buf.x, (double)buf.y, (double)buf.z);
}
/* Let user know everything is ok */
- printf("\tOK: MPU6K GYRO passed all tests successfully\n");
+ printf("\tOK: GYRO passed all tests successfully\n");
close(fd);
return OK;
}
static int
-gyro(int argc, char *argv[])
+gyro1(int argc, char *argv[])
{
- printf("\tGYRO: test start\n");
+ printf("\tGYRO1: test start\n");
fflush(stdout);
int fd;
struct gyro_report buf;
int ret;
- fd = open("/dev/gyro", O_RDONLY);
+ fd = open("/dev/gyro1", O_RDONLY);
if (fd < 0) {
- printf("\tGYRO: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
+ printf("\tGYRO1: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
return ERROR;
}
@@ -241,15 +256,15 @@ gyro(int argc, char *argv[])
ret = read(fd, &buf, sizeof(buf));
if (ret != sizeof(buf)) {
- printf("\tGYRO: read fail (%d)\n", ret);
+ printf("\tGYRO1: read fail (%d)\n", ret);
return ERROR;
} else {
- printf("\tGYRO rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)buf.x, (double)buf.y, (double)buf.z);
+ printf("\tGYRO1 rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)buf.x, (double)buf.y, (double)buf.z);
}
/* Let user know everything is ok */
- printf("\tOK: GYRO passed all tests successfully\n");
+ printf("\tOK: GYRO1 passed all tests successfully\n");
close(fd);
return OK;
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index 06e5d20e6..a57d04be3 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -108,7 +108,7 @@ 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[]);
-extern int test_dataman(int argc, char *argv[]);
+extern int test_rc(int argc, char *argv[]);
__END_DECLS
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 789c9d8b6..30ae5b4ec 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -105,6 +105,7 @@ const struct {
{"bson", test_bson, 0},
{"file", test_file, 0},
{"mixer", test_mixer, OPT_NOJIGTEST | OPT_NOALLTEST},
+ {"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST},
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
{"dataman", test_dataman, OPT_NOALLTEST},
{NULL, NULL, 0}