APM:Libraries
RCInputToRCOutput.cpp
Go to the documentation of this file.
1 /*
2  RC input pass trough to RC output
3  Max RC channels 14
4  Max update rate 10 Hz
5 */
6 
7 #include <AP_HAL/AP_HAL.h>
8 
9 void setup();
10 void loop();
11 
13 
14 #define MAX_CHANNELS 14
15 
16 static uint8_t max_channels = 0;
17 static uint16_t last_value[MAX_CHANNELS];
18 
19 void setup(void)
20 {
21  hal.console->printf("Starting RCInputToRCOutput test\n");
22 
23  for (uint8_t i = 0; i < MAX_CHANNELS; i++) {
24  hal.rcout->enable_ch(i);
25  }
26 }
27 
28 void loop(void)
29 {
30  bool changed = false;
31  uint8_t nchannels = hal.rcin->num_channels();
32 
33  if (nchannels > MAX_CHANNELS) {
34  nchannels = MAX_CHANNELS;
35  }
36 
37  for (uint8_t i = 0; i < nchannels; i++) {
38  uint16_t v = hal.rcin->read(i);
39  if (last_value[i] != v) {
40  hal.rcout->write(i, v);
41  changed = true;
42  last_value[i] = v;
43  }
44  if (i > max_channels) {
45  max_channels = i;
46  }
47  }
48  if (changed) {
49  for (uint8_t i = 0; i < max_channels; i++) {
50  hal.console->printf("%2u:%04u ", (unsigned)(i + 1), (unsigned)last_value[i]);
51  }
52  hal.console->printf("\n");
53  }
54  hal.scheduler->delay(100);
55 }
56 
57 AP_HAL_MAIN();
virtual uint8_t num_channels()=0
AP_HAL::UARTDriver * console
Definition: HAL.h:110
AP_HAL_MAIN()
virtual uint16_t read(uint8_t ch)=0
virtual void delay(uint16_t ms)=0
virtual void enable_ch(uint8_t ch)=0
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void loop()
static uint8_t max_channels
virtual void write(uint8_t ch, uint16_t period_us)=0
void setup()
float v
Definition: Printf.cpp:15
const HAL & get_HAL()
#define MAX_CHANNELS
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static uint16_t last_value[MAX_CHANNELS]
AP_HAL::RCOutput * rcout
Definition: HAL.h:113
AP_HAL::RCInput * rcin
Definition: HAL.h:112
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114