aboutsummaryrefslogtreecommitdiff
path: root/Tools
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:48:15 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-25 09:48:15 +0100
commit25af4b266ca48b183a1ad375856396f67d6ab30f (patch)
tree64e031ec3747ab706e5ae8ed9fd052e12ee3248b /Tools
parentad189cf7d69b8de16244b90d398e1d84ed6d0f4b (diff)
parent9b535f6553944f3468bbec9203301623412524ad (diff)
downloadpx4-firmware-25af4b266ca48b183a1ad375856396f67d6ab30f.tar.gz
px4-firmware-25af4b266ca48b183a1ad375856396f67d6ab30f.tar.bz2
px4-firmware-25af4b266ca48b183a1ad375856396f67d6ab30f.zip
Merge remote-tracking branch 'upstream/master' into dev_ros
Conflicts: .gitignore src/lib/uavcan
Diffstat (limited to 'Tools')
-rw-r--r--Tools/px4params/srcparser.py2
-rw-r--r--Tools/px4params/srcscanner.py7
-rw-r--r--Tools/tests-host/.gitignore6
-rw-r--r--Tools/tests-host/Makefile54
-rw-r--r--Tools/tests-host/arch/board/board.h0
-rw-r--r--Tools/tests-host/autodeclination_test.cpp28
-rw-r--r--Tools/tests-host/board_config.h0
-rw-r--r--Tools/tests-host/data/fit_linear_voltage.m14
-rw-r--r--Tools/tests-host/data/px4io_v1.3.csv70
-rw-r--r--Tools/tests-host/debug.h5
-rw-r--r--Tools/tests-host/hrt.cpp16
-rw-r--r--Tools/tests-host/mixer_test.cpp14
-rw-r--r--Tools/tests-host/nuttx/config.h0
-rw-r--r--Tools/tests-host/queue.h133
-rwxr-xr-xTools/tests-host/run_tests.sh6
-rw-r--r--Tools/tests-host/sbus2_test.cpp76
-rw-r--r--Tools/tests-host/sf0x_test.cpp65
-rw-r--r--Tools/tests-host/st24_test.cpp76
18 files changed, 7 insertions, 565 deletions
diff --git a/Tools/px4params/srcparser.py b/Tools/px4params/srcparser.py
index 0a4d21d26..8e6092195 100644
--- a/Tools/px4params/srcparser.py
+++ b/Tools/px4params/srcparser.py
@@ -103,7 +103,7 @@ class SourceParser(object):
Returns list of supported file extensions that can be parsed by this
parser.
"""
- return ["cpp", "c"]
+ return [".cpp", ".c"]
def Parse(self, contents):
"""
diff --git a/Tools/px4params/srcscanner.py b/Tools/px4params/srcscanner.py
index d7eca72d7..1f0ea4e89 100644
--- a/Tools/px4params/srcscanner.py
+++ b/Tools/px4params/srcscanner.py
@@ -26,5 +26,10 @@ class SourceScanner(object):
parser.Parse method.
"""
with codecs.open(path, 'r', 'utf-8') as f:
- contents = f.read()
+ try:
+ contents = f.read()
+ except:
+ contents = ''
+ print('Failed reading file: %s, skipping content.' % path)
+ pass
parser.Parse(contents)
diff --git a/Tools/tests-host/.gitignore b/Tools/tests-host/.gitignore
deleted file mode 100644
index 37e923b5e..000000000
--- a/Tools/tests-host/.gitignore
+++ /dev/null
@@ -1,6 +0,0 @@
-./obj/*
-mixer_test
-sf0x_test
-sbus2_test
-autodeclination_test
-st24_test
diff --git a/Tools/tests-host/Makefile b/Tools/tests-host/Makefile
deleted file mode 100644
index 8742e2f7c..000000000
--- a/Tools/tests-host/Makefile
+++ /dev/null
@@ -1,54 +0,0 @@
-
-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/Tools/tests-host/arch/board/board.h b/Tools/tests-host/arch/board/board.h
deleted file mode 100644
index e69de29bb..000000000
--- a/Tools/tests-host/arch/board/board.h
+++ /dev/null
diff --git a/Tools/tests-host/autodeclination_test.cpp b/Tools/tests-host/autodeclination_test.cpp
deleted file mode 100644
index 93bc340bb..000000000
--- a/Tools/tests-host/autodeclination_test.cpp
+++ /dev/null
@@ -1,28 +0,0 @@
-
-#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/Tools/tests-host/board_config.h b/Tools/tests-host/board_config.h
deleted file mode 100644
index e69de29bb..000000000
--- a/Tools/tests-host/board_config.h
+++ /dev/null
diff --git a/Tools/tests-host/data/fit_linear_voltage.m b/Tools/tests-host/data/fit_linear_voltage.m
deleted file mode 100644
index 7d0c2c27f..000000000
--- a/Tools/tests-host/data/fit_linear_voltage.m
+++ /dev/null
@@ -1,14 +0,0 @@
-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/Tools/tests-host/data/px4io_v1.3.csv b/Tools/tests-host/data/px4io_v1.3.csv
deleted file mode 100644
index b41ee8f1f..000000000
--- a/Tools/tests-host/data/px4io_v1.3.csv
+++ /dev/null
@@ -1,70 +0,0 @@
-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/Tools/tests-host/debug.h b/Tools/tests-host/debug.h
deleted file mode 100644
index 9824d13fc..000000000
--- a/Tools/tests-host/debug.h
+++ /dev/null
@@ -1,5 +0,0 @@
-
-#pragma once
-
-#include <systemlib/err.h>
-#define lowsyslog warnx \ No newline at end of file
diff --git a/Tools/tests-host/hrt.cpp b/Tools/tests-host/hrt.cpp
deleted file mode 100644
index 01b5958b7..000000000
--- a/Tools/tests-host/hrt.cpp
+++ /dev/null
@@ -1,16 +0,0 @@
-#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/Tools/tests-host/mixer_test.cpp b/Tools/tests-host/mixer_test.cpp
deleted file mode 100644
index 06499afd0..000000000
--- a/Tools/tests-host/mixer_test.cpp
+++ /dev/null
@@ -1,14 +0,0 @@
-#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/Tools/tests-host/nuttx/config.h b/Tools/tests-host/nuttx/config.h
deleted file mode 100644
index e69de29bb..000000000
--- a/Tools/tests-host/nuttx/config.h
+++ /dev/null
diff --git a/Tools/tests-host/queue.h b/Tools/tests-host/queue.h
deleted file mode 100644
index 0fdb170db..000000000
--- a/Tools/tests-host/queue.h
+++ /dev/null
@@ -1,133 +0,0 @@
-/************************************************************************
- * 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/Tools/tests-host/run_tests.sh b/Tools/tests-host/run_tests.sh
deleted file mode 100755
index ff5ee509a..000000000
--- a/Tools/tests-host/run_tests.sh
+++ /dev/null
@@ -1,6 +0,0 @@
-#!/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/Tools/tests-host/sbus2_test.cpp b/Tools/tests-host/sbus2_test.cpp
deleted file mode 100644
index e2c18369c..000000000
--- a/Tools/tests-host/sbus2_test.cpp
+++ /dev/null
@@ -1,76 +0,0 @@
-
-#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/Tools/tests-host/sf0x_test.cpp b/Tools/tests-host/sf0x_test.cpp
deleted file mode 100644
index 82d19fcbe..000000000
--- a/Tools/tests-host/sf0x_test.cpp
+++ /dev/null
@@ -1,65 +0,0 @@
-
-#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/Tools/tests-host/st24_test.cpp b/Tools/tests-host/st24_test.cpp
deleted file mode 100644
index 25a9355e2..000000000
--- a/Tools/tests-host/st24_test.cpp
+++ /dev/null
@@ -1,76 +0,0 @@
-
-#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);
- }
-
-}