sumd.cpp 9.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379
  1. /*
  2. SUMD decoder, based on PX4Firmware/src/rc/lib/rc/sumd.c from PX4Firmware
  3. modified for use in AP_HAL_* by Andrew Tridgell
  4. */
  5. /****************************************************************************
  6. *
  7. * Copyright (c) 2015 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. * @file sumd.h
  39. *
  40. * RC protocol definition for Graupner HoTT transmitter (SUMD/SUMH Protocol)
  41. *
  42. * @author Marco Bauer <marco@wtns.de>
  43. */
  44. #include <stdio.h>
  45. #include <stdint.h>
  46. #include <AP_Math/crc.h>
  47. #include "sumd.h"
  48. #define SUMD_MAX_CHANNELS 32
  49. #define SUMD_HEADER_LENGTH 3
  50. #define SUMD_HEADER_ID 0xA8
  51. #define SUMD_ID_SUMH 0x00
  52. #define SUMD_ID_SUMD 0x01
  53. #define SUMD_ID_FAILSAFE 0x81
  54. #pragma pack(push, 1)
  55. typedef struct {
  56. uint8_t header; ///< 0xA8 for a valid packet
  57. uint8_t status; ///< 0x01 valid and live SUMD data frame / 0x00 = SUMH / 0x81 = Failsafe
  58. uint8_t length; ///< Channels
  59. uint8_t sumd_data[SUMD_MAX_CHANNELS * 2]; ///< ChannelData (High Byte/ Low Byte)
  60. uint8_t crc16_high; ///< High Byte of 16 Bit CRC
  61. uint8_t crc16_low; ///< Low Byte of 16 Bit CRC
  62. uint8_t telemetry; ///< Telemetry request
  63. uint8_t crc8; ///< SUMH CRC8
  64. } ReceiverFcPacketHoTT;
  65. #pragma pack(pop)
  66. enum SUMD_DECODE_STATE {
  67. SUMD_DECODE_STATE_UNSYNCED = 0,
  68. SUMD_DECODE_STATE_GOT_HEADER,
  69. SUMD_DECODE_STATE_GOT_STATE,
  70. SUMD_DECODE_STATE_GOT_LEN,
  71. SUMD_DECODE_STATE_GOT_DATA,
  72. SUMD_DECODE_STATE_GOT_CRC,
  73. SUMD_DECODE_STATE_GOT_CRC16_BYTE_1,
  74. SUMD_DECODE_STATE_GOT_CRC16_BYTE_2
  75. };
  76. /*
  77. const char *decode_states[] = {"UNSYNCED",
  78. "GOT_HEADER",
  79. "GOT_STATE",
  80. "GOT_LEN",
  81. "GOT_DATA",
  82. "GOT_CRC",
  83. "GOT_CRC16_BYTE_1",
  84. "GOT_CRC16_BYTE_2"
  85. };
  86. */
  87. static uint8_t _crc8 = 0x00;
  88. static uint16_t _crc16 = 0x0000;
  89. static bool _sumd = true;
  90. static bool _crcOK = false;
  91. static bool _debug = false;
  92. /* define range mapping here, -+100% -> 1000..2000 */
  93. #define SUMD_RANGE_MIN 0.0f
  94. #define SUMD_RANGE_MAX 4096.0f
  95. #define SUMD_TARGET_MIN 1000.0f
  96. #define SUMD_TARGET_MAX 2000.0f
  97. /* pre-calculate the floating point stuff as far as possible at compile time */
  98. #define SUMD_SCALE_FACTOR ((SUMD_TARGET_MAX - SUMD_TARGET_MIN) / (SUMD_RANGE_MAX - SUMD_RANGE_MIN))
  99. #define SUMD_SCALE_OFFSET (int)(SUMD_TARGET_MIN - (SUMD_SCALE_FACTOR * SUMD_RANGE_MIN + 0.5f))
  100. static enum SUMD_DECODE_STATE _decode_state = SUMD_DECODE_STATE_UNSYNCED;
  101. static uint8_t _rxlen;
  102. static ReceiverFcPacketHoTT _rxpacket;
  103. static uint8_t sumd_crc8(uint8_t crc, uint8_t value)
  104. {
  105. crc += value;
  106. return crc;
  107. }
  108. int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels,
  109. uint16_t max_chan_count)
  110. {
  111. int ret = 1;
  112. switch (_decode_state) {
  113. case SUMD_DECODE_STATE_UNSYNCED:
  114. if (_debug) {
  115. printf(" SUMD_DECODE_STATE_UNSYNCED \n") ;
  116. }
  117. if (byte == SUMD_HEADER_ID) {
  118. _rxpacket.header = byte;
  119. _sumd = true;
  120. _rxlen = 0;
  121. _crc16 = 0x0000;
  122. _crc8 = 0x00;
  123. _crcOK = false;
  124. _crc16 = crc_xmodem_update(_crc16, byte);
  125. _crc8 = sumd_crc8(_crc8, byte);
  126. _decode_state = SUMD_DECODE_STATE_GOT_HEADER;
  127. if (_debug) {
  128. printf(" SUMD_DECODE_STATE_GOT_HEADER: %x \n", byte) ;
  129. }
  130. } else {
  131. ret = 3;
  132. }
  133. break;
  134. case SUMD_DECODE_STATE_GOT_HEADER:
  135. if (byte == SUMD_ID_SUMD || byte == SUMD_ID_SUMH) {
  136. _rxpacket.status = byte;
  137. if (byte == SUMD_ID_SUMH) {
  138. _sumd = false;
  139. }
  140. if (_sumd) {
  141. _crc16 = crc_xmodem_update(_crc16, byte);
  142. } else {
  143. _crc8 = sumd_crc8(_crc8, byte);
  144. }
  145. _decode_state = SUMD_DECODE_STATE_GOT_STATE;
  146. if (_debug) {
  147. printf(" SUMD_DECODE_STATE_GOT_STATE: %x \n", byte) ;
  148. }
  149. } else {
  150. _decode_state = SUMD_DECODE_STATE_UNSYNCED;
  151. }
  152. break;
  153. case SUMD_DECODE_STATE_GOT_STATE:
  154. if (byte >= 2 && byte <= SUMD_MAX_CHANNELS) {
  155. _rxpacket.length = byte;
  156. if (_sumd) {
  157. _crc16 = crc_xmodem_update(_crc16, byte);
  158. } else {
  159. _crc8 = sumd_crc8(_crc8, byte);
  160. }
  161. _rxlen++;
  162. _decode_state = SUMD_DECODE_STATE_GOT_LEN;
  163. if (_debug) {
  164. printf(" SUMD_DECODE_STATE_GOT_LEN: %x (%d) \n", byte, byte) ;
  165. }
  166. } else {
  167. _decode_state = SUMD_DECODE_STATE_UNSYNCED;
  168. }
  169. break;
  170. case SUMD_DECODE_STATE_GOT_LEN:
  171. _rxpacket.sumd_data[_rxlen] = byte;
  172. if (_sumd) {
  173. _crc16 = crc_xmodem_update(_crc16, byte);
  174. } else {
  175. _crc8 = sumd_crc8(_crc8, byte);
  176. }
  177. _rxlen++;
  178. if (_rxlen <= ((_rxpacket.length * 2))) {
  179. if (_debug) {
  180. printf(" SUMD_DECODE_STATE_GOT_DATA[%d]: %x\n", _rxlen - 2, byte) ;
  181. }
  182. } else {
  183. _decode_state = SUMD_DECODE_STATE_GOT_DATA;
  184. if (_debug) {
  185. printf(" SUMD_DECODE_STATE_GOT_DATA -- finish --\n") ;
  186. }
  187. }
  188. break;
  189. case SUMD_DECODE_STATE_GOT_DATA:
  190. _rxpacket.crc16_high = byte;
  191. if (_debug) {
  192. printf(" SUMD_DECODE_STATE_GOT_CRC16[1]: %x [%x]\n", byte, ((_crc16 >> 8) & 0xff)) ;
  193. }
  194. if (_sumd) {
  195. _decode_state = SUMD_DECODE_STATE_GOT_CRC;
  196. } else {
  197. _decode_state = SUMD_DECODE_STATE_GOT_CRC16_BYTE_1;
  198. }
  199. break;
  200. case SUMD_DECODE_STATE_GOT_CRC16_BYTE_1:
  201. _rxpacket.crc16_low = byte;
  202. if (_debug) {
  203. printf(" SUMD_DECODE_STATE_GOT_CRC16[2]: %x [%x]\n", byte, (_crc16 & 0xff)) ;
  204. }
  205. _decode_state = SUMD_DECODE_STATE_GOT_CRC16_BYTE_2;
  206. break;
  207. case SUMD_DECODE_STATE_GOT_CRC16_BYTE_2:
  208. _rxpacket.telemetry = byte;
  209. if (_debug) {
  210. printf(" SUMD_DECODE_STATE_GOT_SUMH_TELEMETRY: %x\n", byte) ;
  211. }
  212. _decode_state = SUMD_DECODE_STATE_GOT_CRC;
  213. break;
  214. case SUMD_DECODE_STATE_GOT_CRC:
  215. if (_sumd) {
  216. _rxpacket.crc16_low = byte;
  217. if (_debug) {
  218. printf(" SUMD_DECODE_STATE_GOT_CRC[2]: %x [%x]\n\n", byte, (_crc16 & 0xff)) ;
  219. }
  220. if (_crc16 == (uint16_t)(_rxpacket.crc16_high << 8) + _rxpacket.crc16_low) {
  221. _crcOK = true;
  222. }
  223. } else {
  224. _rxpacket.crc8 = byte;
  225. if (_debug) {
  226. printf(" SUMD_DECODE_STATE_GOT_CRC8_SUMH: %x [%x]\n\n", byte, _crc8) ;
  227. }
  228. if (_crc8 == _rxpacket.crc8) {
  229. _crcOK = true;
  230. }
  231. }
  232. if (_crcOK) {
  233. if (_debug) {
  234. printf(" CRC - OK \n") ;
  235. }
  236. if (_sumd) {
  237. if (_debug) {
  238. printf(" Got valid SUMD Packet\n") ;
  239. }
  240. } else {
  241. if (_debug) {
  242. printf(" Got valid SUMH Packet\n") ;
  243. }
  244. }
  245. if (_debug) {
  246. printf(" RXLEN: %d [Chans: %d] \n\n", _rxlen - 1, (_rxlen - 1) / 2) ;
  247. }
  248. ret = 0;
  249. unsigned i;
  250. uint8_t _cnt = *rx_count + 1;
  251. *rx_count = _cnt;
  252. *rssi = 100;
  253. /* received Channels */
  254. if ((uint16_t)_rxpacket.length > max_chan_count) {
  255. _rxpacket.length = (uint8_t) max_chan_count;
  256. }
  257. *channel_count = (uint16_t)_rxpacket.length;
  258. /* decode the actual packet */
  259. /* reorder first 4 channels */
  260. /* ch1 = roll -> sumd = ch2 */
  261. channels[0] = (uint16_t)((_rxpacket.sumd_data[1 * 2 + 1] << 8) | _rxpacket.sumd_data[1 * 2 + 2]) >> 3;
  262. /* ch2 = pitch -> sumd = ch2 */
  263. channels[1] = (uint16_t)((_rxpacket.sumd_data[2 * 2 + 1] << 8) | _rxpacket.sumd_data[2 * 2 + 2]) >> 3;
  264. /* ch3 = throttle -> sumd = ch2 */
  265. channels[2] = (uint16_t)((_rxpacket.sumd_data[0 * 2 + 1] << 8) | _rxpacket.sumd_data[0 * 2 + 2]) >> 3;
  266. /* ch4 = yaw -> sumd = ch2 */
  267. channels[3] = (uint16_t)((_rxpacket.sumd_data[3 * 2 + 1] << 8) | _rxpacket.sumd_data[3 * 2 + 2]) >> 3;
  268. /* we start at channel 5(index 4) */
  269. unsigned chan_index = 4;
  270. for (i = 4; i < _rxpacket.length; i++) {
  271. if (_debug) {
  272. printf("ch[%u] : %x %x [ %x %d ]\n", i + 1, _rxpacket.sumd_data[i * 2 + 1], _rxpacket.sumd_data[i * 2 + 2],
  273. ((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3,
  274. ((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3);
  275. }
  276. channels[chan_index] = (uint16_t)((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3;
  277. /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
  278. //channels[chan_index] = (uint16_t)(channels[chan_index] * SUMD_SCALE_FACTOR + .5f) + SUMD_SCALE_OFFSET;
  279. chan_index++;
  280. }
  281. } else {
  282. /* decoding failed */
  283. ret = 4;
  284. if (_debug) {
  285. printf(" CRC - fail \n") ;
  286. }
  287. }
  288. _decode_state = SUMD_DECODE_STATE_UNSYNCED;
  289. break;
  290. }
  291. return ret;
  292. }