APM:Libraries
RC_PPM_parser.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 */
5 #pragma GCC optimize ("O2")
6 
7 #include <exti.h>
8 #include <timer.h>
9 #include "RCInput.h"
10 #include <pwm_in.h>
11 #include <AP_HAL/utility/dsm.h>
12 #include <AP_HAL/utility/sumd.h>
13 #include "sbus.h"
14 #include "GPIO.h"
15 #include "ring_buffer_pulse.h"
16 
17 #include "RC_PPM_parser.h"
18 
19 #include "UARTDriver.h"
20 #include "UART_PPM.h"
21 
22 using namespace F4Light;
23 
24 
25 extern const AP_HAL::HAL& hal;
26 
27 
28 void PPM_parser::init(uint8_t ch){
29  memset((void *)&_val[0], 0, sizeof(_val));
30  _last_signal=0;
31  _last_change=0;
32  _channels=0;
33 
34  channel_ctr=0;
35 
36  _ch = ch + 1;
37 
38  last_pulse = {0,0};
39 
41  // TODO Panic on IOC not allocated ?
42 
43  // callback is called on each edge so must be as fast as possible
45  pwm_setHandler(h.h, _ch-1);
46 
49 }
50 
51 
54 }
55 
57  if(_ch==0) return; // not initialized
58 
59  Pulse p;
60 #if 0 // [ statistics to tune memory usage
61  uint16_t np = getPPM_count(_ch);
63 #endif //]
64 
65  while( getPPM_Pulse(&p, _ch-1)){
67  last_pulse = p;
68  }
69 }
70 
71 
72 void PPM_parser::rxIntRC(uint16_t last_value, uint16_t value, bool state)
73 {
74 
75  if(state) { // was 1 so falling
77  _process_ppmsum_pulse( (last_value + value) >>1 ); // process PPM only if no protocols detected
78  }
79 
80  if((_rc_mode & ~BOARD_RC_SBUS_NI) == 0){
81  // test for non-inverted SBUS in 2nd memory structures
82  _process_sbus_pulse(value>>1, last_value>>1, sbus_state[1]); // was 1 so now is length of 1, last is a length of 0
83  }
84 
85  } else { // was 0 so rising
86 
87  if((_rc_mode & ~BOARD_RC_SBUS) == 0){
88  // try treat as SBUS (inverted)
89  // SBUS protocols detection occures on the beginning of start bit of next frame
90  _process_sbus_pulse(value>>1, last_value>>1, sbus_state[0]); // was 0 so now is length of 0, last is a length of 1
91  }
92 
93 
94  if((_rc_mode & ~(BOARD_RC_DSM | BOARD_RC_SUMD)) == 0){
95  // try treat as DSM or SUMD. Detection occures on the end of stop bit
96  _process_dsm_pulse(value>>1, last_value>>1);
97  }
98 
99  }
100 }
101 
102 
104 {
105  if (value >= 2700) { // Frame synchronization
108  }
109  channel_ctr = 0;
110  _got_ppm=true;
111 
112  return true;
113  } else if(value > 700 && value < 2300) {
116  if(_val[channel_ctr] != value) _last_change = _last_signal;
118 
119  channel_ctr++;
122  }
123  }
124  return true;
125  } else { // try another protocols
126  return false;
127  }
128 }
129 
130 
131 
132 
133 
134 /*
135  process a SBUS input pulse of the given width
136 
137  pulses are captured on each edges and SBUS parser called on rising edge - beginning of start bit
138 */
139 
140 void PPM_parser::_process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, F4Light::PPM_parser::SbusState &state)
141 {
142  // convert to bit widths, allowing for up to 4usec error, assuming 100000 bps - inverted
143  uint16_t bits_s0 = (width_s0+4) / 10;
144  uint16_t bits_s1 = (width_s1+4) / 10;
145 
146  uint8_t byte_ofs = state.bit_ofs/12;
147  uint8_t bit_ofs = state.bit_ofs%12;
148  uint16_t nlow;
149 
150  if (bits_s1 == 0 || bits_s0 == 0) { // invalid data
151  goto reset;
152  }
153 
154  if (bits_s1+bit_ofs > 10) { // invalid data as last two bits must be stop bits
155  goto reset;
156  }
157 
158 
159  // pull in the high bits
160  state.bytes[byte_ofs] |= ((1U<<bits_s1)-1) << bit_ofs;
161  state.bit_ofs += bits_s1;
162  bit_ofs += bits_s1;
163 
164  // pull in the low bits
165  nlow = bits_s0; // length of low bits
166  if (nlow + bit_ofs > 12) { // goes over byte boundary?
167  nlow = 12 - bit_ofs; // remaining part of byte
168  }
169  bits_s0 -= nlow; // zero bit residual
170  state.bit_ofs += nlow; // fill by zeros till byte end
171 
172  if (state.bit_ofs == 25*12 && bits_s0 > 12) { // all frame got and was gap
173  // we have a full frame
174  uint8_t bytes[25];
175  uint16_t i;
176 
177  for (i=0; i<25; i++) {
178  // get inverted data
179  uint16_t v = ~state.bytes[i];
180 
181  if ((v & 1) != 0) { // check start bit
182  goto reset;
183  }
184 
185  if ((v & 0xC00) != 0xC00) {// check stop bits
186  goto reset;
187  }
188  // check parity
189  uint8_t parity = 0, j;
190  for (j=1; j<=8; j++) {
191  parity ^= (v & (1U<<j))?1:0;
192  }
193  if (parity != (v&0x200)>>9) {
194  goto reset;
195  }
196  bytes[i] = ((v>>1) & 0xFF);
197  }
198 
199  uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
200  uint16_t num_values=0;
201  bool sbus_failsafe=false, sbus_frame_drop=false;
202 
203 
204  if (sbus_decode(bytes, values, &num_values,
205  &sbus_failsafe, &sbus_frame_drop,
207  num_values >= F4Light_RC_INPUT_MIN_CHANNELS)
208  {
209 
210  for (i=0; i<num_values; i++) {
211  if(_val[i] != values[i]) _last_change = systick_uptime();
212  _val[i] = values[i];
213  }
214  _channels = num_values;
215 
216  _rc_mode = state.mode; // lock input mode, SBUS has a parity and other checks so false positive is unreal
217 
218  if (!sbus_failsafe) {
219  _got_dsm = true;
221  }
222  }
223  goto reset_ok;
224  } else if (bits_s0 > 12) { // Was inter-frame gap but not full frame
225  goto reset;
226  }
227  return;
228 reset:
229 
230 reset_ok:
231  state.bit_ofs=0;
232  memset(&state.bytes, 0, sizeof(state.bytes));
233 }
234 
235 
236 
237 /*
238  process a DSM satellite input pulse of the given width
239 
240  pulses are captured on each edges and DSM parser called on falling edge - eg. beginning of start bit
241 */
242 
243 void PPM_parser::_process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
244 {
245  // convert to bit widths, allowing for up to 1uSec error, assuming 115200 bps
246  uint16_t bits_s0 = ((width_s0+4)*(uint32_t)115200) / 1000000;
247  uint16_t bits_s1 = ((width_s1+4)*(uint32_t)115200) / 1000000;
248  uint8_t bit_ofs, byte_ofs;
249  uint16_t nbits;
250 
251  if (bits_s0 == 0 || bits_s1 == 0) {
252  // invalid data
253  goto reset;
254  }
255 
256  byte_ofs = dsm_state.bit_ofs/10;
257  bit_ofs = dsm_state.bit_ofs%10;
258 
259  if(byte_ofs > 15) {
260  // invalid data
261  goto reset;
262  }
263 
264  // pull in the high bits
265  nbits = bits_s0;
266  if (nbits+bit_ofs > 10) {
267  nbits = 10 - bit_ofs;
268  }
269  dsm_state.bytes[byte_ofs] |= ((1U<<nbits)-1) << bit_ofs;
270  dsm_state.bit_ofs += nbits;
271  bit_ofs += nbits;
272 
273 
274  if (bits_s0 - nbits > 10) {
275  if (dsm_state.bit_ofs == 16*10) {
276  // we have a full frame
277  uint8_t bytes[16];
278  uint8_t i;
279  for (i=0; i<16; i++) {
280  // get raw data
281  uint16_t v = dsm_state.bytes[i];
282 
283  // check start bit
284  if ((v & 1) != 0) {
285  goto reset;
286  }
287  // check stop bits
288  if ((v & 0x200) != 0x200) {
289  goto reset;
290  }
291  uint8_t bt= ((v>>1) & 0xFF);
292  bytes[i] = bt;
293 
294  if(_rc_mode != BOARD_RC_DSM) {
295  // try to decode SUMD data on each byte, decoder butters frame itself.
296  uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
297  uint8_t rssi;
298  uint8_t rx_count;
299  uint16_t channel_count;
300 
301  if (sumd_decode(bt, &rssi, &rx_count, &channel_count, values, F4Light_RC_INPUT_NUM_CHANNELS) == 0) {
302  if (channel_count > F4Light_RC_INPUT_NUM_CHANNELS) {
303  continue;
304  }
306  for (uint8_t j=0; j<channel_count; j++) {
307  if (values[j] != 0) {
308  if(_val[j] != values[j]) _last_change = systick_uptime();
309  _val[j] = values[j];
310  }
311  }
312  _channels = channel_count;
314 // _rssi = rssi;
315  }
316  }
317 
318  if(_rc_mode == BOARD_RC_NONE) { // if protocol not decoded
319  UART_PPM::putch(bt, _ch); // push received bytes to memory queue to get via fake UARTs
320  }
321  }
322  if(_rc_mode != BOARD_RC_SUMD) { // try to decode buffer as DSM on full frame
323  uint16_t values[F4Light_RC_INPUT_NUM_CHANNELS];
324  uint16_t num_values=0;
325  if (dsm_decode(AP_HAL::micros64(), bytes, values, &num_values, F4Light_RC_INPUT_NUM_CHANNELS) &&
326  num_values >= F4Light_RC_INPUT_MIN_CHANNELS) {
327 
328  _rc_mode = BOARD_RC_DSM; // lock input mode, DSM has a checksum so false positive is unreal
329 
330  for (i=0; i<num_values; i++) {
331  if(_val[i] != values[i]) _last_change = systick_uptime();
332  _val[i] = values[i];
333  }
334 
335  uint32_t nc=num_values+1;
336  if(nc>_channels)
337  _channels = nc;
338  _val[_channels-1]=bytes[0]; // rssi
339  _got_dsm = true;
341  }
342  }
343  }
344  memset(&dsm_state, 0, sizeof(dsm_state));
345  }
346 
347  byte_ofs = dsm_state.bit_ofs/10;
348  bit_ofs = dsm_state.bit_ofs%10;
349 
350  if (bits_s1+bit_ofs > 10) {
351  // invalid data
352  goto reset;
353  }
354 
355  // pull in the low bits
356  dsm_state.bit_ofs += bits_s1;
357  return;
358 reset:
359  memset(&dsm_state, 0, sizeof(dsm_state));
360 }
361 
362 
AP_HAL::MemberProc mp
Definition: handler.h:18
Handler h
Definition: handler.h:20
bool state
Definition: pwm_in.h:42
Simple circular buffer for PEM input.
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
Definition: systick.h:44
void reset()
static void pwm_setHandler(Handler handler, uint8_t ch)
Definition: pwm_in.h:75
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
timer interface.
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
struct SbusState sbus_state[2]
Definition: RC_PPM_parser.h:71
static void putch(uint8_t c, uint8_t n)
Definition: UART_PPM.cpp:53
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 F4Light_RC_INPUT_MIN_CHANNELS
Definition: Config.h:11
bool _process_ppmsum_pulse(uint16_t value)
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint64_t micros64()
Definition: system.cpp:162
static int state
Definition: Util.cpp:20
bool getPPM_Pulse(Pulse *p, uint8_t ch)
Definition: pwm_in.c:183
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
static void do_io_completion(uint8_t id)
Definition: Scheduler.h:422
float v
Definition: Printf.cpp:15
void _process_sbus_pulse(uint16_t width_s0, uint16_t width_s1, struct PPM_parser::SbusState &state)
void init(uint8_t ch)
static uint16_t max_num_pulses
Definition: RCInput.h:51
Definition: pwm_in.h:40
volatile uint8_t _channels
Definition: RC_parser.h:24
volatile uint16_t _val[F4Light_RC_INPUT_NUM_CHANNELS]
Definition: RC_parser.h:22
volatile uint64_t _last_signal
Definition: RC_parser.h:21
float value
void rxIntRC(uint16_t value0, uint16_t value1, bool state)
#define F4Light_RC_INPUT_NUM_CHANNELS
Definition: Config.h:12
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
unsigned int length
Definition: pwm_in.h:41
static uint16_t last_value[MAX_CHANNELS]
Definition: RCInput.cpp:15
void _process_dsm_pulse(uint16_t width_s0, uint16_t width_s1)
enum BOARD_RC_MODE _rc_mode
Definition: RC_PPM_parser.h:79
struct F4Light::PPM_parser::DSM_State dsm_state
uint64_t _last_change
Definition: RC_parser.h:23
uint16_t getPPM_count(uint8_t ch)
Definition: pwm_in.c:193
static uint8_t register_io_completion(Handler handle)
Definition: Scheduler.cpp:1219