mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: fixed and updated RCInput example.
This commit is contained in:
parent
9df58e1e0a
commit
4a6447575c
|
@ -8,7 +8,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
|
||||
#define MAX_CHANNELS 16
|
||||
|
||||
static uint8_t max_channels = 0;
|
||||
static uint8_t max_channels_display = 8; //Set to 0 for display numbers of channels detected.
|
||||
static uint16_t last_value[MAX_CHANNELS];
|
||||
|
||||
void setup(void)
|
||||
|
@ -19,26 +19,33 @@ void setup(void)
|
|||
void loop(void)
|
||||
{
|
||||
bool changed = false;
|
||||
uint8_t nchannels = hal.rcin->num_channels();
|
||||
uint8_t nchannels = hal.rcin->num_channels(); //Get the numbers channels detected by RC_INPUT.
|
||||
if (nchannels > MAX_CHANNELS) {
|
||||
nchannels = MAX_CHANNELS;
|
||||
}
|
||||
for (uint8_t i=0; i<nchannels; i++) {
|
||||
if (nchannels != 0) { //If channels detected, process.
|
||||
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;
|
||||
}
|
||||
if (i > max_channels) {
|
||||
max_channels = i;
|
||||
}
|
||||
if (max_channels_display > nchannels) {
|
||||
max_channels_display = nchannels;
|
||||
}
|
||||
if (max_channels_display > 0) {
|
||||
if (changed) {
|
||||
for (uint8_t i=0; i<max_channels; i++) {
|
||||
for (uint8_t i = 0; i < max_channels_display; i++) {
|
||||
hal.console->printf("%2u:%04u ", (unsigned)i+1, (unsigned)last_value[i]);
|
||||
}
|
||||
hal.console->println();
|
||||
}
|
||||
} else {
|
||||
hal.console->printf("Channels detected: %2u\n", nchannels);
|
||||
hal.console->printf("Set max_channels_display > 0 to display channels values\n");
|
||||
}
|
||||
}
|
||||
hal.scheduler->delay(100);
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue