APM:Libraries
RCInput.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 */
5 
6 #include <AP_HAL/HAL.h>
8 
9 #include <exti.h>
10 #include <timer.h>
11 #include "RCInput.h"
12 #include <pwm_in.h>
13 #include <AP_HAL/utility/dsm.h>
14 #include "sbus.h"
15 #include "GPIO.h"
16 #include "ring_buffer_pulse.h"
17 
18 #include "RC_PPM_parser.h"
19 
20 #ifdef BOARD_SPEKTRUM_RX_PIN
21  #include "RC_DSM_parser.h"
22 #endif
23 #ifdef BOARD_SBUS_UART
24  #include "RC_SBUS_parser.h"
25 #endif
26 
27 
28 // Constructors ////////////////////////////////////////////////////////////////
29 using namespace F4Light;
30 
31 
32 /*
33  DSM satellite connection
34  1 2 3 4
35 pins * * * * * * *
36 use gnd vcc 26 103 xxx xxx xxx
37 DSM GND rx en
38 
39 */
40 
41 
42 extern const AP_HAL::HAL& hal;
43 /*
44 input_channels:
45  4, // PB14 T12/1 - PPM
46  5, // PB15 T12/2 - PPM2
47  12, // PC6 T8/1 - 6_tx
48  13, // PC7 T8/2 - 6_rx
49  14, // PC8 T8/3 - Soft_scl / soft_TX
50  15, // PC9 T8/4 - Soft_sda / soft_RX
51 */
52 
53 _parser * RCInput::parsers[MAX_RC_PARSERS] IN_CCM; // individual parsers on each PPM pin and DSM/SBUS USART
55 
56 
57 uint8_t RCInput::_valid_channels IN_CCM; // = 0;
58 uint64_t RCInput::_last_read IN_CCM; // = 0;
59 
60 
63 
65 
67 
69 
72 
74 
75 /* constrain captured pulse to be between min and max pulsewidth. */
76 static inline uint16_t constrain_pulse(uint16_t p) {
79  return p;
80 }
81 
82 
83 
84 
86 { }
87 
88 void RCInput::init() {
89  caddr_t ptr;
90 
91  memset((void *)&_override[0], 0, sizeof(_override));
92 
93 /* OPLINK AIR port pinout
94 1 2 3 4 5 6 7
95  PD2 PA15
96 gnd +5 26 103
97 used as
98 for DSM: rx pow
99 for RFM int cs
100 
101 */
102 
103  is_PPM=true;
104  _last_read_from=0;
105  max_num_pulses=0;
106 
107  clear_overrides();
108 
109  pwmInit(is_PPM); // PPM sum mode
110 
111  uint8_t pp=0;
112 
113  ptr = sbrk_ccm(sizeof(PPM_parser)); // allocate memory in CCM
114  parsers[pp++] = new(ptr) PPM_parser;
115 
116  ptr = sbrk_ccm(sizeof(PPM_parser)); // allocate memory in CCM
117  parsers[pp++] = new(ptr) PPM_parser;
118 
119 #ifdef BOARD_SPEKTRUM_RX_PIN
120  ptr = sbrk_ccm(sizeof(DSM_parser)); // allocate memory in CCM
121  parsers[pp++] =new(ptr) DSM_parser;
122 #endif
123 #ifdef BOARD_NRF_CS_PIN
124  ptr = sbrk_ccm(sizeof(NRF_parser)); // allocate memory in CCM
125  parsers[pp++] =new(ptr) NRF_parser;
126 #endif
127 #ifdef BOARD_SBUS_UART
128  ptr = sbrk_ccm(sizeof(SBUS_parser)); // allocate memory in CCM
129  parsers[pp++] =new(ptr) SBUS_parser;
130 #endif
131 
132  num_parsers = pp; // counter
133 
134  for(uint8_t i=0; i<num_parsers;i++) {
135  parsers[i]->init(i);
136  }
137 
138 }
139 
140 
141 void RCInput::late_init(uint8_t b) {
142 
143  for(uint8_t i=0; i<num_parsers;i++) {
144  parsers[i]->late_init(b);
145  }
146 
148 }
149 
150 // we can have 4 individual sources of data - internal DSM from UART5, SBUS from UART1 and 2 PPM parsers
152 {
153  if(_override_valid) return true;
154 
155  uint8_t inp=hal_param_helper->_rc_input;
156  if(inp && inp < num_parsers+1){
157  inp-=1;
158 
159  return parsers[inp]->get_last_signal() > _last_read;
160  }
161 
162  for(uint8_t i=0; i<num_parsers;i++) {
163  if(parsers[i]->get_last_signal() >_last_read) return true;
164  }
165 
166  return false;
167 }
168 
169 
171 {
172  return _valid_channels;
173 }
174 
175 
176 uint16_t RCInput::last_4=0;
177 
178 //#define LOST_TIME 50 // this is wrong! Any packet lost and viola...
179 #define LOST_TIME 500
180 #define FRAME_TIME 50 // time between packets
181 
182 uint16_t RCInput::_read_ppm(uint8_t ch,uint8_t n){
183  const _parser *p = parsers[n];
185  return p->get_val(ch);
186 }
187 
188 
189 
190 uint16_t RCInput::read(uint8_t ch)
191 {
192  uint16_t data=0;
193  uint64_t pulse=0;
194  uint64_t last=0;
195 
196  if(ch>=F4Light_RC_INPUT_NUM_CHANNELS) return 0;
197 
198  uint64_t now=systick_uptime();
199  uint8_t got=0;
200 
201 
202  uint32_t dead_time = hal_param_helper->_rc_fs * 1000UL; // time in seconds
203 
204  uint8_t inp=hal_param_helper->_rc_input;
205  if(inp && inp < num_parsers+1 ){
206  inp-=1;
207 
208  const _parser *p = parsers[inp];
209  pulse = p->get_last_signal();
210  last = p->get_last_change();
211  data = p->get_val(ch);
213  got = inp+1;
214 
215  } else if(now - _last_read > FRAME_TIME) { // seems that we loose 1 frame on current RC receiver so should select new one
216  uint32_t best_t=(uint32_t) -1;
217 
218  for(uint8_t i=0; i<num_parsers;i++) {
219 
220  const _parser *p = parsers[i];
221  uint64_t pt = p->get_last_signal();
222  uint64_t lt = p->get_last_change();
223 
224  uint32_t dt = now-pt; // time from signal
225 
226  if( pt >_last_read && // data is newer than last
227  dt<best_t && // and most recent
228  ((now - lt ) < dead_time || !rc_failsafe_enabled)) // and time from last change less than DEAD_TIME
229  {
230  best_t = dt;
231  data = p->get_val(ch);
233  pulse = pt;
234  last = lt;
235  got = i+1;
236  }
237  }
238  // now we have a most recent data
239  }
240 
241  if(got) {
242  _last_read_from = got;
243  _last_read = pulse;
244  } else {
245  if(_last_read_from) { // read from the last channel
246  uint8_t n = _last_read_from-1;
247  const _parser *p = parsers[n];
248  pulse = p->get_last_signal();
249  last = p->get_last_change();
250  data = p->get_val(ch);
252  _last_read = pulse;
253 
254  } else { // no data at all
255 
256  if( ch == 2) data = 899; // to know the source
257  else data = 1000;
258  }
259  }
260 
261  /* Check for override */
262  uint16_t over = _override[ch];
263  if(over) return over;
264 
265  if( ch == 4) {
266  last_4 = data;
267  }
268 
269  if(ch == 2) { // throttle
270  if( (now-pulse) > LOST_TIME || // last pulse is very old
271  ((now-last) > dead_time && rc_failsafe_enabled) ) // pulses OK but last change is very old
272  {
273  data = 900;
274 
275  if(!fs_flag) {
276  fs_flag=true;
277 #ifdef DEBUG_BUILD
278  printf("\n failsafe! now=%lld last pulse=%lld last change=%lld\n",now, pulse, last);
279 #endif
280  }
281  } else {
282  fs_flag=false;
283  }
284 
285  if(hal_param_helper->_aibao_fs) {
286 /*
287  Receiver-DEVO-RX719-for-Walkera-Aibao
288  failsafe: mode below 1000 and throttle at 1500
289 */
290  if(last_4 < 990 && data >1300 && data < 1700){
291  if(!aibao_fs_flag){
292  aibao_fs_flag=true;
293 #ifdef DEBUG_BUILD
294  printf("\nAibao failsafe! ch4=%d ch2=%d\n",last_4, data);
295 #endif
296  }
297  data = 901; // to know the source
298  } else {
299  aibao_fs_flag=false;
300  }
301  }
302 
303  }
304  return data;
305 }
306 
307 uint8_t RCInput::read(uint16_t* periods, uint8_t len)
308 {
309 
310  for (uint8_t i = 0; i < len; i++){
311  periods[i] = read(i);
312  }
313 
314  return _valid_channels;
315 }
316 
317 
318 bool RCInput::set_override(uint8_t channel, int16_t override)
319 {
320  if (override < 0) return false; /* -1: no change. */
321  if (channel < F4Light_RC_INPUT_NUM_CHANNELS) {
322  _override[channel] = override;
323  if (override != 0) {
324  _override_valid = true;
325  return true;
326  }
327  }
328  return false;
329 }
330 
332 {
333  for (int i = 0; i < F4Light_RC_INPUT_NUM_CHANNELS; i++) {
334  set_override(i, 0);
335  }
336 }
337 
338 bool RCInput::rc_bind(int dsmMode){
339 #ifdef BOARD_SPEKTRUM_RX_PIN
340  return parsers[2]->bind(dsmMode); // only DSM
341 #else
342  return false;
343 #endif
344 
345 }
346 
bool rc_bind(int dsmMode) override
Definition: RCInput.cpp:338
int printf(const char *fmt,...)
Definition: stdio.c:113
static _parser * parsers[MAX_RC_PARSERS]
Definition: RCInput.h:54
virtual uint64_t get_last_signal() const
Definition: RC_parser.h:13
virtual void late_init(uint8_t b)
Definition: RC_parser.h:11
static bool is_PPM
Definition: RCInput.h:58
uint16_t read(uint8_t ch) override
Definition: RCInput.cpp:190
static uint8_t _last_read_from
Definition: RCInput.h:56
Simple circular buffer for PEM input.
#define MAX_RC_PARSERS
Definition: RCInput.h:31
bool new_input() override
Definition: RCInput.cpp:151
void pwmInit(bool ppmsum)
Definition: pwm_in.c:165
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
Definition: systick.h:44
virtual uint64_t get_last_change() const
Definition: RC_parser.h:14
uint8_t num_channels() override
Definition: RCInput.cpp:170
caddr_t sbrk_ccm(int nbytes)
Definition: syscalls.c:121
timer interface.
#define RC_INPUT_MIN_PULSEWIDTH
Definition: RCInput.h:5
static uint8_t num_parsers
Definition: RCInput.h:55
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void late_init(uint8_t b)
Definition: RCInput.cpp:141
virtual uint16_t get_val(uint8_t ch) const
Definition: RC_parser.h:16
#define BOARD_RC_FAILSAFE
Definition: RCInput.h:13
bool set_override(uint8_t channel, int16_t override) override
Definition: RCInput.cpp:318
static bool rc_failsafe_enabled
Definition: RCInput.h:73
void init() override
Definition: RCInput.cpp:88
virtual void init(uint8_t ch)=0
#define LOST_TIME
Definition: RCInput.cpp:179
static uint16_t max_num_pulses
Definition: RCInput.h:51
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCInput.cpp:10
#define RC_INPUT_MAX_PULSEWIDTH
Definition: RCInput.h:6
_parser *RCInput::parsers [MAX_RC_PARSERS] IN_CCM
Definition: RCInput.cpp:53
static bool _override_valid
Definition: RCInput.h:71
static bool fs_flag
Definition: RCInput.h:75
static uint8_t _valid_channels
Definition: RCInput.h:61
static uint16_t _override[F4Light_RC_INPUT_NUM_CHANNELS]
Definition: RCInput.h:70
static uint16_t constrain_pulse(uint16_t p)
Definition: RCInput.cpp:76
static bool aibao_fs_flag
Definition: RCInput.h:75
uint16_t _read_ppm(uint8_t ch, uint8_t n)
Definition: RCInput.cpp:182
virtual bool bind(int dsmMode) const
Definition: RC_parser.h:18
virtual uint8_t get_valid_channels() const
Definition: RC_parser.h:15
#define F4Light_RC_INPUT_NUM_CHANNELS
Definition: Config.h:12
void clear_overrides() override
Definition: RCInput.cpp:331
#define FRAME_TIME
Definition: RCInput.cpp:180
static uint16_t last_4
Definition: RCInput.h:67
static uint64_t _last_read
Definition: RCInput.h:60