dsm.cpp 16 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571
  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. #include <stdint.h>
  38. #include <stdio.h>
  39. #include "dsm.h"
  40. #define DSM_FRAME_SIZE 16 /**<DSM frame size in bytes*/
  41. #define DSM_FRAME_CHANNELS 7 /**<Max supported DSM channels*/
  42. static uint64_t dsm_last_frame_time; /**< Timestamp for start of last dsm frame */
  43. static unsigned dsm_channel_shift; /**< Channel resolution, 0=unknown, 10=10 bit, 11=11 bit */
  44. //#define DEBUG
  45. #ifdef DEBUG
  46. # define debug(fmt, args...) printf(fmt "\n", ##args)
  47. #else
  48. # define debug(fmt, args...) do {} while(0)
  49. #endif
  50. /**
  51. * Attempt to decode a single channel raw channel datum
  52. *
  53. * The DSM* protocol doesn't provide any explicit framing,
  54. * so we detect dsm frame boundaries by the inter-dsm frame delay.
  55. *
  56. * The minimum dsm frame spacing is 11ms; with 16 bytes at 115200bps
  57. * dsm frame transmission time is ~1.4ms.
  58. *
  59. * We expect to only be called when bytes arrive for processing,
  60. * and if an interval of more than 5ms passes between calls,
  61. * the first byte we read will be the first byte of a dsm frame.
  62. *
  63. * In the case where byte(s) are dropped from a dsm frame, this also
  64. * provides a degree of protection. Of course, it would be better
  65. * if we didn't drop bytes...
  66. *
  67. * Upon receiving a full dsm frame we attempt to decode it
  68. *
  69. * @param[in] raw 16 bit raw channel value from dsm frame
  70. * @param[in] shift position of channel number in raw data
  71. * @param[out] channel pointer to returned channel number
  72. * @param[out] value pointer to returned channel value
  73. * @return true=raw value successfully decoded
  74. */
  75. static bool
  76. dsm_decode_channel(uint16_t raw, unsigned shift, unsigned *channel, unsigned *value)
  77. {
  78. if (raw == 0xffff)
  79. return false;
  80. *channel = (raw >> shift) & 0xf;
  81. uint16_t data_mask = (1 << shift) - 1;
  82. *value = raw & data_mask;
  83. //debug("DSM: %d 0x%04x -> %d %d", shift, raw, *channel, *value);
  84. return true;
  85. }
  86. /**
  87. * Attempt to guess if receiving 10 or 11 bit channel values
  88. *
  89. * @param[in] reset true=reset the 10/11 bit state to unknown
  90. */
  91. static void
  92. dsm_guess_format(bool reset, const uint8_t dsm_frame[16])
  93. {
  94. static uint32_t cs10;
  95. static uint32_t cs11;
  96. static unsigned samples;
  97. /* reset the 10/11 bit sniffed channel masks */
  98. if (reset) {
  99. cs10 = 0;
  100. cs11 = 0;
  101. samples = 0;
  102. dsm_channel_shift = 0;
  103. return;
  104. }
  105. /* scan the channels in the current dsm_frame in both 10- and 11-bit mode */
  106. for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
  107. const uint8_t *dp = &dsm_frame[2 + (2 * i)];
  108. uint16_t raw = (dp[0] << 8) | dp[1];
  109. unsigned channel, value;
  110. /* if the channel decodes, remember the assigned number */
  111. if (dsm_decode_channel(raw, 10, &channel, &value) && (channel < 31))
  112. cs10 |= (1 << channel);
  113. if (dsm_decode_channel(raw, 11, &channel, &value) && (channel < 31))
  114. cs11 |= (1 << channel);
  115. /* XXX if we cared, we could look for the phase bit here to decide 1 vs. 2-dsm_frame format */
  116. }
  117. /* wait until we have seen plenty of frames - 5 should normally be enough */
  118. if (samples++ < 5)
  119. return;
  120. /*
  121. * Iterate the set of sensible sniffed channel sets and see whether
  122. * decoding in 10 or 11-bit mode has yielded anything we recognize.
  123. *
  124. * XXX Note that due to what seem to be bugs in the DSM2 high-resolution
  125. * stream, we may want to sniff for longer in some cases when we think we
  126. * are talking to a DSM2 receiver in high-resolution mode (so that we can
  127. * reject it, ideally).
  128. * See e.g. http://git.openpilot.org/cru/OPReview-116 for a discussion
  129. * of this issue.
  130. */
  131. static uint32_t masks[] = {
  132. 0x3f, /* 6 channels (DX6) */
  133. 0x7f, /* 7 channels (DX7) */
  134. 0xff, /* 8 channels (DX8) */
  135. 0x1ff, /* 9 channels (DX9, etc.) */
  136. 0x3ff, /* 10 channels (DX10) */
  137. 0x1fff, /* 13 channels (DX10t) */
  138. 0x3fff /* 18 channels (DX10) */
  139. };
  140. unsigned votes10 = 0;
  141. unsigned votes11 = 0;
  142. for (unsigned i = 0; i < sizeof(masks)/sizeof(masks[0]); i++) {
  143. if (cs10 == masks[i])
  144. votes10++;
  145. if (cs11 == masks[i])
  146. votes11++;
  147. }
  148. if ((votes11 == 1) && (votes10 == 0)) {
  149. dsm_channel_shift = 11;
  150. debug("DSM: 11-bit format");
  151. return;
  152. }
  153. if ((votes10 == 1) && (votes11 == 0)) {
  154. dsm_channel_shift = 10;
  155. debug("DSM: 10-bit format");
  156. return;
  157. }
  158. /* call ourselves to reset our state ... we have to try again */
  159. debug("DSM: format detect fail, 10: 0x%08x %u 11: 0x%08x %u", cs10, votes10, cs11, votes11);
  160. dsm_guess_format(true, dsm_frame);
  161. }
  162. /**
  163. * Decode the entire dsm frame (all contained channels)
  164. *
  165. */
  166. bool
  167. dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16], uint16_t *values, uint16_t *num_values, uint16_t max_values)
  168. {
  169. /*
  170. debug("DSM dsm_frame %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x %02x%02x",
  171. dsm_frame[0], dsm_frame[1], dsm_frame[2], dsm_frame[3], dsm_frame[4], dsm_frame[5], dsm_frame[6], dsm_frame[7],
  172. dsm_frame[8], dsm_frame[9], dsm_frame[10], dsm_frame[11], dsm_frame[12], dsm_frame[13], dsm_frame[14], dsm_frame[15]);
  173. */
  174. /*
  175. * If we have lost signal for at least a second, reset the
  176. * format guessing heuristic.
  177. */
  178. if (((frame_time - dsm_last_frame_time) > 1000000) && (dsm_channel_shift != 0))
  179. dsm_guess_format(true, dsm_frame);
  180. /* we have received something we think is a dsm_frame */
  181. dsm_last_frame_time = frame_time;
  182. /* if we don't know the dsm_frame format, update the guessing state machine */
  183. if (dsm_channel_shift == 0) {
  184. dsm_guess_format(false, dsm_frame);
  185. return false;
  186. }
  187. /*
  188. * The encoding of the first two bytes is uncertain, so we're
  189. * going to ignore them for now.
  190. *
  191. * Each channel is a 16-bit unsigned value containing either a 10-
  192. * or 11-bit channel value and a 4-bit channel number, shifted
  193. * either 10 or 11 bits. The MSB may also be set to indicate the
  194. * second dsm_frame in variants of the protocol where more than
  195. * seven channels are being transmitted.
  196. */
  197. for (unsigned i = 0; i < DSM_FRAME_CHANNELS; i++) {
  198. const uint8_t *dp = &dsm_frame[2 + (2 * i)];
  199. uint16_t raw = (dp[0] << 8) | dp[1];
  200. unsigned channel, value;
  201. if (!dsm_decode_channel(raw, dsm_channel_shift, &channel, &value))
  202. continue;
  203. /* ignore channels out of range */
  204. if (channel >= max_values)
  205. continue;
  206. /* update the decoded channel count */
  207. if (channel >= *num_values)
  208. *num_values = channel + 1;
  209. /* convert 0-1024 / 0-2048 values to 1000-2000 ppm encoding. */
  210. if (dsm_channel_shift == 10)
  211. value *= 2;
  212. /*
  213. * Spektrum scaling is special. There are these basic considerations
  214. *
  215. * * Midpoint is 1520 us
  216. * * 100% travel channels are +- 400 us
  217. *
  218. * We obey the original Spektrum scaling (so a default setup will scale from
  219. * 1100 - 1900 us), but we do not obey the weird 1520 us center point
  220. * and instead (correctly) center the center around 1500 us. This is in order
  221. * to get something useful without requiring the user to calibrate on a digital
  222. * link for no reason.
  223. */
  224. /* scaled integer for decent accuracy while staying efficient */
  225. value = ((((int)value - 1024) * 1000) / 1700) + 1500;
  226. /*
  227. * Store the decoded channel into the R/C input buffer, taking into
  228. * account the different ideas about channel assignement that we have.
  229. *
  230. * Specifically, the first four channels in rc_channel_data are roll, pitch, thrust, yaw,
  231. * but the first four channels from the DSM receiver are thrust, roll, pitch, yaw.
  232. */
  233. switch (channel) {
  234. case 0:
  235. channel = 2;
  236. break;
  237. case 1:
  238. channel = 0;
  239. break;
  240. case 2:
  241. channel = 1;
  242. default:
  243. break;
  244. }
  245. values[channel] = value;
  246. }
  247. /*
  248. * Spektrum likes to send junk in higher channel numbers to fill
  249. * their packets. We don't know about a 13 channel model in their TX
  250. * lines, so if we get a channel count of 13, we'll return 12 (the last
  251. * data index that is stable).
  252. */
  253. if (*num_values == 13)
  254. *num_values = 12;
  255. #if 0
  256. if (dsm_channel_shift == 11) {
  257. /* Set the 11-bit data indicator */
  258. *num_values |= 0x8000;
  259. }
  260. #endif
  261. /*
  262. * XXX Note that we may be in failsafe here; we need to work out how to detect that.
  263. */
  264. return true;
  265. }
  266. #if defined(TEST_MAIN_PROGRAM) || defined(TEST_HEX_STRING)
  267. static uint8_t dsm_partial_frame_count;
  268. static uint8_t dsm_frame[DSM_FRAME_SIZE];
  269. static enum DSM_DECODE_STATE {
  270. DSM_DECODE_STATE_DESYNC = 0,
  271. DSM_DECODE_STATE_SYNC
  272. } dsm_decode_state = DSM_DECODE_STATE_DESYNC;
  273. static uint64_t dsm_last_rx_time; /**< Timestamp when we last received data */
  274. static uint16_t dsm_chan_count;
  275. static uint16_t dsm_frame_drops;
  276. static bool
  277. dsm_parse(uint64_t now, uint8_t *frame, unsigned len, uint16_t *values,
  278. uint16_t *num_values, bool *dsm_11_bit, unsigned *frame_drops, uint16_t max_channels)
  279. {
  280. /* this is set by the decoding state machine and will default to false
  281. * once everything that was decodable has been decoded.
  282. */
  283. bool decode_ret = false;
  284. /* keep decoding until we have consumed the buffer */
  285. for (unsigned d = 0; d < len; d++) {
  286. /* overflow check */
  287. if (dsm_partial_frame_count == sizeof(dsm_frame) / sizeof(dsm_frame[0])) {
  288. dsm_partial_frame_count = 0;
  289. dsm_decode_state = DSM_DECODE_STATE_DESYNC;
  290. #ifdef DSM_DEBUG
  291. printf("DSM: RESET (BUF LIM)\n");
  292. #endif
  293. }
  294. if (dsm_partial_frame_count == DSM_FRAME_SIZE) {
  295. dsm_partial_frame_count = 0;
  296. dsm_decode_state = DSM_DECODE_STATE_DESYNC;
  297. #ifdef DSM_DEBUG
  298. printf("DSM: RESET (PACKET LIM)\n");
  299. #endif
  300. }
  301. #ifdef DSM_DEBUG
  302. #if 1
  303. printf("dsm state: %s%s, count: %d, val: %02x\n",
  304. (dsm_decode_state == DSM_DECODE_STATE_DESYNC) ? "DSM_DECODE_STATE_DESYNC" : "",
  305. (dsm_decode_state == DSM_DECODE_STATE_SYNC) ? "DSM_DECODE_STATE_SYNC" : "",
  306. dsm_partial_frame_count,
  307. (unsigned)frame[d]);
  308. #endif
  309. #endif
  310. switch (dsm_decode_state) {
  311. case DSM_DECODE_STATE_DESYNC:
  312. /* we are de-synced and only interested in the frame marker */
  313. if ((now - dsm_last_rx_time) > 5000) {
  314. printf("resync %u\n", dsm_partial_frame_count);
  315. dsm_decode_state = DSM_DECODE_STATE_SYNC;
  316. dsm_partial_frame_count = 0;
  317. dsm_chan_count = 0;
  318. dsm_frame[dsm_partial_frame_count++] = frame[d];
  319. }
  320. break;
  321. case DSM_DECODE_STATE_SYNC: {
  322. dsm_frame[dsm_partial_frame_count++] = frame[d];
  323. /* decode whatever we got and expect */
  324. if (dsm_partial_frame_count < DSM_FRAME_SIZE) {
  325. break;
  326. }
  327. /*
  328. * Great, it looks like we might have a frame. Go ahead and
  329. * decode it.
  330. */
  331. decode_ret = dsm_decode(now, dsm_frame, values, &dsm_chan_count, max_channels);
  332. #if 1
  333. printf("%u %u: ", ((unsigned)(now/1000)) % 1000000, len);
  334. for (uint8_t i=0; i<DSM_FRAME_SIZE; i++) {
  335. printf("%02x ", (unsigned)dsm_frame[i]);
  336. }
  337. printf("\n");
  338. #endif
  339. /* we consumed the partial frame, reset */
  340. dsm_partial_frame_count = 0;
  341. /* if decoding failed, set proto to desync */
  342. if (decode_ret == false) {
  343. dsm_decode_state = DSM_DECODE_STATE_DESYNC;
  344. dsm_frame_drops++;
  345. printf("drop ");
  346. for (uint8_t i=0; i<DSM_FRAME_SIZE; i++) {
  347. printf("%02x ", (unsigned)dsm_frame[i]);
  348. }
  349. printf("\n");
  350. }
  351. }
  352. break;
  353. default:
  354. #ifdef DSM_DEBUG
  355. printf("UNKNOWN PROTO STATE");
  356. #endif
  357. decode_ret = false;
  358. }
  359. }
  360. if (frame_drops) {
  361. *frame_drops = dsm_frame_drops;
  362. }
  363. if (decode_ret) {
  364. *num_values = dsm_chan_count;
  365. }
  366. dsm_last_rx_time = now;
  367. /* return false as default */
  368. return decode_ret;
  369. }
  370. #endif
  371. #ifdef TEST_MAIN_PROGRAM
  372. /*
  373. test harness for use under Linux with USB serial adapter
  374. */
  375. #include <sys/types.h>
  376. #include <sys/stat.h>
  377. #include <fcntl.h>
  378. #include <time.h>
  379. #include <unistd.h>
  380. #include <stdlib.h>
  381. #include <termios.h>
  382. #include <string.h>
  383. static uint64_t micros64(void)
  384. {
  385. struct timespec ts;
  386. clock_gettime(CLOCK_MONOTONIC, &ts);
  387. return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)));
  388. }
  389. int main(int argc, const char *argv[])
  390. {
  391. int fd = open(argv[1], O_RDONLY|O_CLOEXEC);
  392. if (fd == -1) {
  393. perror(argv[1]);
  394. exit(1);
  395. }
  396. struct termios options;
  397. tcgetattr(fd, &options);
  398. cfsetispeed(&options, B115200);
  399. cfsetospeed(&options, B115200);
  400. options.c_cflag &= ~(PARENB|CSTOPB|CSIZE);
  401. options.c_cflag |= CS8;
  402. options.c_lflag &= ~(ICANON|ECHO|ECHOE|ISIG);
  403. options.c_iflag &= ~(IXON|IXOFF|IXANY);
  404. options.c_oflag &= ~OPOST;
  405. if (tcsetattr(fd, TCSANOW, &options) != 0) {
  406. perror("tcsetattr");
  407. exit(1);
  408. }
  409. tcflush(fd, TCIOFLUSH);
  410. uint16_t values[18];
  411. memset(values, 0, sizeof(values));
  412. while (true) {
  413. uint8_t b[16];
  414. uint16_t num_values = 0;
  415. fd_set fds;
  416. struct timeval tv;
  417. FD_ZERO(&fds);
  418. FD_SET(fd, &fds);
  419. tv.tv_sec = 1;
  420. tv.tv_usec = 0;
  421. // check if any bytes are available
  422. if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
  423. break;
  424. }
  425. ssize_t nread;
  426. if ((nread = read(fd, b, sizeof(b))) < 1) {
  427. break;
  428. }
  429. bool dsm_11_bit;
  430. unsigned frame_drops;
  431. if (dsm_parse(micros64(), b, nread, values, &num_values, &dsm_11_bit, &frame_drops, 18)) {
  432. #if 1
  433. printf("%u: ", num_values);
  434. for (uint8_t i=0; i<num_values; i++) {
  435. printf("%u:%4u ", i+1, values[i]);
  436. }
  437. printf("\n");
  438. #endif
  439. }
  440. }
  441. }
  442. #elif defined(TEST_HEX_STRING)
  443. /*
  444. test harness providing hex string to decode
  445. */
  446. #include <string.h>
  447. int main(int argc, const char *argv[])
  448. {
  449. uint8_t b[16];
  450. uint64_t t = 0;
  451. for (uint8_t i=1; i<argc; i++) {
  452. unsigned v;
  453. if (sscanf(argv[i], "%02x", &v) != 1 || v > 255) {
  454. printf("Bad hex value at %u : %s\n", (unsigned)i, argv[i]);
  455. return 1;
  456. }
  457. b[i-1] = v;
  458. }
  459. uint16_t values[18];
  460. memset(values, 0, sizeof(values));
  461. while (true) {
  462. uint16_t num_values = 0;
  463. bool dsm_11_bit;
  464. unsigned frame_drops;
  465. t += 11000;
  466. if (dsm_parse(t, b, sizeof(b), values, &num_values, &dsm_11_bit, &frame_drops, 18)) {
  467. #if 1
  468. printf("%u: ", num_values);
  469. for (uint8_t i=0; i<num_values; i++) {
  470. printf("%u:%4u ", i+1, values[i]);
  471. }
  472. printf("\n");
  473. #endif
  474. }
  475. }
  476. }
  477. #endif