|
|
|
@ -1,9 +1,19 @@
@@ -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 <AP_HAL/AP_HAL.h> |
|
|
|
|
|
|
|
|
|
// we need a boardconfig created so that the io processor's enable
|
|
|
|
|
// parameter is available
|
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS |
|
|
|
|
#include <AP_BoardConfig/AP_BoardConfig.h> |
|
|
|
|
#include <AP_IOMCU/AP_IOMCU.h> |
|
|
|
|
AP_BoardConfig BoardConfig; |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
void setup(); |
|
|
|
|
void loop(); |
|
|
|
|
|
|
|
|
@ -12,6 +22,9 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
@@ -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)
@@ -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); |
|
|
|
|