From 8e36c1cd60c81dc0fe745138ed03facd39c9e5aa Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 2 Dec 2014 15:03:59 +1100 Subject: [PATCH] AP_HAL: fixed RCOutput example --- .../AP_HAL/examples/RCOutput/RCOutput.pde | 61 +++++++++++++------ 1 file changed, 44 insertions(+), 17 deletions(-) diff --git a/libraries/AP_HAL/examples/RCOutput/RCOutput.pde b/libraries/AP_HAL/examples/RCOutput/RCOutput.pde index 0f041d5766..2b26f780f7 100644 --- a/libraries/AP_HAL/examples/RCOutput/RCOutput.pde +++ b/libraries/AP_HAL/examples/RCOutput/RCOutput.pde @@ -1,39 +1,66 @@ - -#include -#include -#include -#include -#include - +/* + simple test of RC output interface + */ #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; void setup (void) { - hal.console->printf_P(PSTR("Starting AP_HAL::RCOutput test\r\n")); - uint8_t i; - - hal.console->printf_P(PSTR("Testing 14 channels 1050+i*50\n")); - for (i=0; i<14; i++) { + hal.console->println("Starting AP_HAL::RCOutput test"); + for (uint8_t i=0; i<14; i++) { hal.rcout->enable_ch(i); - hal.rcout->write(i, 1050 + i*50); } - hal.rcout->set_freq(0xFF, 490); } +static uint16_t pwm = 1500; +static int8_t delta = 1; + void loop (void) { uint8_t i; for (i=0; i<14; i++) { - hal.rcout->enable_ch(i); - hal.rcout->write(i, 1050 + i*50); + hal.rcout->write(i, pwm); + pwm += delta; + if (delta > 0 && pwm >= 2000) { + delta = -1; + hal.console->printf("reversing\n"); + } else if (delta < 0 && pwm <= 1000) { + delta = 1; + hal.console->printf("reversing\n"); + } } - hal.scheduler->delay(10); + hal.scheduler->delay(5); } AP_HAL_MAIN();