aboutsummaryrefslogtreecommitdiff
path: root/src/systemcmds
diff options
context:
space:
mode:
Diffstat (limited to 'src/systemcmds')
-rw-r--r--src/systemcmds/preflight_check/preflight_check.c2
-rw-r--r--src/systemcmds/pwm/pwm.c2
-rw-r--r--src/systemcmds/tests/module.mk6
-rw-r--r--src/systemcmds/tests/test_dataman.c182
-rw-r--r--src/systemcmds/tests/test_file.c (renamed from src/systemcmds/tests/tests_file.c)2
-rw-r--r--src/systemcmds/tests/test_param.c (renamed from src/systemcmds/tests/tests_param.c)2
-rw-r--r--src/systemcmds/tests/test_ppm_loopback.c178
-rw-r--r--src/systemcmds/tests/test_rc.c146
-rw-r--r--src/systemcmds/tests/test_sensors.c107
-rw-r--r--src/systemcmds/tests/test_servo.c66
-rw-r--r--src/systemcmds/tests/test_uart_loopback.c70
-rw-r--r--src/systemcmds/tests/tests.h10
-rw-r--r--src/systemcmds/tests/tests_main.c15
13 files changed, 665 insertions, 123 deletions
diff --git a/src/systemcmds/preflight_check/preflight_check.c b/src/systemcmds/preflight_check/preflight_check.c
index 07581459b..982b03782 100644
--- a/src/systemcmds/preflight_check/preflight_check.c
+++ b/src/systemcmds/preflight_check/preflight_check.c
@@ -200,7 +200,7 @@ system_eval:
led_toggle(leds, LED_BLUE);
/* display and sound error */
- for (int i = 0; i < 50; i++)
+ for (int i = 0; i < 14; i++)
{
led_toggle(leds, LED_BLUE);
led_toggle(leds, LED_AMBER);
diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c
index 898c04cd5..7c23f38c2 100644
--- a/src/systemcmds/pwm/pwm.c
+++ b/src/systemcmds/pwm/pwm.c
@@ -210,7 +210,7 @@ pwm_main(int argc, char *argv[])
err(1, "PWM_SERVO_GET_COUNT");
if (!strcmp(argv[1], "arm")) {
- /* tell IO that its ok to disable its safety with the switch */
+ /* tell safety that its ok to disable it with the switch */
ret = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
if (ret != OK)
err(1, "PWM_SERVO_SET_ARM_OK");
diff --git a/src/systemcmds/tests/module.mk b/src/systemcmds/tests/module.mk
index 6729ce4ae..68a080c77 100644
--- a/src/systemcmds/tests/module.mk
+++ b/src/systemcmds/tests/module.mk
@@ -24,6 +24,8 @@ SRCS = test_adc.c \
test_uart_loopback.c \
test_uart_send.c \
test_mixer.cpp \
- tests_file.c \
+ test_file.c \
tests_main.c \
- tests_param.c
+ test_param.c \
+ test_ppm_loopback.c \
+ test_rc.c
diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c
new file mode 100644
index 000000000..5b121e34e
--- /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, 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, 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, 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, i, buffer, sizeof(buffer)) != 0) {
+ warnx("Restart power-on failed");
+ return -1;
+ }
+ }
+ return 0;
+}
diff --git a/src/systemcmds/tests/tests_file.c b/src/systemcmds/tests/test_file.c
index 7f3a654bf..798724cf1 100644
--- a/src/systemcmds/tests/tests_file.c
+++ b/src/systemcmds/tests/test_file.c
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file tests_file.c
+ * @file test_file.c
*
* File write test.
*/
diff --git a/src/systemcmds/tests/tests_param.c b/src/systemcmds/tests/test_param.c
index 13f17bc43..318d2505b 100644
--- a/src/systemcmds/tests/tests_param.c
+++ b/src/systemcmds/tests/test_param.c
@@ -32,7 +32,7 @@
****************************************************************************/
/**
- * @file tests_param.c
+ * @file test_param.c
*
* Tests related to the parameter system.
*/
diff --git a/src/systemcmds/tests/test_ppm_loopback.c b/src/systemcmds/tests/test_ppm_loopback.c
new file mode 100644
index 000000000..b9041b013
--- /dev/null
+++ b/src/systemcmds/tests/test_ppm_loopback.c
@@ -0,0 +1,178 @@
+/****************************************************************************
+ *
+ * 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 <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 <uORB/topics/rc_channels.h>
+#include <systemlib/err.h>
+
+#include "tests.h"
+
+#include <math.h>
+#include <float.h>
+
+int test_ppm_loopback(int argc, char *argv[])
+{
+
+ int _rc_sub = orb_subscribe(ORB_ID(input_rc));
+
+ int servo_fd, result;
+ servo_position_t data[PWM_OUTPUT_MAX_CHANNELS];
+ servo_position_t pos;
+
+ servo_fd = open(PWM_OUTPUT_DEVICE_PATH, O_RDWR);
+
+ if (servo_fd < 0) {
+ printf("failed opening /dev/pwm_servo\n");
+ }
+
+ printf("Servo readback, pairs of values should match defaults\n");
+
+ unsigned servo_count;
+ result = ioctl(servo_fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count);
+ if (result != OK) {
+ warnx("PWM_SERVO_GET_COUNT");
+ return ERROR;
+ }
+
+ for (unsigned i = 0; i < servo_count; i++) {
+ result = ioctl(servo_fd, PWM_SERVO_GET(i), (unsigned long)&pos);
+
+ if (result < 0) {
+ printf("failed reading channel %u\n", i);
+ }
+
+ //printf("%u: %u %u\n", i, pos, data[i]);
+
+ }
+
+ // /* tell safety that its ok to disable it with the switch */
+ // result = ioctl(servo_fd, PWM_SERVO_SET_ARM_OK, 0);
+ // if (result != OK)
+ // warnx("FAIL: PWM_SERVO_SET_ARM_OK");
+ // tell output device that the system is armed (it will output values if safety is off)
+ // result = ioctl(servo_fd, PWM_SERVO_ARM, 0);
+ // if (result != OK)
+ // warnx("FAIL: PWM_SERVO_ARM");
+
+ int pwm_values[] = {1200, 1300, 1900, 1700, 1500, 1250, 1800, 1400};
+
+
+ // for (unsigned i = 0; (i < servo_count) && (i < sizeof(pwm_values) / sizeof(pwm_values[0])); i++) {
+ // result = ioctl(servo_fd, PWM_SERVO_SET(i), pwm_values[i]);
+
+ // if (result) {
+ // (void)close(servo_fd);
+ // return ERROR;
+ // } else {
+ // warnx("channel %d set to %d", i, pwm_values[i]);
+ // }
+ // }
+
+ warnx("servo count: %d", servo_count);
+
+ struct pwm_output_values pwm_out = {.values = {0}, .channel_count = 0};
+
+ for (unsigned i = 0; (i < servo_count) && (i < sizeof(pwm_values) / sizeof(pwm_values[0])); i++) {
+ pwm_out.values[i] = pwm_values[i];
+ //warnx("channel %d: disarmed PWM: %d", i+1, pwm_values[i]);
+ pwm_out.channel_count++;
+ }
+
+ result = ioctl(servo_fd, PWM_SERVO_SET_DISARMED_PWM, (long unsigned int)&pwm_out);
+
+ /* give driver 10 ms to propagate */
+
+ /* read low-level values from FMU or IO RC inputs (PPM, Spektrum, S.Bus) */
+ struct rc_input_values rc_input;
+ 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);
+
+ if (rc_updated) {
+
+ orb_copy(ORB_ID(input_rc), _rc_sub, &rc_input);
+
+ // int ppm_fd = open(RC_INPUT_DEVICE_PATH, O_RDONLY);
+
+
+
+ // struct rc_input_values rc;
+ // result = read(ppm_fd, &rc, sizeof(rc));
+
+ // if (result != sizeof(rc)) {
+ // warnx("Error reading RC output");
+ // (void)close(servo_fd);
+ // (void)close(ppm_fd);
+ // return ERROR;
+ // }
+
+ /* go and check values */
+ for (unsigned i = 0; (i < servo_count) && (i < sizeof(pwm_values) / sizeof(pwm_values[0])); i++) {
+ if (fabsf(rc_input.values[i] - pwm_values[i]) > 10) {
+ warnx("comparison fail: RC: %d, expected: %d", rc_input.values[i], pwm_values[i]);
+ (void)close(servo_fd);
+ return ERROR;
+ }
+ }
+ } else {
+ warnx("failed reading RC input data");
+ return ERROR;
+ }
+
+ warnx("PPM LOOPBACK TEST PASSED SUCCESSFULLY!");
+
+ return 0;
+}
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 14503276c..096106ff3 100644
--- a/src/systemcmds/tests/test_sensors.c
+++ b/src/systemcmds/tests/test_sensors.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * 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
@@ -49,6 +48,8 @@
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
+#include <math.h>
+#include <systemlib/err.h>
#include <arch/board/board.h>
@@ -77,6 +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 accel1(int argc, char *argv[]);
+static int gyro1(int argc, char *argv[]);
/****************************************************************************
* Private Data
@@ -91,6 +94,8 @@ struct {
{"gyro", "/dev/gyro", gyro},
{"mag", "/dev/mag", mag},
{"baro", "/dev/baro", baro},
+ {"accel1", "/dev/accel1", accel1},
+ {"gyro1", "/dev/gyro1", gyro1},
{NULL, NULL, NULL}
};
@@ -133,23 +138,58 @@ accel(int argc, char *argv[])
printf("\tACCEL accel: x:%8.4f\ty:%8.4f\tz:%8.4f m/s^2\n", (double)buf.x, (double)buf.y, (double)buf.z);
}
- // /* wait at least 10ms, sensor should have data after no more than 2ms */
- // usleep(100000);
+ if (fabsf(buf.x) > 30.0f || fabsf(buf.y) > 30.0f || fabsf(buf.z) > 30.0f) {
+ warnx("ACCEL1 acceleration values out of range!");
+ return ERROR;
+ }
+
+ /* Let user know everything is ok */
+ printf("\tOK: ACCEL passed all tests successfully\n");
+ close(fd);
+
+ return OK;
+}
+
+static int
+accel1(int argc, char *argv[])
+{
+ printf("\tACCEL1: test start\n");
+ fflush(stdout);
+
+ int fd;
+ struct accel_report buf;
+ int ret;
- // ret = read(fd, buf, sizeof(buf));
+ fd = open("/dev/accel1", O_RDONLY);
- // if (ret != sizeof(buf)) {
- // printf("\tMPU-6000: read2 fail (%d)\n", ret);
- // return ERROR;
+ if (fd < 0) {
+ printf("\tACCEL1: open fail, run <mpu6000 start> or <lsm303d start> first.\n");
+ return ERROR;
+ }
+
+ /* wait at least 100ms, sensor should have data after no more than 20ms */
+ usleep(100000);
+
+ /* read data - expect samples */
+ ret = read(fd, &buf, sizeof(buf));
+
+ if (ret != sizeof(buf)) {
+ printf("\tACCEL1: read1 fail (%d)\n", ret);
+ return ERROR;
- // } else {
- // printf("\tMPU-6000 values: acc: x:%d\ty:%d\tz:%d\tgyro: r:%d\tp:%d\ty:%d\n", buf[0], buf[1], buf[2], buf[3], buf[4], buf[5]);
- // }
+ } else {
+ 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);
+ }
- /* XXX more tests here */
+ if (fabsf(buf.x) > 30.0f || fabsf(buf.y) > 30.0f || fabsf(buf.z) > 30.0f) {
+ warnx("ACCEL1 acceleration values out of range!");
+ return ERROR;
+ }
/* Let user know everything is ok */
- printf("\tOK: ACCEL passed all tests successfully\n");
+ printf("\tOK: ACCEL1 passed all tests successfully\n");
+
+ close(fd);
return OK;
}
@@ -187,6 +227,45 @@ gyro(int argc, char *argv[])
/* Let user know everything is ok */
printf("\tOK: GYRO passed all tests successfully\n");
+ close(fd);
+
+ return OK;
+}
+
+static int
+gyro1(int argc, char *argv[])
+{
+ printf("\tGYRO1: test start\n");
+ fflush(stdout);
+
+ int fd;
+ struct gyro_report buf;
+ int ret;
+
+ fd = open("/dev/gyro1", O_RDONLY);
+
+ if (fd < 0) {
+ printf("\tGYRO1: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
+ return ERROR;
+ }
+
+ /* wait at least 5 ms, sensor should have data after that */
+ usleep(5000);
+
+ /* read data - expect samples */
+ ret = read(fd, &buf, sizeof(buf));
+
+ if (ret != sizeof(buf)) {
+ printf("\tGYRO1: read fail (%d)\n", ret);
+ return ERROR;
+
+ } else {
+ 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: GYRO1 passed all tests successfully\n");
+ close(fd);
return OK;
}
@@ -224,6 +303,7 @@ mag(int argc, char *argv[])
/* Let user know everything is ok */
printf("\tOK: MAG passed all tests successfully\n");
+ close(fd);
return OK;
}
@@ -261,6 +341,7 @@ baro(int argc, char *argv[])
/* Let user know everything is ok */
printf("\tOK: BARO passed all tests successfully\n");
+ close(fd);
return OK;
}
diff --git a/src/systemcmds/tests/test_servo.c b/src/systemcmds/tests/test_servo.c
index f95760ca8..ef8512bf5 100644
--- a/src/systemcmds/tests/test_servo.c
+++ b/src/systemcmds/tests/test_servo.c
@@ -1,7 +1,6 @@
/****************************************************************************
- * px4/sensors/test_hrt.c
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -13,7 +12,7 @@
* 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
+ * 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.
*
@@ -32,9 +31,11 @@
*
****************************************************************************/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+/**
+ * @file test_servo.c
+ * Tests the servo outputs
+ *
+ */
#include <nuttx/config.h>
@@ -55,39 +56,6 @@
#include "tests.h"
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: test_servo
- ****************************************************************************/
-
int test_servo(int argc, char *argv[])
{
int fd, result;
@@ -110,7 +78,14 @@ int test_servo(int argc, char *argv[])
printf("Servo readback, pairs of values should match defaults\n");
- for (unsigned i = 0; i < PWM_OUTPUT_MAX_CHANNELS; i++) {
+ unsigned servo_count;
+ result = ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count);
+ if (result != OK) {
+ warnx("PWM_SERVO_GET_COUNT");
+ return ERROR;
+ }
+
+ for (unsigned i = 0; i < servo_count; i++) {
result = ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&pos);
if (result < 0) {
@@ -122,11 +97,20 @@ int test_servo(int argc, char *argv[])
}
- printf("Servos arming at default values\n");
+ /* tell safety that its ok to disable it with the switch */
+ result = ioctl(fd, PWM_SERVO_SET_ARM_OK, 0);
+ if (result != OK)
+ warnx("FAIL: PWM_SERVO_SET_ARM_OK");
+ /* tell output device that the system is armed (it will output values if safety is off) */
result = ioctl(fd, PWM_SERVO_ARM, 0);
+ if (result != OK)
+ warnx("FAIL: PWM_SERVO_ARM");
+
usleep(5000000);
printf("Advancing channel 0 to 1500\n");
result = ioctl(fd, PWM_SERVO_SET(0), 1500);
+ printf("Advancing channel 1 to 1800\n");
+ result = ioctl(fd, PWM_SERVO_SET(1), 1800);
out:
return 0;
}
diff --git a/src/systemcmds/tests/test_uart_loopback.c b/src/systemcmds/tests/test_uart_loopback.c
index 3be152004..f1d41739b 100644
--- a/src/systemcmds/tests/test_uart_loopback.c
+++ b/src/systemcmds/tests/test_uart_loopback.c
@@ -1,8 +1,6 @@
/****************************************************************************
- * px4/sensors/test_gpio.c
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Lorenz Meier <lm@inf.ethz.ch>
+ * 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
@@ -14,7 +12,7 @@
* 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
+ * 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.
*
@@ -33,9 +31,11 @@
*
****************************************************************************/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+/**
+ * @file test_uart_loopback.c
+ * Tests the uart outputs
+ *
+ */
#include <nuttx/config.h>
@@ -55,40 +55,6 @@
#include <math.h>
#include <float.h>
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: test_led
- ****************************************************************************/
-
int test_uart_loopback(int argc, char *argv[])
{
@@ -97,11 +63,11 @@ int test_uart_loopback(int argc, char *argv[])
int uart5_nwrite = 0;
int uart2_nwrite = 0;
- int uart1 = open("/dev/ttyS0", O_RDWR | O_NOCTTY); //
+ /* opening stdout */
+ int stdout_fd = 1;
- /* assuming NuttShell is on UART1 (/dev/ttyS0) */
- int uart2 = open("/dev/ttyS1", O_RDWR | O_NONBLOCK | O_NOCTTY); //
- int uart5 = open("/dev/ttyS2", O_RDWR | O_NONBLOCK | O_NOCTTY); //
+ int uart2 = open("/dev/ttyS1", O_RDWR | O_NONBLOCK | O_NOCTTY);
+ int uart5 = open("/dev/ttyS2", O_RDWR | O_NONBLOCK | O_NOCTTY);
if (uart2 < 0) {
printf("ERROR opening UART2, aborting..\n");
@@ -113,7 +79,7 @@ int test_uart_loopback(int argc, char *argv[])
exit(uart5);
}
- uint8_t sample_uart1[] = {'C', 'O', 'U', 'N', 'T', ' ', '#', '\n'};
+ uint8_t sample_stdout_fd[] = {'C', 'O', 'U', 'N', 'T', ' ', '#', '\n'};
uint8_t sample_uart2[] = {'C', 'O', 'U', 'N', 'T', ' ', '#', 0};
uint8_t sample_uart5[] = {'C', 'O', 'U', 'N', 'T', ' ', '#', 0};
@@ -121,7 +87,7 @@ int test_uart_loopback(int argc, char *argv[])
for (i = 0; i < 1000; i++) {
// printf("TEST #%d\n",i);
- write(uart1, sample_uart1, sizeof(sample_uart1));
+ write(stdout_fd, sample_stdout_fd, sizeof(sample_stdout_fd));
/* uart2 -> uart5 */
r = write(uart2, sample_uart2, sizeof(sample_uart2));
@@ -130,7 +96,7 @@ int test_uart_loopback(int argc, char *argv[])
uart2_nwrite += r;
// printf("TEST #%d\n",i);
- write(uart1, sample_uart1, sizeof(sample_uart1));
+ write(stdout_fd, sample_stdout_fd, sizeof(sample_stdout_fd));
/* uart2 -> uart5 */
r = write(uart5, sample_uart5, sizeof(sample_uart5));
@@ -139,7 +105,7 @@ int test_uart_loopback(int argc, char *argv[])
uart5_nwrite += r;
// printf("TEST #%d\n",i);
- write(uart1, sample_uart1, sizeof(sample_uart1));
+ write(stdout_fd, sample_stdout_fd, sizeof(sample_stdout_fd));
/* try to read back values */
do {
@@ -150,7 +116,7 @@ int test_uart_loopback(int argc, char *argv[])
} while (r > 0);
// printf("TEST #%d\n",i);
- write(uart1, sample_uart1, sizeof(sample_uart1));
+ write(stdout_fd, sample_stdout_fd, sizeof(sample_stdout_fd));
do {
r = read(uart2, sample_uart5, sizeof(sample_uart5));
@@ -160,7 +126,7 @@ int test_uart_loopback(int argc, char *argv[])
} while (r > 0);
// printf("TEST #%d\n",i);
-// write(uart1, sample_uart1, sizeof(sample_uart5));
+// write(stdout_fd, sample_stdout_fd, sizeof(sample_uart5));
}
for (i = 0; i < 200000; i++) {
@@ -181,7 +147,7 @@ int test_uart_loopback(int argc, char *argv[])
}
- close(uart1);
+ close(stdout_fd);
close(uart2);
close(uart5);
diff --git a/src/systemcmds/tests/tests.h b/src/systemcmds/tests/tests.h
index c483108cf..a57d04be3 100644
--- a/src/systemcmds/tests/tests.h
+++ b/src/systemcmds/tests/tests.h
@@ -1,6 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * 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
@@ -34,6 +34,12 @@
#ifndef __APPS_PX4_TESTS_H
#define __APPS_PX4_TESTS_H
+/**
+ * @file tests.h
+ * Tests declaration file.
+ *
+ */
+
/****************************************************************************
* Included Files
****************************************************************************/
@@ -88,6 +94,7 @@ extern int test_int(int argc, char *argv[]);
extern int test_float(int argc, char *argv[]);
extern int test_ppm(int argc, char *argv[]);
extern int test_servo(int argc, char *argv[]);
+extern int test_ppm_loopback(int argc, char *argv[]);
extern int test_uart_loopback(int argc, char *argv[]);
extern int test_uart_baudchange(int argc, char *argv[]);
extern int test_cpuload(int argc, char *argv[]);
@@ -101,6 +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_rc(int argc, char *argv[]);
__END_DECLS
diff --git a/src/systemcmds/tests/tests_main.c b/src/systemcmds/tests/tests_main.c
index 9eb9c632e..1088a4407 100644
--- a/src/systemcmds/tests/tests_main.c
+++ b/src/systemcmds/tests/tests_main.c
@@ -1,7 +1,6 @@
/****************************************************************************
*
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * 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
@@ -35,6 +34,8 @@
/**
* @file tests_main.c
* Tests main file, loads individual tests.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
*/
#include <nuttx/config.h>
@@ -58,14 +59,6 @@
#include "tests.h"
/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
* Private Function Prototypes
****************************************************************************/
@@ -94,6 +87,7 @@ const struct {
{"hrt", test_hrt, OPT_NOJIGTEST | OPT_NOALLTEST},
{"ppm", test_ppm, OPT_NOJIGTEST | OPT_NOALLTEST},
{"servo", test_servo, OPT_NOJIGTEST | OPT_NOALLTEST},
+ {"ppm_loopback", test_ppm_loopback, OPT_NOALLTEST},
{"adc", test_adc, OPT_NOJIGTEST},
{"jig_voltages", test_jig_voltages, OPT_NOALLTEST},
{"uart_loopback", test_uart_loopback, OPT_NOJIGTEST | OPT_NOALLTEST},
@@ -111,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},
{NULL, NULL, 0}
};