APM:Libraries
AP_RCProtocol_SBUS.cpp
Go to the documentation of this file.
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 
54 #include "AP_RCProtocol_SBUS.h"
55 
56 #define SBUS_FRAME_SIZE 25
57 #define SBUS_INPUT_CHANNELS 16
58 #define SBUS_FLAGS_BYTE 23
59 #define SBUS_FAILSAFE_BIT 3
60 #define SBUS_FRAMELOST_BIT 2
61 
62 /* define range mapping here, -+100% -> 1000..2000 */
63 #define SBUS_RANGE_MIN 200.0f
64 #define SBUS_RANGE_MAX 1800.0f
65 
66 #define SBUS_TARGET_MIN 1000.0f
67 #define SBUS_TARGET_MAX 2000.0f
68 
69 /* pre-calculate the floating point stuff as far as possible at compile time */
70 #define SBUS_SCALE_FACTOR ((SBUS_TARGET_MAX - SBUS_TARGET_MIN) / (SBUS_RANGE_MAX - SBUS_RANGE_MIN))
71 #define SBUS_SCALE_OFFSET (int)(SBUS_TARGET_MIN - (SBUS_SCALE_FACTOR * SBUS_RANGE_MIN + 0.5f))
72 
73 /*
74  * S.bus decoder matrix.
75  *
76  * Each channel value can come from up to 3 input bytes. Each row in the
77  * matrix describes up to three bytes, and each entry gives:
78  *
79  * - byte offset in the data portion of the frame
80  * - right shift applied to the data byte
81  * - mask for the data byte
82  * - left shift applied to the result into the channel value
83  */
84 struct sbus_bit_pick {
85  uint8_t byte;
86  uint8_t rshift;
87  uint8_t mask;
88  uint8_t lshift;
89 };
90 static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3] = {
91  /* 0 */ { { 0, 0, 0xff, 0}, { 1, 0, 0x07, 8}, { 0, 0, 0x00, 0} },
92  /* 1 */ { { 1, 3, 0x1f, 0}, { 2, 0, 0x3f, 5}, { 0, 0, 0x00, 0} },
93  /* 2 */ { { 2, 6, 0x03, 0}, { 3, 0, 0xff, 2}, { 4, 0, 0x01, 10} },
94  /* 3 */ { { 4, 1, 0x7f, 0}, { 5, 0, 0x0f, 7}, { 0, 0, 0x00, 0} },
95  /* 4 */ { { 5, 4, 0x0f, 0}, { 6, 0, 0x7f, 4}, { 0, 0, 0x00, 0} },
96  /* 5 */ { { 6, 7, 0x01, 0}, { 7, 0, 0xff, 1}, { 8, 0, 0x03, 9} },
97  /* 6 */ { { 8, 2, 0x3f, 0}, { 9, 0, 0x1f, 6}, { 0, 0, 0x00, 0} },
98  /* 7 */ { { 9, 5, 0x07, 0}, {10, 0, 0xff, 3}, { 0, 0, 0x00, 0} },
99  /* 8 */ { {11, 0, 0xff, 0}, {12, 0, 0x07, 8}, { 0, 0, 0x00, 0} },
100  /* 9 */ { {12, 3, 0x1f, 0}, {13, 0, 0x3f, 5}, { 0, 0, 0x00, 0} },
101  /* 10 */ { {13, 6, 0x03, 0}, {14, 0, 0xff, 2}, {15, 0, 0x01, 10} },
102  /* 11 */ { {15, 1, 0x7f, 0}, {16, 0, 0x0f, 7}, { 0, 0, 0x00, 0} },
103  /* 12 */ { {16, 4, 0x0f, 0}, {17, 0, 0x7f, 4}, { 0, 0, 0x00, 0} },
104  /* 13 */ { {17, 7, 0x01, 0}, {18, 0, 0xff, 1}, {19, 0, 0x03, 9} },
105  /* 14 */ { {19, 2, 0x3f, 0}, {20, 0, 0x1f, 6}, { 0, 0, 0x00, 0} },
106  /* 15 */ { {20, 5, 0x07, 0}, {21, 0, 0xff, 3}, { 0, 0, 0x00, 0} }
107 };
108 
109 
110 bool AP_RCProtocol_SBUS::sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values,
111  bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
112 {
113  /* check frame boundary markers to avoid out-of-sync cases */
114  if ((frame[0] != 0x0f)) {
115  return false;
116  }
117 
118  switch (frame[24]) {
119  case 0x00:
120  /* this is S.BUS 1 */
121  break;
122  case 0x03:
123  /* S.BUS 2 SLOT0: RX battery and external voltage */
124  break;
125  case 0x83:
126  /* S.BUS 2 SLOT1 */
127  break;
128  case 0x43:
129  case 0xC3:
130  case 0x23:
131  case 0xA3:
132  case 0x63:
133  case 0xE3:
134  break;
135  default:
136  /* we expect one of the bits above, but there are some we don't know yet */
137  break;
138  }
139 
140  unsigned chancount = (max_values > SBUS_INPUT_CHANNELS) ?
141  SBUS_INPUT_CHANNELS : max_values;
142 
143  /* use the decoder matrix to extract channel data */
144  for (unsigned channel = 0; channel < chancount; channel++) {
145  unsigned value = 0;
146 
147  for (unsigned pick = 0; pick < 3; pick++) {
148  const struct sbus_bit_pick *decode = &sbus_decoder[channel][pick];
149 
150  if (decode->mask != 0) {
151  unsigned piece = frame[1 + decode->byte];
152  piece >>= decode->rshift;
153  piece &= decode->mask;
154  piece <<= decode->lshift;
155 
156  value |= piece;
157  }
158  }
159 
160 
161  /* convert 0-2048 values to 1000-2000 ppm encoding in a not too sloppy fashion */
162  values[channel] = (uint16_t)(value * SBUS_SCALE_FACTOR +.5f) + SBUS_SCALE_OFFSET;
163  }
164 
165  /* decode switch channels if data fields are wide enough */
166  if (max_values > 17 && chancount > 15) {
167  chancount = 18;
168 
169  /* channel 17 (index 16) */
170  values[16] = (frame[SBUS_FLAGS_BYTE] & (1 << 0)) * 1000 + 998;
171  /* channel 18 (index 17) */
172  values[17] = (frame[SBUS_FLAGS_BYTE] & (1 << 1)) * 1000 + 998;
173  }
174 
175  /* note the number of channels decoded */
176  *num_values = chancount;
177 
178  /* decode and handle failsafe and frame-lost flags */
179  if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FAILSAFE_BIT)) { /* failsafe */
180  /* report that we failed to read anything valid off the receiver */
181  *sbus_failsafe = true;
182  *sbus_frame_drop = true;
183  }
184  else if (frame[SBUS_FLAGS_BYTE] & (1 << SBUS_FRAMELOST_BIT)) { /* a frame was lost */
185  /* set a special warning flag
186  *
187  * Attention! This flag indicates a skipped frame only, not a total link loss! Handling this
188  * condition as fail-safe greatly reduces the reliability and range of the radio link,
189  * e.g. by prematurely issuing return-to-launch!!! */
190 
191  *sbus_failsafe = false;
192  *sbus_frame_drop = true;
193  } else {
194  *sbus_failsafe = false;
195  *sbus_frame_drop = false;
196  }
197 
198  return true;
199 }
200 
201 
202 /*
203  process a SBUS input pulse of the given width
204  */
205 void AP_RCProtocol_SBUS::process_pulse(uint32_t width_s0, uint32_t width_s1)
206 {
207  // convert to bit widths, allowing for up to 1usec error, assuming 100000 bps
208  uint16_t bits_s0 = (width_s0+1) / 10;
209  uint16_t bits_s1 = (width_s1+1) / 10;
210  uint16_t nlow;
211 
212  uint8_t byte_ofs = sbus_state.bit_ofs/12;
213  uint8_t bit_ofs = sbus_state.bit_ofs%12;
214 
215  if (bits_s0 == 0 || bits_s1 == 0) {
216  // invalid data
217  goto reset;
218  }
219 
220  if (bits_s0+bit_ofs > 10) {
221  // invalid data as last two bits must be stop bits
222  goto reset;
223  }
224 
225  // pull in the high bits
226  sbus_state.bytes[byte_ofs] |= ((1U<<bits_s0)-1) << bit_ofs;
227  sbus_state.bit_ofs += bits_s0;
228  bit_ofs += bits_s0;
229 
230  // pull in the low bits
231  nlow = bits_s1;
232  if (nlow + bit_ofs > 12) {
233  nlow = 12 - bit_ofs;
234  }
235  bits_s1 -= nlow;
236  sbus_state.bit_ofs += nlow;
237 
238  if (sbus_state.bit_ofs == 25*12 && bits_s1 > 12) {
239  // we have a full frame
240  uint8_t bytes[25];
241  uint8_t i;
242  for (i=0; i<25; i++) {
243  // get inverted data
244  uint16_t v = ~sbus_state.bytes[i];
245  // check start bit
246  if ((v & 1) != 0) {
247  goto reset;
248  }
249  // check stop bits
250  if ((v & 0xC00) != 0xC00) {
251  goto reset;
252  }
253  // check parity
254  uint8_t parity = 0, j;
255  for (j=1; j<=8; j++) {
256  parity ^= (v & (1U<<j))?1:0;
257  }
258  if (parity != (v&0x200)>>9) {
259  goto reset;
260  }
261  bytes[i] = ((v>>1) & 0xFF);
262  }
263  uint16_t values[MAX_RCIN_CHANNELS];
264  uint16_t num_values=0;
265  bool sbus_failsafe=false, sbus_frame_drop=false;
266  if (sbus_decode(bytes, values, &num_values,
267  &sbus_failsafe, &sbus_frame_drop,
269  num_values >= MIN_RCIN_CHANNELS) {
270  add_input(num_values, values, sbus_failsafe);
271  }
272  goto reset;
273  } else if (bits_s1 > 12) {
274  // break
275  goto reset;
276  }
277  return;
278 reset:
279  memset(&sbus_state, 0, sizeof(sbus_state));
280 }
uint8_t byte
Definition: sbus.cpp:71
#define SBUS_SCALE_OFFSET
void reset()
#define MAX_RCIN_CHANNELS
Definition: AP_RCProtocol.h:21
uint8_t rshift
Definition: sbus.cpp:72
#define SBUS_INPUT_CHANNELS
bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
Definition: sbus.cpp:97
uint8_t mask
Definition: sbus.cpp:73
#define f(i)
#define MIN_RCIN_CHANNELS
Definition: AP_RCProtocol.h:22
float v
Definition: Printf.cpp:15
bool sbus_decode(const uint8_t frame[25], uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_values)
#define SBUS_FAILSAFE_BIT
static const struct sbus_bit_pick sbus_decoder[SBUS_INPUT_CHANNELS][3]
float value
#define SBUS_FRAMELOST_BIT
#define SBUS_SCALE_FACTOR
void process_pulse(uint32_t width_s0, uint32_t width_s1) override
uint8_t lshift
Definition: sbus.cpp:74
#define SBUS_FLAGS_BYTE