APM:Libraries
RCInput.cpp
Go to the documentation of this file.
1 #include <errno.h>
2 #include <fcntl.h>
3 #include <poll.h>
4 #include <stdint.h>
5 #include <stdio.h>
6 #include <stdlib.h>
7 #include <string.h>
8 #include <sys/mman.h>
9 #include <sys/stat.h>
10 #include <sys/time.h>
11 #include <unistd.h>
12 
13 #include <AP_HAL/AP_HAL.h>
14 #include <AP_HAL/utility/dsm.h>
15 #include <AP_HAL/utility/sumd.h>
16 #include <AP_HAL/utility/st24.h>
17 #include <AP_HAL/utility/srxl.h>
18 
19 #include "RCInput.h"
20 #include "sbus.h"
21 
22 #define MIN_NUM_CHANNELS 5
23 
24 extern const AP_HAL::HAL& hal;
25 
26 using namespace Linux;
27 
29 {
30  ppm_state._channel_counter = -1;
31 }
32 
34 {
35 }
36 
38 {
39  bool ret = rc_input_count != last_rc_input_count;
40  if (ret) {
42  }
43  return ret;
44 }
45 
47 {
48  return _num_channels;
49 }
50 
51 uint16_t RCInput::read(uint8_t ch)
52 {
53  if (_override[ch]) {
54  return _override[ch];
55  }
56  if (ch >= _num_channels) {
57  return 0;
58  }
59  return _pwm_values[ch];
60 }
61 
62 uint8_t RCInput::read(uint16_t* periods, uint8_t len)
63 {
64  uint8_t i;
65  for (i=0; i<len; i++) {
66  periods[i] = read(i);
67  }
68  return len;
69 }
70 
71 bool RCInput::set_override(uint8_t channel, int16_t override)
72 {
73  if (override < 0) return false; /* -1: no change. */
74  if (channel < LINUX_RC_INPUT_NUM_CHANNELS) {
75  _override[channel] = override;
76  if (override != 0) {
78  return true;
79  }
80  }
81  return false;
82 }
83 
85 {
86  for (uint8_t i = 0; i < LINUX_RC_INPUT_NUM_CHANNELS; i++) {
87  _override[i] = 0;
88  }
89 }
90 
91 
92 /*
93  process a PPM-sum pulse of the given width
94  */
95 void RCInput::_process_ppmsum_pulse(uint16_t width_usec)
96 {
97  if (width_usec >= 2700) {
98  // a long pulse indicates the end of a frame. Reset the
99  // channel counter so next pulse is channel 0
100  if (ppm_state._channel_counter >= MIN_NUM_CHANNELS) {
101  for (uint8_t i=0; i<ppm_state._channel_counter; i++) {
102  _pwm_values[i] = ppm_state._pulse_capt[i];
103  }
104  _num_channels = ppm_state._channel_counter;
105  rc_input_count++;
106  }
107  ppm_state._channel_counter = 0;
108  return;
109  }
110  if (ppm_state._channel_counter == -1) {
111  // we are not synchronised
112  return;
113  }
114 
115  /*
116  we limit inputs to between 700usec and 2300usec. This allows us
117  to decode SBUS on the same pin, as SBUS will have a maximum
118  pulse width of 100usec
119  */
120  if (width_usec > 700 && width_usec < 2300) {
121  // take a reading for the current channel
122  // buffer these
123  ppm_state._pulse_capt[ppm_state._channel_counter] = width_usec;
124 
125  // move to next channel
126  ppm_state._channel_counter++;
127  }
128 
129  // if we have reached the maximum supported channels then
130  // mark as unsynchronised, so we wait for a wide pulse
131  if (ppm_state._channel_counter >= LINUX_RC_INPUT_NUM_CHANNELS) {
132  for (uint8_t i=0; i<ppm_state._channel_counter; i++) {
133  _pwm_values[i] = ppm_state._pulse_capt[i];
134  }
135  _num_channels = ppm_state._channel_counter;
136  rc_input_count++;
137  ppm_state._channel_counter = -1;
138  }
139 }
140 
141 /*
142  process a SBUS input pulse of the given width
143  */
144 void RCInput::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
145 {
146  // convert to bit widths, allowing for up to 1usec error, assuming 100000 bps
147  uint16_t bits_s0 = (width_s0+1) / 10;
148  uint16_t bits_s1 = (width_s1+1) / 10;
149  uint16_t nlow;
150 
151  uint8_t byte_ofs = sbus_state.bit_ofs/12;
152  uint8_t bit_ofs = sbus_state.bit_ofs%12;
153 
154  if (bits_s0 == 0 || bits_s1 == 0) {
155  // invalid data
156  goto reset;
157  }
158 
159  if (bits_s0+bit_ofs > 10) {
160  // invalid data as last two bits must be stop bits
161  goto reset;
162  }
163 
164  // pull in the high bits
165  sbus_state.bytes[byte_ofs] |= ((1U<<bits_s0)-1) << bit_ofs;
166  sbus_state.bit_ofs += bits_s0;
167  bit_ofs += bits_s0;
168 
169  // pull in the low bits
170  nlow = bits_s1;
171  if (nlow + bit_ofs > 12) {
172  nlow = 12 - bit_ofs;
173  }
174  bits_s1 -= nlow;
175  sbus_state.bit_ofs += nlow;
176 
177  if (sbus_state.bit_ofs == 25*12 && bits_s1 > 12) {
178  // we have a full frame
179  uint8_t bytes[25];
180  uint8_t i;
181  for (i=0; i<25; i++) {
182  // get inverted data
183  uint16_t v = ~sbus_state.bytes[i];
184  // check start bit
185  if ((v & 1) != 0) {
186  goto reset;
187  }
188  // check stop bits
189  if ((v & 0xC00) != 0xC00) {
190  goto reset;
191  }
192  // check parity
193  uint8_t parity = 0, j;
194  for (j=1; j<=8; j++) {
195  parity ^= (v & (1U<<j))?1:0;
196  }
197  if (parity != (v&0x200)>>9) {
198  goto reset;
199  }
200  bytes[i] = ((v>>1) & 0xFF);
201  }
202  uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
203  uint16_t num_values=0;
204  bool sbus_failsafe=false, sbus_frame_drop=false;
205  if (sbus_decode(bytes, values, &num_values,
206  &sbus_failsafe, &sbus_frame_drop,
208  num_values >= MIN_NUM_CHANNELS) {
209  for (i=0; i<num_values; i++) {
210  _pwm_values[i] = values[i];
211  }
212  _num_channels = num_values;
213  if (!sbus_failsafe) {
214  rc_input_count++;
215  }
216  }
217  goto reset;
218  } else if (bits_s1 > 12) {
219  // break
220  goto reset;
221  }
222  return;
223 reset:
224  memset(&sbus_state, 0, sizeof(sbus_state));
225 }
226 
227 void RCInput::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
228 {
229  // convert to bit widths, allowing for up to 1usec error, assuming 115200 bps
230  uint16_t bits_s0 = ((width_s0+4)*(uint32_t)115200) / 1000000;
231  uint16_t bits_s1 = ((width_s1+4)*(uint32_t)115200) / 1000000;
232  uint8_t bit_ofs, byte_ofs;
233  uint16_t nbits;
234 
235  if (bits_s0 == 0 || bits_s1 == 0) {
236  // invalid data
237  goto reset;
238  }
239 
240  byte_ofs = dsm_state.bit_ofs/10;
241  bit_ofs = dsm_state.bit_ofs%10;
242 
243  if(byte_ofs > 15) {
244  // invalid data
245  goto reset;
246  }
247 
248  // pull in the high bits
249  nbits = bits_s0;
250  if (nbits+bit_ofs > 10) {
251  nbits = 10 - bit_ofs;
252  }
253  dsm_state.bytes[byte_ofs] |= ((1U<<nbits)-1) << bit_ofs;
254  dsm_state.bit_ofs += nbits;
255  bit_ofs += nbits;
256 
257  if (bits_s0 - nbits > 10) {
258  if (dsm_state.bit_ofs == 16*10) {
259  // we have a full frame
260  uint8_t bytes[16];
261  uint8_t i;
262  for (i=0; i<16; i++) {
263  // get raw data
264  uint16_t v = dsm_state.bytes[i];
265 
266  // check start bit
267  if ((v & 1) != 0) {
268  goto reset;
269  }
270  // check stop bits
271  if ((v & 0x200) != 0x200) {
272  goto reset;
273  }
274  bytes[i] = ((v>>1) & 0xFF);
275  }
276  uint16_t values[8];
277  uint16_t num_values=0;
278  if (dsm_decode(AP_HAL::micros64(), bytes, values, &num_values, 8) &&
279  num_values >= MIN_NUM_CHANNELS) {
280  for (i=0; i<num_values; i++) {
281  _pwm_values[i] = values[i];
282  }
283  _num_channels = num_values;
284  rc_input_count++;
285  }
286  }
287  memset(&dsm_state, 0, sizeof(dsm_state));
288  }
289 
290  byte_ofs = dsm_state.bit_ofs/10;
291  bit_ofs = dsm_state.bit_ofs%10;
292 
293  if (bits_s1+bit_ofs > 10) {
294  // invalid data
295  goto reset;
296  }
297 
298  // pull in the low bits
299  dsm_state.bit_ofs += bits_s1;
300  return;
301 reset:
302  memset(&dsm_state, 0, sizeof(dsm_state));
303 }
304 
305 /*
306  process a RC input pulse of the given width
307  */
308 void RCInput::_process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
309 {
310 #if 0
311  // useful for debugging
312  static FILE *rclog;
313  if (rclog == nullptr) {
314  rclog = fopen("/tmp/rcin.log", "w");
315  }
316  if (rclog) {
317  fprintf(rclog, "%u %u\n", (unsigned)width_s0, (unsigned)width_s1);
318  }
319 #endif
320  // treat as PPM-sum
321  _process_ppmsum_pulse(width_s0 + width_s1);
322 
323  // treat as SBUS
324  _process_sbus_pulse(width_s0, width_s1);
325 
326  // treat as DSM
327  _process_dsm_pulse(width_s0, width_s1);
328 }
329 
330 /*
331  * Update channel values directly
332  */
333 void RCInput::_update_periods(uint16_t *periods, uint8_t len)
334 {
335  if (len > LINUX_RC_INPUT_NUM_CHANNELS) {
337  }
338  for (unsigned int i=0; i < len; i++) {
339  _pwm_values[i] = periods[i];
340  }
341  _num_channels = len;
342  rc_input_count++;
343 }
344 
345 
346 /*
347  add some bytes of input in DSM serial stream format, coping with partial packets
348  */
349 bool RCInput::add_dsm_input(const uint8_t *bytes, size_t nbytes)
350 {
351  if (nbytes == 0) {
352  return false;
353  }
354  const uint8_t dsm_frame_size = sizeof(dsm.frame);
355  bool ret = false;
356 
357  uint32_t now = AP_HAL::millis();
358  if (now - dsm.last_input_ms > 5) {
359  // resync based on time
360  dsm.partial_frame_count = 0;
361  }
362  dsm.last_input_ms = now;
363 
364  while (nbytes > 0) {
365  size_t n = nbytes;
366  if (dsm.partial_frame_count + n > dsm_frame_size) {
367  n = dsm_frame_size - dsm.partial_frame_count;
368  }
369  if (n > 0) {
370  memcpy(&dsm.frame[dsm.partial_frame_count], bytes, n);
371  dsm.partial_frame_count += n;
372  nbytes -= n;
373  bytes += n;
374  }
375 
376  if (dsm.partial_frame_count == dsm_frame_size) {
377  dsm.partial_frame_count = 0;
378  uint16_t values[16] {};
379  uint16_t num_values=0;
380  /*
381  we only accept input when nbytes==0 as dsm is highly
382  sensitive to framing, and extra bytes may be an
383  indication this is really SRXL
384  */
385  if (dsm_decode(AP_HAL::micros64(), dsm.frame, values, &num_values, 16) &&
386  num_values >= MIN_NUM_CHANNELS &&
387  nbytes == 0) {
388  for (uint8_t i=0; i<num_values; i++) {
389  if (values[i] != 0) {
390  _pwm_values[i] = values[i];
391  }
392  }
393  /*
394  the apparent number of channels can change on DSM,
395  as they are spread across multiple frames. We just
396  use the max num_values we get
397  */
398  if (num_values > _num_channels) {
399  _num_channels = num_values;
400  }
401  rc_input_count++;
402 #if 0
403  printf("Decoded DSM %u channels %u %u %u %u %u %u %u %u\n",
404  (unsigned)num_values,
405  values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7]);
406 #endif
407  ret = true;
408  }
409  }
410  }
411  return ret;
412 }
413 
414 
415 /*
416  add some bytes of input in SUMD serial stream format, coping with partial packets
417  */
418 bool RCInput::add_sumd_input(const uint8_t *bytes, size_t nbytes)
419 {
420  uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
421  uint8_t rssi;
422  uint8_t rx_count;
423  uint16_t channel_count;
424  bool ret = false;
425 
426  while (nbytes > 0) {
427  if (sumd_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) {
428  if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
429  continue;
430  }
431  for (uint8_t i=0; i<channel_count; i++) {
432  if (values[i] != 0) {
433  _pwm_values[i] = values[i];
434  }
435  }
436  _num_channels = channel_count;
437  rc_input_count++;
438  ret = true;
439  _rssi = rssi;
440  }
441  nbytes--;
442  }
443  return ret;
444 }
445 
446 /*
447  add some bytes of input in ST24 serial stream format, coping with partial packets
448  */
449 bool RCInput::add_st24_input(const uint8_t *bytes, size_t nbytes)
450 {
451  uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
452  uint8_t rssi;
453  uint8_t rx_count;
454  uint16_t channel_count;
455  bool ret = false;
456 
457  while (nbytes > 0) {
458  if (st24_decode(*bytes++, &rssi, &rx_count, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS) == 0) {
459  if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
460  continue;
461  }
462  for (uint8_t i=0; i<channel_count; i++) {
463  if (values[i] != 0) {
464  _pwm_values[i] = values[i];
465  }
466  }
467  _num_channels = channel_count;
468  rc_input_count++;
469  ret = true;
470  _rssi = rssi;
471  }
472  nbytes--;
473  }
474  return ret;
475 }
476 
477 /*
478  add some bytes of input in SRXL serial stream format, coping with partial packets
479  */
480 bool RCInput::add_srxl_input(const uint8_t *bytes, size_t nbytes)
481 {
482  uint16_t values[LINUX_RC_INPUT_NUM_CHANNELS];
483  uint8_t channel_count;
484  uint64_t now = AP_HAL::micros64();
485  bool ret = false;
486  bool failsafe_state;
487 
488  while (nbytes > 0) {
489  if (srxl_decode(now, *bytes++, &channel_count, values, LINUX_RC_INPUT_NUM_CHANNELS, &failsafe_state) == 0) {
490  if (channel_count > LINUX_RC_INPUT_NUM_CHANNELS) {
491  continue;
492  }
493  for (uint8_t i=0; i<channel_count; i++) {
494  _pwm_values[i] = values[i];
495  }
496  _num_channels = channel_count;
497  if (failsafe_state == false) {
498  rc_input_count++;
499  }
500  ret = true;
501  }
502  nbytes--;
503  }
504  return ret;
505 }
506 
507 
508 /*
509  add some bytes of input in SBUS serial stream format, coping with partial packets
510  */
511 void RCInput::add_sbus_input(const uint8_t *bytes, size_t nbytes)
512 {
513  if (nbytes == 0) {
514  return;
515  }
516  const uint8_t sbus_frame_size = sizeof(sbus.frame);
517 
518  uint32_t now = AP_HAL::millis();
519  if (now - sbus.last_input_ms > 5) {
520  // resync based on time
521  sbus.partial_frame_count = 0;
522  }
523  sbus.last_input_ms = now;
524 
525  while (nbytes > 0) {
526  size_t n = nbytes;
527  if (sbus.partial_frame_count + n > sbus_frame_size) {
528  n = sbus_frame_size - sbus.partial_frame_count;
529  }
530  if (n > 0) {
531  memcpy(&sbus.frame[sbus.partial_frame_count], bytes, n);
532  sbus.partial_frame_count += n;
533  nbytes -= n;
534  bytes += n;
535  }
536 
537  if (sbus.partial_frame_count == sbus_frame_size) {
538  sbus.partial_frame_count = 0;
539  uint16_t values[16] {};
540  uint16_t num_values=0;
541  bool sbus_failsafe;
542  bool sbus_frame_drop;
543  if (sbus_decode(sbus.frame, values, &num_values, &sbus_failsafe, &sbus_frame_drop, 16) &&
544  num_values >= MIN_NUM_CHANNELS) {
545  for (uint8_t i=0; i<num_values; i++) {
546  if (values[i] != 0) {
547  _pwm_values[i] = values[i];
548  }
549  }
550  /*
551  the apparent number of channels can change on SBUS,
552  as they are spread across multiple frames. We just
553  use the max num_values we get
554  */
555  if (num_values > _num_channels) {
556  _num_channels = num_values;
557  }
558  if (!sbus_failsafe) {
559  rc_input_count++;
560  }
561 #if 0
562  printf("Decoded SBUS %u channels %u %u %u %u %u %u %u %u %s\n",
563  (unsigned)num_values,
564  values[0], values[1], values[2], values[3], values[4], values[5], values[6], values[7],
565  sbus_failsafe?"FAIL":"OK");
566 #endif
567  }
568  }
569  }
570 }
int printf(const char *fmt,...)
Definition: stdio.c:113
#define LINUX_RC_INPUT_NUM_CHANNELS
Definition: RCInput.h:7
bool set_override(uint8_t channel, int16_t override)
Definition: RCInput.cpp:71
virtual void init()
Definition: RCInput.cpp:33
std::atomic< unsigned int > rc_input_count
Definition: RCInput.h:55
bool add_st24_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:449
int16_t _rssi
Definition: RCInput.h:100
uint8_t num_channels()
Definition: RCInput.cpp:46
void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:227
int srxl_decode(uint64_t timestamp_us, uint8_t byte, uint8_t *num_values, uint16_t *values, uint16_t max_values, bool *failsafe_state)
Definition: srxl.cpp:262
bool new_input()
Definition: RCInput.cpp:37
struct Linux::RCInput::@96 dsm
void _process_ppmsum_pulse(uint16_t width)
Definition: RCInput.cpp:95
void reset()
void _process_rc_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:308
struct Linux::RCInput::@93 ppm_state
bool add_srxl_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:480
int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Definition: sumd.cpp:137
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1)
Definition: RCInput.cpp:144
std::atomic< unsigned int > last_rc_input_count
Definition: RCInput.h:56
bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
Definition: sbus.cpp:97
#define MIN_NUM_CHANNELS
Definition: RCInput.cpp:22
uint16_t bit_ofs
Definition: RCInput.h:77
bool add_sumd_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:418
uint32_t millis()
Definition: system.cpp:157
struct Linux::RCInput::@94 sbus_state
uint64_t micros64()
Definition: system.cpp:162
bool dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16], uint16_t *values, uint16_t *num_values, uint16_t max_values)
Definition: dsm.cpp:195
float v
Definition: Printf.cpp:15
struct Linux::RCInput::@95 dsm_state
uint16_t _pwm_values[LINUX_RC_INPUT_NUM_CHANNELS]
Definition: RCInput.h:58
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: RCInput.cpp:10
uint16_t _override[LINUX_RC_INPUT_NUM_CHANNELS]
Definition: RCInput.h:66
bool add_dsm_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:349
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
Definition: posix.c:772
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
uint16_t read(uint8_t ch)
Definition: RCInput.cpp:51
struct Linux::RCInput::@97 sbus
uint16_t bytes[25]
Definition: RCInput.h:76
uint8_t _num_channels
Definition: RCInput.h:59
int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Definition: st24.cpp:195
void _update_periods(uint16_t *periods, uint8_t len)
Definition: RCInput.cpp:333
void add_sbus_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:511
void clear_overrides()
Definition: RCInput.cpp:84