From 4f1dd85e470eb69aa4eddfe6ca34995c4318c7bc Mon Sep 17 00:00:00 2001 From: mirkix Date: Thu, 5 Mar 2015 20:31:02 +0000 Subject: [PATCH] AP_HAL: Add test sketch for RC input to RC output pass through --- .../examples/RCInputToRCOutput/Makefile | 1 + .../RCInputToRCOutput/RCInputToRCOutput.pde | 86 +++++++++++++++++++ 2 files changed, 87 insertions(+) create mode 100644 libraries/AP_HAL/examples/RCInputToRCOutput/Makefile create mode 100644 libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.pde diff --git a/libraries/AP_HAL/examples/RCInputToRCOutput/Makefile b/libraries/AP_HAL/examples/RCInputToRCOutput/Makefile new file mode 100644 index 0000000000..f5daf25151 --- /dev/null +++ b/libraries/AP_HAL/examples/RCInputToRCOutput/Makefile @@ -0,0 +1 @@ +include ../../../../mk/apm.mk diff --git a/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.pde b/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.pde new file mode 100644 index 0000000000..50a8f12c23 --- /dev/null +++ b/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.pde @@ -0,0 +1,86 @@ +/* + RC input pass trough to RC output + Max RC channels 14 + Max update rate 10 Hz +*/ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +const AP_HAL::HAL& hal = AP_HAL_BOARD_DRIVER; + +#define MAX_CHANNELS 14 + +static uint8_t max_channels = 0; +static uint16_t last_value[MAX_CHANNELS]; + +void setup(void) +{ + hal.console->printf("Starting RCInputToRCOutput test\n"); + + for(uint8_t i = 0; i < MAX_CHANNELS; i++) { + hal.rcout->enable_ch(i); + } +} + +void loop(void) +{ + bool changed = false; + uint8_t nchannels = hal.rcin->num_channels(); + + if(nchannels > MAX_CHANNELS) { + nchannels = MAX_CHANNELS; + } + + for(uint8_t i = 0; i < nchannels; i++) { + uint16_t v = hal.rcin->read(i); + if(last_value[i] != v) { + hal.rcout->write(i, v); + changed = true; + last_value[i] = v; + } + if(i > max_channels) { + max_channels = i; + } + } + if(changed) { + for(uint8_t i = 0; i < max_channels; i++) { + hal.console->printf("%2u:%04u ", (unsigned)i + 1, (unsigned)last_value[i]); + } + hal.console->println(); + } + hal.scheduler->delay(100); +} + +AP_HAL_MAIN();