From 931367a7ea99f2e22893936cef3c88c39806fc17 Mon Sep 17 00:00:00 2001 From: heitiane Date: Mon, 10 Sep 2018 01:59:04 -0700 Subject: [PATCH] AP_HAL: fix RCOutput, RCOutput2 and RCInputToRCOutput examples to prevent the failure of reading and writing channels. --- .../RCInputToRCOutput/RCInputToRCOutput.cpp | 13 +++++++++++++ libraries/AP_HAL/examples/RCOutput/RCOutput.cpp | 17 +++++++++++++++-- .../AP_HAL/examples/RCOutput2/RCOutput.cpp | 13 +++++++++++++ 3 files changed, 41 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp b/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp index 962ef8dfb5..2b5a3da5a3 100644 --- a/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp +++ b/libraries/AP_HAL/examples/RCInputToRCOutput/RCInputToRCOutput.cpp @@ -2,10 +2,20 @@ RC input pass trough to RC output Max RC channels 14 Max update rate 10 Hz + Attention: If your board has safety switch, + don't forget to push it to enable the PWM output. */ #include +// we need a boardconfig created so that the io processor's enable +// parameter is available +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include +#include +AP_BoardConfig BoardConfig; +#endif + void setup(); void loop(); @@ -20,6 +30,9 @@ void setup(void) { hal.console->printf("Starting RCInputToRCOutput test\n"); +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + BoardConfig.init(); +#endif for (uint8_t i = 0; i < MAX_CHANNELS; i++) { hal.rcout->enable_ch(i); } diff --git a/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp b/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp index f84dfc8d37..88e3b36c17 100644 --- a/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp +++ b/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp @@ -1,9 +1,19 @@ /* simple test of RC output interface + Attention: If your board has safety switch, + don't forget to push it to enable the PWM output. */ #include +// we need a boardconfig created so that the io processor's enable +// parameter is available +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include +#include +AP_BoardConfig BoardConfig; +#endif + void setup(); void loop(); @@ -12,6 +22,9 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); void setup (void) { hal.console->printf("Starting AP_HAL::RCOutput test\n"); +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + BoardConfig.init(); +#endif for (uint8_t i = 0; i< 14; i++) { hal.rcout->enable_ch(i); } @@ -27,10 +40,10 @@ void loop (void) pwm += delta; if (delta > 0 && pwm >= 2000) { delta = -1; - hal.console->printf("reversing\n"); + hal.console->printf("decreasing\n"); } else if (delta < 0 && pwm <= 1000) { delta = 1; - hal.console->printf("reversing\n"); + hal.console->printf("increasing\n"); } } hal.scheduler->delay(5); diff --git a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp index 588632605d..ff6e57cb65 100644 --- a/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp +++ b/libraries/AP_HAL/examples/RCOutput2/RCOutput.cpp @@ -1,11 +1,21 @@ /* Simple test of RC output interface with Menu + Attention: If your board has safety switch, + don't forget to push it to enable the PWM output. */ #include #include #include +// we need a boardconfig created so that the io processor's enable +// parameter is available +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS +#include +#include +AP_BoardConfig BoardConfig; +#endif + void setup(); void loop(); void drive(uint16_t hz_speed); @@ -78,6 +88,9 @@ MENU(menu, "Menu: ", rcoutput_menu_commands); void setup(void) { hal.console->printf("Starting AP_HAL::RCOutput test\n"); +#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS + BoardConfig.init(); +#endif for (uint8_t i = 0; i < 14; i++) { hal.rcout->enable_ch(i); }