mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 07:09:48 +08:00
Break test_tone and test_ppm out of the test_hrt.cpp file into their own respective files.
This commit is contained in:
@@ -59,6 +59,7 @@ set(srcs
|
||||
test_param.c
|
||||
test_parameters.cpp
|
||||
test_perf.c
|
||||
test_ppm.cpp
|
||||
test_ppm_loopback.c
|
||||
test_rc.c
|
||||
test_search_min.cpp
|
||||
@@ -66,6 +67,7 @@ set(srcs
|
||||
test_servo.c
|
||||
test_sleep.c
|
||||
test_smooth_z.cpp
|
||||
test_tone.cpp
|
||||
test_uart_baudchange.c
|
||||
test_uart_console.c
|
||||
test_uart_loopback.c
|
||||
|
||||
@@ -36,117 +36,12 @@
|
||||
* Tests the high resolution timer.
|
||||
*/
|
||||
|
||||
#include <px4_config.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <px4_posix.h>
|
||||
#include <sys/types.h>
|
||||
#include <sys/time.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <stdlib.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <time.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_tone_alarm.h>
|
||||
|
||||
#include "tests_main.h"
|
||||
|
||||
|
||||
extern uint16_t ppm_buffer[];
|
||||
extern unsigned ppm_decoded_channels;
|
||||
// extern uint16_t ppm_edge_history[];
|
||||
// extern uint16_t ppm_pulse_history[];
|
||||
|
||||
int test_ppm(int argc, char *argv[])
|
||||
{
|
||||
#ifdef HRT_PPM_CHANNEL
|
||||
unsigned i;
|
||||
|
||||
printf("channels: %u\n", ppm_decoded_channels);
|
||||
|
||||
for (i = 0; i < ppm_decoded_channels; i++) {
|
||||
printf(" %u\n", ppm_buffer[i]);
|
||||
}
|
||||
|
||||
// printf("edges\n");
|
||||
|
||||
// for (i = 0; i < 32; i++) {
|
||||
// printf(" %u\n", ppm_edge_history[i]);
|
||||
// }
|
||||
|
||||
// printf("pulses\n");
|
||||
|
||||
// for (i = 0; i < 32; i++) {
|
||||
// printf(" %u\n", ppm_pulse_history[i]);
|
||||
// }
|
||||
|
||||
fflush(stdout);
|
||||
#else
|
||||
printf("PPM not configured\n");
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
int test_tone(int argc, char *argv[])
|
||||
{
|
||||
int fd, result;
|
||||
unsigned long tone;
|
||||
|
||||
fd = px4_open(TONE_ALARM0_DEVICE_PATH, O_WRONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
printf("failed opening " TONE_ALARM0_DEVICE_PATH "\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
tone = 1;
|
||||
|
||||
if (argc == 2) {
|
||||
tone = atoi(argv[1]);
|
||||
}
|
||||
|
||||
if (tone == 0) {
|
||||
result = px4_ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
|
||||
|
||||
if (result < 0) {
|
||||
printf("failed clearing alarms\n");
|
||||
goto out;
|
||||
|
||||
} else {
|
||||
printf("Alarm stopped.\n");
|
||||
}
|
||||
|
||||
} else {
|
||||
result = px4_ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
|
||||
|
||||
if (result < 0) {
|
||||
printf("failed clearing alarms\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
result = px4_ioctl(fd, TONE_SET_ALARM, tone);
|
||||
|
||||
if (result < 0) {
|
||||
printf("failed setting alarm %lu\n", tone);
|
||||
|
||||
} else {
|
||||
printf("Alarm %lu (disable with: tests tone 0)\n", tone);
|
||||
}
|
||||
}
|
||||
|
||||
out:
|
||||
|
||||
if (fd >= 0) {
|
||||
px4_close(fd);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int test_hrt(int argc, char *argv[])
|
||||
{
|
||||
struct hrt_call call;
|
||||
|
||||
@@ -0,0 +1,78 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2019 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file test_ppm.cpp
|
||||
* Test for ppm channel values.
|
||||
*/
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "tests_main.h"
|
||||
|
||||
|
||||
extern uint16_t ppm_buffer[];
|
||||
extern unsigned ppm_decoded_channels;
|
||||
// extern uint16_t ppm_edge_history[];
|
||||
// extern uint16_t ppm_pulse_history[];
|
||||
|
||||
|
||||
int test_ppm(int argc, char *argv[])
|
||||
{
|
||||
#ifdef HRT_PPM_CHANNEL
|
||||
unsigned i;
|
||||
|
||||
printf("channels: %u\n", ppm_decoded_channels);
|
||||
|
||||
for (i = 0; i < ppm_decoded_channels; i++) {
|
||||
printf(" %u\n", ppm_buffer[i]);
|
||||
}
|
||||
|
||||
// printf("edges\n");
|
||||
|
||||
// for (i = 0; i < 32; i++) {
|
||||
// printf(" %u\n", ppm_edge_history[i]);
|
||||
// }
|
||||
|
||||
// printf("pulses\n");
|
||||
|
||||
// for (i = 0; i < 32; i++) {
|
||||
// printf(" %u\n", ppm_pulse_history[i]);
|
||||
// }
|
||||
|
||||
fflush(stdout);
|
||||
#else
|
||||
printf("PPM not configured\n");
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
@@ -0,0 +1,102 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2019 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.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* @file test_tone.cpp
|
||||
* Test for audio tones.
|
||||
*/
|
||||
|
||||
#include <stdlib.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/drv_tone_alarm.h>
|
||||
#include <px4_posix.h>
|
||||
|
||||
#include "tests_main.h"
|
||||
|
||||
|
||||
int test_tone(int argc, char *argv[])
|
||||
{
|
||||
int fd, result;
|
||||
unsigned long tone;
|
||||
|
||||
fd = px4_open(TONE_ALARM0_DEVICE_PATH, O_WRONLY);
|
||||
|
||||
if (fd < 0) {
|
||||
printf("failed opening " TONE_ALARM0_DEVICE_PATH "\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
tone = 1;
|
||||
|
||||
if (argc == 2) {
|
||||
tone = atoi(argv[1]);
|
||||
}
|
||||
|
||||
if (tone == 0) {
|
||||
result = px4_ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
|
||||
|
||||
if (result < 0) {
|
||||
printf("failed clearing alarms\n");
|
||||
goto out;
|
||||
|
||||
} else {
|
||||
printf("Alarm stopped.\n");
|
||||
}
|
||||
|
||||
} else {
|
||||
result = px4_ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
|
||||
|
||||
if (result < 0) {
|
||||
printf("failed clearing alarms\n");
|
||||
goto out;
|
||||
}
|
||||
|
||||
result = px4_ioctl(fd, TONE_SET_ALARM, tone);
|
||||
|
||||
if (result < 0) {
|
||||
printf("failed setting alarm %lu\n", tone);
|
||||
|
||||
} else {
|
||||
printf("Alarm %lu (disable with: tests tone 0)\n", tone);
|
||||
}
|
||||
}
|
||||
|
||||
out:
|
||||
|
||||
if (fd >= 0) {
|
||||
px4_close(fd);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -51,105 +51,101 @@
|
||||
#define TESTS_EIGEN_DISABLE
|
||||
|
||||
|
||||
static int test_all(int argc, char *argv[]);
|
||||
static int test_help(int argc, char *argv[]);
|
||||
static int test_jig(int argc, char *argv[]);
|
||||
static int test_runner(unsigned option);
|
||||
|
||||
static int test_all(int argc, char *argv[]);
|
||||
static int test_jig(int argc, char *argv[]);
|
||||
|
||||
const struct {
|
||||
const char *name;
|
||||
int (* fn)(int argc, char *argv[]);
|
||||
unsigned options;
|
||||
#define OPT_NOHELP (1<<0)
|
||||
#define OPT_NOALLTEST (1<<1)
|
||||
#define OPT_NOJIGTEST (1<<2)
|
||||
const char *name;
|
||||
int (* fn)(int argc, char *argv[]);
|
||||
unsigned options;
|
||||
#define OPT_NOHELP (1<<0)
|
||||
#define OPT_NOALLTEST (1<<1)
|
||||
#define OPT_NOJIGTEST (1<<2)
|
||||
} tests[] = {
|
||||
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
|
||||
{"all", test_all, OPT_NOALLTEST | OPT_NOJIGTEST},
|
||||
{"jig", test_jig, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"all", test_all, OPT_NOALLTEST | OPT_NOJIGTEST},
|
||||
{"help", test_help, OPT_NOALLTEST | OPT_NOHELP | OPT_NOJIGTEST},
|
||||
{"jig", test_jig, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
#ifdef __PX4_NUTTX
|
||||
{"adc", test_adc, OPT_NOJIGTEST},
|
||||
{"file", test_file, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"led", test_led, 0},
|
||||
{"sensors", test_sensors, 0},
|
||||
{"time", test_time, OPT_NOJIGTEST},
|
||||
{"uart_baudchange", test_uart_baudchange, OPT_NOJIGTEST},
|
||||
{"uart_break", test_uart_break, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"uart_console", test_uart_console, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"adc", test_adc, OPT_NOJIGTEST},
|
||||
{"file", test_file, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"led", test_led, 0},
|
||||
{"sensors", test_sensors, 0},
|
||||
{"time", test_time, OPT_NOJIGTEST},
|
||||
{"uart_baudchange", test_uart_baudchange, OPT_NOJIGTEST},
|
||||
{"uart_break", test_uart_break, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"uart_console", test_uart_console, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
#else
|
||||
{"rc", rc_tests_main, 0},
|
||||
{"mavlink", mavlink_tests_main, 0},
|
||||
{"rc", rc_tests_main, 0},
|
||||
#endif /* __PX4_NUTTX */
|
||||
|
||||
/* external tests */
|
||||
{"commander", commander_tests_main, 0},
|
||||
{"controllib", controllib_test_main, 0},
|
||||
#ifndef __PX4_NUTTX
|
||||
{"mavlink", mavlink_tests_main, 0},
|
||||
#endif
|
||||
{"sf0x", sf0x_tests_main, 0},
|
||||
{"uorb", uorb_tests_main, 0},
|
||||
{"hysteresis", test_hysteresis, 0},
|
||||
{"commander", commander_tests_main, 0},
|
||||
{"controllib", controllib_test_main, 0},
|
||||
{"sf0x", sf0x_tests_main, 0},
|
||||
{"uorb", uorb_tests_main, 0},
|
||||
|
||||
{"mixer", test_mixer, OPT_NOJIGTEST},
|
||||
{"autodeclination", test_autodeclination, 0},
|
||||
{"bezier", test_bezierQuad, 0},
|
||||
{"bson", test_bson, 0},
|
||||
{"conv", test_conv, 0},
|
||||
{"dataman", test_dataman, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"file2", test_file2, OPT_NOJIGTEST},
|
||||
{"float", test_float, 0},
|
||||
{"hott_telemetry", test_hott_telemetry, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"hrt", test_hrt, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"int", test_int, 0},
|
||||
{"jig_voltages", test_jig_voltages, OPT_NOALLTEST},
|
||||
{"mathlib", test_mathlib, 0},
|
||||
{"matrix", test_matrix, 0},
|
||||
{"microbench_hrt", test_microbench_hrt, 0},
|
||||
{"microbench_math", test_microbench_math, 0},
|
||||
{"microbench_matrix", test_microbench_matrix, 0},
|
||||
{"microbench_uorb", test_microbench_uorb, 0},
|
||||
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"param", test_param, 0},
|
||||
{"parameters", test_parameters, 0},
|
||||
{"perf", test_perf, OPT_NOJIGTEST},
|
||||
{"ppm", test_ppm, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"ppm_loopback", test_ppm_loopback, OPT_NOALLTEST},
|
||||
{"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"search_min", test_search_min, 0},
|
||||
{"servo", test_servo, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"sleep", test_sleep, OPT_NOJIGTEST},
|
||||
{"tone", test_tone, 0},
|
||||
{"uart_loopback", test_uart_loopback, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"uart_send", test_uart_send, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"versioning", test_versioning, 0},
|
||||
{"ctlmath", test_controlmath, 0},
|
||||
{"smoothz", test_smooth_z, 0},
|
||||
{NULL, NULL, 0}
|
||||
{"autodeclination", test_autodeclination, 0},
|
||||
{"bezier", test_bezierQuad, 0},
|
||||
{"bson", test_bson, 0},
|
||||
{"conv", test_conv, 0},
|
||||
{"ctlmath", test_controlmath, 0},
|
||||
{"dataman", test_dataman, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"file2", test_file2, OPT_NOJIGTEST},
|
||||
{"float", test_float, 0},
|
||||
{"hott_telemetry", test_hott_telemetry, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"hrt", test_hrt, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"hysteresis", test_hysteresis, 0},
|
||||
{"int", test_int, 0},
|
||||
{"jig_voltages", test_jig_voltages, OPT_NOALLTEST},
|
||||
{"mathlib", test_mathlib, 0},
|
||||
{"matrix", test_matrix, 0},
|
||||
{"microbench_hrt", test_microbench_hrt, 0},
|
||||
{"microbench_math", test_microbench_math, 0},
|
||||
{"microbench_matrix", test_microbench_matrix, 0},
|
||||
{"microbench_uorb", test_microbench_uorb, 0},
|
||||
{"mixer", test_mixer, OPT_NOJIGTEST},
|
||||
{"mount", test_mount, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"param", test_param, 0},
|
||||
{"parameters", test_parameters, 0},
|
||||
{"perf", test_perf, OPT_NOJIGTEST},
|
||||
{"ppm", test_ppm, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"ppm_loopback", test_ppm_loopback, OPT_NOALLTEST},
|
||||
{"rc", test_rc, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"search_min", test_search_min, 0},
|
||||
{"servo", test_servo, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"sleep", test_sleep, OPT_NOJIGTEST},
|
||||
{"smooth_z", test_smooth_z, 0},
|
||||
{"tone", test_tone, 0},
|
||||
{"uart_loopback", test_uart_loopback, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"uart_send", test_uart_send, OPT_NOJIGTEST | OPT_NOALLTEST},
|
||||
{"versioning", test_versioning, 0},
|
||||
{NULL, NULL, 0}
|
||||
};
|
||||
|
||||
#define NTESTS (sizeof(tests) / sizeof(tests[0]))
|
||||
|
||||
static int
|
||||
test_all(int argc, char *argv[])
|
||||
{
|
||||
return test_runner(OPT_NOALLTEST);
|
||||
}
|
||||
|
||||
static int
|
||||
test_help(int argc, char *argv[])
|
||||
{
|
||||
unsigned i;
|
||||
|
||||
printf("Available tests:\n");
|
||||
|
||||
for (i = 0; tests[i].name; i++) {
|
||||
for (size_t i = 0; tests[i].name; i++) {
|
||||
printf(" %s\n", tests[i].name);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int
|
||||
test_all(int argc, char *argv[])
|
||||
{
|
||||
return test_runner(OPT_NOALLTEST);
|
||||
}
|
||||
|
||||
static int
|
||||
test_jig(int argc, char *argv[])
|
||||
{
|
||||
@@ -159,11 +155,11 @@ test_jig(int argc, char *argv[])
|
||||
static int
|
||||
test_runner(unsigned option)
|
||||
{
|
||||
unsigned i;
|
||||
char *args[2] = {"all", NULL};
|
||||
size_t i = 0;
|
||||
char *args[2] = {"all", NULL};
|
||||
unsigned int failcount = 0;
|
||||
unsigned int testcount = 0;
|
||||
unsigned passed[NTESTS];
|
||||
unsigned passed[NTESTS] = {};
|
||||
|
||||
printf("\nRunning all tests...\n\n");
|
||||
|
||||
@@ -262,7 +258,7 @@ int tests_main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
for (unsigned i = 0; tests[i].name; i++) {
|
||||
for (size_t i = 0; tests[i].name; i++) {
|
||||
if (!strcmp(tests[i].name, argv[1])) {
|
||||
if (tests[i].fn(argc - 1, argv + 1) == 0) {
|
||||
printf("%s PASSED\n", tests[i].name);
|
||||
|
||||
Reference in New Issue
Block a user