sbus.cpp 6.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186
  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. #include <stdint.h>
  38. #include "sbus.h"
  39. #define SBUS_FRAME_SIZE 25
  40. #define SBUS_INPUT_CHANNELS 16
  41. #define SBUS_FLAGS_BYTE 23
  42. #define SBUS_FAILSAFE_BIT 3
  43. #define SBUS_FRAMELOST_BIT 2
  44. /* define range mapping here, -+100% -> 1000..2000 */
  45. #define SBUS_RANGE_MIN 200.0f
  46. #define SBUS_RANGE_MAX 1800.0f
  47. #define SBUS_TARGET_MIN 1000.0f
  48. #define SBUS_TARGET_MAX 2000.0f
  49. /* pre-calculate the floating point stuff as far as possible at compile time */
  50. #define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN))
  51. #define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f))
  52. /*
  53. * S.bus decoder matrix.
  54. *
  55. * Each channel value can come from up to 3 input bytes. Each row in the
  56. * matrix describes up to three bytes, and each entry gives:
  57. *
  58. * - byte offset in the data portion of the frame
  59. * - right shift applied to the data byte
  60. * - mask for the data byte
  61. * - left shift applied to the result into the channel value
  62. */
  63. struct sbus_bit_pick {
  64. uint8_t byte;
  65. uint8_t rshift;
  66. uint8_t mask;
  67. uint8_t lshift;
  68. };
  69. static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
  70. /* 0 */ { { 0, 0, 0xff, 0}, { 1, 0, 0x07, 8}, { 0, 0, 0x00, 0} },
  71. /* 1 */ { { 1, 3, 0x1f, 0}, { 2, 0, 0x3f, 5}, { 0, 0, 0x00, 0} },
  72. /* 2 */ { { 2, 6, 0x03, 0}, { 3, 0, 0xff, 2}, { 4, 0, 0x01, 10} },
  73. /* 3 */ { { 4, 1, 0x7f, 0}, { 5, 0, 0x0f, 7}, { 0, 0, 0x00, 0} },
  74. /* 4 */ { { 5, 4, 0x0f, 0}, { 6, 0, 0x7f, 4}, { 0, 0, 0x00, 0} },
  75. /* 5 */ { { 6, 7, 0x01, 0}, { 7, 0, 0xff, 1}, { 8, 0, 0x03, 9} },
  76. /* 6 */ { { 8, 2, 0x3f, 0}, { 9, 0, 0x1f, 6}, { 0, 0, 0x00, 0} },
  77. /* 7 */ { { 9, 5, 0x07, 0}, {10, 0, 0xff, 3}, { 0, 0, 0x00, 0} },
  78. /* 8 */ { {11, 0, 0xff, 0}, {12, 0, 0x07, 8}, { 0, 0, 0x00, 0} },
  79. /* 9 */ { {12, 3, 0x1f, 0}, {13, 0, 0x3f, 5}, { 0, 0, 0x00, 0} },
  80. /* 10 */ { {13, 6, 0x03, 0}, {14, 0, 0xff, 2}, {15, 0, 0x01, 10} },
  81. /* 11 */ { {15, 1, 0x7f, 0}, {16, 0, 0x0f, 7}, { 0, 0, 0x00, 0} },
  82. /* 12 */ { {16, 4, 0x0f, 0}, {17, 0, 0x7f, 4}, { 0, 0, 0x00, 0} },
  83. /* 13 */ { {17, 7, 0x01, 0}, {18, 0, 0xff, 1}, {19, 0, 0x03, 9} },
  84. /* 14 */ { {19, 2, 0x3f, 0}, {20, 0, 0x1f, 6}, { 0, 0, 0x00, 0} },
  85. /* 15 */ { {20, 5, 0x07, 0}, {21, 0, 0xff, 3}, { 0, 0, 0x00, 0} }
  86. };
  87. bool
  88. sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
  89. bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
  90. {
  91. /* check frame boundary markers to avoid out-of-sync cases */
  92. if ((frame[0] != 0x0f)) {
  93. return false;
  94. }
  95. switch (frame[24]) {
  96. case 0x00:
  97. /* this is S.BUS 1 */
  98. break;
  99. case 0x03:
  100. /* S.BUS 2 SLOT0: RX battery and external voltage */
  101. break;
  102. case 0x83:
  103. /* S.BUS 2 SLOT1 */
  104. break;
  105. case 0x43:
  106. case 0xC3:
  107. case 0x23:
  108. case 0xA3:
  109. case 0x63:
  110. case 0xE3:
  111. break;
  112. default:
  113. /* we expect one of the bits above, but there are some we don't know yet */
  114. break;
  115. }
  116. unsigned chancount = (max_values > SBUS_INPUT_CHANNELS) ?
  117. SBUS_INPUT_CHANNELS : max_values;
  118. /* use the decoder matrix to extract channel data */
  119. for (unsigned channel = 0; channel < chancount; channel++) {
  120. unsigned value = 0;
  121. for (unsigned pick = 0; pick < 3; pick++) {
  122. const struct sbus_bit_pick *decode = &sbus_decoder[channel][pick];
  123. if (decode->mask != 0) {
  124. unsigned piece = frame[1 + decode->byte];
  125. piece >>= decode->rshift;
  126. piece &= decode->mask;
  127. piece <<= decode->lshift;
  128. value |= piece;
  129. }
  130. }
  131. /* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */
  132. values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR +.5f) + SBUS_SCALE_OFFSET;
  133. }
  134. /* decode switch channels if data fields are wide enough */
  135. if (max_values > 17 && chancount > 15) {
  136. chancount = 18;
  137. /* channel 17 (index 16) */
  138. values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0)) * 1000 + 998;
  139. /* channel 18 (index 17) */
  140. values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1)) * 1000 + 998;
  141. }
  142. /* note the number of channels decoded */
  143. *num_values = chancount;
  144. /* decode and handle failsafe and frame-lost flags */
  145. if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
  146. /* report that we failed to read anything valid off the receiver */
  147. *sbus_failsafe = true;
  148. *sbus_frame_drop = true;
  149. }
  150. else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
  151. /* set a special warning flag
  152. *
  153. * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
  154. * condition as fail-safe greatly reduces the reliability and range of the radio link,
  155. * e.g. by prematurely issuing return-to-launch!!! */
  156. *sbus_failsafe = false;
  157. *sbus_frame_drop = true;
  158. } else {
  159. *sbus_failsafe = false;
  160. *sbus_frame_drop = false;
  161. }
  162. return true;
  163. }