2014-12-02 00:03:59 -04:00
|
|
|
/*
|
|
|
|
simple test of RC output interface
|
|
|
|
*/
|
2015-10-20 09:34:10 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-07-30 09:57:20 -03:00
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
void setup();
|
|
|
|
void loop();
|
|
|
|
|
2015-10-16 17:22:11 -03:00
|
|
|
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
2013-07-30 09:57:20 -03:00
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
void setup (void)
|
2013-07-30 09:57:20 -03:00
|
|
|
{
|
2017-01-21 00:37:51 -04:00
|
|
|
hal.console->printf("Starting AP_HAL::RCOutput test\n");
|
2017-04-13 08:31:16 -03:00
|
|
|
for (uint8_t i = 0; i< 14; i++) {
|
2013-07-30 09:57:20 -03:00
|
|
|
hal.rcout->enable_ch(i);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2014-12-02 00:03:59 -04:00
|
|
|
static uint16_t pwm = 1500;
|
|
|
|
static int8_t delta = 1;
|
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
void loop (void)
|
2013-07-30 09:57:20 -03:00
|
|
|
{
|
2017-04-13 08:31:16 -03:00
|
|
|
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("reversing\n");
|
|
|
|
} else if (delta < 0 && pwm <= 1000) {
|
|
|
|
delta = 1;
|
|
|
|
hal.console->printf("reversing\n");
|
|
|
|
}
|
2013-07-30 09:57:20 -03:00
|
|
|
}
|
2014-12-02 00:03:59 -04:00
|
|
|
hal.scheduler->delay(5);
|
2013-07-30 09:57:20 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL_MAIN();
|