AP_RCProtocol_SRXL.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. /*
  14. SRXL protocol decoder, tested against AR7700 SRXL port
  15. Andrew Tridgell, September 2016
  16. Co author: Roman Kirchner, September 2016
  17. - 2016.10.23: SRXL variant V1 sucessfully (Testbench and Pixhawk/MissionPlanner) tested with RX-9-DR M-LINK (SW v1.26)
  18. */
  19. #include "AP_RCProtocol_SRXL.h"
  20. #include <AP_Math/crc.h>
  21. #include <AP_Math/AP_Math.h>
  22. // #define SUMD_DEBUG
  23. extern const AP_HAL::HAL& hal;
  24. void AP_RCProtocol_SRXL::process_pulse(uint32_t width_s0, uint32_t width_s1)
  25. {
  26. uint8_t b;
  27. if (ss.process_pulse(width_s0, width_s1, b)) {
  28. _process_byte(ss.get_byte_timestamp_us(), b);
  29. }
  30. }
  31. /**
  32. * Get RC channel information as microsecond pulsewidth representation from srxl version 1 and 2
  33. *
  34. * This function extracts RC channel information from srxl dataframe. The function expects the whole dataframe
  35. * in correct order in static array "buffer[SRXL_FRAMELEN_MAX]". After extracting all RC channel information, the data
  36. * is transferred to "values" array from parameter list. If the pixhawk does not support all channels from srxl datastream,
  37. * only supported number of channels will be refreshed.
  38. *
  39. * IMPORTANT SAFETY NOTICE: This function shall only be used after CRC has been successful.
  40. *
  41. * Structure of SRXL v1 dataframe --> 12 channels, 12 Bit per channel
  42. * Byte0: Header 0xA1
  43. * Byte1: Bits7-4:Empty Bits3-0:Channel1 MSB
  44. * Byte2: Bits7-0: Channel1 LSB
  45. * (....)
  46. * Byte23: Bits7-4:Empty Bits3-0:Channel12 MSB
  47. * Byte24: Bits7-0: Channel12 LSB
  48. * Byte25: CRC16 MSB
  49. * Byte26: CRC16 LSB
  50. *
  51. * Structure of SRXL v2 dataframe --> 16 channels, 12 Bit per channel
  52. * Byte0: Header 0xA2
  53. * Byte1: Bits7-4:Empty Bits3-0:Channel1 MSB
  54. * Byte2: Bits7-0: Channel1 LSB
  55. * (....)
  56. * Byte31: Bits7-4:Empty Bits3-0:Channel16 MSB
  57. * Byte32: Bits7-0: Channel16 LSB
  58. * Byte33: CRC16 MSB
  59. * Byte34: CRC16 LSB
  60. *
  61. * @param[in] max_values - maximum number of values supported by the pixhawk
  62. * @param[out] num_values - number of RC channels extracted from srxl frame
  63. * @param[out] values - array of RC channels with refreshed information as pulsewidth in microseconds Range: 800us - 2200us
  64. * @param[out] failsafe_state - true: RC-receiver is in failsafe state, false: RC-receiver is not in failsafe state
  65. * @retval 0 success
  66. */
  67. int AP_RCProtocol_SRXL::srxl_channels_get_v1v2(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state)
  68. {
  69. uint8_t loop;
  70. uint32_t channel_raw_value;
  71. *num_values = (uint8_t)((frame_len_full - 3U)/2U);
  72. *failsafe_state = 0U; /* this protocol version does not support failsafe information */
  73. /* get data channel data from frame */
  74. for (loop=0U; loop < *num_values; loop++) {
  75. 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) */
  76. channels[loop] = (uint16_t)(((channel_raw_value * (uint32_t)1400U) >> 12U) + (uint32_t)800U); /* convert raw value to servo/esc signal pulsewidth in us */
  77. }
  78. /* provide channel data to FMU */
  79. if ((uint16_t)*num_values > max_values) {
  80. *num_values = (uint8_t)max_values;
  81. }
  82. memcpy(values, channels, (*num_values)*2);
  83. return 0; /* for srxl protocol version 1 and 2 it is not expected, that any error happen during decode process */
  84. }
  85. /**
  86. * Get RC channel information as microsecond pulsewidth representation from srxl version 5
  87. *
  88. * This function extracts RC channel information from srxl dataframe. The function expects the whole dataframe
  89. * in correct order in static array "buffer[SRXL_FRAMELEN_MAX]". After extracting all RC channel information, the data
  90. * is transferred to "values" array from parameter list. If the pixhawk does not support all channels from srxl datastream,
  91. * only supported number of channels will be refreshed.
  92. *
  93. * IMPORTANT SAFETY NOTICE: This function shall only be used after CRC has been successful.
  94. *
  95. * Structure of SRXL v5 dataframe
  96. * Byte0: Header 0xA5
  97. * Byte1 - Byte16: Payload
  98. * Byte17: CRC16 MSB
  99. * Byte18: CRC16 LSB
  100. *
  101. * @param[in] max_values - maximum number of values supported by the pixhawk
  102. * @param[out] num_values - number of RC channels extracted from srxl frame
  103. * @param[out] values - array of RC channels with refreshed information as pulsewidth in microseconds Range: 800us - 2200us
  104. * @param[out] failsafe_state - true: RC-receiver is in failsafe state, false: RC-receiver is not in failsafe state
  105. * @retval 0 success
  106. */
  107. int AP_RCProtocol_SRXL::srxl_channels_get_v5(uint16_t max_values, uint8_t *num_values, uint16_t *values, bool *failsafe_state)
  108. {
  109. // up to 7 channel values per packet. Each channel value is 16
  110. // bits, with 11 bits of data and 4 bits of channel number. The
  111. // top bit indicates a special X-Plus channel
  112. for (uint8_t i=0; i<7; i++) {
  113. uint16_t b = buffer[i*2+2] << 8 | buffer[i*2+3];
  114. uint16_t c = b >> 11; // channel number
  115. int32_t v = b & 0x7FF;
  116. if (b & 0x8000) {
  117. continue;
  118. }
  119. if (c == 12) {
  120. // special handling for channel 12
  121. // see http://www.deviationtx.com/forum/protocol-development/2088-18-channels-for-dsm2-dsmx?start=40
  122. //printf("c12: 0x%x %02x %02x\n", (unsigned)(b>>9), (unsigned)buffer[0], (unsigned)buffer[1]);
  123. v = (b & 0x1FF) << 2;
  124. c = 10 + ((b >> 9) & 0x7);
  125. if (buffer[1] & 1) {
  126. c += 4;
  127. }
  128. } else if (c > 12) {
  129. // invalid
  130. v = 0;
  131. }
  132. // if channel number if greater than 16 then it is a X-Plus
  133. // channel. We don't yet know how to decode those. There is some information here:
  134. // http://www.deviationtx.com/forum/protocol-development/2088-18-channels-for-dsm2-dsmx?start=40
  135. // but we really need some sample data to confirm
  136. if (c < SRXL_MAX_CHANNELS) {
  137. v = (((v - 0x400) * 500) / 876) + 1500;
  138. channels[c] = v;
  139. if (c >= max_channels) {
  140. max_channels = c+1;
  141. }
  142. }
  143. //printf("%u:%u ", (unsigned)c, (unsigned)v);
  144. }
  145. //printf("\n");
  146. *num_values = max_channels;
  147. if (*num_values > max_values) {
  148. *num_values = max_values;
  149. }
  150. memcpy(values, channels, (*num_values)*2);
  151. // check failsafe bit, this goes low when connection to the
  152. // transmitter is lost
  153. *failsafe_state = ((buffer[1] & 2) == 0);
  154. // success
  155. return 0;
  156. }
  157. void AP_RCProtocol_SRXL::_process_byte(uint32_t timestamp_us, uint8_t byte)
  158. {
  159. /*----------------------------------------distinguish different srxl variants at the beginning of each frame---------------------------------------------- */
  160. /* Check if we have a new begin of a frame --> indicators: Time gap in datastream + SRXL header 0xA<VARIANT>*/
  161. if ((timestamp_us - last_data_us) >= SRXL_MIN_FRAMESPACE_US) {
  162. /* Now detect SRXL variant based on header */
  163. switch (byte) {
  164. case SRXL_HEADER_V1:
  165. frame_len_full = SRXL_FRAMELEN_V1;
  166. frame_header = SRXL_HEADER_V1;
  167. decode_state = STATE_NEW;
  168. break;
  169. case SRXL_HEADER_V2:
  170. frame_len_full = SRXL_FRAMELEN_V2;
  171. frame_header = SRXL_HEADER_V2;
  172. decode_state = STATE_NEW;
  173. break;
  174. case SRXL_HEADER_V5:
  175. frame_len_full = SRXL_FRAMELEN_V5;
  176. frame_header = SRXL_HEADER_V5;
  177. decode_state = STATE_NEW;
  178. break;
  179. default:
  180. frame_len_full = 0U;
  181. frame_header = SRXL_HEADER_NOT_IMPL;
  182. decode_state = STATE_IDLE;
  183. buflen = 0;
  184. return; /* protocol version not implemented --> no channel data --> unknown packet */
  185. }
  186. }
  187. /*--------------------------------------------collect all data from stream and decode-------------------------------------------------------*/
  188. switch (decode_state) {
  189. case STATE_NEW: /* buffer header byte and prepare for frame reception and decoding */
  190. buffer[0U]=byte;
  191. crc_fmu = crc_xmodem_update(0U,byte);
  192. buflen = 1U;
  193. decode_state_next = STATE_COLLECT;
  194. break;
  195. case STATE_COLLECT: /* receive all bytes. After reception decode frame and provide rc channel information to FMU */
  196. if (buflen >= frame_len_full) {
  197. // a logic bug in the state machine, this shouldn't happen
  198. decode_state = STATE_IDLE;
  199. buflen = 0;
  200. frame_len_full = 0;
  201. frame_header = SRXL_HEADER_NOT_IMPL;
  202. return;
  203. }
  204. buffer[buflen] = byte;
  205. buflen++;
  206. /* CRC not over last 2 frame bytes as these bytes inhabitate the crc */
  207. if (buflen <= (frame_len_full-2)) {
  208. crc_fmu = crc_xmodem_update(crc_fmu,byte);
  209. }
  210. if (buflen == frame_len_full) {
  211. /* CRC check here */
  212. crc_receiver = ((uint16_t)buffer[buflen-2] << 8U) | ((uint16_t)buffer[buflen-1]);
  213. if (crc_receiver == crc_fmu) {
  214. /* at this point buffer contains all frame data and crc is valid --> extract channel info according to SRXL variant */
  215. const uint8_t max_values = MIN((unsigned)SRXL_MAX_CHANNELS,(unsigned)MAX_RCIN_CHANNELS);
  216. uint16_t values[max_values];
  217. uint8_t num_values;
  218. bool failsafe_state;
  219. switch (frame_header) {
  220. case SRXL_HEADER_V1:
  221. srxl_channels_get_v1v2(max_values, &num_values, values, &failsafe_state);
  222. add_input(num_values, values, failsafe_state);
  223. break;
  224. case SRXL_HEADER_V2:
  225. srxl_channels_get_v1v2(max_values, &num_values, values, &failsafe_state);
  226. add_input(num_values, values, failsafe_state);
  227. break;
  228. case SRXL_HEADER_V5:
  229. srxl_channels_get_v5(max_values, &num_values, values, &failsafe_state);
  230. add_input(num_values, values, failsafe_state);
  231. break;
  232. default:
  233. break;
  234. }
  235. }
  236. decode_state_next = STATE_IDLE; /* frame data buffering and decoding finished --> statemachine not in use until new header drops is */
  237. } else {
  238. /* frame not completely received --> frame data buffering still ongoing */
  239. decode_state_next = STATE_COLLECT;
  240. }
  241. break;
  242. default:
  243. break;
  244. } /* switch (decode_state) */
  245. decode_state = decode_state_next;
  246. last_data_us = timestamp_us;
  247. }
  248. /*
  249. process a byte provided by a uart
  250. */
  251. void AP_RCProtocol_SRXL::process_byte(uint8_t byte, uint32_t baudrate)
  252. {
  253. if (baudrate != 115200) {
  254. return;
  255. }
  256. _process_byte(AP_HAL::micros(), byte);
  257. }