Merge pull request #2500 from mcharleb/systemcmds-tests-posix

Systemcmds tests posix
This commit is contained in:
Lorenz Meier 2015-07-01 23:25:54 +02:00
commit 13e585f9fb
31 changed files with 291 additions and 238 deletions

View File

@ -18,6 +18,9 @@ MODULES += modules/sensors
#
MODULES += systemcmds/param
MODULES += systemcmds/mixer
#MODULES += systemcmds/esc_calib
MODULES += systemcmds/tests
#MODULES += systemcmds/reboot
MODULES += systemcmds/topic_listener
MODULES += systemcmds/ver

View File

@ -40,7 +40,6 @@ SRCS = \
param/param.c \
conversions.c \
cpuload.c \
getopt_long.c \
pid/pid.c \
airspeed.c \
system_params.c \

View File

@ -115,6 +115,9 @@ typedef param_t px4_param_t;
#ifndef PRIu64
#define PRIu64 "llu"
#endif
#ifndef PRId64
#define PRId64 "lld"
#endif
/*
* POSIX Specific defines

View File

@ -18,7 +18,6 @@ SRCS = test_adc.c \
test_sensors.c \
test_servo.c \
test_sleep.c \
test_time.c \
test_uart_baudchange.c \
test_uart_console.c \
test_uart_loopback.c \
@ -35,5 +34,14 @@ SRCS = test_adc.c \
test_mount.c \
test_eigen.cpp
EXTRACXXFLAGS = -Wframe-larger-than=2500 -Wno-float-equal -Wno-double-promotion -Wno-error=logical-op
ifeq ($(PX4_TARGET_OS), nuttx)
SRCS += test_time.c
endif
EXTRACXXFLAGS = -Wframe-larger-than=2500 -Wno-float-equal
# Flag is only valid for GCC, not clang
ifneq ($(USE_GCC), 0)
EXTRACXXFLAGS += -Wno-double-promotion -Wno-error=logical-op
endif

View File

@ -37,7 +37,9 @@
*/
#include <px4_config.h>
#include <nuttx/arch.h>
#include <px4_adc.h>
#include <px4_posix.h>
#include <px4_log.h>
#include <sys/types.h>
@ -46,22 +48,17 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/spi.h>
#include "tests.h"
#include <nuttx/analog/adc.h>
#include <drivers/drv_adc.h>
#include <systemlib/err.h>
int test_adc(int argc, char *argv[])
{
int fd = open(ADC0_DEVICE_PATH, O_RDONLY);
int fd = px4_open(ADC0_DEVICE_PATH, O_RDONLY);
if (fd < 0) {
warnx("ERROR: can't open ADC device");
PX4_ERR("ERROR: can't open ADC device");
return 1;
}
@ -69,7 +66,7 @@ int test_adc(int argc, char *argv[])
/* make space for a maximum of twelve channels */
struct adc_msg_s data[12];
/* read all channels available */
ssize_t count = read(fd, data, sizeof(data));
ssize_t count = px4_read(fd, data, sizeof(data));
if (count < 0) {
goto errout_with_dev;
@ -85,11 +82,11 @@ int test_adc(int argc, char *argv[])
usleep(150000);
}
warnx("\t ADC test successful.\n");
printf("\t ADC test successful.\n");
errout_with_dev:
if (fd != 0) { close(fd); }
if (fd != 0) { px4_close(fd); }
return OK;
}

View File

