aboutsummaryrefslogtreecommitdiff
path: root/unittests
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2014-12-20 13:54:58 +0100
committerLorenz Meier <lm@inf.ethz.ch>2014-12-20 13:54:58 +0100
commit6e0cf5002914e9045082bdfe1d3acc484a37f7fb (patch)
treedceede05053ad0fb51e641e7e26509b4d1309dee /unittests
parent19d5383c56b78132e63ea30ef1625b0aaa4a0dee (diff)
downloadpx4-firmware-6e0cf5002914e9045082bdfe1d3acc484a37f7fb.tar.gz
px4-firmware-6e0cf5002914e9045082bdfe1d3acc484a37f7fb.tar.bz2
px4-firmware-6e0cf5002914e9045082bdfe1d3acc484a37f7fb.zip
Move unittests into a more perceivable directory
Diffstat (limited to 'unittests')
-rw-r--r--unittests/.gitignore6
-rw-r--r--unittests/Makefile54
-rw-r--r--unittests/arch/board/board.h0
-rw-r--r--unittests/autodeclination_test.cpp28
-rw-r--r--unittests/board_config.h0
-rw-r--r--unittests/data/fit_linear_voltage.m14
-rw-r--r--unittests/data/px4io_v1.3.csv70
-rw-r--r--unittests/debug.h5
-rw-r--r--unittests/hrt.cpp16
-rw-r--r--unittests/mixer_test.cpp14
-rw-r--r--unittests/nuttx/config.h0
-rw-r--r--unittests/queue.h133
-rwxr-xr-xunittests/run_tests.sh6
-rw-r--r--unittests/sbus2_test.cpp76
-rw-r--r--unittests/sf0x_test.cpp65
-rw-r--r--unittests/st24_test.cpp76
16 files changed, 563 insertions, 0 deletions
diff --git a/unittests/.gitignore b/unittests/.gitignore
new file mode 100644
index 000000000..37e923b5e
--- /dev/null
+++ b/unittests/.gitignore
@@ -0,0 +1,6 @@
+./obj/*
+mixer_test
+sf0x_test
+sbus2_test
+autodeclination_test
+st24_test
diff --git a/unittests/Makefile b/unittests/Makefile
new file mode 100644
index 000000000..8742e2f7c
--- /dev/null
+++ b/unittests/Makefile
@@ -0,0 +1,54 @@
+
+CC=g++
+CFLAGS=-I. -I../../src/modules -I ../../src/include -I../../src/drivers \
+ -I../../src -I../../src/lib -D__EXPORT="" -Dnullptr="0" -lm
+
+all: mixer_test sbus2_test autodeclination_test st24_test sf0x_test
+
+MIXER_FILES=../../src/systemcmds/tests/test_mixer.cpp \
+ ../../src/systemcmds/tests/test_conv.cpp \
+ ../../src/modules/systemlib/mixer/mixer_simple.cpp \
+ ../../src/modules/systemlib/mixer/mixer_multirotor.cpp \
+ ../../src/modules/systemlib/mixer/mixer.cpp \
+ ../../src/modules/systemlib/mixer/mixer_group.cpp \
+ ../../src/modules/systemlib/mixer/mixer_load.c \
+ ../../src/modules/systemlib/pwm_limit/pwm_limit.c \
+ hrt.cpp \
+ mixer_test.cpp
+
+SBUS2_FILES=../../src/modules/px4iofirmware/sbus.c \
+ hrt.cpp \
+ sbus2_test.cpp
+
+ST24_FILES=../../src/lib/rc/st24.c \
+ hrt.cpp \
+ st24_test.cpp
+
+SF0X_FILES= \
+ hrt.cpp \
+ sf0x_test.cpp \
+ ../../src/drivers/sf0x/sf0x_parser.cpp
+
+AUTODECLINATION_FILES= ../../src/lib/geo_lookup/geo_mag_declination.c \
+ hrt.cpp \
+ autodeclination_test.cpp
+
+mixer_test: $(MIXER_FILES)
+ $(CC) -o mixer_test $(MIXER_FILES) $(CFLAGS)
+
+sbus2_test: $(SBUS2_FILES)
+ $(CC) -o sbus2_test $(SBUS2_FILES) $(CFLAGS)
+
+sf0x_test: $(SF0X_FILES)
+ $(CC) -o sf0x_test $(SF0X_FILES) $(CFLAGS)
+
+autodeclination_test: $(SBUS2_FILES)
+ $(CC) -o autodeclination_test $(AUTODECLINATION_FILES) $(CFLAGS)
+
+st24_test: $(ST24_FILES)
+ $(CC) -o st24_test $(ST24_FILES) $(CFLAGS)
+
+.PHONY: clean
+
+clean:
+ rm -f $(ODIR)/*.o *~ core $(INCDIR)/*~ mixer_test sbus2_test autodeclination_test st24_test sf0x_test
diff --git a/unittests/arch/board/board.h b/unittests/arch/board/board.h
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/unittests/arch/board/board.h
diff --git a/unittests/autodeclination_test.cpp b/unittests/autodeclination_test.cpp
new file mode 100644
index 000000000..93bc340bb
--- /dev/null
+++ b/unittests/autodeclination_test.cpp
@@ -0,0 +1,28 @@
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <systemlib/mixer/mixer.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <px4iofirmware/px4io.h>
+#include "../../src/systemcmds/tests/tests.h"
+#include <geo/geo.h>
+
+int main(int argc, char *argv[]) {
+ warnx("autodeclination test started");
+
+ if (argc < 3)
+ errx(1, "Need lat/lon!");
+
+ char* p_end;
+
+ float lat = strtod(argv[1], &p_end);
+ float lon = strtod(argv[2], &p_end);
+
+ float declination = get_mag_declination(lat, lon);
+
+ printf("lat: %f lon: %f, dec: %f\n", lat, lon, declination);
+
+}
diff --git a/unittests/board_config.h b/unittests/board_config.h
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/unittests/board_config.h
diff --git a/unittests/data/fit_linear_voltage.m b/unittests/data/fit_linear_voltage.m
new file mode 100644
index 000000000..7d0c2c27f
--- /dev/null
+++ b/unittests/data/fit_linear_voltage.m
@@ -0,0 +1,14 @@
+close all;
+clear all;
+M = importdata('px4io_v1.3.csv');
+voltage = M.data(:, 1);
+counts = M.data(:, 2);
+plot(counts, voltage, 'b*-', 'LineWidth', 2, 'MarkerSize', 15);
+coeffs = polyfit(counts, voltage, 1);
+fittedC = linspace(min(counts), max(counts), 500);
+fittedV = polyval(coeffs, fittedC);
+hold on
+plot(fittedC, fittedV, 'r-', 'LineWidth', 3);
+
+slope = coeffs(1)
+y_intersection = coeffs(2)
diff --git a/unittests/data/px4io_v1.3.csv b/unittests/data/px4io_v1.3.csv
new file mode 100644
index 000000000..b41ee8f1f
--- /dev/null
+++ b/unittests/data/px4io_v1.3.csv
@@ -0,0 +1,70 @@
+voltage, counts
+4.3, 950
+4.4, 964
+4.5, 986
+4.6, 1009
+4.7, 1032
+4.8, 1055
+4.9, 1078
+5.0, 1101
+5.2, 1124
+5.3, 1148
+5.4, 1171
+5.5, 1195
+6.0, 1304
+6.1, 1329
+6.2, 1352
+7.0, 1517
+7.1, 1540
+7.2, 1564
+7.3, 1585
+7.4, 1610
+7.5, 1636
+8.0, 1728
+8.1, 1752
+8.2, 1755
+8.3, 1798
+8.4, 1821
+9.0, 1963
+9.1, 1987
+9.3, 2010
+9.4, 2033
+10.0, 2174
+10.1, 2198
+10.2, 2221
+10.3, 2245
+10.4, 2268
+11.0, 2385
+11.1, 2409
+11.2, 2432
+11.3, 2456
+11.4, 2480
+11.5, 2502
+11.6, 2526
+11.7, 2550
+11.8, 2573
+11.9, 2597
+12.0, 2621
+12.1, 2644
+12.3, 2668
+12.4, 2692
+12.5, 2716
+12.6, 2737
+12.7, 2761
+13.0, 2832
+13.5, 2950
+13.6, 2973
+14.1, 3068
+14.2, 3091
+14.7, 3209
+15.0, 3280
+15.1, 3304
+15.5, 3374
+15.6, 3397
+15.7, 3420
+16.0, 3492
+16.1, 3514
+16.2, 3538
+16.9, 3680
+17.0, 3704
+17.1, 3728
diff --git a/unittests/debug.h b/unittests/debug.h
new file mode 100644
index 000000000..9824d13fc
--- /dev/null
+++ b/unittests/debug.h
@@ -0,0 +1,5 @@
+
+#pragma once
+
+#include <systemlib/err.h>
+#define lowsyslog warnx \ No newline at end of file
diff --git a/unittests/hrt.cpp b/unittests/hrt.cpp
new file mode 100644
index 000000000..01b5958b7
--- /dev/null
+++ b/unittests/hrt.cpp
@@ -0,0 +1,16 @@
+#include <sys/time.h>
+#include <inttypes.h>
+#include <drivers/drv_hrt.h>
+#include <stdio.h>
+
+hrt_abstime hrt_absolute_time() {
+ struct timeval te;
+ gettimeofday(&te, NULL); // get current time
+ hrt_abstime us = static_cast<uint64_t>(te.tv_sec) * 1e6 + te.tv_usec; // caculate us
+ return us;
+}
+
+hrt_abstime hrt_elapsed_time(const volatile hrt_abstime *then) {
+ // not thread safe
+ return hrt_absolute_time() - *then;
+}
diff --git a/unittests/mixer_test.cpp b/unittests/mixer_test.cpp
new file mode 100644
index 000000000..06499afd0
--- /dev/null
+++ b/unittests/mixer_test.cpp
@@ -0,0 +1,14 @@
+#include <systemlib/mixer/mixer.h>
+#include <systemlib/err.h>
+#include "../../src/systemcmds/tests/tests.h"
+
+int main(int argc, char *argv[]) {
+ warnx("Host execution started");
+
+ char* args[] = {argv[0], "../../ROMFS/px4fmu_common/mixers/IO_pass.mix",
+ "../../ROMFS/px4fmu_common/mixers/FMU_quad_w.mix"};
+
+ test_mixer(3, args);
+
+ test_conv(1, args);
+}
diff --git a/unittests/nuttx/config.h b/unittests/nuttx/config.h
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/unittests/nuttx/config.h
diff --git a/unittests/queue.h b/unittests/queue.h
new file mode 100644
index 000000000..0fdb170db
--- /dev/null
+++ b/unittests/queue.h
@@ -0,0 +1,133 @@
+/************************************************************************
+ * include/queue.h
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ************************************************************************/
+
+#ifndef __INCLUDE_QUEUE_H
+#define __INCLUDE_QUEUE_H
+
+#ifndef FAR
+#define FAR
+#endif
+
+/************************************************************************
+ * Included Files
+ ************************************************************************/
+
+#include <sys/types.h>
+
+/************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************/
+
+#define sq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
+#define dq_init(q) do { (q)->head = NULL; (q)->tail = NULL; } while (0)
+
+#define sq_next(p) ((p)->flink)
+#define dq_next(p) ((p)->flink)
+#define dq_prev(p) ((p)->blink)
+
+#define sq_empty(q) ((q)->head == NULL)
+#define dq_empty(q) ((q)->head == NULL)
+
+#define sq_peek(q) ((q)->head)
+#define dq_peek(q) ((q)->head)
+
+/************************************************************************
+ * Global Type Declarations
+ ************************************************************************/
+
+struct sq_entry_s
+{
+ FAR struct sq_entry_s *flink;
+};
+typedef struct sq_entry_s sq_entry_t;
+
+struct dq_entry_s
+{
+ FAR struct dq_entry_s *flink;
+ FAR struct dq_entry_s *blink;
+};
+typedef struct dq_entry_s dq_entry_t;
+
+struct sq_queue_s
+{
+ FAR sq_entry_t *head;
+ FAR sq_entry_t *tail;
+};
+typedef struct sq_queue_s sq_queue_t;
+
+struct dq_queue_s
+{
+ FAR dq_entry_t *head;
+ FAR dq_entry_t *tail;
+};
+typedef struct dq_queue_s dq_queue_t;
+
+/************************************************************************
+ * Global Function Prototypes
+ ************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN void sq_addfirst(FAR sq_entry_t *node, sq_queue_t *queue);
+EXTERN void dq_addfirst(FAR dq_entry_t *node, dq_queue_t *queue);
+EXTERN void sq_addlast(FAR sq_entry_t *node, sq_queue_t *queue);
+EXTERN void dq_addlast(FAR dq_entry_t *node, dq_queue_t *queue);
+EXTERN void sq_addafter(FAR sq_entry_t *prev, FAR sq_entry_t *node,
+ sq_queue_t *queue);
+EXTERN void dq_addafter(FAR dq_entry_t *prev, FAR dq_entry_t *node,
+ dq_queue_t *queue);
+EXTERN void dq_addbefore(FAR dq_entry_t *next, FAR dq_entry_t *node,
+ dq_queue_t *queue);
+
+EXTERN FAR sq_entry_t *sq_remafter(FAR sq_entry_t *node, sq_queue_t *queue);
+EXTERN void sq_rem(FAR sq_entry_t *node, sq_queue_t *queue);
+EXTERN void dq_rem(FAR dq_entry_t *node, dq_queue_t *queue);
+EXTERN FAR sq_entry_t *sq_remlast(sq_queue_t *queue);
+EXTERN FAR dq_entry_t *dq_remlast(dq_queue_t *queue);
+EXTERN FAR sq_entry_t *sq_remfirst(sq_queue_t *queue);
+EXTERN FAR dq_entry_t *dq_remfirst(dq_queue_t *queue);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __INCLUDE_QUEUE_H_ */
+
diff --git a/unittests/run_tests.sh b/unittests/run_tests.sh
new file mode 100755
index 000000000..ff5ee509a
--- /dev/null
+++ b/unittests/run_tests.sh
@@ -0,0 +1,6 @@
+#!/bin/sh
+
+make clean
+make all
+./mixer_test
+./sbus2_test ../../../../data/sbus2/sbus2_r7008SB_gps_baro_tx_off.txt \ No newline at end of file
diff --git a/unittests/sbus2_test.cpp b/unittests/sbus2_test.cpp
new file mode 100644
index 000000000..e2c18369c
--- /dev/null
+++ b/unittests/sbus2_test.cpp
@@ -0,0 +1,76 @@
+
+#include <stdio.h>
+#include <unistd.h>
+#include <string.h>
+#include <systemlib/mixer/mixer.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <px4iofirmware/px4io.h>
+#include "../../src/systemcmds/tests/tests.h"
+
+int main(int argc, char *argv[]) {
+ warnx("SBUS2 test started");
+
+ if (argc < 2)
+ errx(1, "Need a filename for the input file");
+
+ warnx("loading data from: %s", argv[1]);
+
+ FILE *fp;
+
+ fp = fopen(argv[1],"rt");
+
+ if (!fp)
+ errx(1, "failed opening file");
+
+ float f;
+ unsigned x;
+ int ret;
+
+ // Trash the first 20 lines
+ for (unsigned i = 0; i < 20; i++) {
+ char buf[200];
+ (void)fgets(buf, sizeof(buf), fp);
+ }
+
+ // Init the parser
+ uint8_t frame[30];
+ unsigned partial_frame_count = 0;
+ uint16_t rc_values[18];
+ uint16_t num_values;
+ bool sbus_failsafe;
+ bool sbus_frame_drop;
+ uint16_t max_channels = sizeof(rc_values) / sizeof(rc_values[0]);
+
+ float last_time = 0;
+
+ while (EOF != (ret = fscanf(fp, "%f,%x,,", &f, &x))) {
+ if (((f - last_time) * 1000 * 1000) > 3000) {
+ partial_frame_count = 0;
+ warnx("FRAME RESET\n\n");
+ }
+
+ frame[partial_frame_count] = x;
+ partial_frame_count++;
+
+ //warnx("%f: 0x%02x, first: 0x%02x, last: 0x%02x, pcount: %u", (double)f, x, frame[0], frame[24], partial_frame_count);
+
+ if (partial_frame_count == sizeof(frame))
+ partial_frame_count = 0;
+
+ last_time = f;
+
+ // Pipe the data into the parser
+ hrt_abstime now = hrt_absolute_time();
+
+ //if (partial_frame_count % 25 == 0)
+ //sbus_parse(now, frame, &partial_frame_count, rc_values, &num_values, &sbus_failsafe, &sbus_frame_drop, max_channels);
+ }
+
+ if (ret == EOF) {
+ warnx("Test finished, reached end of file");
+ } else {
+ warnx("Test aborted, errno: %d", ret);
+ }
+
+}
diff --git a/unittests/sf0x_test.cpp b/unittests/sf0x_test.cpp
new file mode 100644
index 000000000..82d19fcbe
--- /dev/null
+++ b/unittests/sf0x_test.cpp
@@ -0,0 +1,65 @@
+
+#include <unistd.h>
+#include <string.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+
+#include <drivers/sf0x/sf0x_parser.h>
+
+int main(int argc, char *argv[])
+{
+ warnx("SF0X test started");
+
+ int ret = 0;
+
+ const char LINE_MAX = 20;
+ char _linebuf[LINE_MAX];
+ _linebuf[0] = '\0';
+
+ const char *lines[] = {"0.01\r\n",
+ "0.02\r\n",
+ "0.03\r\n",
+ "0.04\r\n",
+ "0",
+ ".",
+ "0",
+ "5",
+ "\r",
+ "\n",
+ "0",
+ "3\r",
+ "\n"
+ "\r\n",
+ "0.06",
+ "\r\n"
+ };
+
+ enum SF0X_PARSE_STATE state = SF0X_PARSE_STATE0_UNSYNC;
+ float dist_m;
+ char _parserbuf[LINE_MAX];
+ unsigned _parsebuf_index = 0;
+
+ for (unsigned l = 0; l < sizeof(lines) / sizeof(lines[0]); l++) {
+
+ printf("\n%s", _linebuf);
+
+ int parse_ret;
+
+ for (int i = 0; i < strlen(lines[l]); i++) {
+ parse_ret = sf0x_parser(lines[l][i], _parserbuf, &_parsebuf_index, &state, &dist_m);
+
+ if (parse_ret == 0) {
+ printf("\nparsed: %f %s\n", dist_m, (parse_ret == 0) ? "OK" : "");
+ }
+ }
+
+ printf("%s", lines[l]);
+
+ }
+
+ warnx("test finished");
+
+ return ret;
+}
diff --git a/unittests/st24_test.cpp b/unittests/st24_test.cpp
new file mode 100644
index 000000000..25a9355e2
--- /dev/null
+++ b/unittests/st24_test.cpp
@@ -0,0 +1,76 @@
+
+#include <stdio.h>
+#include <unistd.h>
+#include <string.h>
+#include <systemlib/err.h>
+#include <drivers/drv_hrt.h>
+#include <rc/st24.h>
+#include "../../src/systemcmds/tests/tests.h"
+
+int main(int argc, char *argv[])
+{
+ warnx("ST24 test started");
+
+ if (argc < 2) {
+ errx(1, "Need a filename for the input file");
+ }
+
+ warnx("loading data from: %s", argv[1]);
+
+ FILE *fp;
+
+ fp = fopen(argv[1], "rt");
+
+ if (!fp) {
+ errx(1, "failed opening file");
+ }
+
+ float f;
+ unsigned x;
+ int ret;
+
+ // Trash the first 20 lines
+ for (unsigned i = 0; i < 20; i++) {
+ char buf[200];
+ (void)fgets(buf, sizeof(buf), fp);
+ }
+
+ float last_time = 0;
+
+ while (EOF != (ret = fscanf(fp, "%f,%x,,", &f, &x))) {
+ if (((f - last_time) * 1000 * 1000) > 3000) {
+ // warnx("FRAME RESET\n\n");
+ }
+
+ uint8_t b = static_cast<uint8_t>(x);
+
+ last_time = f;
+
+ // Pipe the data into the parser
+ hrt_abstime now = hrt_absolute_time();
+
+ uint8_t rssi;
+ uint8_t rx_count;
+ uint16_t channel_count;
+ uint16_t channels[20];
+
+
+ if (!st24_decode(b, &rssi, &rx_count, &channel_count, channels, sizeof(channels) / sizeof(channels[0]))) {
+ warnx("decoded: %u channels (converted to PPM range)", (unsigned)channel_count);
+
+ for (unsigned i = 0; i < channel_count; i++) {
+
+ int16_t val = channels[i];
+ warnx("channel %u: %d 0x%03X", i, static_cast<int>(val), static_cast<int>(val));
+ }
+ }
+ }
+
+ if (ret == EOF) {
+ warnx("Test finished, reached end of file");
+
+ } else {
+ warnx("Test aborted, errno: %d", ret);
+ }
+
+}