APM:Libraries
dsm.cpp
Go to the documentation of this file.
1 /*
2  DSM decoder, based on src/modules/px4iofirmware/dsm.c from PX4Firmware
3  modified for use in AP_HAL_* by Andrew Tridgell
4  */
5 /****************************************************************************
6  *
7  * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * 1. Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * 2. Redistributions in binary form must reproduce the above copyright
16  * notice, this list of conditions and the following disclaimer in
17  * the documentation and/or other materials provided with the
18  * distribution.
19  * 3. Neither the name PX4 nor the names of its contributors may be
20  * used to endorse or promote products derived from this software
21  * without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
30  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
31  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  ****************************************************************************/
37 
38 #include <stdint.h>
39 #include <stdio.h>
40 
41 #include "dsm.h"
42 
43 #define DSM_FRAME_SIZE 16
44 #define DSM_FRAME_CHANNELS 7
46 static uint64_t dsm_last_frame_time;
47 static unsigned dsm_channel_shift;
49 //#define DEBUG
50 
51 #ifdef DEBUG
52 # define debug(fmt, args...) printf(fmt "\n", ##args)
53 #else
54 # define debug(fmt, args...) do {} while(0)
55 #endif
56 
82 static bool
83 dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
84 {
85 
86  if (raw == 0xffff)
87  return false;
88 
89  *channel = (raw >> shift) & 0xf;
90 
91  uint16_t data_mask = (1 << shift) - 1;
92  *value = raw & data_mask;
93 
94  //debug("DSM: %d 0x%04x -> %d %d", shift, raw, *channel, *value);
95 
96  return true;
97 }
98 
104 static void
105 dsm_guess_format(bool reset, const uint8_t dsm_frame[16])
106 {
107  static uint32_t cs10;
108  static uint32_t cs11;
109  static unsigned samples;
110 
111  /* reset the 10/11 bit sniffed channel masks */
112  if (reset) {
113  cs10 = 0;
114  cs11 = 0;
115  samples = 0;
116  dsm_channel_shift = 0;
117  return;
118  }
119 
120  /* scan the channels in the current dsm_frame in both 10- and 11-bit mode */
121  for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
122 
123  const uint8_t *dp = &dsm_frame[2 + (2 * i)];
124  uint16_t raw = (dp[0] << 8) | dp[1];
125  unsigned channel, value;
126 
127  /* if the channel decodes, remember the assigned number */
128  if (dsm_decode_channel(raw, 10, &channel, &value) && (channel < 31))
129  cs10 |= (1 << channel);
130 
131  if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
132  cs11 |= (1 << channel);
133 
134  /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */
135  }
136 
137  /* wait until we have seen plenty of frames - 5 should normally be enough */
138  if (samples++ < 5)
139  return;
140 
141  /*
142  * Iterate the set of sensible sniffed channel sets and see whether
143  * decoding in 10 or 11-bit mode has yielded anything we recognize.
144  *
145  * XXX Note that due to what seem to be bugs in the DSM2 high-resolution
146  * stream, we may want to sniff for longer in some cases when we think we
147  * are talking to a DSM2 receiver in high-resolution mode (so that we can
148  * reject it, ideally).
149  * See e.g. http://git.openpilot.org/cru/OPReview-116 for a discussion
150  * of this issue.
151  */
152  static uint32_t masks[] = {
153  0x3f, /* 6 channels (DX6) */
154  0x7f, /* 7 channels (DX7) */
155  0xff, /* 8 channels (DX8) */
156  0x1ff, /* 9 channels (DX9, etc.) */
157  0x3ff, /* 10 channels (DX10) */
158  0x1fff, /* 13 channels (DX10t) */
159  0x3fff /* 18 channels (DX10) */
160  };
161  unsigned votes10 = 0;
162  unsigned votes11 = 0;
163 
164  for (unsigned i = 0; i < sizeof(masks)/sizeof(masks[0]); i++) {
165 
166  if (cs10 == masks[i])
167  votes10++;
168 
169  if (cs11 == masks[i])
170  votes11++;
171  }
172 
173  if ((votes11 == 1) && (votes10 == 0)) {
174  dsm_channel_shift = 11;
175  debug("DSM: 11-bit format");
176  return;
177  }
178 
179  if ((votes10 == 1) && (votes11 == 0)) {
180  dsm_channel_shift = 10;
181  debug("DSM: 10-bit format");
182  return;
183  }
184 
185  /* call ourselves to reset our state ... we have to try again */
186  debug("DSM: format detect fail, 10: 0x%08x %d 11: 0x%08x %d", cs10, votes10, cs11, votes11);
187  dsm_guess_format(true, dsm_frame);
188 }
189 
194 bool
195 dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16], uint16_t *values, uint16_t *num_values, uint16_t max_values)
196 {
197  /*
198  debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
199  dsm_frame[0], dsm_frame[1], dsm_frame[2], dsm_frame[3], dsm_frame[4], dsm_frame[5], dsm_frame[6], dsm_frame[7],
200  dsm_frame[8], dsm_frame[9], dsm_frame[10], dsm_frame[11], dsm_frame[12], dsm_frame[13], dsm_frame[14], dsm_frame[15]);
201  */
202  /*
203  * If we have lost signal for at least a second, reset the
204  * format guessing heuristic.
205  */
206  if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0))
207  dsm_guess_format(true, dsm_frame);
208 
209  /* we have received something we think is a dsm_frame */
210  dsm_last_frame_time = frame_time;
211 
212  /* if we don't know the dsm_frame format, update the guessing state machine */
213  if (dsm_channel_shift == 0) {
214  dsm_guess_format(false, dsm_frame);
215  return false;
216  }
217 
218  /*
219  * The encoding of the first two bytes is uncertain, so we're
220  * going to ignore them for now.
221  *
222  * Each channel is a 16-bit unsigned value containing either a 10-
223  * or 11-bit channel value and a 4-bit channel number, shifted
224  * either 10 or 11 bits. The MSB may also be set to indicate the
225  * second dsm_frame in variants of the protocol where more than
226  * seven channels are being transmitted.
227  */
228 
229  for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
230 
231  const uint8_t *dp = &dsm_frame[2 + (2 * i)];
232  uint16_t raw = (dp[0] << 8) | dp[1];
233  unsigned channel, value;
234 
235  if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
236  continue;
237 
238  /* ignore channels out of range */
239  if (channel >= max_values)
240  continue;
241 
242  /* update the decoded channel count */
243  if (channel >= *num_values)
244  *num_values = channel + 1;
245 
246  /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
247  if (dsm_channel_shift == 10)
248  value *= 2;
249 
250  /*
251  * Spektrum scaling is special. There are these basic considerations
252  *
253  * * Midpoint is 1520 us
254  * * 100% travel channels are +- 400 us
255  *
256  * We obey the original Spektrum scaling (so a default setup will scale from
257  * 1100 - 1900 us), but we do not obey the weird 1520 us center point
258  * and instead (correctly) center the center around 1500 us. This is in order
259  * to get something useful without requiring the user to calibrate on a digital
260  * link for no reason.
261  */
262 
263  /* scaled integer for decent accuracy while staying efficient */
264  value = ((((int)value - 1024) * 1000) / 1700) + 1500;
265 
266  /*
267  * Store the decoded channel into the R/C input buffer, taking into
268  * account the different ideas about channel assignement that we have.
269  *
270  * Specifically, the first four channels in rc_channel_data are roll, pitch, thrust, yaw,
271  * but the first four channels from the DSM receiver are thrust, roll, pitch, yaw.
272  */
273  switch (channel) {
274  case 0:
275  channel = 2;
276  break;
277 
278  case 1:
279  channel = 0;
280  break;
281 
282  case 2:
283  channel = 1;
284 
285  default:
286  break;
287  }
288 
289  values[channel] = value;
290  }
291 
292  /*
293  * Spektrum likes to send junk in higher channel numbers to fill
294  * their packets. We don't know about a 13 channel model in their TX
295  * lines, so if we get a channel count of 13, we'll return 12 (the last
296  * data index that is stable).
297  */
298  if (*num_values == 13)
299  *num_values = 12;
300 
301 #if 0
302  if (dsm_channel_shift == 11) {
303  /* Set the 11-bit data indicator */
304  *num_values |= 0x8000;
305  }
306 #endif
307 
308  /*
309  * XXX Note that we may be in failsafe here; we need to work out how to detect that.
310  */
311  return true;
312 }
313 
314 #if defined(TEST_MAIN_PROGRAM) || defined(TEST_HEX_STRING)
315 static uint8_t dsm_partial_frame_count;
316 static uint8_t dsm_frame[DSM_FRAME_SIZE];
317 static enum DSM_DECODE_STATE {
318  DSM_DECODE_STATE_DESYNC = 0,
319  DSM_DECODE_STATE_SYNC
320 } dsm_decode_state = DSM_DECODE_STATE_DESYNC;
321 static uint64_t dsm_last_rx_time;
322 static uint16_t dsm_chan_count;
323 static uint16_t dsm_frame_drops;
324 
325 static bool
326 dsm_parse(uint64_t now, uint8_t *frame, unsigned len, uint16_t *values,
327  uint16_t *num_values, bool *dsm_11_bit, unsigned *frame_drops, uint16_t max_channels)
328 {
329 
330  /* this is set by the decoding state machine and will default to false
331  * once everything that was decodable has been decoded.
332  */
333  bool decode_ret = false;
334 
335  /* keep decoding until we have consumed the buffer */
336  for (unsigned d = 0; d < len; d++) {
337 
338  /* overflow check */
339  if (dsm_partial_frame_count == sizeof(dsm_frame) / sizeof(dsm_frame[0])) {
340  dsm_partial_frame_count = 0;
341  dsm_decode_state = DSM_DECODE_STATE_DESYNC;
342 #ifdef DSM_DEBUG
343  printf("DSM: RESET (BUF LIM)\n");
344 #endif
345  }
346 
347  if (dsm_partial_frame_count == DSM_FRAME_SIZE) {
348  dsm_partial_frame_count = 0;
349  dsm_decode_state = DSM_DECODE_STATE_DESYNC;
350 #ifdef DSM_DEBUG
351  printf("DSM: RESET (PACKET LIM)\n");
352 #endif
353  }
354 
355 #ifdef DSM_DEBUG
356 #if 1
357  printf("dsm state: %s%s, count: %d, val: %02x\n",
358  (dsm_decode_state == DSM_DECODE_STATE_DESYNC) ? "DSM_DECODE_STATE_DESYNC" : "",
359  (dsm_decode_state == DSM_DECODE_STATE_SYNC) ? "DSM_DECODE_STATE_SYNC" : "",
360  dsm_partial_frame_count,
361  (unsigned)frame[d]);
362 #endif
363 #endif
364 
365  switch (dsm_decode_state) {
366  case DSM_DECODE_STATE_DESYNC:
367 
368  /* we are de-synced and only interested in the frame marker */
369  if ((now - dsm_last_rx_time) > 5000) {
370  printf("resync %u\n", dsm_partial_frame_count);
371  dsm_decode_state = DSM_DECODE_STATE_SYNC;
372  dsm_partial_frame_count = 0;
373  dsm_chan_count = 0;
374  dsm_frame[dsm_partial_frame_count++] = frame[d];
375  }
376 
377  break;
378 
379  case DSM_DECODE_STATE_SYNC: {
380  dsm_frame[dsm_partial_frame_count++] = frame[d];
381 
382  /* decode whatever we got and expect */
383  if (dsm_partial_frame_count < DSM_FRAME_SIZE) {
384  break;
385  }
386 
387  /*
388  * Great, it looks like we might have a frame. Go ahead and
389  * decode it.
390  */
391  decode_ret = dsm_decode(now, dsm_frame, values, &dsm_chan_count, max_channels);
392 
393 #if 1
394  printf("%u %u: ", ((unsigned)(now/1000)) % 1000000, len);
395  for (uint8_t i=0; i<DSM_FRAME_SIZE; i++) {
396  printf("%02x ", (unsigned)dsm_frame[i]);
397  }
398  printf("\n");
399 #endif
400 
401 
402  /* we consumed the partial frame, reset */
403  dsm_partial_frame_count = 0;
404 
405  /* if decoding failed, set proto to desync */
406  if (decode_ret == false) {
407  dsm_decode_state = DSM_DECODE_STATE_DESYNC;
408  dsm_frame_drops++;
409  printf("drop ");
410  for (uint8_t i=0; i<DSM_FRAME_SIZE; i++) {
411  printf("%02x ", (unsigned)dsm_frame[i]);
412  }
413  printf("\n");
414  }
415  }
416  break;
417 
418  default:
419 #ifdef DSM_DEBUG
420  printf("UNKNOWN PROTO STATE");
421 #endif
422  decode_ret = false;
423  }
424 
425 
426  }
427 
428  if (frame_drops) {
429  *frame_drops = dsm_frame_drops;
430  }
431 
432  if (decode_ret) {
433  *num_values = dsm_chan_count;
434  }
435 
436  dsm_last_rx_time = now;
437 
438  /* return false as default */
439  return decode_ret;
440 }
441 #endif
442 
443 
444 #ifdef TEST_MAIN_PROGRAM
445 /*
446  test harness for use under Linux with USB serial adapter
447  */
448 #include <sys/types.h>
449 #include <sys/stat.h>
450 #include <fcntl.h>
451 #include <time.h>
452 #include <unistd.h>
453 #include <stdlib.h>
454 #include <termios.h>
455 #include <string.h>
456 
457 static uint64_t micros64(void)
458 {
459  struct timespec ts;
460  clock_gettime(CLOCK_MONOTONIC, &ts);
461  return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)));
462 }
463 
464 int main(int argc, const char *argv[])
465 {
466  int fd = open(argv[1], O_RDONLY|O_CLOEXEC);
467  if (fd == -1) {
468  perror(argv[1]);
469  exit(1);
470  }
471 
472  struct termios options;
473 
474  tcgetattr(fd, &options);
475 
476  cfsetispeed(&options, B115200);
477  cfsetospeed(&options, B115200);
478 
479  options.c_cflag &= ~(PARENB|CSTOPB|CSIZE);
480  options.c_cflag |= CS8;
481 
482  options.c_lflag &= ~(ICANON|ECHO|ECHOE|ISIG);
483  options.c_iflag &= ~(IXON|IXOFF|IXANY);
484  options.c_oflag &= ~OPOST;
485 
486  if (tcsetattr(fd, TCSANOW, &options) != 0) {
487  perror("tcsetattr");
488  exit(1);
489  }
490  tcflush(fd, TCIOFLUSH);
491 
492  uint16_t values[18];
493  memset(values, 0, sizeof(values));
494 
495  while (true) {
496  uint8_t b[16];
497  uint16_t num_values = 0;
498  fd_set fds;
499  struct timeval tv;
500 
501  FD_ZERO(&fds);
502  FD_SET(fd, &fds);
503 
504  tv.tv_sec = 1;
505  tv.tv_usec = 0;
506 
507  // check if any bytes are available
508  if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
509  break;
510  }
511 
512  ssize_t nread;
513  if ((nread = read(fd, b, sizeof(b))) < 1) {
514  break;
515  }
516 
517  bool dsm_11_bit;
518  unsigned frame_drops;
519 
520  if (dsm_parse(micros64(), b, nread, values, &num_values, &dsm_11_bit, &frame_drops, 18)) {
521 #if 1
522  printf("%u: ", num_values);
523  for (uint8_t i=0; i<num_values; i++) {
524  printf("%u:%4u ", i+1, values[i]);
525  }
526  printf("\n");
527 #endif
528  }
529  }
530 }
531 #elif defined(TEST_HEX_STRING)
532 /*
533  test harness providing hex string to decode
534  */
535 #include <string.h>
536 
537 int main(int argc, const char *argv[])
538 {
539  uint8_t b[16];
540  uint64_t t = 0;
541 
542  for (uint8_t i=1; i<argc; i++) {
543  unsigned v;
544  if (sscanf(argv[i], "%02x", &v) != 1 || v > 255) {
545  printf("Bad hex value at %u : %s\n", (unsigned)i, argv[i]);
546  return 1;
547  }
548  b[i-1] = v;
549  }
550  uint16_t values[18];
551  memset(values, 0, sizeof(values));
552 
553  while (true) {
554  uint16_t num_values = 0;
555  bool dsm_11_bit;
556  unsigned frame_drops;
557 
558  t += 11000;
559 
560  if (dsm_parse(t, b, sizeof(b), values, &num_values, &dsm_11_bit, &frame_drops, 18)) {
561 #if 1
562  printf("%u: ", num_values);
563  for (uint8_t i=0; i<num_values; i++) {
564  printf("%u:%4u ", i+1, values[i]);
565  }
566  printf("\n");
567 #endif
568  }
569  }
570 }
571 #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
#define DSM_FRAME_CHANNELS
Definition: dsm.cpp:44
#define DSM_FRAME_SIZE
Definition: dsm.cpp:43
void reset()
#define debug(fmt, args...)
Definition: dsm.cpp:54
static bool dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
Definition: dsm.cpp:83
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
static uint8_t max_channels
int sscanf(const char *buf, const char *fmt,...)
Definition: stdio.c:136
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
int main(int argc, char const **argv)
Definition: RingBuffer.cpp:65
static uint64_t dsm_last_frame_time
Definition: dsm.cpp:46
float value
static unsigned dsm_channel_shift
Definition: dsm.cpp:47
static void dsm_guess_format(bool reset, const uint8_t dsm_frame[16])
Definition: dsm.cpp:105