AP_RCProtocol_SBUS.cpp 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269
  1. /*
  2. SBUS decoder, based on src/modules/px4iofirmware/sbus.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. * This file is free software: you can redistribute it and/or modify it
  39. * under the terms of the GNU General Public License as published by the
  40. * Free Software Foundation, either version 3 of the License, or
  41. * (at your option) any later version.
  42. *
  43. * This file is distributed in the hope that it will be useful, but
  44. * WITHOUT ANY WARRANTY; without even the implied warranty of
  45. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  46. * See the GNU General Public License for more details.
  47. *
  48. * You should have received a copy of the GNU General Public License along
  49. * with this program. If not, see <http://www.gnu.org/licenses/>.
  50. *
  51. * Code by Andrew Tridgell and Siddharth Bharat Purohit
  52. */
  53. #include "AP_RCProtocol_SBUS.h"
  54. #define SBUS_FRAME_SIZE 25
  55. #define SBUS_INPUT_CHANNELS 16
  56. #define SBUS_FLAGS_BYTE 23
  57. #define SBUS_FAILSAFE_BIT 3
  58. #define SBUS_FRAMELOST_BIT 2
  59. /* define range mapping here, -+100% -> 1000..2000 */
  60. #define SBUS_RANGE_MIN 200.0f
  61. #define SBUS_RANGE_MAX 1800.0f
  62. #define SBUS_TARGET_MIN 1000.0f
  63. #define SBUS_TARGET_MAX 2000.0f
  64. /* pre-calculate the floating point stuff as far as possible at compile time */
  65. #define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN))
  66. #define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f))
  67. /*
  68. * S.bus decoder matrix.
  69. *
  70. * Each channel value can come from up to 3 input bytes. Each row in the
  71. * matrix describes up to three bytes, and each entry gives:
  72. *
  73. * - byte offset in the data portion of the frame
  74. * - right shift applied to the data byte
  75. * - mask for the data byte
  76. * - left shift applied to the result into the channel value
  77. */
  78. struct sbus_bit_pick {
  79. uint8_t byte;
  80. uint8_t rshift;
  81. uint8_t mask;
  82. uint8_t lshift;
  83. };
  84. static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
  85. /* 0 */ { { 0, 0, 0xff, 0}, { 1, 0, 0x07, 8}, { 0, 0, 0x00, 0} },
  86. /* 1 */ { { 1, 3, 0x1f, 0}, { 2, 0, 0x3f, 5}, { 0, 0, 0x00, 0} },
  87. /* 2 */ { { 2, 6, 0x03, 0}, { 3, 0, 0xff, 2}, { 4, 0, 0x01, 10} },
  88. /* 3 */ { { 4, 1, 0x7f, 0}, { 5, 0, 0x0f, 7}, { 0, 0, 0x00, 0} },
  89. /* 4 */ { { 5, 4, 0x0f, 0}, { 6, 0, 0x7f, 4}, { 0, 0, 0x00, 0} },
  90. /* 5 */ { { 6, 7, 0x01, 0}, { 7, 0, 0xff, 1}, { 8, 0, 0x03, 9} },
  91. /* 6 */ { { 8, 2, 0x3f, 0}, { 9, 0, 0x1f, 6}, { 0, 0, 0x00, 0} },
  92. /* 7 */ { { 9, 5, 0x07, 0}, {10, 0, 0xff, 3}, { 0, 0, 0x00, 0} },
  93. /* 8 */ { {11, 0, 0xff, 0}, {12, 0, 0x07, 8}, { 0, 0, 0x00, 0} },
  94. /* 9 */ { {12, 3, 0x1f, 0}, {13, 0, 0x3f, 5}, { 0, 0, 0x00, 0} },
  95. /* 10 */ { {13, 6, 0x03, 0}, {14, 0, 0xff, 2}, {15, 0, 0x01, 10} },
  96. /* 11 */ { {15, 1, 0x7f, 0}, {16, 0, 0x0f, 7}, { 0, 0, 0x00, 0} },
  97. /* 12 */ { {16, 4, 0x0f, 0}, {17, 0, 0x7f, 4}, { 0, 0, 0x00, 0} },
  98. /* 13 */ { {17, 7, 0x01, 0}, {18, 0, 0xff, 1}, {19, 0, 0x03, 9} },
  99. /* 14 */ { {19, 2, 0x3f, 0}, {20, 0, 0x1f, 6}, { 0, 0, 0x00, 0} },
  100. /* 15 */ { {20, 5, 0x07, 0}, {21, 0, 0xff, 3}, { 0, 0, 0x00, 0} }
  101. };
  102. // constructor
  103. AP_RCProtocol_SBUS::AP_RCProtocol_SBUS(AP_RCProtocol &_frontend, bool _inverted) :
  104. AP_RCProtocol_Backend(_frontend),
  105. inverted(_inverted)
  106. {}
  107. // decode a full SBUS frame
  108. bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
  109. bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
  110. {
  111. /* check frame boundary markers to avoid out-of-sync cases */
  112. if ((frame[0] != 0x0f)) {
  113. return false;
  114. }
  115. switch (frame[24]) {
  116. case 0x00:
  117. /* this is S.BUS 1 */
  118. break;
  119. case 0x03:
  120. /* S.BUS 2 SLOT0: RX battery and external voltage */
  121. break;
  122. case 0x83:
  123. /* S.BUS 2 SLOT1 */
  124. break;
  125. case 0x43:
  126. case 0xC3:
  127. case 0x23:
  128. case 0xA3:
  129. case 0x63:
  130. case 0xE3:
  131. break;
  132. default:
  133. /* we expect one of the bits above, but there are some we don't know yet */
  134. break;
  135. }
  136. unsigned chancount = (max_values > SBUS_INPUT_CHANNELS) ?
  137. SBUS_INPUT_CHANNELS : max_values;
  138. /* use the decoder matrix to extract channel data */
  139. for (unsigned channel = 0; channel < chancount; channel++) {
  140. unsigned value = 0;
  141. for (unsigned pick = 0; pick < 3; pick++) {
  142. const struct sbus_bit_pick *decode = &sbus_decoder[channel][pick];
  143. if (decode->mask != 0) {
  144. unsigned piece = frame[1 + decode->byte];
  145. piece >>= decode->rshift;
  146. piece &= decode->mask;
  147. piece <<= decode->lshift;
  148. value |= piece;
  149. }
  150. }
  151. /* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */
  152. values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR +.5f) + SBUS_SCALE_OFFSET;
  153. }
  154. /* decode switch channels if data fields are wide enough */
  155. if (max_values > 17 && chancount > 15) {
  156. chancount = 18;
  157. /* channel 17 (index 16) */
  158. values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0))?1998:998;
  159. /* channel 18 (index 17) */
  160. values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1))?1998:998;
  161. }
  162. /* note the number of channels decoded */
  163. *num_values = chancount;
  164. /* decode and handle failsafe and frame-lost flags */
  165. if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
  166. /* report that we failed to read anything valid off the receiver */
  167. *sbus_failsafe = true;
  168. *sbus_frame_drop = true;
  169. } else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
  170. /* set a special warning flag
  171. *
  172. * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
  173. * condition as fail-safe greatly reduces the reliability and range of the radio link,
  174. * e.g. by prematurely issuing return-to-launch!!! */
  175. *sbus_failsafe = false;
  176. *sbus_frame_drop = true;
  177. } else {
  178. *sbus_failsafe = false;
  179. *sbus_frame_drop = false;
  180. }
  181. return true;
  182. }
  183. /*
  184. process a SBUS input pulse of the given width
  185. */
  186. void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1)
  187. {
  188. uint32_t w0 = width_s0;
  189. uint32_t w1 = width_s1;
  190. if (inverted) {
  191. w0 = saved_width;
  192. w1 = width_s0;
  193. saved_width = width_s1;
  194. }
  195. uint8_t b;
  196. if (ss.process_pulse(w0, w1, b)) {
  197. _process_byte(ss.get_byte_timestamp_us(), b);
  198. }
  199. }
  200. // support byte input
  201. void AP_RCProtocol_SBUS::_process_byte(uint32_t timestamp_us, uint8_t b)
  202. {
  203. const bool have_frame_gap = (timestamp_us - byte_input.last_byte_us >= 2000U);
  204. byte_input.last_byte_us = timestamp_us;
  205. if (have_frame_gap) {
  206. // if we have a frame gap then this must be the start of a new
  207. // frame
  208. byte_input.ofs = 0;
  209. }
  210. if (b != 0x0F && byte_input.ofs == 0) {
  211. // definately not SBUS, missing header byte
  212. return;
  213. }
  214. if (byte_input.ofs == 0 && !have_frame_gap) {
  215. // must have a frame gap before the start of a new SBUS frame
  216. return;
  217. }
  218. byte_input.buf[byte_input.ofs++] = b;
  219. if (byte_input.ofs == sizeof(byte_input.buf)) {
  220. uint16_t values[SBUS_INPUT_CHANNELS];
  221. uint16_t num_values=0;
  222. bool sbus_failsafe = false;
  223. bool sbus_frame_drop = false;
  224. if (sbus_decode(byte_input.buf, values, &num_values,
  225. &sbus_failsafe, &sbus_frame_drop, SBUS_INPUT_CHANNELS) &&
  226. num_values >= MIN_RCIN_CHANNELS) {
  227. add_input(num_values, values, sbus_failsafe);
  228. }
  229. byte_input.ofs = 0;
  230. }
  231. }
  232. // support byte input
  233. void AP_RCProtocol_SBUS::process_byte(uint8_t b, uint32_t baudrate)
  234. {
  235. if (baudrate != 100000) {
  236. return;
  237. }
  238. _process_byte(AP_HAL::micros(), b);
  239. }