@ -37,9 +37,14 @@
* Tests for the bson en/decoder
*/
#define __STDC_FORMAT_MACROS
#include <inttypes.h>
#include <px4_defines.h>
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <limits.h>
#include <math.h>
#include <systemlib/err.h>
@ -59,27 +64,33 @@ static int
encode(bson_encoder_t encoder)
{
if (bson_encoder_append_bool(encoder, "bool1", sample_bool) != 0) {
warnx("FAIL: encoder: append bool failed");
PX4_ERR("FAIL: encoder: append bool failed");
return 1;
}
if (bson_encoder_append_int(encoder, "int1", sample_small_int) != 0) {
warnx("FAIL: encoder: append int failed");
PX4_ERR("FAIL: encoder: append int failed");
return 1;
}
if (bson_encoder_append_int(encoder, "int2", sample_big_int) != 0) {
warnx("FAIL: encoder: append int failed");
PX4_ERR("FAIL: encoder: append int failed");
return 1;
}
if (bson_encoder_append_double(encoder, "double1", sample_double) != 0) {
warnx("FAIL: encoder: append double failed");
PX4_ERR("FAIL: encoder: append double failed");
return 1;
}
if (bson_encoder_append_string(encoder, "string1", sample_string) != 0) {
warnx("FAIL: encoder: append string failed");
PX4_ERR("FAIL: encoder: append string failed");
return 1;
}
if (bson_encoder_append_binary(encoder, "data1", BSON_BIN_BINARY, sizeof(sample_data), sample_data) != 0) {
warnx("FAIL: encoder: append data failed");
PX4_ERR("FAIL: encoder: append data failed");
return 1;
}
bson_encoder_fini(encoder);
@ -94,29 +105,29 @@ decode_callback(bson_decoder_t decoder, void *private, bson_node_t node)
if (!strcmp(node->name, "bool1")) {
if (node->type != BSON_BOOL) {
warnx("FAIL: decoder: bool1 type %d, expected %d", node->type, BSON_BOOL);
PX4_ERR("FAIL: decoder: bool1 type %d, expected %d", node->type, BSON_BOOL);
return 1;
}
if (node->b != sample_bool) {
warnx("FAIL: decoder: bool1 value %s, expected %s",
PX4_ERR("FAIL: decoder: bool1 value %s, expected %s",
(node->b ? "true" : "false"),
(sample_bool ? "true" : "false"));
return 1;
}
warnx("PASS: decoder: bool1");
PX4_INFO("PASS: decoder: bool1");
return 1;
}
if (!strcmp(node->name, "int1")) {
if (node->type != BSON_INT32) {
warnx("FAIL: decoder: int1 type %d, expected %d", node->type, BSON_INT32);
PX4_ERR("FAIL: decoder: int1 type %d, expected %d", node->type, BSON_INT32);
return 1;
}
if (node->i != sample_small_int) {
warnx("FAIL: decoder: int1 value %lld, expected %d", node->i, sample_small_int);
PX4_ERR("FAIL: decoder: int1 value %" PRIu64 ", expected %d", node->i, sample_small_int);
return 1;
}
@ -126,12 +137,12 @@ decode_callback(bson_decoder_t decoder, void *private, bson_node_t node)
if (!strcmp(node->name, "int2")) {
if (node->type != BSON_INT64) {
warnx("FAIL: decoder: int2 type %d, expected %d", node->type, BSON_INT64);
PX4_ERR("FAIL: decoder: int2 type %d, expected %d", node->type, BSON_INT64);
return 1;
}
if (node->i != sample_big_int) {
warnx("FAIL: decoder: int2 value %lld, expected %lld", node->i, sample_big_int);
PX4_ERR("FAIL: decoder: int2 value %" PRIu64 ", expected %" PRIu64, node->i, sample_big_int);
return 1;
}
@ -141,12 +152,12 @@ decode_callback(bson_decoder_t decoder, void *private, bson_node_t node)
if (!strcmp(node->name, "double1")) {
if (node->type != BSON_DOUBLE) {
warnx("FAIL: decoder: double1 type %d, expected %d", node->type, BSON_DOUBLE);
PX4_ERR("FAIL: decoder: double1 type %d, expected %d", node->type, BSON_DOUBLE);
return 1;
}
if (fabs(node->d - sample_double) > 1e-12) {
warnx("FAIL: decoder: double1 value %f, expected %f", node->d, sample_double);
PX4_ERR("FAIL: decoder: double1 value %f, expected %f", node->d, sample_double);
return 1;
}
@ -156,36 +167,36 @@ decode_callback(bson_decoder_t decoder, void *private, bson_node_t node)
if (!strcmp(node->name, "string1")) {
if (node->type != BSON_STRING) {
warnx("FAIL: decoder: string1 type %d, expected %d", node->type, BSON_STRING);
PX4_ERR("FAIL: decoder: string1 type %d, expected %d", node->type, BSON_STRING);
return 1;
}
len = bson_decoder_data_pending(decoder);
if (len != strlen(sample_string) + 1) {
warnx("FAIL: decoder: string1 length %d wrong, expected %d", len, strlen(sample_string) + 1);
PX4_ERR("FAIL: decoder: string1 length %d wrong, expected %zd", len, strlen(sample_string) + 1);
return 1;
}
char sbuf[len];
if (bson_decoder_copy_data(decoder, sbuf)) {
warnx("FAIL: decoder: string1 copy failed");
PX4_ERR("FAIL: decoder: string1 copy failed");
return 1;
}
if (bson_decoder_data_pending(decoder) != 0) {
warnx("FAIL: decoder: string1 copy did not exhaust all data");
PX4_ERR("FAIL: decoder: string1 copy did not exhaust all data");
return 1;
}
if (sbuf[len - 1] != '\0') {
warnx("FAIL: decoder: string1 not 0-terminated");
PX4_ERR("FAIL: decoder: string1 not 0-terminated");
return 1;
}
if (strcmp(sbuf, sample_string)) {
warnx("FAIL: decoder: string1 value '%s', expected '%s'", sbuf, sample_string);
PX4_ERR("FAIL: decoder: string1 value '%s', expected '%s'", sbuf, sample_string);
return 1;
}
@ -195,45 +206,45 @@ decode_callback(bson_decoder_t decoder, void *private, bson_node_t node)
if (!strcmp(node->name, "data1")) {
if (node->type != BSON_BINDATA) {
warnx("FAIL: decoder: data1 type %d, expected %d", node->type, BSON_BINDATA);
PX4_ERR("FAIL: decoder: data1 type %d, expected %d", node->type, BSON_BINDATA);
return 1;
}
len = bson_decoder_data_pending(decoder);
if (len != sizeof(sample_data)) {
warnx("FAIL: decoder: data1 length %d, expected %d", len, sizeof(sample_data));
PX4_ERR("FAIL: decoder: data1 length %d, expected %zu", len, sizeof(sample_data));
return 1;
}
if (node->subtype != BSON_BIN_BINARY) {
warnx("FAIL: decoder: data1 subtype %d, expected %d", node->subtype, BSON_BIN_BINARY);
PX4_ERR("FAIL: decoder: data1 subtype %d, expected %d", node->subtype, BSON_BIN_BINARY);
return 1;
}
uint8_t dbuf[len];
if (bson_decoder_copy_data(decoder, dbuf)) {
warnx("FAIL: decoder: data1 copy failed");
PX4_ERR("FAIL: decoder: data1 copy failed");
return 1;
}
if (bson_decoder_data_pending(decoder) != 0) {
warnx("FAIL: decoder: data1 copy did not exhaust all data");
PX4_ERR("FAIL: decoder: data1 copy did not exhaust all data");
return 1;
}
if (memcmp(sample_data, dbuf, len)) {
warnx("FAIL: decoder: data1 compare fail");
PX4_ERR("FAIL: decoder: data1 compare fail");
return 1;
}
warnx("PASS: decoder: data1");
PX4_INFO("PASS: decoder: data1");
return 1;
}
if (node->type != BSON_EOO) {
warnx("FAIL: decoder: unexpected node name '%s'", node->name);
PX4_ERR("FAIL: decoder: unexpected node name '%s'", node->name);
}
return 1;
@ -259,29 +270,33 @@ test_bson(int argc, char *argv[])
/* encode data to a memory buffer */
if (bson_encoder_init_buf(&encoder, NULL, 0)) {
errx(1, "FAIL: bson_encoder_init_buf");
PX4_ERR("FAIL: bson_encoder_init_buf");
return 1;
}
encode(&encoder);
len = bson_encoder_buf_size(&encoder);
if (len <= 0) {
errx(1, "FAIL: bson_encoder_buf_len");
PX4_ERR("FAIL: bson_encoder_buf_len");
return 1;
}
buf = bson_encoder_buf_data(&encoder);
if (buf == NULL) {
errx(1, "FAIL: bson_encoder_buf_data");
PX4_ERR("FAIL: bson_encoder_buf_data");
return 1;
}
/* now test-decode it */
if (bson_decoder_init_buf(&decoder, buf, len, decode_callback, NULL)) {
errx(1, "FAIL: bson_decoder_init_buf");
PX4_ERR("FAIL: bson_decoder_init_buf");
return 1;
}
decode(&decoder);
free(buf);
return OK;
return PX4_OK;
}

View File

@ -59,20 +59,20 @@
int test_conv(int argc, char *argv[])
{
warnx("Testing system conversions");
PX4_INFO("Testing system conversions");
for (int i = -10000; i <= 10000; i += 1) {
float f = i / 10000.0f;
float fres = REG_TO_FLOAT(FLOAT_TO_REG(f));
if (fabsf(f - fres) > 0.0001f) {
warnx("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", (double)f, REG_TO_SIGNED(FLOAT_TO_REG(f)),
PX4_ERR("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", (double)f, REG_TO_SIGNED(FLOAT_TO_REG(f)),
(double)fres);
return 1;
}
}
warnx("All conversions clean");
PX4_INFO("All conversions clean");
return 0;
}

View File

@ -97,7 +97,7 @@ test_file(int argc, char *argv[])
/* check if microSD card is mounted */
struct stat buffer;
if (stat("/fs/microsd/", &buffer)) {
if (stat(PX4_ROOTFSDIR "/fs/microsd/", &buffer)) {
warnx("no microSD card mounted, aborting file test");
return 1;
}
@ -125,7 +125,7 @@ test_file(int argc, char *argv[])
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
hrt_abstime start, end;
int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
int fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
warnx("testing unaligned writes - please wait..");
@ -154,10 +154,10 @@ test_file(int argc, char *argv[])
end = hrt_absolute_time();
warnx("write took %llu us", (end - start));
warnx("write took %" PRIu64 " us", (end - start));
close(fd);
fd = open("/fs/microsd/testfile", O_RDONLY);
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
/* read back data for validation */
for (unsigned i = 0; i < iterations; i++) {
@ -195,8 +195,8 @@ test_file(int argc, char *argv[])
*/
close(fd);
int ret = unlink("/fs/microsd/testfile");
fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
int ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
warnx("testing aligned writes - please wait.. (CTRL^C to abort)");
@ -219,7 +219,7 @@ test_file(int argc, char *argv[])
warnx("reading data aligned..");
close(fd);
fd = open("/fs/microsd/testfile", O_RDONLY);
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
bool align_read_ok = true;
@ -256,7 +256,7 @@ test_file(int argc, char *argv[])
warnx("reading data unaligned..");
close(fd);
fd = open("/fs/microsd/testfile", O_RDONLY);
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
bool unalign_read_ok = true;
int unalign_read_err_count = 0;
@ -297,7 +297,7 @@ test_file(int argc, char *argv[])
}
ret = unlink("/fs/microsd/testfile");
ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
close(fd);
if (ret) {
@ -310,7 +310,7 @@ test_file(int argc, char *argv[])
/* list directory */
DIR *d;
struct dirent *dir;
d = opendir("/fs/microsd");
d = opendir(PX4_ROOTFSDIR "/fs/microsd");
if (d) {

View File

@ -37,17 +37,17 @@
* File write test.
*/
#include <px4_defines.h>
#include <sys/stat.h>
#include <dirent.h>
#include <stdio.h>
#include <stddef.h>
#include <unistd.h>
#include <fcntl.h>
#include <systemlib/err.h>
#include <systemlib/perf_counter.h>
#include <string.h>
#include <stdlib.h>
#include <getopt.h>
#include <px4_getopt.h>
#include "tests.h"
@ -133,13 +133,13 @@ static void test_corruption(const char *filename, uint32_t write_chunk, uint32_t
if (read(fd, buffer, sizeof(buffer)) != (int)sizeof(buffer)) {
printf("read failed at offset %u\n", ofs);
exit(1);
return;
}
for (uint16_t j = 0; j < write_chunk; j++) {
if (buffer[j] != get_value(ofs)) {
printf("corruption at ofs=%u got %u\n", ofs, buffer[j]);
exit(1);
return;
}
ofs++;
@ -170,11 +170,13 @@ int test_file2(int argc, char *argv[])
{
int opt;
uint16_t flags = 0;
const char *filename = "/fs/microsd/testfile2.dat";
const char *filename = PX4_ROOTFSDIR "/fs/microsd/testfile2.dat";
uint32_t write_chunk = 64;
uint32_t write_size = 5 * 1024;
while ((opt = getopt(argc, argv, "c:s:FLh")) != EOF) {
int myoptind = 1;
const char *myoptarg = NULL;
while ((opt = px4_getopt(argc, argv, "c:s:FLh", &myoptind, &myoptarg)) != EOF) {
switch (opt) {
case 'F':
flags |= FLAG_FSYNC;
@ -185,22 +187,22 @@ int test_file2(int argc, char *argv[])
break;
case 's':
write_size = strtoul(optarg, NULL, 0);
write_size = strtoul(myoptarg, NULL, 0);
break;
case 'c':
write_chunk = strtoul(optarg, NULL, 0);
write_chunk = strtoul(myoptarg, NULL, 0);
break;
case 'h':
default:
usage();
exit(1);
return 1;
}
}
argc -= optind;
argv += optind;
argc -= myoptind;
argv += myoptind;
if (argc > 0) {
filename = argv[0];
@ -209,8 +211,8 @@ int test_file2(int argc, char *argv[])
/* check if microSD card is mounted */
struct stat buffer;
if (stat("/fs/microsd/", &buffer)) {
warnx("no microSD card mounted, aborting file test");
if (stat(PX4_ROOTFSDIR "/fs/microsd/", &buffer)) {
fprintf(stderr, "no microSD card mounted, aborting file test");
return 1;
}

View File

@ -39,12 +39,12 @@
#include <px4_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include "tests.h"
#include <math.h>
#include <float.h>

View File

@ -37,6 +37,7 @@
****************************************************************************/
#include <px4_config.h>
#include <px4_posix.h>
#include <sys/types.h>
@ -45,9 +46,8 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/analog/adc.h>
#include <px4_adc.h>
#include "tests.h"
@ -93,7 +93,7 @@ int test_gpio(int argc, char *argv[])
#ifdef PX4IO_DEVICE_PATH
int fd = open(PX4IO_DEVICE_PATH, 0);
int fd = px4_open(PX4IO_DEVICE_PATH, 0);
if (fd < 0) {
printf("GPIO: open fail\n");
@ -101,16 +101,16 @@ int test_gpio(int argc, char *argv[])
}
/* set all GPIOs to default state */
ioctl(fd, GPIO_RESET, ~0);
px4_ioctl(fd, GPIO_RESET, ~0);
/* XXX need to add some GPIO waving stuff here */
/* Go back to default */
ioctl(fd, GPIO_RESET, ~0);
px4_ioctl(fd, GPIO_RESET, ~0);
close(fd);
px4_close(fd);
printf("\t GPIO test successful.\n");
#endif

View File

@ -45,10 +45,11 @@
#include <drivers/drv_gpio.h>
#include <px4_config.h>
#include <px4_defines.h>
#include <px4_log.h>
#include <sys/types.h>
#include <systemlib/err.h>
#include <debug.h>
#include <errno.h>
#include <fcntl.h>
#include <poll.h>
@ -92,7 +93,7 @@ static int open_uart(const char *device)
int uart = open(device, O_RDWR | O_NOCTTY);
if (uart < 0) {
errx(1, "FAIL: Error opening port");
PX4_ERR("FAIL: Error opening port");
return ERROR;
}
@ -107,12 +108,12 @@ static int open_uart(const char *device)
/* Set baud rate */
if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) {
errx(1, "FAIL: Error setting baudrate / termios config for cfsetispeed, cfsetospeed");
PX4_ERR("FAIL: Error setting baudrate / termios config for cfsetispeed, cfsetospeed");
return ERROR;
}
if (tcsetattr(uart, TCSANOW, &uart_config) < 0) {
errx(1, "FAIL: Error setting baudrate / termios config for tcsetattr");
PX4_ERR("FAIL: Error setting baudrate / termios config for tcsetattr");
return ERROR;
}
@ -129,11 +130,11 @@ static int open_uart(const char *device)
int test_hott_telemetry(int argc, char *argv[])
{
warnx("HoTT Telemetry Test Requirements:");
warnx("- Radio on and Electric Air. Mod on (telemetry -> sensor select).");
warnx("- Receiver telemetry port must be in telemetry mode.");
warnx("- Connect telemetry wire to /dev/ttyS1 (USART2).");
warnx("Testing...");
PX4_INFO("HoTT Telemetry Test Requirements:");
PX4_INFO("- Radio on and Electric Air. Mod on (telemetry -> sensor select).");
PX4_INFO("- Receiver telemetry port must be in telemetry mode.");
PX4_INFO("- Connect telemetry wire to /dev/ttyS1 (USART2).");
PX4_INFO("Testing...");
const char device[] = "/dev/ttyS1";
int fd = open_uart(device);
@ -143,8 +144,10 @@ int test_hott_telemetry(int argc, char *argv[])
return ERROR;
}
#ifdef TIOCSSINGLEWIRE
/* Activate single wire mode */
ioctl(fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
#endif
char send = 'a';
write(fd, &send, 1);
@ -154,12 +157,13 @@ int test_hott_telemetry(int argc, char *argv[])
struct pollfd fds[] = { { .fd = fd, .events = POLLIN } };
if (poll(fds, 1, timeout) == 0) {
errx(1, "FAIL: Could not read sent data.");
PX4_ERR("FAIL: Could not read sent data.");
return 1;
}
char receive;
read(fd, &receive, 1);
warnx("PASS: Single wire enabled. Sent %x and received %x", send, receive);
PX4_INFO("PASS: Single wire enabled. Sent %x and received %x", send, receive);
/* Attempt to read HoTT poll messages from the HoTT receiver */
@ -170,8 +174,8 @@ int test_hott_telemetry(int argc, char *argv[])
for (; received_count < 5; received_count++) {
if (poll(fds, 1, timeout) == 0) {
errx(1, "FAIL: Could not read sent data. Is your HoTT receiver plugged in on %s?", device);
break;
PX4_ERR("FAIL: Could not read sent data. Is your HoTT receiver plugged in on %s?", device);
return 1;
} else {
read(fd, &byte, 1);
@ -187,21 +191,23 @@ int test_hott_telemetry(int argc, char *argv[])
if (received_count > 0 && valid_count > 0) {
if (received_count == max_polls && valid_count == max_polls) {
warnx("PASS: Received %d out of %d valid byte pairs from the HoTT receiver device.", received_count, max_polls);
PX4_INFO("PASS: Received %d out of %d valid byte pairs from the HoTT receiver device.", received_count, max_polls);
} else {
warnx("WARN: Received %d out of %d byte pairs of which %d were valid from the HoTT receiver device.", received_count,
PX4_WARN("WARN: Received %d out of %d byte pairs of which %d were valid from the HoTT receiver device.", received_count,
max_polls, valid_count);
}
} else {
/* Let's work out what went wrong */
if (received_count == 0) {
errx(1, "FAIL: Could not read any polls from HoTT receiver device.");
PX4_ERR("FAIL: Could not read any polls from HoTT receiver device.");
return 1;
}
if (valid_count == 0) {
errx(1, "FAIL: Received unexpected values from the HoTT receiver device.");
PX4_ERR("FAIL: Received unexpected values from the HoTT receiver device.");
return 1;
}
}
@ -221,21 +227,24 @@ int test_hott_telemetry(int argc, char *argv[])
usleep(1000);
}
warnx("PASS: Response sent to the HoTT receiver device. Voltage should now show 2.5V.");
PX4_INFO("PASS: Response sent to the HoTT receiver device. Voltage should now show 2.5V.");
#ifdef TIOCSSINGLEWIRE
/* Disable single wire */
ioctl(fd, TIOCSSINGLEWIRE, ~SER_SINGLEWIRE_ENABLED);
#endif
write(fd, &send, 1);
/* We should timeout as there will be nothing to read (TX and RX no longer connected) */
if (poll(fds, 1, timeout) == 0) {
errx(1, "FAIL: timeout expected.");
PX4_ERR("FAIL: timeout expected.");
return 1;
}
warnx("PASS: Single wire disabled.");
PX4_INFO("PASS: Single wire disabled.");
close(fd);
exit(0);
return 0;
}

View File

@ -46,7 +46,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <time.h>
#include <unistd.h>
@ -54,7 +53,7 @@
#include <drivers/drv_hrt.h>
#include <drivers/drv_tone_alarm.h>
#include <nuttx/spi.h>
//#include <nuttx/spi.h>
#include "tests.h"
@ -127,7 +126,7 @@ int test_tone(int argc, char *argv[])
int fd, result;
unsigned long tone;
fd = open(TONEALARM0_DEVICE_PATH, O_WRONLY);
fd = px4_open(TONEALARM0_DEVICE_PATH, O_WRONLY);
if (fd < 0) {
printf("failed opening " TONEALARM0_DEVICE_PATH "\n");
@ -141,7 +140,7 @@ int test_tone(int argc, char *argv[])
}
if (tone == 0) {
result = ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
result = px4_ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
if (result < 0) {
printf("failed clearing alarms\n");
@ -152,14 +151,14 @@ int test_tone(int argc, char *argv[])
}
} else {
result = ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
result = px4_ioctl(fd, TONE_SET_ALARM, TONE_STOP_TUNE);
if (result < 0) {
printf("failed clearing alarms\n");
goto out;
}
result = ioctl(fd, TONE_SET_ALARM, tone);
result = px4_ioctl(fd, TONE_SET_ALARM, tone);
if (result < 0) {
printf("failed setting alarm %lu\n", tone);
@ -172,7 +171,7 @@ int test_tone(int argc, char *argv[])
out:
if (fd >= 0) {
close(fd);
px4_close(fd);
}
return 0;

View File

@ -36,16 +36,20 @@
* Included Files
****************************************************************************/
#define __STDC_FORMAT_MACROS
#include <inttypes.h>
#include <px4_config.h>
#include <px4_defines.h>
#include <sys/types.h>
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
@ -105,10 +109,10 @@ int test_int(int argc, char *argv[])
int64_t calc = large * 5;
if (calc == 1770781647990) {
printf("\t success: 354156329598 * 5 == %lld\n", calc);
printf("\t success: 354156329598 * 5 == %" PRId64 "\n", calc);
} else {
printf("\t FAIL: 354156329598 * 5 != %lld\n", calc);
printf("\t FAIL: 354156329598 * 5 != %" PRId64 "\n", calc);
ret = -1;
}
@ -127,10 +131,10 @@ int test_int(int argc, char *argv[])
uint64_t small_times_large = large_int * (uint64_t)small;
if (small_times_large == 107374182350) {
printf("\t success: 64bit calculation: 50 * 2147483647 (max int val) == %lld\n", small_times_large);
printf("\t success: 64bit calculation: 50 * 2147483647 (max int val) == %" PRId64 "\n", small_times_large);
} else {
printf("\t FAIL: 50 * 2147483647 != %lld, 64bit cast might fail\n", small_times_large);
printf("\t FAIL: 50 * 2147483647 != %" PRId64 ", 64bit cast might fail\n", small_times_large);
ret = -1;
}

View File

@ -36,7 +36,7 @@
****************************************************************************/
#include <px4_config.h>
#include <nuttx/arch.h>
#include <px4_defines.h>
#include <sys/types.h>
@ -45,13 +45,12 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <nuttx/spi.h>
//#include <nuttx/spi.h>
#include "tests.h"
#include <nuttx/analog/adc.h>
#include <px4_adc.h>
#include <drivers/drv_adc.h>
#include <systemlib/err.h>

View File

@ -37,6 +37,7 @@
****************************************************************************/
#include <px4_config.h>
#include <px4_posix.h>
#include <sys/types.h>
@ -45,7 +46,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
@ -91,15 +91,15 @@ int test_led(int argc, char *argv[])
int fd;
int ret = 0;
fd = open(LED0_DEVICE_PATH, 0);
fd = px4_open(LED0_DEVICE_PATH, 0);
if (fd < 0) {
printf("\tLED: open fail\n");
return ERROR;
}
if (ioctl(fd, LED_ON, LED_BLUE) ||
ioctl(fd, LED_ON, LED_AMBER)) {
if (px4_ioctl(fd, LED_ON, LED_BLUE) ||
px4_ioctl(fd, LED_ON, LED_AMBER)) {
printf("\tLED: ioctl fail\n");
return ERROR;
@ -112,12 +112,12 @@ int test_led(int argc, char *argv[])
for (i = 0; i < 10; i++) {
if (ledon) {
ioctl(fd, LED_ON, LED_BLUE);
ioctl(fd, LED_OFF, LED_AMBER);
px4_ioctl(fd, LED_ON, LED_BLUE);
px4_ioctl(fd, LED_OFF, LED_AMBER);
} else {
ioctl(fd, LED_OFF, LED_BLUE);
ioctl(fd, LED_ON, LED_AMBER);
px4_ioctl(fd, LED_OFF, LED_BLUE);
px4_ioctl(fd, LED_ON, LED_AMBER);
}
ledon = !ledon;
@ -125,8 +125,8 @@ int test_led(int argc, char *argv[])
}
/* Go back to default */
ioctl(fd, LED_ON, LED_BLUE);
ioctl(fd, LED_OFF, LED_AMBER);
px4_ioctl(fd, LED_ON, LED_BLUE);
px4_ioctl(fd, LED_OFF, LED_AMBER);
printf("\t LED test completed, no errors.\n");

View File

@ -37,6 +37,7 @@
* Mathlib test
*/
#include <px4_log.h>
#include <stdio.h>
#include <stdlib.h>
#include <unistd.h>
@ -48,14 +49,14 @@
#include "tests.h"
#define TEST_OP(_title, _op) { unsigned int n = 60000; hrt_abstime t0, t1; t0 = hrt_absolute_time(); for (unsigned int j = 0; j < n; j++) { _op; }; t1 = hrt_absolute_time(); warnx(_title ": %.6fus", (double)(t1 - t0) / n); }
#define TEST_OP(_title, _op) { unsigned int n = 60000; hrt_abstime t0, t1; t0 = hrt_absolute_time(); for (unsigned int j = 0; j < n; j++) { _op; }; t1 = hrt_absolute_time(); PX4_INFO(_title ": %.6fus", (double)(t1 - t0) / n); }
using namespace math;
int test_mathlib(int argc, char *argv[])
{
int rc = 0;
warnx("testing mathlib");
PX4_INFO("testing mathlib");
{
Vector<2> v;
@ -158,7 +159,7 @@ int test_mathlib(int argc, char *argv[])
}
{
warnx("Nonsymmetric matrix operations test");
PX4_INFO("Nonsymmetric matrix operations test");
// test nonsymmetric +, -, +=, -=
float data1[2][3] = {{1, 2, 3}, {4, 5, 6}};
@ -170,7 +171,7 @@ int test_mathlib(int argc, char *argv[])
Matrix<2, 3> m3(data3);
if (m1 + m2 != m3) {
warnx("Matrix<2, 3> + Matrix<2, 3> failed!");
PX4_ERR("Matrix<2, 3> + Matrix<2, 3> failed!");
(m1 + m2).print();
printf("!=\n");
m3.print();
@ -178,7 +179,7 @@ int test_mathlib(int argc, char *argv[])
}
if (m3 - m2 != m1) {
warnx("Matrix<2, 3> - Matrix<2, 3> failed!");
PX4_ERR("Matrix<2, 3> - Matrix<2, 3> failed!");
(m3 - m2).print();
printf("!=\n");
m1.print();
@ -188,7 +189,7 @@ int test_mathlib(int argc, char *argv[])
m1 += m2;
if (m1 != m3) {
warnx("Matrix<2, 3> += Matrix<2, 3> failed!");
PX4_ERR("Matrix<2, 3> += Matrix<2, 3> failed!");
m1.print();
printf("!=\n");
m3.print();
@ -199,7 +200,7 @@ int test_mathlib(int argc, char *argv[])
Matrix<2, 3> m1_orig(data1);
if (m1 != m1_orig) {
warnx("Matrix<2, 3> -= Matrix<2, 3> failed!");
PX4_ERR("Matrix<2, 3> -= Matrix<2, 3> failed!");
m1.print();
printf("!=\n");
m1_orig.print();
@ -216,7 +217,7 @@ int test_mathlib(int argc, char *argv[])
float diff = 0.1f;
float tol = 0.00001f;
warnx("Quaternion transformation methods test.");
PX4_INFO("Quaternion transformation methods test.");
for (float roll = -M_PI_F; roll <= M_PI_F; roll += diff) {
for (float pitch = -M_PI_2_F; pitch <= M_PI_2_F; pitch += diff) {
@ -228,7 +229,7 @@ int test_mathlib(int argc, char *argv[])
for (int i = 0; i < 3; i++) {
for (int j = 0; j < 3; j++) {
if (fabsf(R_orig.data[i][j] - R.data[i][j]) > 0.00001f) {
warnx("Quaternion method 'from_dcm' or 'to_dcm' outside tolerance!");
PX4_WARN("Quaternion method 'from_dcm' or 'to_dcm' outside tolerance!");
rc = 1;
}
}
@ -245,7 +246,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 4; i++) {
if (fabsf(q.data[i] - q_true.data[i]) > tol) {
warnx("Quaternion method 'from_dcm()' outside tolerance!");
PX4_WARN("Quaternion method 'from_dcm()' outside tolerance!");
rc = 1;
}
}
@ -255,7 +256,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 4; i++) {
if (fabsf(q.data[i] - q_true.data[i]) > tol) {
warnx("Quaternion method 'from_euler()' outside tolerance!");
PX4_WARN("Quaternion method 'from_euler()' outside tolerance!");
rc = 1;
}
}
@ -265,7 +266,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 4; i++) {
if (fabsf(q.data[i] - q_true.data[i]) > tol) {
warnx("Quaternion method 'from_euler()' outside tolerance!");
PX4_WARN("Quaternion method 'from_euler()' outside tolerance!");
rc = 1;
}
}
@ -275,7 +276,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 4; i++) {
if (fabsf(q.data[i] - q_true.data[i]) > tol) {
warnx("Quaternion method 'from_euler()' outside tolerance!");
PX4_WARN("Quaternion method 'from_euler()' outside tolerance!");
rc = 1;
}
}
@ -292,7 +293,7 @@ int test_mathlib(int argc, char *argv[])
float diff = 0.1f;
float tol = 0.00001f;
warnx("Quaternion vector rotation method test.");
PX4_INFO("Quaternion vector rotation method test.");
for (float roll = -M_PI_F; roll <= M_PI_F; roll += diff) {
for (float pitch = -M_PI_2_F; pitch <= M_PI_2_F; pitch += diff) {
@ -304,7 +305,7 @@ int test_mathlib(int argc, char *argv[])
for (int i = 0; i < 3; i++) {
if (fabsf(vector_r(i) - vector_q(i)) > tol) {
warnx("Quaternion method 'rotate' outside tolerance");
PX4_WARN("Quaternion method 'rotate' outside tolerance");
rc = 1;
}
}
@ -320,7 +321,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 3; i++) {
if (fabsf(vector_true(i) - vector_q(i)) > tol) {
warnx("Quaternion method 'rotate' outside tolerance");
PX4_WARN("Quaternion method 'rotate' outside tolerance");
rc = 1;
}
}
@ -331,7 +332,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 3; i++) {
if (fabsf(vector_true(i) - vector_q(i)) > tol) {
warnx("Quaternion method 'rotate' outside tolerance");
PX4_WARN("Quaternion method 'rotate' outside tolerance");
rc = 1;
}
}
@ -342,7 +343,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 3; i++) {
if (fabsf(vector_true(i) - vector_q(i)) > tol) {
warnx("Quaternion method 'rotate' outside tolerance");
PX4_WARN("Quaternion method 'rotate' outside tolerance");
rc = 1;
}
}
@ -353,7 +354,7 @@ int test_mathlib(int argc, char *argv[])
for (unsigned i = 0; i < 3; i++) {
if (fabsf(vector_true(i) - vector_q(i)) > tol) {
warnx("Quaternion method 'rotate' outside tolerance");
PX4_WARN("Quaternion method 'rotate' outside tolerance");
rc = 1;
}
}

View File

@ -80,7 +80,7 @@ int test_mixer(int argc, char *argv[])
uint16_t servo_predicted[output_max];
int16_t reverse_pwm_mask = 0;
warnx("testing mixer");
PX4_INFO("testing mixer");
const char *filename = "/etc/mixers/IO_pass.mix";
@ -88,14 +88,14 @@ int test_mixer(int argc, char *argv[])
filename = argv[1];
}
warnx("loading: %s", filename);
PX4_INFO("loading: %s", filename);
char buf[2048];
load_mixer_file(filename, &buf[0], sizeof(buf));
unsigned loaded = strlen(buf);
warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded);
PX4_INFO("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded);
/* load the mixer in chunks, like
* in the case of a remote load,
@ -109,7 +109,7 @@ int test_mixer(int argc, char *argv[])
/* load at once test */
unsigned xx = loaded;
mixer_group.load_from_buf(&buf[0], xx);
warnx("complete buffer load: loaded %u mixers", mixer_group.count());
PX4_INFO("complete buffer load: loaded %u mixers", mixer_group.count());
if (mixer_group.count() != 8) {
return 1;
@ -121,7 +121,7 @@ int test_mixer(int argc, char *argv[])
empty_buf[1] = '\0';
mixer_group.reset();
mixer_group.load_from_buf(&empty_buf[0], empty_load);
warnx("empty buffer load: loaded %u mixers, used: %u", mixer_group.count(), empty_load);
PX4_INFO("empty buffer load: loaded %u mixers, used: %u", mixer_group.count(), empty_load);
if (empty_load != 0) {
return 1;
@ -135,7 +135,7 @@ int test_mixer(int argc, char *argv[])
unsigned transmitted = 0;
warnx("transmitted: %d, loaded: %d", transmitted, loaded);
PX4_INFO("transmitted: %d, loaded: %d", transmitted, loaded);
while (transmitted < loaded) {
@ -150,7 +150,7 @@ int test_mixer(int argc, char *argv[])
memcpy(&mixer_text[mixer_text_length], &buf[transmitted], text_length);
mixer_text_length += text_length;
mixer_text[mixer_text_length] = '\0';
warnx("buflen %u, text:\n\"%s\"", mixer_text_length, &mixer_text[0]);
PX4_INFO("buflen %u, text:\n\"%s\"", mixer_text_length, &mixer_text[0]);
/* process the text buffer, adding new mixers as their descriptions can be parsed */
unsigned resid = mixer_text_length;
@ -158,7 +158,7 @@ int test_mixer(int argc, char *argv[])
/* if anything was parsed */
if (resid != mixer_text_length) {
warnx("used %u", mixer_text_length - resid);
PX4_INFO("used %u", mixer_text_length - resid);
/* copy any leftover text to the base of the buffer for re-use */
if (resid > 0) {
@ -171,7 +171,7 @@ int test_mixer(int argc, char *argv[])
transmitted += text_length;
}
warnx("chunked load: loaded %u mixers", mixer_group.count());
PX4_INFO("chunked load: loaded %u mixers", mixer_group.count());
if (mixer_group.count() != 8) {
return 1;
@ -194,7 +194,7 @@ int test_mixer(int argc, char *argv[])
r_page_servo_control_max[i] = PWM_DEFAULT_MAX;
}
warnx("ARMING TEST: STARTING RAMP");
PX4_INFO("ARMING TEST: STARTING RAMP");
unsigned sleep_quantum_us = 10000;
hrt_abstime starttime = hrt_absolute_time();
@ -213,13 +213,13 @@ int test_mixer(int argc, char *argv[])
/* check mixed outputs to be zero during init phase */
if (hrt_elapsed_time(&starttime) < INIT_TIME_US &&
r_page_servos[i] != r_page_servo_disarmed[i]) {
warnx("disarmed servo value mismatch");
PX4_ERR("disarmed servo value mismatch");
return 1;
}
if (hrt_elapsed_time(&starttime) >= INIT_TIME_US &&
r_page_servos[i] + 1 <= r_page_servo_disarmed[i]) {
warnx("ramp servo value mismatch");
PX4_ERR("ramp servo value mismatch");
return 1;
}
@ -237,7 +237,7 @@ int test_mixer(int argc, char *argv[])
printf("\n");
warnx("ARMING TEST: NORMAL OPERATION");
PX4_INFO("ARMING TEST: NORMAL OPERATION");
for (int j = -jmax; j <= jmax; j++) {
@ -254,20 +254,20 @@ int test_mixer(int argc, char *argv[])
pwm_limit_calc(should_arm, mixed, reverse_pwm_mask, r_page_servo_disarmed, r_page_servo_control_min, r_page_servo_control_max, outputs,
r_page_servos, &pwm_limit);
warnx("mixed %d outputs (max %d)", mixed, output_max);
PX4_INFO("mixed %d outputs (max %d)", mixed, output_max);
for (unsigned i = 0; i < mixed; i++) {
servo_predicted[i] = 1500 + outputs[i] * (r_page_servo_control_max[i] - r_page_servo_control_min[i]) / 2.0f;
if (fabsf(servo_predicted[i] - r_page_servos[i]) > 2) {
printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]);
warnx("mixer violated predicted value");
PX4_ERR("mixer violated predicted value");
return 1;
}
}
}
warnx("ARMING TEST: DISARMING");
PX4_INFO("ARMING TEST: DISARMING");
starttime = hrt_absolute_time();
sleepcount = 0;
@ -285,7 +285,7 @@ int test_mixer(int argc, char *argv[])
for (unsigned i = 0; i < mixed; i++) {
/* check mixed outputs to be zero during init phase */
if (r_page_servos[i] != r_page_servo_disarmed[i]) {
warnx("disarmed servo value mismatch");
PX4_ERR("disarmed servo value mismatch");
return 1;
}
@ -303,7 +303,7 @@ int test_mixer(int argc, char *argv[])
printf("\n");
warnx("ARMING TEST: REARMING: STARTING RAMP");
PX4_INFO("ARMING TEST: REARMING: STARTING RAMP");
starttime = hrt_absolute_time();
sleepcount = 0;
@ -327,7 +327,7 @@ int test_mixer(int argc, char *argv[])
if (hrt_elapsed_time(&starttime) < RAMP_TIME_US &&
(r_page_servos[i] + 1 <= r_page_servo_disarmed[i] ||
r_page_servos[i] > servo_predicted[i])) {
warnx("ramp servo value mismatch");
PX4_ERR("ramp servo value mismatch");
return 1;
}
@ -335,7 +335,7 @@ int test_mixer(int argc, char *argv[])
if (hrt_elapsed_time(&starttime) > RAMP_TIME_US &&
fabsf(servo_predicted[i] - r_page_servos[i]) > 2) {
printf("\t %d: %8.4f predicted: %d, servo: %d\n", i, (double)outputs[i], servo_predicted[i], (int)r_page_servos[i]);
warnx("mixer violated predicted value");
PX4_ERR("mixer violated predicted value");
return 1;
}
@ -366,18 +366,18 @@ int test_mixer(int argc, char *argv[])
load_mixer_file(filename, &buf[0], sizeof(buf));
loaded = strlen(buf);
warnx("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded);
PX4_INFO("loaded: \n\"%s\"\n (%d chars)", &buf[0], loaded);
unsigned mc_loaded = loaded;
mixer_group.load_from_buf(&buf[0], mc_loaded);
warnx("complete buffer load: loaded %u mixers", mixer_group.count());
PX4_INFO("complete buffer load: loaded %u mixers", mixer_group.count());
if (mixer_group.count() != 5) {
warnx("FAIL: Quad W mixer load failed");
PX4_ERR("FAIL: Quad W mixer load failed");
return 1;
}
warnx("SUCCESS: No errors in mixer test");
PX4_INFO("SUCCESS: No errors in mixer test");
return 0;
}

View File

@ -69,15 +69,15 @@ test_mount(int argc, char *argv[])
/* check if microSD card is mounted */
struct stat buffer;
if (stat("/fs/microsd/", &buffer)) {
warnx("no microSD card mounted, aborting file test");
if (stat(PX4_ROOTFSDIR "/fs/microsd/", &buffer)) {
PX4_ERR("no microSD card mounted, aborting file test");
return 1;
}
/* list directory */
DIR *d;
struct dirent *dir;
d = opendir("/fs/microsd");
d = opendir(PX4_ROOTFSDIR "/fs/microsd");
if (d) {
@ -87,11 +87,11 @@ test_mount(int argc, char *argv[])
closedir(d);
warnx("directory listing ok (FS mounted and readable)");
PX4_INFO("directory listing ok (FS mounted and readable)");
} else {
/* failed opening dir */
warnx("FAILED LISTING MICROSD ROOT DIRECTORY");
PX4_ERR("FAILED LISTING MICROSD ROOT DIRECTORY");
if (stat(cmd_filename, &buffer) == OK) {
(void)unlink(cmd_filename);
@ -131,7 +131,7 @@ test_mount(int argc, char *argv[])
it_left_abort = abort_tries;
}
warnx("Iterations left: #%d / #%d of %d / %d\n(%s)", it_left_fsync, it_left_abort,
PX4_INFO("Iterations left: #%d / #%d of %d / %d\n(%s)", it_left_fsync, it_left_abort,
fsync_tries, abort_tries, buf);
int it_left_fsync_prev = it_left_fsync;
@ -147,7 +147,7 @@ test_mount(int argc, char *argv[])
/* announce mode switch */
if (it_left_fsync_prev != it_left_fsync && it_left_fsync == 0) {
warnx("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC");
PX4_INFO("\n SUCCESSFULLY PASSED FSYNC'ED WRITES, CONTINUTING WITHOUT FSYNC");
fsync(fileno(stdout));
fsync(fileno(stderr));
usleep(20000);
@ -165,7 +165,7 @@ test_mount(int argc, char *argv[])
/* this must be the first iteration, do something */
cmd_fd = open(cmd_filename, O_TRUNC | O_WRONLY | O_CREAT, PX4_O_MODE_666);
warnx("First iteration of file test\n");
PX4_INFO("First iteration of file test\n");
}
char buf[64];
@ -200,17 +200,17 @@ test_mount(int argc, char *argv[])
uint8_t read_buf[chunk_sizes[c] + alignments] __attribute__((aligned(64)));
int fd = open("/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
int fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_TRUNC | O_WRONLY | O_CREAT);
for (unsigned i = 0; i < iterations; i++) {
int wret = write(fd, write_buf + a, chunk_sizes[c]);
if (wret != (int)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);
PX4_ERR("memory is unaligned, align shift: %d", a);
}
return 1;
@ -237,14 +237,14 @@ test_mount(int argc, char *argv[])
usleep(200000);
close(fd);
fd = open("/fs/microsd/testfile", O_RDONLY);
fd = open(PX4_ROOTFSDIR "/fs/microsd/testfile", O_RDONLY);
/* read back data for validation */
for (unsigned i = 0; i < iterations; i++) {
int rret = read(fd, read_buf, chunk_sizes[c]);
if (rret != (int)chunk_sizes[c]) {
warnx("READ ERROR!");
PX4_ERR("READ ERROR!");
return 1;
}
@ -253,24 +253,24 @@ test_mount(int argc, char *argv[])
for (unsigned 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_WARN("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;
}
}
int ret = unlink("/fs/microsd/testfile");
int ret = unlink(PX4_ROOTFSDIR "/fs/microsd/testfile");
close(fd);
if (ret) {
warnx("UNLINKING FILE FAILED");
PX4_ERR("UNLINKING FILE FAILED");
return 1;
}
@ -284,7 +284,7 @@ test_mount(int argc, char *argv[])
/* we always reboot for the next test if we get here */
warnx("Iteration done, rebooting..");
PX4_INFO("Iteration done, rebooting..");
fsync(fileno(stdout));
fsync(fileno(stderr));
usleep(50000);

View File

@ -37,6 +37,7 @@
* Tests related to the parameter system.
*/
#include <px4_defines.h>
#include <stdio.h>
#include "systemlib/err.h"
#include "systemlib/param/param.h"
@ -54,41 +55,49 @@ test_param(int argc, char *argv[])
p = param_find("test");
if (p == PARAM_INVALID) {
errx(1, "test parameter not found");
warnx("test parameter not found");
return 1;
}
if (param_reset(p) != OK) {
errx(1, "failed param reset");
warnx("failed param reset");
return 1;
}
param_type_t t = param_type(p);
if (t != PARAM_TYPE_INT32) {
errx(1, "test parameter type mismatch (got %u)", (unsigned)t);
warnx("test parameter type mismatch (got %u)", (unsigned)t);
return 1;
}
int32_t val;
if (param_get(p, &val) != OK) {
errx(1, "failed to read test parameter");
warnx("failed to read test parameter");
return 1;
}
if (val != PARAM_MAGIC1) {
errx(1, "parameter value mismatch");
warnx("parameter value mismatch");
return 1;
}
val = PARAM_MAGIC2;
if (param_set(p, &val) != OK) {
errx(1, "failed to write test parameter");
warnx("failed to write test parameter");
return 1;
}
if (param_get(p, &val) != OK) {
errx(1, "failed to re-read test parameter");
warnx("failed to re-read test parameter");
return 1;
}
if ((uint32_t)val != PARAM_MAGIC2) {
errx(1, "parameter value mismatch after write");
warnx("parameter value mismatch after write");
return 1;
}
warnx("parameter test PASS");

View File

@ -46,7 +46,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>

View File

@ -47,7 +47,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
@ -76,8 +75,8 @@ int test_rc(int argc, char *argv[])
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.");
PX4_INFO("Reading PPM values - press any key to abort");
PX4_INFO("This test guarantees: 10 Hz update rates, no glitches (channel values), no channel count changes.");
if (rc_updated) {
@ -108,7 +107,7 @@ int test_rc(int argc, char *argv[])
/* 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]);
PX4_ERR("comparison fail: RC: %d, expected: %d", rc_input.values[i], rc_last.values[i]);
(void)close(_rc_sub);
return ERROR;
}
@ -117,13 +116,13 @@ int test_rc(int argc, char *argv[])
}
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);
PX4_ERR("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_last_signal > 100000) {
warnx("TIMEOUT, less than 10 Hz updates");
PX4_ERR("TIMEOUT, less than 10 Hz updates");
(void)close(_rc_sub);
return ERROR;
}
@ -137,11 +136,11 @@ int test_rc(int argc, char *argv[])
}
} else {
warnx("failed reading RC input data");
PX4_ERR("failed reading RC input data");
return ERROR;
}
warnx("PPM CONTINUITY TEST PASSED SUCCESSFULLY!");
PX4_INFO("PPM CONTINUITY TEST PASSED SUCCESSFULLY!");
return 0;
}

View File

@ -39,6 +39,7 @@
*/
#include <px4_config.h>
#include <px4_posix.h>
#include <sys/types.h>
@ -47,13 +48,12 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <math.h>
#include <systemlib/err.h>
#include <arch/board/board.h>
#include <nuttx/spi.h>
//#include <nuttx/spi.h>
#include "tests.h"
@ -95,7 +95,7 @@ accel(int argc, char *argv[], const char *path)
struct accel_report buf;
int ret;
fd = open(path, O_RDONLY);
fd = px4_open(path, O_RDONLY);
if (fd < 0) {
printf("\tACCEL: open fail, run <mpu6000 start> or <lsm303 start> or <bma180 start> first.\n");
@ -106,7 +106,7 @@ accel(int argc, char *argv[], const char *path)
usleep(100000);
/* read data - expect samples */
ret = read(fd, &buf, sizeof(buf));
ret = px4_read(fd, &buf, sizeof(buf));
if (ret != sizeof(buf)) {
printf("\tACCEL: read1 fail (%d)\n", ret);
@ -130,7 +130,7 @@ accel(int argc, char *argv[], const char *path)
/* Let user know everything is ok */
printf("\tOK: ACCEL passed all tests successfully\n");
close(fd);
px4_close(fd);
return OK;
}
@ -145,7 +145,7 @@ gyro(int argc, char *argv[], const char *path)
struct gyro_report buf;
int ret;
fd = open(path, O_RDONLY);
fd = px4_open(path, O_RDONLY);
if (fd < 0) {
printf("\tGYRO: open fail, run <l3gd20 start> or <mpu6000 start> first.\n");
@ -156,7 +156,7 @@ gyro(int argc, char *argv[], const char *path)
usleep(5000);
/* read data - expect samples */
ret = read(fd, &buf, sizeof(buf));
ret = px4_read(fd, &buf, sizeof(buf));
if (ret != sizeof(buf)) {
printf("\tGYRO: read fail (%d)\n", ret);
@ -175,7 +175,7 @@ gyro(int argc, char *argv[], const char *path)
/* Let user know everything is ok */
printf("\tOK: GYRO passed all tests successfully\n");
close(fd);
px4_close(fd);
return OK;
}
@ -190,7 +190,7 @@ mag(int argc, char *argv[], const char *path)
struct mag_report buf;
int ret;
fd = open(path, O_RDONLY);
fd = px4_open(path, O_RDONLY);
if (fd < 0) {
printf("\tMAG: open fail, run <hmc5883 start> or <lsm303 start> first.\n");
@ -201,7 +201,7 @@ mag(int argc, char *argv[], const char *path)
usleep(5000);
/* read data - expect samples */
ret = read(fd, &buf, sizeof(buf));
ret = px4_read(fd, &buf, sizeof(buf));
if (ret != sizeof(buf)) {
printf("\tMAG: read fail (%d)\n", ret);
@ -220,7 +220,7 @@ mag(int argc, char *argv[], const char *path)
/* Let user know everything is ok */
printf("\tOK: MAG passed all tests successfully\n");
close(fd);
px4_close(fd);
return OK;
}
@ -235,7 +235,7 @@ baro(int argc, char *argv[], const char *path)
struct baro_report buf;
int ret;
fd = open(path, O_RDONLY);
fd = px4_open(path, O_RDONLY);
if (fd < 0) {
printf("\tBARO: open fail, run <ms5611 start> or <lps331 start> first.\n");
@ -246,7 +246,7 @@ baro(int argc, char *argv[], const char *path)
usleep(5000);
/* read data - expect samples */
ret = read(fd, &buf, sizeof(buf));
ret = px4_read(fd, &buf, sizeof(buf));
if (ret != sizeof(buf)) {
printf("\tBARO: read fail (%d)\n", ret);
@ -259,7 +259,7 @@ baro(int argc, char *argv[], const char *path)
/* Let user know everything is ok */
printf("\tOK: BARO passed all tests successfully\n");
close(fd);
px4_close(fd);
return OK;
}

View File

@ -46,14 +46,13 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <time.h>
#include <arch/board/board.h>
#include <drivers/drv_pwm_output.h>
#include <systemlib/err.h>
#include <nuttx/spi.h>
//#include <nuttx/spi.h>
#include "tests.h"

View File

@ -37,6 +37,7 @@
****************************************************************************/
#include <px4_config.h>
#include <px4_defines.h>
#include <sys/types.h>
@ -45,7 +46,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>

View File

@ -45,7 +45,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
@ -104,7 +103,7 @@ cycletime(void)
****************************************************************************/
/****************************************************************************
* Name: test_led
* Name: test_time
****************************************************************************/
int test_time(int argc, char *argv[])
@ -153,11 +152,11 @@ int test_time(int argc, char *argv[])
}
if (deltadelta > 1000) {
fprintf(stderr, "h %llu c %llu d %lld\n", h, c, delta - lowdelta);
fprintf(stderr, "h %" PRIu64 " c %" PRIu64 " d %" PRId64 "\n", h, c, delta - lowdelta);
}
}
printf("Maximum jitter %lldus\n", maxdelta);
printf("Maximum jitter %" PRId64 "us\n", maxdelta);
return 0;
}

View File

@ -38,6 +38,7 @@
****************************************************************************/
#include <px4_config.h>
#include <px4_defines.h>
#include <sys/types.h>
@ -46,7 +47,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <termios.h>
#include <string.h>
@ -109,12 +109,15 @@ int test_uart_baudchange(int argc, char *argv[])
int termios_state = 0;
int ret;
#define UART_BAUDRATE_RUNTIME_CONF
#ifdef UART_BAUDRATE_RUNTIME_CONF
if ((termios_state = tcgetattr(uart2, &uart2_config)) < 0) {
printf("ERROR getting termios config for UART2: %d\n", termios_state);
exit(termios_state);
ret = termios_state;
goto cleanup;
}
memcpy(&uart2_config_original, &uart2_config, sizeof(struct termios));
@ -122,18 +125,21 @@ int test_uart_baudchange(int argc, char *argv[])
/* Set baud rate */
if (cfsetispeed(&uart2_config, B9600) < 0 || cfsetospeed(&uart2_config, B9600) < 0) {
printf("ERROR setting termios config for UART2: %d\n", termios_state);
exit(ERROR);
ret = ERROR;
goto cleanup;
}
if ((termios_state = tcsetattr(uart2, TCSANOW, &uart2_config)) < 0) {
printf("ERROR setting termios config for UART2\n");
exit(termios_state);
ret = termios_state;
goto cleanup;
}
/* Set back to original settings */
if ((termios_state = tcsetattr(uart2, TCSANOW, &uart2_config_original)) < 0) {
printf("ERROR setting termios config for UART2\n");
exit(termios_state);
ret = termios_state;
goto cleanup;
}
#endif
@ -156,4 +162,8 @@ int test_uart_baudchange(int argc, char *argv[])
printf("uart2_nwrite %d\n", uart2_nwrite);
return OK;
cleanup:
close(uart2);
return ret;
}

View File

@ -46,7 +46,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>

View File

@ -43,10 +43,10 @@
#include <stdio.h>
#include <stdlib.h>
#include <stdint.h>
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>

View File

@ -46,7 +46,6 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>

View File

@ -48,11 +48,10 @@
#include <unistd.h>
#include <fcntl.h>
#include <errno.h>
#include <debug.h>
#include <arch/board/board.h>
#include <nuttx/spi.h>
//#include <nuttx/spi.h>
#include <systemlib/perf_counter.h>
@ -97,7 +96,9 @@ const struct {
{"hott_telemetry", test_hott_telemetry, OPT_NOJIGTEST | OPT_NOALLTEST},
{"tone", test_tone, 0},
{"sleep", test_sleep, OPT_NOJIGTEST},
#ifdef __PX4_NUTTX
{"time", test_time, OPT_NOJIGTEST},
#endif
{"perf", test_perf, OPT_NOJIGTEST},
{"all", test_all, OPT_NOALLTEST | OPT_NOJIGTEST},
{"jig", test_jig, OPT_NOJIGTEST | OPT_NOALLTEST},