APM:Libraries
RCInput.cpp
Go to the documentation of this file.
1 /*
2  simple test of RC input interface
3  */
4 #include <AP_Common/AP_Common.h>
5 #include <AP_HAL/AP_HAL.h>
6 
7 void setup();
8 void loop();
9 
11 
12 #define MAX_CHANNELS 16
13 
14 static uint8_t max_channels_display = 8; // Set to 0 for display numbers of channels detected.
15 static uint16_t last_value[MAX_CHANNELS];
16 
17 void setup(void)
18 {
19  hal.console->printf("Starting RCInput test\n");
20 }
21 
22 void loop(void)
23 {
24  bool changed = false;
25  uint8_t nchannels = hal.rcin->num_channels(); // Get the numbers channels detected by RC_INPUT.
26  if (nchannels > MAX_CHANNELS) {
27  nchannels = MAX_CHANNELS;
28  }
29  if (nchannels != 0) { // If channels detected, process.
30  for (uint8_t i = 0; i < nchannels; i++) {
31  uint16_t v = hal.rcin->read(i);
32  if (last_value[i] != v) {
33  changed = true;
34  last_value[i] = v;
35  }
36  }
37  if (max_channels_display > nchannels) {
38  max_channels_display = nchannels;
39  }
40  if (max_channels_display > 0) {
41  if (changed) {
42  for (uint8_t i = 0; i < max_channels_display; i++) {
43  hal.console->printf("%2u:%04u ", (unsigned)i+1, (unsigned)last_value[i]);
44  }
45  hal.console->printf("\n");
46  }
47  } else {
48  hal.console->printf("Channels detected: %2u\n", nchannels);
49  hal.console->printf("Set max_channels_display > 0 to display channels values\n");
50  }
51  }
52  hal.scheduler->delay(100);
53 }
54 
55 AP_HAL_MAIN();
virtual uint8_t num_channels()=0
AP_HAL::UARTDriver * console
Definition: HAL.h:110
virtual uint16_t read(uint8_t ch)=0
#define MAX_CHANNELS
Definition: RCInput.cpp:12
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
float v
Definition: Printf.cpp:15
const HAL & get_HAL()
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCInput.cpp:10
static uint8_t max_channels_display
Definition: RCInput.cpp:14
Common definitions and utility routines for the ArduPilot libraries.
AP_HAL_MAIN()
static uint16_t last_value[MAX_CHANNELS]
Definition: RCInput.cpp:15
AP_HAL::RCInput * rcin
Definition: HAL.h:112
void setup()
Definition: RCInput.cpp:17
void loop()
Definition: RCInput.cpp:22
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114