APM:Libraries
RCInput.cpp
Go to the documentation of this file.
1 
2 #include "RCInput.h"
3 
4 using namespace Empty;
6 {}
7 
9 {}
10 
12  return false;
13 }
14 
16  return 0;
17 }
18 
19 uint16_t RCInput::read(uint8_t ch) {
20  if (ch == 2) return 900; /* throttle should be low, for safety */
21  else return 1500;
22 }
23 
24 uint8_t RCInput::read(uint16_t* periods, uint8_t len) {
25  for (uint8_t i = 0; i < len; i++){
26  if (i == 2) periods[i] = 900;
27  else periods[i] = 1500;
28  }
29  return len;
30 }
31 
32 bool RCInput::set_override(uint8_t channel, int16_t override) {
33  return true;
34 }
35 
37 {}
38 
bool set_override(uint8_t channel, int16_t override)
Definition: RCInput.cpp:32
uint8_t num_channels()
Definition: RCInput.cpp:15
uint16_t read(uint8_t ch)
Definition: RCInput.cpp:19
bool new_input()
Definition: RCInput.cpp:11
void clear_overrides()
Definition: RCInput.cpp:36
void init()
Definition: RCInput.cpp:8