st24.cpp 9.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343
  1. /*
  2. st24 decoder, based on PX4Firmware/src/rc/lib/rc/st24.c from PX4Firmware
  3. modified for use in AP_HAL_* by Andrew Tridgell
  4. */
  5. /****************************************************************************
  6. *
  7. * Copyright (c) 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. * @file st24.cpp
  39. *
  40. * RC protocol implementation for Yuneec ST24 transmitter.
  41. *
  42. * @author Lorenz Meier <lm@inf.ethz.ch>
  43. */
  44. #include <stdio.h>
  45. #include <stdint.h>
  46. #include "st24.h"
  47. #define ST24_DATA_LEN_MAX 64
  48. #define ST24_STX1 0x55
  49. #define ST24_STX2 0x55
  50. enum ST24_PACKET_TYPE {
  51. ST24_PACKET_TYPE_CHANNELDATA12 = 0,
  52. ST24_PACKET_TYPE_CHANNELDATA24,
  53. ST24_PACKET_TYPE_TRANSMITTERGPSDATA
  54. };
  55. #pragma pack(push, 1)
  56. typedef struct {
  57. uint8_t header1; ///< 0x55 for a valid packet
  58. uint8_t header2; ///< 0x55 for a valid packet
  59. uint8_t length; ///< length includes type, data, and crc = sizeof(type)+sizeof(data[payload_len])+sizeof(crc8)
  60. uint8_t type; ///< from enum ST24_PACKET_TYPE
  61. uint8_t st24_data[ST24_DATA_LEN_MAX];
  62. uint8_t crc8; ///< crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data
  63. } ReceiverFcPacket;
  64. /**
  65. * RC Channel data (12 channels).
  66. *
  67. * This is incoming from the ST24
  68. */
  69. typedef struct {
  70. uint16_t t; ///< packet counter or clock
  71. uint8_t rssi; ///< signal strength
  72. uint8_t packet_count; ///< Number of UART packets sent since reception of last RF frame (this tells something about age / rate)
  73. uint8_t channel[18]; ///< channel data, 12 channels (12 bit numbers)
  74. } ChannelData12;
  75. /**
  76. * RC Channel data (12 channels).
  77. *
  78. */
  79. typedef struct {
  80. uint16_t t; ///< packet counter or clock
  81. uint8_t rssi; ///< signal strength
  82. uint8_t packet_count; ///< Number of UART packets sent since reception of last RF frame (this tells something about age / rate)
  83. uint8_t channel[36]; ///< channel data, 24 channels (12 bit numbers)
  84. } ChannelData24;
  85. /**
  86. * Telemetry packet
  87. *
  88. * This is outgoing to the ST24
  89. *
  90. * imuStatus:
  91. * 8 bit total
  92. * bits 0-2 for status
  93. * - value 0 is FAILED
  94. * - value 1 is INITIALIZING
  95. * - value 2 is RUNNING
  96. * - values 3 through 7 are reserved
  97. * bits 3-7 are status for sensors (0 or 1)
  98. * - mpu6050
  99. * - accelerometer
  100. * - primary gyro x
  101. * - primary gyro y
  102. * - primary gyro z
  103. *
  104. * pressCompassStatus
  105. * 8 bit total
  106. * bits 0-3 for compass status
  107. * - value 0 is FAILED
  108. * - value 1 is INITIALIZING
  109. * - value 2 is RUNNING
  110. * - value 3 - 15 are reserved
  111. * bits 4-7 for pressure status
  112. * - value 0 is FAILED
  113. * - value 1 is INITIALIZING
  114. * - value 2 is RUNNING
  115. * - value 3 - 15 are reserved
  116. *
  117. */
  118. typedef struct {
  119. uint16_t t; ///< packet counter or clock
  120. int32_t lat; ///< lattitude (degrees) +/- 90 deg
  121. int32_t lon; ///< longitude (degrees) +/- 180 deg
  122. int32_t alt; ///< 0.01m resolution, altitude (meters)
  123. int16_t vx, vy, vz; ///< velocity 0.01m res, +/-320.00 North-East- Down
  124. uint8_t nsat; ///<number of satellites
  125. uint8_t voltage; ///< 25.4V voltage = 5 + 255*0.1 = 30.5V, min=5V
  126. uint8_t current; ///< 0.5A resolution
  127. int16_t roll, pitch, yaw; ///< 0.01 degree resolution
  128. uint8_t motorStatus; ///< 1 bit per motor for status 1=good, 0= fail
  129. uint8_t imuStatus; ///< inertial measurement unit status
  130. uint8_t pressCompassStatus; ///< baro / compass status
  131. } TelemetryData;
  132. #pragma pack(pop)
  133. enum ST24_DECODE_STATE {
  134. ST24_DECODE_STATE_UNSYNCED = 0,
  135. ST24_DECODE_STATE_GOT_STX1,
  136. ST24_DECODE_STATE_GOT_STX2,
  137. ST24_DECODE_STATE_GOT_LEN,
  138. ST24_DECODE_STATE_GOT_TYPE,
  139. ST24_DECODE_STATE_GOT_DATA
  140. };
  141. /* define range mapping here, -+100% -> 1000..2000 */
  142. #define ST24_RANGE_MIN 0.0f
  143. #define ST24_RANGE_MAX 4096.0f
  144. #define ST24_TARGET_MIN 1000.0f
  145. #define ST24_TARGET_MAX 2000.0f
  146. /* pre-calculate the floating point stuff as far as possible at compile time */
  147. #define ST24_SCALE_FACTOR ((ST24_TARGET_MAX - ST24_TARGET_MIN) / (ST24_RANGE_MAX - ST24_RANGE_MIN))
  148. #define ST24_SCALE_OFFSET (int)(ST24_TARGET_MIN - (ST24_SCALE_FACTOR * ST24_RANGE_MIN + 0.5f))
  149. static enum ST24_DECODE_STATE _decode_state = ST24_DECODE_STATE_UNSYNCED;
  150. static uint8_t _rxlen;
  151. static ReceiverFcPacket _rxpacket;
  152. static uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len)
  153. {
  154. uint8_t i, crc ;
  155. crc = 0;
  156. while (len--) {
  157. for (i = 0x80; i != 0; i >>= 1) {
  158. if ((crc & 0x80) != 0) {
  159. crc <<= 1;
  160. crc ^= 0x07;
  161. } else {
  162. crc <<= 1;
  163. }
  164. if ((*ptr & i) != 0) {
  165. crc ^= 0x07;
  166. }
  167. }
  168. ptr++;
  169. }
  170. return (crc);
  171. }
  172. int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels,
  173. uint16_t max_chan_count)
  174. {
  175. int ret = 1;
  176. switch (_decode_state) {
  177. case ST24_DECODE_STATE_UNSYNCED:
  178. if (byte == ST24_STX1) {
  179. _decode_state = ST24_DECODE_STATE_GOT_STX1;
  180. } else {
  181. ret = 3;
  182. }
  183. break;
  184. case ST24_DECODE_STATE_GOT_STX1:
  185. if (byte == ST24_STX2) {
  186. _decode_state = ST24_DECODE_STATE_GOT_STX2;
  187. } else {
  188. _decode_state = ST24_DECODE_STATE_UNSYNCED;
  189. }
  190. break;
  191. case ST24_DECODE_STATE_GOT_STX2:
  192. /* ensure no data overflow failure or hack is possible */
  193. if ((unsigned)byte <= sizeof(_rxpacket.length) + sizeof(_rxpacket.type) + sizeof(_rxpacket.st24_data)) {
  194. _rxpacket.length = byte;
  195. _rxlen = 0;
  196. _decode_state = ST24_DECODE_STATE_GOT_LEN;
  197. } else {
  198. _decode_state = ST24_DECODE_STATE_UNSYNCED;
  199. }
  200. break;
  201. case ST24_DECODE_STATE_GOT_LEN:
  202. _rxpacket.type = byte;
  203. _rxlen++;
  204. _decode_state = ST24_DECODE_STATE_GOT_TYPE;
  205. break;
  206. case ST24_DECODE_STATE_GOT_TYPE:
  207. _rxpacket.st24_data[_rxlen - 1] = byte;
  208. _rxlen++;
  209. if (_rxlen == (_rxpacket.length - 1)) {
  210. _decode_state = ST24_DECODE_STATE_GOT_DATA;
  211. }
  212. break;
  213. case ST24_DECODE_STATE_GOT_DATA:
  214. _rxpacket.crc8 = byte;
  215. _rxlen++;
  216. if (st24_common_crc8((uint8_t *) & (_rxpacket.length), _rxlen) == _rxpacket.crc8) {
  217. ret = 0;
  218. /* decode the actual packet */
  219. switch (_rxpacket.type) {
  220. case ST24_PACKET_TYPE_CHANNELDATA12: {
  221. ChannelData12 *d = (ChannelData12 *)_rxpacket.st24_data;
  222. *rssi = d->rssi;
  223. *rx_count = d->packet_count;
  224. /* this can lead to rounding of the strides */
  225. *channel_count = (max_chan_count < 12) ? max_chan_count : 12;
  226. unsigned stride_count = (*channel_count * 3) / 2;
  227. unsigned chan_index = 0;
  228. for (unsigned i = 0; i < stride_count; i += 3) {
  229. channels[chan_index] = ((uint16_t)d->channel[i] << 4);
  230. channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
  231. /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
  232. channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
  233. chan_index++;
  234. channels[chan_index] = ((uint16_t)d->channel[i + 2]);
  235. channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
  236. /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
  237. channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
  238. chan_index++;
  239. }
  240. }
  241. break;
  242. case ST24_PACKET_TYPE_CHANNELDATA24: {
  243. ChannelData24 *d = (ChannelData24 *)&_rxpacket.st24_data;
  244. *rssi = d->rssi;
  245. *rx_count = d->packet_count;
  246. /* this can lead to rounding of the strides */
  247. *channel_count = (max_chan_count < 24) ? max_chan_count : 24;
  248. unsigned stride_count = (*channel_count * 3) / 2;
  249. unsigned chan_index = 0;
  250. for (unsigned i = 0; i < stride_count; i += 3) {
  251. channels[chan_index] = ((uint16_t)d->channel[i] << 4);
  252. channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
  253. /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
  254. channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
  255. chan_index++;
  256. channels[chan_index] = ((uint16_t)d->channel[i + 2]);
  257. channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
  258. /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
  259. channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
  260. chan_index++;
  261. }
  262. }
  263. break;
  264. case ST24_PACKET_TYPE_TRANSMITTERGPSDATA: {
  265. // ReceiverFcPacket* d = (ReceiverFcPacket*)&_rxpacket.st24_data;
  266. /* we silently ignore this data for now, as it is unused */
  267. ret = 2;
  268. }
  269. break;
  270. default:
  271. ret = 2;
  272. break;
  273. }
  274. } else {
  275. /* decoding failed */
  276. ret = 4;
  277. }
  278. _decode_state = ST24_DECODE_STATE_UNSYNCED;
  279. break;
  280. }
  281. return ret;
  282. }