systemcmds/tests: split out microbenchmarks and remove obsolete tests

- reorganize Jenkins HIL tests
This commit is contained in:
Daniel Agar
2021-07-18 11:09:49 -04:00
parent 0101934f47
commit 774ad80ba0
41 changed files with 653 additions and 835 deletions
+330 -397
View File
File diff suppressed because it is too large Load Diff
+2 -2
View File
@@ -61,7 +61,7 @@ def do_nsh_cmd(port, baudrate, cmd):
# run command
timeout_start = time.time()
timeout = 2 # 2 seconds
timeout = 1 # 1 second
success_cmd = "cmd succeeded!"
@@ -84,7 +84,7 @@ def do_nsh_cmd(port, baudrate, cmd):
timeout_start = time.time()
timeout = 30 # 30 seconds
timeout = 180 # 3 minutes
while True:
serial_line = ser.readline().decode("ascii", errors='ignore')
+19 -19
View File
@@ -91,7 +91,7 @@ def do_test(port, baudrate, test_name):
# print results, wait for final result (PASSED or FAILED)
timeout = 180 # 3 minutes
timeout = 300 # 5 minutes
timeout_start = time.time()
timeout_newline = timeout_start
@@ -139,15 +139,30 @@ class TestHardwareMethods(unittest.TestCase):
def test_bson(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "bson"))
# def test_dataman(self):
# self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "dataman"))
def test_conv(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "conv"))
def floattest_float(self):
def test_dataman(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "dataman"))
# def test_file(self):
# self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "file"))
def test_file2(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "file2"))
def test_float(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "float"))
def test_hrt(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "hrt"))
def test_int(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "int"))
def test_i2c_spi_cli(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "i2c_spi_cli"))
def test_IntrusiveQueue(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "IntrusiveQueue"))
@@ -163,21 +178,6 @@ class TestHardwareMethods(unittest.TestCase):
def test_matrix(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "matrix"))
def test_microbench_atomic(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "microbench_atomic"))
def test_microbench_hrt(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "microbench_hrt"))
def test_microbench_math(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "microbench_math"))
def test_microbench_matrix(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "microbench_matrix"))
def test_microbench_uorb(self):
self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "microbench_uorb"))
# def test_mixer(self):
# self.assertTrue(do_test(self.TEST_DEVICE, self.TEST_BAUDRATE, "mixer"))
+1
View File
@@ -102,6 +102,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -103,6 +103,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -100,6 +100,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -98,6 +98,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -98,6 +98,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -102,6 +102,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -95,6 +95,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -100,6 +100,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -94,6 +94,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -97,6 +97,7 @@ px4_add_board(
#i2cdetect
#led_control
mft
microbench
mixer
#motor_ramp
#motor_test
+1
View File
@@ -101,6 +101,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -100,6 +100,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -100,6 +100,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1 -1
View File
@@ -69,7 +69,7 @@ px4_add_board(
flight_mode_manager
fw_att_control
fw_pos_control_l1
gyro_calibration
#gyro_calibration
#gyro_fft
land_detector
#landing_target_estimator
+1
View File
@@ -107,6 +107,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
#motor_ramp
motor_test
+2 -2
View File
@@ -71,8 +71,8 @@ px4_add_board(
flight_mode_manager
fw_att_control
fw_pos_control_l1
gyro_calibration
gyro_fft
#gyro_calibration
#gyro_fft
land_detector
#landing_target_estimator
load_mon
+1
View File
@@ -101,6 +101,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -103,6 +103,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+1
View File
@@ -99,6 +99,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_ramp
motor_test
+2 -1
View File
@@ -73,7 +73,7 @@ px4_add_board(
land_detector
landing_target_estimator
load_mon
local_position_estimator
#local_position_estimator
logger
mavlink
mc_att_control
@@ -100,6 +100,7 @@ px4_add_board(
i2cdetect
led_control
mft
microbench
mixer
motor_test
mtd
-6
View File
@@ -19,17 +19,11 @@ set(tests
List
mathlib
matrix
microbench_atomic
microbench_hrt
microbench_math
microbench_matrix
microbench_uorb
mixer
param
parameters
perf
search_min
servo
sleep
versioning
)
@@ -36,7 +36,7 @@ include_directories(${PX4_SOURCE_DIR}/mavlink/include/mavlink)
px4_add_module(
MODULE modules__mavlink__mavlink_tests
MAIN mavlink_tests
STACK_MAIN 5000
STACK_MAIN 8192
COMPILE_FLAGS
-DMAVLINK_FTP_UNIT_TEST
#-DMAVLINK_FTP_DEBUG
+53
View File
@@ -0,0 +1,53 @@
############################################################################
#
# Copyright (c) 2015-2021 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.
#
############################################################################
px4_add_module(
MODULE systemcmds__microbench
MAIN microbench
STACK_MAIN 4096
COMPILE_FLAGS
-Wno-double-promotion
-Wno-unused-but-set-variable
-Wno-unused-variable
-Wno-write-strings
SRCS
microbench_main.cpp
test_microbench_atomic.cpp
test_microbench_hrt.cpp
test_microbench_math.cpp
test_microbench_matrix.cpp
test_microbench_uorb.cpp
DEPENDS
)
@@ -0,0 +1,167 @@
/****************************************************************************
*
* Copyright (C) 2015-2021 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.
*
****************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/log.h>
#include <stdio.h>
#include <string.h>
#include <fcntl.h>
#include <errno.h>
__BEGIN_DECLS
extern int test_microbench_atomic(int argc, char *argv[]);
extern int test_microbench_hrt(int argc, char *argv[]);
extern int test_microbench_math(int argc, char *argv[]);
extern int test_microbench_matrix(int argc, char *argv[]);
extern int test_microbench_uorb(int argc, char *argv[]);
__END_DECLS
static int microbench_help(int argc, char *argv[]);
static int microbench_all(int argc, char *argv[]);
static int microbench_runner(unsigned option);
const struct {
const char *name;
int (* fn)(int argc, char *argv[]);
unsigned options;
#define OPT_NOHELP (1<<0)
#define OPT_NOALLTEST (1<<1)
} microbenchmarks[] = {
{"help", microbench_help, OPT_NOALLTEST | OPT_NOHELP},
{"all", microbench_all, OPT_NOALLTEST},
{"microbench_atomic", test_microbench_atomic, 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},
{NULL, NULL, 0}
};
#define NMICROBENCHMARKS (sizeof(microbenchmarks) / sizeof(microbenchmarks[0]))
static int microbench_help(int argc, char *argv[])
{
printf("Available tests:\n");
for (int i = 0; microbenchmarks[i].name; i++) {
printf(" %s\n", microbenchmarks[i].name);
}
return 0;
}
static int microbench_all(int argc, char *argv[])
{
return microbench_runner(OPT_NOALLTEST);
}
static int microbench_runner(unsigned option)
{
size_t i;
char *args[2] = {"all", NULL};
unsigned int failcount = 0;
unsigned int testcount = 0;
unsigned int passed[NMICROBENCHMARKS];
printf("\nRunning all microbenchmarks...\n\n");
for (i = 0; microbenchmarks[i].name; i++) {
// Only run tests that are not excluded.
if (!(microbenchmarks[i].options & option)) {
for (int j = 0; j < 80; j++) {
printf("-");
}
printf("\n [%s] \t\tSTARTING TEST\n", microbenchmarks[i].name);
fflush(stdout);
/* Execute test */
if (microbenchmarks[i].fn(1, args) != 0) {
fprintf(stderr, " [%s] \t\tFAIL\n", microbenchmarks[i].name);
fflush(stderr);
failcount++;
passed[i] = 0;
} else {
printf(" [%s] \t\tPASS\n", microbenchmarks[i].name);
fflush(stdout);
passed[i] = 1;
}
for (int j = 0; j < 80; j++) {
printf("-");
}
testcount++;
printf("\n\n");
}
}
for (size_t k = 0; k < i; k++) {
if (!passed[k] && !(microbenchmarks[k].options & option)) {
printf(" [%s] to obtain details, please re-run with\n\t nsh> microbench %s\n\n", microbenchmarks[k].name,
microbenchmarks[k].name);
}
}
return 0;
}
extern "C" __EXPORT int microbench_main(int argc, char *argv[])
{
if (argc < 2) {
PX4_WARN("missing test name - 'microbench help' for a list of tests");
return 1;
}
for (size_t i = 0; microbenchmarks[i].name; i++) {
if (!strcmp(microbenchmarks[i].name, argv[1])) {
if (microbenchmarks[i].fn(argc - 1, argv + 1) == 0) {
PX4_INFO("%s PASSED", microbenchmarks[i].name);
return 0;
} else {
PX4_ERR("%s FAILED", microbenchmarks[i].name);
return -1;
}
}
}
PX4_WARN("no test called '%s' - 'microbench help' for a list of tests", argv[1]);
return 1;
}
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2020 PX4 Development Team. All rights reserved.
* Copyright (C) 2020-2021 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
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2018-2019 PX4 Development Team. All rights reserved.
* Copyright (C) 2018-2021 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
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2018-2019 PX4 Development Team. All rights reserved.
* Copyright (C) 2018-2021 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
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2018-2019 PX4 Development Team. All rights reserved.
* Copyright (C) 2018-2021 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
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2018-2019 PX4 Development Team. All rights reserved.
* Copyright (C) 2018-2021 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
@@ -153,7 +153,6 @@ bool MicroBenchORB::time_px4_uorb()
int ret = 0;
bool updated = false;
uint64_t time = 0;
PERF("orb_check vehicle_status", ret = orb_check(fd_status, &updated), 100);
PERF("orb_copy vehicle_status", ret = orb_copy(ORB_ID(vehicle_status), fd_status, &status), 100);
@@ -198,8 +197,6 @@ bool MicroBenchORB::time_px4_uorb()
bool MicroBenchORB::time_px4_uorb_direct()
{
bool ret = false;
bool updated = false;
uint64_t time = 0;
uORB::Subscription vstatus{ORB_ID(vehicle_status)};
PERF("uORB::Subscription orb_check vehicle_status", ret = vstatus.updated(), 100);
-8
View File
@@ -32,7 +32,6 @@
############################################################################
set(srcs
test_adc.cpp
test_atomic_bitset.cpp
test_bezierQuad.cpp
test_bitset.cpp
@@ -47,17 +46,11 @@ set(srcs
test_int.cpp
test_i2c_spi_cli.cpp
test_IntrusiveQueue.cpp
test_jig_voltages.cpp
test_led.c
test_List.cpp
test_IntrusiveSortedList.cpp
test_mathlib.cpp
test_matrix.cpp
test_microbench_atomic.cpp
test_microbench_hrt.cpp
test_microbench_math.cpp
test_microbench_matrix.cpp
test_microbench_uorb.cpp
test_mixer.cpp
test_param.c
test_parameters.cpp
@@ -66,7 +59,6 @@ set(srcs
test_ppm_loopback.c
test_rc.c
test_search_min.cpp
test_servo.c
test_sleep.c
test_uart_baudchange.c
test_uart_console.c
-72
View File
@@ -1,72 +0,0 @@
/****************************************************************************
*
* 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 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_adc.c
* Test for the analog to digital converter.
*/
#include <px4_platform_common/time.h>
#include <px4_platform_common/log.h>
#include "tests_main.h"
#include <drivers/drv_adc.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/adc_report.h>
int test_adc(int argc, char *argv[])
{
uORB::Subscription _adc_sub{ORB_ID(adc_report)};
adc_report_s adc;
px4_usleep(50000); // sleep 50ms and wait for adc report
if (_adc_sub.update(&adc)) {
PX4_INFO_RAW("DeviceID: %" PRIu32 "\n", adc.device_id);
PX4_INFO_RAW("Resolution: %" PRIu32 "\n", adc.resolution);
PX4_INFO_RAW("Voltage Reference: %f\n", adc.v_ref);
for (int i = 0; i < PX4_MAX_ADC_CHANNELS; ++i) {
PX4_INFO_RAW("%" PRIu16 ": %" PRIi32 " ", adc.channel_id[i], adc.raw_data[i]);
}
PX4_INFO_RAW("\n");
PX4_INFO_RAW("\t ADC test successful.\n");
return OK;
} else {
return 1;
}
}
+32 -32
View File
@@ -75,7 +75,7 @@ int check_user_abort(int fd)
case 0x1b: // esc
case 'c':
case 'q': {
warnx("Test aborted.");
printf("Test aborted.\n");
fsync(fd);
close(fd);
return OK;
@@ -90,14 +90,14 @@ int check_user_abort(int fd)
int
test_file(int argc, char *argv[])
{
const unsigned iterations = 100;
const unsigned alignments = 65;
const unsigned iterations = 2;
const unsigned alignments = 33;
/* check if microSD card is mounted */
struct stat buffer;
if (stat(PX4_STORAGEDIR "/", &buffer)) {
warnx("no microSD card mounted, aborting file test");
printf("no microSD card mounted, aborting file test\n");
return 1;
}
@@ -111,7 +111,7 @@ test_file(int argc, char *argv[])
for (unsigned a = 0; a < alignments; a++) {
printf("\n");
warnx("----- alignment test: %u bytes -----", a);
printf("----- alignment test: %u bytes -----\n", a);
uint8_t write_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
@@ -124,9 +124,9 @@ test_file(int argc, char *argv[])
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
hrt_abstime start, end;
int fd = px4_open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT);
int fd = open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT, 0600);
warnx("testing unaligned writes - please wait..");
printf("testing unaligned writes - please wait..\n");
start = hrt_absolute_time();
@@ -134,10 +134,10 @@ test_file(int argc, char *argv[])
int wret = write(fd, write_buf + a, chunk_sizes[c]);
if (wret != chunk_sizes[c]) {
warn("WRITE ERROR!");
PX4_ERR("WRITE ERROR!");
if ((0x3 & (uintptr_t)(write_buf + a))) {
warnx("memory is unaligned, align shift: %d", a);
printf("memory is unaligned, align shift: %d\n", a);
}
return 1;
@@ -153,9 +153,9 @@ test_file(int argc, char *argv[])
end = hrt_absolute_time();
warnx("write took %" PRIu64 " us", (end - start));
printf("write took %" PRIu64 " us\n", (end - start));
px4_close(fd);
close(fd);
fd = open(PX4_STORAGEDIR "/testfile", O_RDONLY);
/* read back data for validation */
@@ -163,7 +163,7 @@ test_file(int argc, char *argv[])
int rret = read(fd, read_buf, chunk_sizes[c]);
if (rret != chunk_sizes[c]) {
warnx("READ ERROR!");
PX4_ERR("READ ERROR!");
return 1;
}
@@ -172,14 +172,14 @@ test_file(int argc, char *argv[])
for (int j = 0; j < chunk_sizes[c]; j++) {
if (read_buf[j] != write_buf[j + a]) {
warnx("COMPARISON ERROR: byte %d, align shift: %d", j, a);
PX4_ERR("COMPARISON ERROR: byte %d, align shift: %d", j, a);
compare_ok = false;
break;
}
}
if (!compare_ok) {
warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
PX4_ERR("ABORTING FURTHER COMPARISON DUE TO ERROR");
return 1;
}
@@ -195,15 +195,15 @@ test_file(int argc, char *argv[])
close(fd);
int ret = unlink(PX4_STORAGEDIR "/testfile");
fd = px4_open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT);
fd = open(PX4_STORAGEDIR "/testfile", O_TRUNC | O_WRONLY | O_CREAT, 0600);
warnx("testing aligned writes - please wait.. (CTRL^C to abort)");
printf("testing aligned writes - please wait.. (CTRL^C to abort)\n");
for (unsigned i = 0; i < iterations; i++) {
int wret = write(fd, write_buf, chunk_sizes[c]);
if (wret != chunk_sizes[c]) {
warnx("WRITE ERROR!");
PX4_ERR("WRITE ERROR!");
return 1;
}
@@ -215,9 +215,9 @@ test_file(int argc, char *argv[])
fsync(fd);
warnx("reading data aligned..");
printf("reading data aligned..\n");
px4_close(fd);
close(fd);
fd = open(PX4_STORAGEDIR "/testfile", O_RDONLY);
bool align_read_ok = true;
@@ -227,13 +227,13 @@ test_file(int argc, char *argv[])
int rret = read(fd, read_buf, chunk_sizes[c]);
if (rret != chunk_sizes[c]) {
warnx("READ ERROR!");
PX4_ERR("READ ERROR!");
return 1;
}
for (int j = 0; j < chunk_sizes[c]; j++) {
if (read_buf[j] != write_buf[j]) {
warnx("COMPARISON ERROR: byte %d: %u != %u", j, (unsigned int)read_buf[j], (unsigned int)write_buf[j]);
PX4_ERR("COMPARISON ERROR: byte %d: %u != %u", j, (unsigned int)read_buf[j], (unsigned int)write_buf[j]);
align_read_ok = false;
break;
}
@@ -244,15 +244,15 @@ test_file(int argc, char *argv[])
}
if (!align_read_ok) {
warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
PX4_ERR("ABORTING FURTHER COMPARISON DUE TO ERROR");
return 1;
}
}
warnx("align read result: %s\n", (align_read_ok) ? "OK" : "ERROR");
printf("align read result: %s\n", (align_read_ok) ? "OK" : "ERROR");
warnx("reading data unaligned..");
printf("reading data unaligned..\n");
close(fd);
fd = open(PX4_STORAGEDIR "/testfile", O_RDONLY);
@@ -267,15 +267,15 @@ test_file(int argc, char *argv[])
int rret = read(fd, read_buf + a, chunk_sizes[c]);
if (rret != chunk_sizes[c]) {
warnx("READ ERROR!");
PX4_ERR("READ ERROR!");
return 1;
}
for (int j = 0; j < chunk_sizes[c]; j++) {
if ((read_buf + a)[j] != write_buf[j]) {
warnx("COMPARISON ERROR: byte %d, align shift: %d: %u != %u", j, a, (unsigned int)read_buf[j + a],
(unsigned int)write_buf[j]);
PX4_ERR("COMPARISON ERROR: byte %d, align shift: %d: %u != %u", j, a, (unsigned int)read_buf[j + a],
(unsigned int)write_buf[j]);
unalign_read_ok = false;
unalign_read_err_count++;
@@ -290,7 +290,7 @@ test_file(int argc, char *argv[])
}
if (!unalign_read_ok) {
warnx("ABORTING FURTHER COMPARISON DUE TO ERROR");
PX4_ERR("ABORTING FURTHER COMPARISON DUE TO ERROR");
return 1;
}
@@ -300,7 +300,7 @@ test_file(int argc, char *argv[])
close(fd);
if (ret) {
warnx("UNLINKING FILE FAILED");
PX4_ERR("UNLINKING FILE FAILED");
return 1;
}
}
@@ -314,16 +314,16 @@ test_file(int argc, char *argv[])
if (d) {
while ((dir = readdir(d)) != NULL) {
//printf("%s\n", dir->d_name);
printf("%s\n", dir->d_name);
}
closedir(d);
warnx("directory listing ok (FS mounted and readable)");
printf("directory listing ok (FS mounted and readable)\n");
} else {
/* failed opening dir */
warnx("FAILED LISTING MICROSD ROOT DIRECTORY");
PX4_ERR("FAILED LISTING MICROSD ROOT DIRECTORY");
return 1;
}
-120
View File
@@ -1,120 +0,0 @@
/****************************************************************************
*
* 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 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_jig_voltages.c
* Tests for jig voltages.
*/
#include <px4_platform_common/defines.h>
#include <unistd.h>
#include "tests_main.h"
#include <drivers/drv_adc.h>
#include <uORB/Subscription.hpp>
#include <uORB/topics/adc_report.h>
int test_jig_voltages(int argc, char *argv[])
{
uORB::Subscription _adc_sub{ORB_ID(adc_report)};
adc_report_s adc;
px4_usleep(50000); // sleep 50ms and wait for adc report
if (_adc_sub.update(&adc)) {
PX4_INFO_RAW("DeviceID: %" PRIu32 "\n", adc.device_id);
PX4_INFO_RAW("Resolution: %" PRIu32 "\n", adc.resolution);
PX4_INFO_RAW("Voltage Reference: %f\n", adc.v_ref);
unsigned channels = 0;
for (int i = 0; i < PX4_MAX_ADC_CHANNELS; ++i) {
PX4_INFO_RAW("%" PRIu16 ": %" PRIi32 " ", adc.channel_id[i], adc.raw_data[i]);
if (adc.channel_id[i] != -1) {
++channels;
}
}
PX4_INFO_RAW("\n");
PX4_INFO("\t ADC operational.\n");
/* Expected values */
int16_t expected_min[] = {2800, 2800, 1800, 800};
int16_t expected_max[] = {3100, 3100, 2100, 1100};
const char *check_res[channels];
if (channels < 4) {
PX4_ERR("not all four test channels available, aborting.");
return 1;
} else {
int ret = OK;
/* Check values */
check_res[0] = (expected_min[0] < adc.raw_data[0] && expected_max[0] > adc.raw_data[0]) ? "OK" : "FAIL";
check_res[1] = (expected_min[1] < adc.raw_data[1] && expected_max[1] > adc.raw_data[1]) ? "OK" : "FAIL";
check_res[2] = (expected_min[2] < adc.raw_data[2] && expected_max[2] > adc.raw_data[2]) ? "OK" : "FAIL";
check_res[3] = (expected_min[3] < adc.raw_data[3] && expected_max[3] > adc.raw_data[3]) ? "OK" : "FAIL";
/* Accumulate result */
ret += (expected_min[0] > adc.raw_data[0] || expected_max[0] < adc.raw_data[0]) ? 1 : 0;
ret += (expected_min[1] > adc.raw_data[1] || expected_max[1] < adc.raw_data[1]) ? 1 : 0;
ret += (expected_min[2] > adc.raw_data[2] || expected_max[2] < adc.raw_data[2]) ? 1 : 0;
ret += (expected_min[3] > adc.raw_data[3] || expected_max[3] < adc.raw_data[3]) ? 1 : 0;
PX4_INFO("Sample:");
PX4_INFO("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s",
adc.channel_id[0], (int)(adc.raw_data[0]), expected_min[0], expected_max[0], check_res[0]);
PX4_INFO("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s",
adc.channel_id[1], (int)(adc.raw_data[1]), expected_min[1], expected_max[1], check_res[1]);
PX4_INFO("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s",
adc.channel_id[2], (int)(adc.raw_data[2]), expected_min[2], expected_max[2], check_res[2]);
PX4_INFO("channel: %d value: %d (allowed min: %d, allowed max: %d), result: %s",
adc.channel_id[3], (int)(adc.raw_data[3]), expected_min[3], expected_max[3], check_res[3]);
if (ret != OK) {
PX4_ERR("\t JIG voltages test FAILED. Some channels where out of allowed range. Check supply voltages.");
return ret;
}
}
PX4_INFO("JIG voltages test successful.");
return OK;
} else {
return 1;
}
}
-127
View File
@@ -1,127 +0,0 @@
/****************************************************************************
*
* 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 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_servo.c
* Tests the servo outputs
*/
#include <px4_platform_common/time.h>
#include <px4_platform_common/px4_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 <drivers/drv_pwm_output.h>
#include <systemlib/err.h>
#include "tests_main.h"
int test_servo(int argc, char *argv[])
{
int fd;
int result = 0;
servo_position_t data[PWM_OUTPUT_MAX_CHANNELS];
servo_position_t pos;
fd = open(PWM_OUTPUT0_DEVICE_PATH, O_RDWR);
if (fd < 0) {
printf("failed opening /dev/pwm_servo\n");
goto out;
}
result = read(fd, &data, sizeof(data));
if (result != sizeof(data)) {
printf("failed bulk-reading channel values\n");
goto out;
}
printf("Servo readback, pairs of values should match defaults\n");
unsigned servo_count;
result = ioctl(fd, PWM_SERVO_GET_COUNT, (unsigned long)&servo_count);
if (result != OK) {
warnx("PWM_SERVO_GET_COUNT");
goto out;
}
for (unsigned i = 0; i < servo_count; i++) {
result = ioctl(fd, PWM_SERVO_GET(i), (unsigned long)&pos);
if (result < 0) {
printf("failed reading channel %u\n", i);
goto out;
}
printf("%u: %u %u\n", i, pos, data[i]);
}
/* 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");
goto out;
}
/* 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");
goto out;
}
px4_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:
if (fd >= 0) {
close(fd);
}
return result;
}
+9
View File
@@ -57,7 +57,16 @@ int test_sleep(int argc, char *argv[])
fflush(stdout);
for (unsigned int i = 0; i < nsleeps; i++) {
const hrt_abstime time_start = hrt_absolute_time();
px4_usleep(100000);
const hrt_abstime time_stop = hrt_absolute_time();
int elapsed = time_stop - time_start;
if (elapsed < 100000) {
PX4_ERR("\t Sleep test failed, only %d us elapsed\n", elapsed);
return PX4_ERROR;
}
}
printf("\t Sleep test successful.\n");
+9 -13
View File
@@ -75,29 +75,25 @@ cycletime(void)
int test_time(int argc, char *argv[])
{
hrt_abstime h, c;
int lowdelta, maxdelta = 0;
int delta, deltadelta;
int maxdelta = 0;
/* enable the cycle counter */
(*(unsigned long *)0xe000edfc) |= (1 << 24); /* DEMCR |= DEMCR_TRCENA */
(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */
/* get an average delta between the two clocks - this should stay roughly the same */
delta = 0;
int delta = 0;
for (unsigned i = 0; i < 100; i++) {
uint32_t flags = px4_enter_critical_section();
h = hrt_absolute_time();
c = cycletime();
irqstate_t flags = px4_enter_critical_section();
hrt_abstime h = hrt_absolute_time();
hrt_abstime c = cycletime();
px4_leave_critical_section(flags);
delta += h - c;
}
lowdelta = abs(delta / 100);
int lowdelta = abs(delta / 100);
/* loop checking the time */
for (unsigned i = 0; i < 100; i++) {
@@ -106,13 +102,13 @@ int test_time(int argc, char *argv[])
uint32_t flags = px4_enter_critical_section();
c = cycletime();
h = hrt_absolute_time();
hrt_abstime c = cycletime();
hrt_abstime h = hrt_absolute_time();
px4_leave_critical_section(flags);
delta = h - c;
deltadelta = abs(delta - lowdelta);
int deltadelta = abs(delta - lowdelta);
if (deltadelta > maxdelta) {
maxdelta = deltadelta;
+4 -18
View File
@@ -77,7 +77,6 @@ const struct {
{"uart_console", test_uart_console, OPT_NOJIGTEST | OPT_NOALLTEST},
#endif /* __PX4_NUTTX */
{"adc", test_adc, OPT_NOJIGTEST},
{"atomic_bitset", test_atomic_bitset, 0},
{"bezier", test_bezierQuad, 0},
{"bitset", test_bitset, 0},
@@ -91,17 +90,10 @@ const struct {
{"int", test_int, 0},
{"i2c_spi_cli", test_i2c_spi_cli, 0},
{"IntrusiveQueue", test_IntrusiveQueue, 0},
{"jig_voltages", test_jig_voltages, OPT_NOALLTEST},
{"IntrusiveSortedList", test_IntrusiveSortedList, 0},
{"List", test_List, 0},
{"mathlib", test_mathlib, 0},
{"matrix", test_matrix, 0},
{"microbench_atomic", test_microbench_atomic, 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},
{"mixer", test_mixer, OPT_NOJIGTEST},
{"param", test_param, 0},
{"parameters", test_parameters, 0},
@@ -110,20 +102,17 @@ const struct {
{"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},
{"uart_loopback", test_uart_loopback, OPT_NOJIGTEST | OPT_NOALLTEST},
{"uart_send", test_uart_send, OPT_NOJIGTEST | OPT_NOALLTEST},
{"versioning", test_versioning, 0},
{"cli", test_cli, 0},
{NULL, NULL, 0}
};
#define NTESTS (sizeof(tests) / sizeof(tests[0]))
static int
test_help(int argc, char *argv[])
static int test_help(int argc, char *argv[])
{
unsigned i;
@@ -136,20 +125,17 @@ test_help(int argc, char *argv[])
return 0;
}
static int
test_all(int argc, char *argv[])
static int test_all(int argc, char *argv[])
{
return test_runner(OPT_NOALLTEST);
}
static int
test_jig(int argc, char *argv[])
static int test_jig(int argc, char *argv[])
{
return test_runner(OPT_NOJIGTEST);
}
static int
test_runner(unsigned option)
static int test_runner(unsigned option)
{
size_t i;
char *args[2] = {"all", NULL};
-8
View File
@@ -43,7 +43,6 @@
__BEGIN_DECLS
extern int test_adc(int argc, char *argv[]);
extern int test_atomic_bitset(int argc, char *argv[]);
extern int test_bezierQuad(int argc, char *argv[]);
extern int test_bitset(int argc, char *argv[]);
@@ -58,17 +57,11 @@ extern int test_hrt(int argc, char *argv[]);
extern int test_int(int argc, char *argv[]);
extern int test_i2c_spi_cli(int argc, char *argv[]);
extern int test_IntrusiveQueue(int argc, char *argv[]);
extern int test_jig_voltages(int argc, char *argv[]);
extern int test_led(int argc, char *argv[]);
extern int test_IntrusiveSortedList(int argc, char *argv[]);
extern int test_List(int argc, char *argv[]);
extern int test_mathlib(int argc, char *argv[]);
extern int test_matrix(int argc, char *argv[]);
extern int test_microbench_atomic(int argc, char *argv[]);
extern int test_microbench_hrt(int argc, char *argv[]);
extern int test_microbench_math(int argc, char *argv[]);
extern int test_microbench_matrix(int argc, char *argv[]);
extern int test_microbench_uorb(int argc, char *argv[]);
extern int test_mixer(int argc, char *argv[]);
extern int test_mount(int argc, char *argv[]);
extern int test_param(int argc, char *argv[]);
@@ -78,7 +71,6 @@ extern int test_ppm(int argc, char *argv[]);
extern int test_ppm_loopback(int argc, char *argv[]);
extern int test_rc(int argc, char *argv[]);
extern int test_search_min(int argc, char *argv[]);
extern int test_servo(int argc, char *argv[]);
extern int test_sleep(int argc, char *argv[]);
extern int test_time(int argc, char *argv[]);
extern int test_uart_baudchange(int argc, char *argv[]);