APM:Libraries
sumd.cpp
Go to the documentation of this file.
1 /*
2  SUMD decoder, based on PX4Firmware/src/rc/lib/rc/sumd.c from PX4Firmware
3  modified for use in AP_HAL_* by Andrew Tridgell
4  */
5 /****************************************************************************
6  *
7  * Copyright (c) 2015 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 /*
39  * @file sumd.h
40  *
41  * RC protocol definition for Graupner HoTT transmitter (SUMD/SUMH Protocol)
42  *
43  * @author Marco Bauer <marco@wtns.de>
44  */
45 
46 #include <stdio.h>
47 #include <stdint.h>
48 #include "sumd.h"
49 
50 #define SUMD_MAX_CHANNELS 32
51 #define SUMD_HEADER_LENGTH 3
52 #define SUMD_HEADER_ID 0xA8
53 #define SUMD_ID_SUMH 0x00
54 #define SUMD_ID_SUMD 0x01
55 #define SUMD_ID_FAILSAFE 0x81
56 
57 
58 #pragma pack(push, 1)
59 typedef struct {
60  uint8_t header;
61  uint8_t status;
62  uint8_t length;
63  uint8_t sumd_data[SUMD_MAX_CHANNELS * 2];
64  uint8_t crc16_high;
65  uint8_t crc16_low;
66  uint8_t telemetry;
67  uint8_t crc8;
69 #pragma pack(pop)
70 
71 
81 };
82 
83 /*
84 const char *decode_states[] = {"UNSYNCED",
85  "GOT_HEADER",
86  "GOT_STATE",
87  "GOT_LEN",
88  "GOT_DATA",
89  "GOT_CRC",
90  "GOT_CRC16_BYTE_1",
91  "GOT_CRC16_BYTE_2"
92  };
93 */
94 
95 static uint8_t _crc8 = 0x00;
96 static uint16_t _crc16 = 0x0000;
97 static bool _sumd = true;
98 static bool _crcOK = false;
99 static bool _debug = false;
100 
101 
102 /* define range mapping here, -+100% -> 1000..2000 */
103 #define SUMD_RANGE_MIN 0.0f
104 #define SUMD_RANGE_MAX 4096.0f
105 
106 #define SUMD_TARGET_MIN 1000.0f
107 #define SUMD_TARGET_MAX 2000.0f
108 
109 /* pre-calculate the floating point stuff as far as possible at compile time */
110 #define SUMD_SCALE_FACTOR ((SUMD_TARGET_MAX - SUMD_TARGET_MIN) / (SUMD_RANGE_MAX - SUMD_RANGE_MIN))
111 #define SUMD_SCALE_OFFSET (int)(SUMD_TARGET_MIN - (SUMD_SCALE_FACTOR * SUMD_RANGE_MIN + 0.5f))
112 
114 static uint8_t _rxlen;
115 
117 
118 
119 static uint16_t sumd_crc16(uint16_t crc, uint8_t value)
120 {
121  int i;
122  crc ^= (uint16_t)value << 8;
123 
124  for (i = 0; i < 8; i++) {
125  crc = (crc & 0x8000) ? (crc << 1) ^ 0x1021 : (crc << 1);
126  }
127 
128  return crc;
129 }
130 
131 static uint8_t sumd_crc8(uint8_t crc, uint8_t value)
132 {
133  crc += value;
134  return crc;
135 }
136 
137 int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels,
138  uint16_t max_chan_count)
139 {
140 
141  int ret = 1;
142 
143  switch (_decode_state) {
145  if (_debug) {
146  printf(" SUMD_DECODE_STATE_UNSYNCED \n") ;
147  }
148 
149  if (byte == SUMD_HEADER_ID) {
150  _rxpacket.header = byte;
151  _sumd = true;
152  _rxlen = 0;
153  _crc16 = 0x0000;
154  _crc8 = 0x00;
155  _crcOK = false;
156  _crc16 = sumd_crc16(_crc16, byte);
157  _crc8 = sumd_crc8(_crc8, byte);
159 
160  if (_debug) {
161  printf(" SUMD_DECODE_STATE_GOT_HEADER: %x \n", byte) ;
162  }
163 
164  } else {
165  ret = 3;
166  }
167 
168  break;
169 
171  if (byte == SUMD_ID_SUMD || byte == SUMD_ID_SUMH) {
172  _rxpacket.status = byte;
173 
174  if (byte == SUMD_ID_SUMH) {
175  _sumd = false;
176  }
177 
178  if (_sumd) {
179  _crc16 = sumd_crc16(_crc16, byte);
180 
181  } else {
182  _crc8 = sumd_crc8(_crc8, byte);
183  }
184 
186 
187  if (_debug) {
188  printf(" SUMD_DECODE_STATE_GOT_STATE: %x \n", byte) ;
189  }
190 
191  } else {
193  }
194 
195  break;
196 
198  if (byte >= 2 && byte <= SUMD_MAX_CHANNELS) {
199  _rxpacket.length = byte;
200 
201  if (_sumd) {
202  _crc16 = sumd_crc16(_crc16, byte);
203 
204  } else {
205  _crc8 = sumd_crc8(_crc8, byte);
206  }
207 
208  _rxlen++;
210 
211  if (_debug) {
212  printf(" SUMD_DECODE_STATE_GOT_LEN: %x (%d) \n", byte, byte) ;
213  }
214 
215  } else {
217  }
218 
219  break;
220 
222  _rxpacket.sumd_data[_rxlen] = byte;
223 
224  if (_sumd) {
225  _crc16 = sumd_crc16(_crc16, byte);
226 
227  } else {
228  _crc8 = sumd_crc8(_crc8, byte);
229  }
230 
231  _rxlen++;
232 
233  if (_rxlen <= ((_rxpacket.length * 2))) {
234  if (_debug) {
235  printf(" SUMD_DECODE_STATE_GOT_DATA[%d]: %x\n", _rxlen - 2, byte) ;
236  }
237 
238  } else {
240 
241  if (_debug) {
242  printf(" SUMD_DECODE_STATE_GOT_DATA -- finish --\n") ;
243  }
244 
245  }
246 
247  break;
248 
250  _rxpacket.crc16_high = byte;
251 
252  if (_debug) {
253  printf(" SUMD_DECODE_STATE_GOT_CRC16[1]: %x [%x]\n", byte, ((_crc16 >> 8) & 0xff)) ;
254  }
255 
256  if (_sumd) {
258 
259  } else {
261  }
262 
263  break;
264 
266  _rxpacket.crc16_low = byte;
267 
268  if (_debug) {
269  printf(" SUMD_DECODE_STATE_GOT_CRC16[2]: %x [%x]\n", byte, (_crc16 & 0xff)) ;
270  }
271 
273 
274  break;
275 
277  _rxpacket.telemetry = byte;
278 
279  if (_debug) {
280  printf(" SUMD_DECODE_STATE_GOT_SUMH_TELEMETRY: %x\n", byte) ;
281  }
282 
284 
285  break;
286 
288  if (_sumd) {
289  _rxpacket.crc16_low = byte;
290 
291  if (_debug) {
292  printf(" SUMD_DECODE_STATE_GOT_CRC[2]: %x [%x]\n\n", byte, (_crc16 & 0xff)) ;
293  }
294 
295  if (_crc16 == (uint16_t)(_rxpacket.crc16_high << 8) + _rxpacket.crc16_low) {
296  _crcOK = true;
297  }
298 
299  } else {
300  _rxpacket.crc8 = byte;
301 
302  if (_debug) {
303  printf(" SUMD_DECODE_STATE_GOT_CRC8_SUMH: %x [%x]\n\n", byte, _crc8) ;
304  }
305 
306  if (_crc8 == _rxpacket.crc8) {
307  _crcOK = true;
308  }
309  }
310 
311  if (_crcOK) {
312  if (_debug) {
313  printf(" CRC - OK \n") ;
314  }
315 
316  if (_sumd) {
317  if (_debug) {
318  printf(" Got valid SUMD Packet\n") ;
319  }
320 
321  } else {
322  if (_debug) {
323  printf(" Got valid SUMH Packet\n") ;
324  }
325 
326  }
327 
328  if (_debug) {
329  printf(" RXLEN: %d [Chans: %d] \n\n", _rxlen - 1, (_rxlen - 1) / 2) ;
330  }
331 
332  ret = 0;
333  unsigned i;
334  uint8_t _cnt = *rx_count + 1;
335  *rx_count = _cnt;
336 
337  *rssi = 100;
338 
339  /* received Channels */
340  if ((uint16_t)_rxpacket.length > max_chan_count) {
341  _rxpacket.length = (uint8_t) max_chan_count;
342  }
343 
344  *channel_count = (uint16_t)_rxpacket.length;
345 
346  /* decode the actual packet */
347  /* reorder first 4 channels */
348 
349  /* ch1 = roll -> sumd = ch2 */
350  channels[0] = (uint16_t)((_rxpacket.sumd_data[1 * 2 + 1] << 8) | _rxpacket.sumd_data[1 * 2 + 2]) >> 3;
351  /* ch2 = pitch -> sumd = ch2 */
352  channels[1] = (uint16_t)((_rxpacket.sumd_data[2 * 2 + 1] << 8) | _rxpacket.sumd_data[2 * 2 + 2]) >> 3;
353  /* ch3 = throttle -> sumd = ch2 */
354  channels[2] = (uint16_t)((_rxpacket.sumd_data[0 * 2 + 1] << 8) | _rxpacket.sumd_data[0 * 2 + 2]) >> 3;
355  /* ch4 = yaw -> sumd = ch2 */
356  channels[3] = (uint16_t)((_rxpacket.sumd_data[3 * 2 + 1] << 8) | _rxpacket.sumd_data[3 * 2 + 2]) >> 3;
357 
358  /* we start at channel 5(index 4) */
359  unsigned chan_index = 4;
360 
361  for (i = 4; i < _rxpacket.length; i++) {
362  if (_debug) {
363  printf("ch[%d] : %x %x [ %x %d ]\n", i + 1, _rxpacket.sumd_data[i * 2 + 1], _rxpacket.sumd_data[i * 2 + 2],
364  ((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3,
365  ((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3);
366  }
367 
368  channels[chan_index] = (uint16_t)((_rxpacket.sumd_data[i * 2 + 1] << 8) | _rxpacket.sumd_data[i * 2 + 2]) >> 3;
369  /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
370  //channels[chan_index] = (uint16_t)(channels[chan_index] * SUMD_SCALE_FACTOR + .5f) + SUMD_SCALE_OFFSET;
371 
372  chan_index++;
373  }
374 
375  } else {
376  /* decoding failed */
377  ret = 4;
378 
379  if (_debug) {
380  printf(" CRC - fail \n") ;
381  }
382 
383  }
384 
386  break;
387  }
388 
389  return ret;
390 }
int printf(const char *fmt,...)
Definition: stdio.c:113
static bool _sumd
Definition: sumd.cpp:97
uint8_t header
0xA8 for a valid packet
Definition: sumd.cpp:60
uint8_t status
0x01 valid and live SUMD data frame / 0x00 = SUMH / 0x81 = Failsafe
Definition: sumd.cpp:61
uint8_t telemetry
Telemetry request.
Definition: sumd.cpp:66
static bool _debug
Definition: sumd.cpp:99
int sumd_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Definition: sumd.cpp:137
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
static uint8_t _rxlen
Definition: sumd.cpp:114
uint8_t sumd_data[SUMD_MAX_CHANNELS *2]
ChannelData (High Byte/ Low Byte)
Definition: sumd.cpp:63
#define SUMD_ID_SUMD
Definition: sumd.cpp:54
uint8_t length
Channels.
Definition: sumd.cpp:62
static bool _crcOK
Definition: sumd.cpp:98
static uint16_t _crc16
Definition: sumd.cpp:96
uint8_t crc16_low
Low Byte of 16 Bit CRC.
Definition: sumd.cpp:65
uint8_t byte
Definition: compat.h:8
static enum SUMD_DECODE_STATE _decode_state
Definition: sumd.cpp:113
uint8_t crc8
SUMH CRC8.
Definition: sumd.cpp:67
static ReceiverFcPacketHoTT _rxpacket
Definition: sumd.cpp:116
uint8_t crc16_high
High Byte of 16 Bit CRC.
Definition: sumd.cpp:64
static uint8_t _crc8
Definition: sumd.cpp:95
float value
static uint8_t sumd_crc8(uint8_t crc, uint8_t value)
Definition: sumd.cpp:131
#define SUMD_MAX_CHANNELS
Definition: sumd.cpp:50
static uint16_t sumd_crc16(uint16_t crc, uint8_t value)
Definition: sumd.cpp:119
#define SUMD_ID_SUMH
Definition: sumd.cpp:53
#define SUMD_HEADER_ID
Definition: sumd.cpp:52
SUMD_DECODE_STATE
Definition: sumd.cpp:72