2015-03-05 16:31:02 -04:00
|
|
|
/*
|
|
|
|
RC input pass trough to RC output
|
|
|
|
Max RC channels 14
|
|
|
|
Max update rate 10 Hz
|
2018-09-10 05:59:04 -03:00
|
|
|
Attention: If your board has safety switch,
|
|
|
|
don't forget to push it to enable the PWM output.
|
2015-03-05 16:31:02 -04:00
|
|
|
*/
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2015-03-05 16:31:02 -04:00
|
|
|
|
2018-09-10 05:59:04 -03:00
|
|
|
// 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
|
|
|
|
|
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();
|
2015-03-05 16:31:02 -04:00
|
|
|
|
|
|
|
#define MAX_CHANNELS 14
|
|
|
|
|
|
|
|
static uint8_t max_channels = 0;
|
|
|
|
static uint16_t last_value[MAX_CHANNELS];
|
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
void setup(void)
|
2015-03-05 16:31:02 -04:00
|
|
|
{
|
|
|
|
hal.console->printf("Starting RCInputToRCOutput test\n");
|
|
|
|
|
2018-09-10 05:59:04 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
|
|
|
BoardConfig.init();
|
|
|
|
#endif
|
2017-04-13 08:31:16 -03:00
|
|
|
for (uint8_t i = 0; i < MAX_CHANNELS; i++) {
|
2015-03-05 16:31:02 -04:00
|
|
|
hal.rcout->enable_ch(i);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
void loop(void)
|
2015-03-05 16:31:02 -04:00
|
|
|
{
|
|
|
|
bool changed = false;
|
|
|
|
uint8_t nchannels = hal.rcin->num_channels();
|
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
if (nchannels > MAX_CHANNELS) {
|
2015-03-05 16:31:02 -04:00
|
|
|
nchannels = MAX_CHANNELS;
|
|
|
|
}
|
|
|
|
|
2017-04-13 08:31:16 -03:00
|
|
|
for (uint8_t i = 0; i < nchannels; i++) {
|
2015-03-05 16:31:02 -04:00
|
|
|
uint16_t v = hal.rcin->read(i);
|
2017-04-13 08:31:16 -03:00
|
|
|
if (last_value[i] != v) {
|
2015-03-05 16:31:02 -04:00
|
|
|
hal.rcout->write(i, v);
|
|
|
|
changed = true;
|
|
|
|
last_value[i] = v;
|
|
|
|
}
|
2017-04-13 08:31:16 -03:00
|
|
|
if (i > max_channels) {
|
2015-03-05 16:31:02 -04:00
|
|
|
max_channels = i;
|
|
|
|
}
|
|
|
|
}
|
2017-04-13 08:31:16 -03:00
|
|
|
if (changed) {
|
|
|
|
for (uint8_t i = 0; i < max_channels; i++) {
|
|
|
|
hal.console->printf("%2u:%04u ", (unsigned)(i + 1), (unsigned)last_value[i]);
|
2015-03-05 16:31:02 -04:00
|
|
|
}
|
2017-01-21 00:37:51 -04:00
|
|
|
hal.console->printf("\n");
|
2015-03-05 16:31:02 -04:00
|
|
|
}
|
|
|
|
hal.scheduler->delay(100);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL_MAIN();
|