ardupilot/libraries/AP_HAL/examples/RCInput/RCInput.cpp

77 lines
1.8 KiB
C++
Raw Normal View History

2014-12-02 00:49:50 -04:00
/*
simple test of RC input interface
*/
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
2014-12-02 00:49:50 -04:00
2018-08-31 00:22:54 -03:00
// we need a boardconfig created so that the io processor's enable
// parameter is available
2019-02-25 01:13:47 -04:00
#if HAL_WITH_IO_MCU
2018-08-31 00:22:54 -03:00
#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();
2014-12-02 00:49:50 -04:00
#define MAX_CHANNELS 16
static uint8_t max_channels_display = 8; // Set to 0 for display numbers of channels detected.
2014-12-02 00:49:50 -04:00
static uint16_t last_value[MAX_CHANNELS];
void setup(void)
2014-12-02 00:49:50 -04:00
{
hal.console->printf("Starting RCInput test\n");
2019-02-25 01:13:47 -04:00
#if HAL_WITH_IO_MCU
2018-08-31 00:22:54 -03:00
BoardConfig.init();
#endif
2014-12-02 00:49:50 -04:00
}
2018-08-31 00:22:54 -03:00
void read_channels(void);
void read_channels(void)
2014-12-02 00:49:50 -04:00
{
uint8_t nchannels = hal.rcin->num_channels(); // Get the numbers channels detected by RC_INPUT.
2018-08-31 00:22:54 -03:00
if (nchannels == 0) {
hal.console->printf("No channels detected\n");
return;
}
if (max_channels_display == 0) {
hal.console->printf("Channels detected: %2u\n", nchannels);
hal.console->printf("Set max_channels_display > 0 to display channels values\n");
return;
}
2014-12-02 00:49:50 -04:00
if (nchannels > MAX_CHANNELS) {
nchannels = MAX_CHANNELS;
}
2018-08-31 00:22:54 -03:00
bool changed = false;
for (uint8_t i = 0; i < nchannels; i++) {
uint16_t v = hal.rcin->read(i);
if (last_value[i] != v) {
changed = true;
last_value[i] = v;
2014-12-02 00:49:50 -04:00
}
2018-08-31 00:22:54 -03:00
}
if (max_channels_display > nchannels) {
max_channels_display = nchannels;
}
if (changed) {
for (uint8_t i = 0; i < max_channels_display; i++) {
hal.console->printf("%2u:%04u ", (unsigned)i+1, (unsigned)last_value[i]);
2014-12-02 00:49:50 -04:00
}
2018-08-31 00:22:54 -03:00
hal.console->printf("\n");
2014-12-02 00:49:50 -04:00
}
2018-08-31 00:22:54 -03:00
}
void loop(void) {
read_channels();
2014-12-02 00:49:50 -04:00
hal.scheduler->delay(100);
}
AP_HAL_MAIN();