APM:Libraries
srxl.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  SRXL protocol decoder, tested against AR7700 SRXL port
17  Andrew Tridgell, September 2016
18 
19  Co author: Roman Kirchner, September 2016
20  - 2016.10.23: SRXL variant V1 sucessfully (Testbench and Pixhawk/MissionPlanner) tested with RX-9-DR M-LINK (SW v1.26)
21  */
22 
23 #include <stdio.h>
24 #include <stdint.h>
25 #include <string.h>
26 #include "srxl.h"
27 
28 
29 
30 /* SRXL datastream characteristics for all variants */
31 #define SRXL_MIN_FRAMESPACE_US 8000U /* Minumum space between srxl frames in us (applies to all variants) */
32 #define SRXL_MAX_CHANNELS 20U /* Maximum number of channels from srxl datastream */
33 
34 /* decode progress states */
35 #define STATE_IDLE 0x00U /* do nothing */
36 #define STATE_NEW 0x01U /* get header of frame + prepare for frame reception + begin new crc cycle */
37 #define STATE_COLLECT 0x02U /* collect RC channel data from frame + concurrently calc crc over payload data + extract channel information */
38 
39 
40 /* Variant specific SRXL datastream characteristics */
41 /* Framelength in byte */
42 #define SRXL_FRAMELEN_V1 27U /* Framelength with header in byte for: Mpx SRXLv1 or XBUS Mode B */
43 #define SRXL_FRAMELEN_V2 35U /* Framelength with header in byte for: Mpx SRXLv2 */
44 #define SRXL_FRAMELEN_V5 18U /* Framelength with header in byte for Spk AR7700 etc. */
45 #define SRXL_FRAMELEN_MAX 35U /* maximum possible framelengh */
46 
47 /* Headerbyte */
48 #define SRXL_HEADER_V1 0xA1U /* Headerbyte for: Mpx SRXLv1 or XBUS Mode B */
49 #define SRXL_HEADER_V2 0xA2U /* Headerbyte for: Mpx SRXLv2 */
50 #define SRXL_HEADER_V5 0xA5U /* Headerbyte for: Spk AR7700 etc. */
51 #define SRXL_HEADER_NOT_IMPL 0xFFU /* Headerbyte for non impemented srxl header*/
52 
53 
54 
55 
56 static uint8_t buffer[SRXL_FRAMELEN_MAX]; /* buffer for raw srxl frame data in correct order --> buffer[0]=byte0 buffer[1]=byte1 */
57 static uint8_t buflen; /* length in number of bytes of received srxl dataframe in buffer */
58 static uint64_t last_data_us; /* timespan since last received data in us */
59 static uint16_t channels[SRXL_MAX_CHANNELS]; /* buffer for extracted RC channel data as pulsewidth in microseconds */
60 
61 static uint8_t frame_header = 0U; /* Frame header from SRXL datastream */
62 static uint8_t frame_len_full = 0U; /* Length in number of bytes of full srxl datastream */
63 static uint8_t decode_state = STATE_IDLE; /* Current state of SRXL frame decoding */
64 static uint8_t decode_state_next = STATE_IDLE; /* State of frame decoding thatwill be applied when the next byte from dataframe drops in */
65 static uint16_t crc_fmu = 0U; /* CRC calculated over payload from srxl datastream on this machine */
66 static uint16_t crc_receiver = 0U; /* CRC extracted from srxl datastream */
67 
68 
69 static uint16_t max_channels;
70 
71 
72 
73 
86 static uint16_t srxl_crc16 (uint16_t crc, uint8_t new_byte)
87 {
88  uint8_t loop;
89  crc = crc ^ (uint16_t)new_byte << 8;
90  for(loop = 0; loop < 8; loop++) {
91  crc = (crc & 0x8000) ? (crc << 1) ^ 0x1021 : (crc << 1);
92  }
93  return crc;
94 }
95 
96 
133 static int srxl_channels_get_v1v2(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state)
134 {
135  uint8_t loop;
136  uint32_t channel_raw_value;
137 
138  *num_values = (uint8_t)((frame_len_full - 3U)/2U);
139  *failsafe_state = 0U; /* this protocol version does not support failsafe information */
140 
141  /* get data channel data from frame */
142  for (loop=0U; loop < *num_values; loop++) {
143  channel_raw_value = ((((uint32_t)buffer[loop*2U+1U])& 0x0000000FU) << 8U) | ((uint32_t)(buffer[loop*2U+2U])); /* get 12bit channel raw value from srxl datastream (mask out unused bits with 0x0000000F) */
144  channels[loop] = (uint16_t)(((channel_raw_value * (uint32_t)1400U) >> 12U) + (uint32_t)800U); /* convert raw value to servo/esc signal pulsewidth in us */
145  }
146 
147  /* provide channel data to FMU */
148  if ( (uint16_t)*num_values > max_values) {
149  *num_values = (uint8_t)max_values;
150  }
151  memcpy(values, channels, (*num_values)*2);
152 
153  return 0; /* for srxl protocol version 1 and 2 it is not expected, that any error happen during decode process */
154  }
155 
156 
179 static int srxl_channels_get_v5(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state)
180 {
181  // up to 7 channel values per packet. Each channel value is 16
182  // bits, with 11 bits of data and 4 bits of channel number. The
183  // top bit indicates a special X-Plus channel
184  for (uint8_t i=0; i<7; i++) {
185  uint16_t b = buffer[i*2+2] << 8 | buffer[i*2+3];
186  uint16_t c = b >> 11; // channel number
187  int32_t v = b & 0x7FF;
188  if (b & 0x8000) {
189  continue;
190  }
191  if (c == 12) {
192  // special handling for channel 12
193  // see http://www.deviationtx.com/forum/protocol-development/2088-18-channels-for-dsm2-dsmx?start=40
194  //printf("c12: 0x%x %02x %02x\n", (unsigned)(b>>9), (unsigned)buffer[0], (unsigned)buffer[1]);
195  v = (b & 0x1FF) << 2;
196  c = 10 + ((b >> 9) & 0x7);
197  if (buffer[1] & 1) {
198  c += 4;
199  }
200 #if 0
201  printf("b=0x%04x v=%u c=%u b[1]=0x%02x\n",
202  (unsigned)b, (unsigned)v, (unsigned)c, (unsigned)buffer[1]);
203 #endif
204  } else if (c > 12) {
205  // invalid
206  v = 0;
207  }
208 
209  // if channel number if greater than 16 then it is a X-Plus
210  // channel. We don't yet know how to decode those. There is some information here:
211  // http://www.deviationtx.com/forum/protocol-development/2088-18-channels-for-dsm2-dsmx?start=40
212  // but we really need some sample data to confirm
213  if (c < SRXL_MAX_CHANNELS) {
214  v = (((v - 0x400) * 500) / 876) + 1500;
215  channels[c] = v;
216  if (c >= max_channels) {
217  max_channels = c+1;
218  }
219  }
220 
221  //printf("%u:%u ", (unsigned)c, (unsigned)v);
222  }
223  //printf("\n");
224 
225  *num_values = max_channels;
226  if (*num_values > max_values) {
227  *num_values = max_values;
228  }
229  memcpy(values, channels, (*num_values)*2);
230 
231  // check failsafe bit, this goes low when connection to the
232  // transmitter is lost
233  *failsafe_state = ((buffer[1] & 2) == 0);
234 
235  // success
236  return 0;
237  }
238 
239 
240 
241 
262 int srxl_decode(uint64_t timestamp_us, uint8_t byte, uint8_t *num_values, uint16_t *values, uint16_t max_values, bool *failsafe_state)
263 {
264  int ret = 1;
265 
266  /*----------------------------------------distinguish different srxl variants at the beginning of each frame---------------------------------------------- */
267  /* Check if we have a new begin of a frame --> indicators: Time gap in datastream + SRXL header 0xA<VARIANT>*/
268  if ( (timestamp_us - last_data_us) >= SRXL_MIN_FRAMESPACE_US) {
269  /* Now detect SRXL variant based on header */
270  switch(byte) {
271  case SRXL_HEADER_V1:
275  break;
276  case SRXL_HEADER_V2:
280  break;
281  case SRXL_HEADER_V5:
285  break;
286  default:
287  frame_len_full = 0U;
290  buflen = 0;
291  return 2; /* protocol version not implemented --> no channel data --> unknown packet */
292  }
293  }
294 
295 
296  /*--------------------------------------------collect all data from stream and decode-------------------------------------------------------*/
297  switch (decode_state) {
298  case STATE_NEW: /* buffer header byte and prepare for frame reception and decoding */
299  buffer[0U]=byte;
300  crc_fmu = srxl_crc16(0U,byte);
301  buflen = 1U;
303  break;
304 
305  case STATE_COLLECT: /* receive all bytes. After reception decode frame and provide rc channel information to FMU */
306  if (buflen >= frame_len_full) {
307  // a logic bug in the state machine, this shouldn't happen
309  buflen = 0;
310  frame_len_full = 0;
312  return 2;
313  }
314  buffer[buflen] = byte;
315  buflen++;
316  /* CRC not over last 2 frame bytes as these bytes inhabitate the crc */
317  if (buflen <= (frame_len_full-2)) {
318  crc_fmu = srxl_crc16(crc_fmu,byte);
319  }
320  if( buflen == frame_len_full ) {
321  /* CRC check here */
322  crc_receiver = ((uint16_t)buffer[buflen-2] << 8U) | ((uint16_t)buffer[buflen-1]);
323  if (crc_receiver == crc_fmu) {
324  /* at this point buffer contains all frame data and crc is valid --> extract channel info according to SRXL variant */
325  switch (frame_header) {
326  case SRXL_HEADER_V1:
327  ret = srxl_channels_get_v1v2(max_values, num_values, values, failsafe_state);
328  break;
329  case SRXL_HEADER_V2:
330  ret = srxl_channels_get_v1v2(max_values, num_values, values, failsafe_state);
331  break;
332  case SRXL_HEADER_V5:
333  ret = srxl_channels_get_v5(max_values, num_values, values, failsafe_state);
334  break;
335  default:
336  ret = 2; /* protocol version not implemented --> no channel data */
337  break;
338  }
339  }
340  else {
341  ret = 4; /* CRC fail --> no channel data */
342  }
343  decode_state_next = STATE_IDLE; /* frame data buffering and decoding finished --> statemachine not in use until new header drops is */
344  }
345  else {
346  /* frame not completely received --> frame data buffering still ongoing */
348  }
349  break;
350 
351  default:
352  ret = 1; /* STATE_IDLE --> do nothing */
353  break;
354  } /* switch (decode_state) */
355 
357  last_data_us = timestamp_us;
358  return ret;
359 }
360 
361 
362 #ifdef TEST_MAIN_PROGRAM
363 /*
364  test harness for use under Linux with USB serial adapter
365  */
366 #include <sys/types.h>
367 #include <sys/stat.h>
368 #include <fcntl.h>
369 #include <time.h>
370 #include <unistd.h>
371 #include <stdlib.h>
372 #include <termios.h>
373 
374 static uint64_t micros64(void)
375 {
376  struct timespec ts;
377  clock_gettime(CLOCK_MONOTONIC, &ts);
378  return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)));
379 }
380 
381 int main(int argc, const char *argv[])
382 {
383  int fd = open(argv[1], O_RDONLY|O_CLOEXEC);
384  if (fd == -1) {
385  perror(argv[1]);
386  exit(1);
387  }
388 
389  struct termios options;
390 
391  tcgetattr(fd, &options);
392 
393  cfsetispeed(&options, B115200);
394  cfsetospeed(&options, B115200);
395 
396  options.c_cflag &= ~(PARENB|CSTOPB|CSIZE);
397  options.c_cflag |= CS8;
398 
399  options.c_lflag &= ~(ICANON|ECHO|ECHOE|ISIG);
400  options.c_iflag &= ~(IXON|IXOFF|IXANY);
401  options.c_oflag &= ~OPOST;
402 
403  if (tcsetattr(fd, TCSANOW, &options) != 0) {
404  perror("tcsetattr");
405  exit(1);
406  }
407  tcflush(fd, TCIOFLUSH);
408 
409  while (true) {
410  uint8_t b;
411  uint8_t num_values = 0;
412  uint16_t values[20];
413  bool failsafe_state;
414  fd_set fds;
415  struct timeval tv;
416 
417  FD_ZERO(&fds);
418  FD_SET(fd, &fds);
419 
420  tv.tv_sec = 1;
421  tv.tv_usec = 0;
422 
423  // check if any bytes are available
424  if (select(fd+1, &fds, NULL, NULL, &tv) != 1) {
425  break;
426  }
427 
428  if (read(fd, &b, 1) != 1) {
429  break;
430  }
431 
432  if (srxl_decode(micros64(), b, &num_values, values, sizeof(values)/sizeof(values[0]), &failsafe_state) == 0) {
433 #if 1
434  printf("%u: ", num_values);
435  for (uint8_t i=0; i<num_values; i++) {
436  printf("%u:%4u ", i+1, values[i]);
437  }
438  printf("%s\n", failsafe_state?"FAIL":"OK");
439 #endif
440  }
441  }
442 }
443 #endif
444 
445 
446 #ifdef TEST_BIN_PROGRAM
447 /*
448  test harness for use under Linux with hex dump in a file
449  */
450 #include <sys/types.h>
451 #include <sys/stat.h>
452 #include <fcntl.h>
453 #include <time.h>
454 #include <unistd.h>
455 #include <stdlib.h>
456 #include <termios.h>
457 
458 int main(int argc, const char *argv[])
459 {
460  FILE *f = fopen(argv[1], "r");
461  if (!f) {
462  perror(argv[1]);
463  exit(1);
464  }
465 
466  uint64_t t=0;
467  while (true) {
468  uint8_t b;
469  uint8_t num_values = 0;
470  uint16_t values[20];
471  bool failsafe_state;
472 
473 
474  uint8_t header;
475  if (fread(&header, 1, 1, f) != 1) {
476  break;
477  }
478 
479  uint8_t frame_size = 0;
480  switch (header) {
481  case SRXL_HEADER_V1:
482  frame_size = SRXL_FRAMELEN_V1;
483  break;
484  case SRXL_HEADER_V2:
485  frame_size = SRXL_FRAMELEN_V2;
486  break;
487  case SRXL_HEADER_V5:
488  frame_size = SRXL_FRAMELEN_V5;
489  break;
490  }
491  if (frame_size == 0) {
492  continue;
493  }
494  uint8_t u[frame_size];
495  u[0] = header;
496  if (fread(&u[1], 1, sizeof(u)-1, f) != sizeof(u)-1) {
497  break;
498  }
499  t += 11000;
500 
501  for (uint8_t i=0; i<sizeof(u); i++) {
502  b = u[i];
503 
504  if (srxl_decode(t, b, &num_values, values, sizeof(values)/sizeof(values[0]), &failsafe_state) == 0) {
505  printf("%u: ", num_values);
506  for (uint8_t i=0; i<num_values; i++) {
507  printf("%u:%4u ", i+1, values[i]);
508  }
509  printf("%s\n", failsafe_state?"FAIL":"OK");
510  }
511  }
512  }
513 }
514 #endif
int printf(const char *fmt,...)
Definition: stdio.c:113
void clock_gettime(uint32_t a1, void *a2)
Definition: syscalls.c:201
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
static uint16_t max_channels
Definition: srxl.cpp:69
#define SRXL_HEADER_V5
Definition: srxl.cpp:50
#define STATE_IDLE
Definition: srxl.cpp:35
#define SRXL_FRAMELEN_V5
Definition: srxl.cpp:44
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
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
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
static uint8_t decode_state_next
Definition: srxl.cpp:64
static uint16_t srxl_crc16(uint16_t crc, uint8_t new_byte)
Definition: srxl.cpp:86
#define SRXL_FRAMELEN_MAX
Definition: srxl.cpp:45
#define STATE_NEW
Definition: srxl.cpp:36
#define STATE_COLLECT
Definition: srxl.cpp:37
void perror(const char *s)
POSIX perror() - convert POSIX errno to text with user message.
Definition: posix.c:1827
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
#define SRXL_FRAMELEN_V1
Definition: srxl.cpp:42
#define f(i)
static int srxl_channels_get_v5(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state)
Definition: srxl.cpp:179
static uint8_t frame_header
Definition: srxl.cpp:61
#define SRXL_FRAMELEN_V2
Definition: srxl.cpp:43
#define SRXL_HEADER_V2
Definition: srxl.cpp:49
void loop()
Definition: AC_PID_test.cpp:34
uint64_t micros64()
Definition: system.cpp:162
static int srxl_channels_get_v1v2(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state)
Definition: srxl.cpp:133
float v
Definition: Printf.cpp:15
uint8_t byte
Definition: compat.h:8
int main(int argc, char const **argv)
Definition: RingBuffer.cpp:65
#define SRXL_HEADER_NOT_IMPL
Definition: srxl.cpp:51
#define NULL
Definition: hal_types.h:59
static uint16_t crc_fmu
Definition: srxl.cpp:65
static uint8_t buflen
Definition: srxl.cpp:57
static uint8_t decode_state
Definition: srxl.cpp:63
static uint64_t last_data_us
Definition: srxl.cpp:58
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
Definition: posix.c:772
static uint8_t frame_len_full
Definition: srxl.cpp:62
#define SRXL_MIN_FRAMESPACE_US
Definition: srxl.cpp:31
#define SRXL_MAX_CHANNELS
Definition: srxl.cpp:32
#define SRXL_HEADER_V1
Definition: srxl.cpp:48
static uint16_t crc_receiver
Definition: srxl.cpp:66