ardupilot/libraries/AP_HAL/examples/RCOutput/RCOutput.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

53 lines
1.2 KiB
C++
Raw Normal View History

2014-12-02 00:03:59 -04:00
/*
simple test of RC output interface
Attention: If your board has safety switch,
don't forget to push it to enable the PWM output.
2014-12-02 00:03:59 -04:00
*/
#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();
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);
}
}
2014-12-02 00:03:59 -04:00
static uint16_t pwm = 1500;
static int8_t delta = 1;
void loop (void)
{
for (uint8_t i=0; i < 14; i++) {
2014-12-02 00:03:59 -04:00
hal.rcout->write(i, pwm);
pwm += delta;
if (delta > 0 && pwm >= 2000) {
delta = -1;
hal.console->printf("decreasing\n");
2014-12-02 00:03:59 -04:00
} else if (delta < 0 && pwm <= 1000) {
delta = 1;
hal.console->printf("increasing\n");
2014-12-02 00:03:59 -04:00
}
}
2014-12-02 00:03:59 -04:00
hal.scheduler->delay(5);
}
AP_HAL_MAIN();