APM:Libraries
st24.cpp
Go to the documentation of this file.
1 /*
2  st24 decoder, based on PX4Firmware/src/rc/lib/rc/st24.c from PX4Firmware
3  modified for use in AP_HAL_* by Andrew Tridgell
4  */
5 /****************************************************************************
6  *
7  * Copyright (c) 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 /*
39  * @file st24.cpp
40  *
41  * RC protocol implementation for Yuneec ST24 transmitter.
42  *
43  * @author Lorenz Meier <lm@inf.ethz.ch>
44  */
45 
46 #include <stdio.h>
47 #include <stdint.h>
48 #include "st24.h"
49 
50 #define ST24_DATA_LEN_MAX 64
51 #define ST24_STX1 0x55
52 #define ST24_STX2 0x55
53 
58 };
59 
60 #pragma pack(push, 1)
61 typedef struct {
62  uint8_t header1;
63  uint8_t header2;
64  uint8_t length;
65  uint8_t type;
66  uint8_t st24_data[ST24_DATA_LEN_MAX];
67  uint8_t crc8;
69 
75 typedef struct {
76  uint16_t t;
77  uint8_t rssi;
78  uint8_t packet_count;
79  uint8_t channel[18];
81 
86 typedef struct {
87  uint16_t t;
88  uint8_t rssi;
89  uint8_t packet_count;
90  uint8_t channel[36];
92 
126 typedef struct {
127  uint16_t t;
128  int32_t lat;
129  int32_t lon;
130  int32_t alt;
131  int16_t vx, vy, vz;
132  uint8_t nsat;
133  uint8_t voltage;
134  uint8_t current;
135  int16_t roll, pitch, yaw;
136  uint8_t motorStatus;
137  uint8_t imuStatus;
139 } TelemetryData;
140 
141 #pragma pack(pop)
142 
150 };
151 
152 /* define range mapping here, -+100% -> 1000..2000 */
153 #define ST24_RANGE_MIN 0.0f
154 #define ST24_RANGE_MAX 4096.0f
155 
156 #define ST24_TARGET_MIN 1000.0f
157 #define ST24_TARGET_MAX 2000.0f
158 
159 /* pre-calculate the floating point stuff as far as possible at compile time */
160 #define ST24_SCALE_FACTOR ((ST24_TARGET_MAX - ST24_TARGET_MIN) / (ST24_RANGE_MAX - ST24_RANGE_MIN))
161 #define ST24_SCALE_OFFSET (int)(ST24_TARGET_MIN - (ST24_SCALE_FACTOR * ST24_RANGE_MIN + 0.5f))
162 
164 static uint8_t _rxlen;
165 
167 
168 static uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len)
169 {
170  uint8_t i, crc ;
171  crc = 0;
172 
173  while (len--) {
174  for (i = 0x80; i != 0; i >>= 1) {
175  if ((crc & 0x80) != 0) {
176  crc <<= 1;
177  crc ^= 0x07;
178 
179  } else {
180  crc <<= 1;
181  }
182 
183  if ((*ptr & i) != 0) {
184  crc ^= 0x07;
185  }
186  }
187 
188  ptr++;
189  }
190 
191  return (crc);
192 }
193 
194 
195 int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels,
196  uint16_t max_chan_count)
197 {
198 
199  int ret = 1;
200 
201  switch (_decode_state) {
203  if (byte == ST24_STX1) {
205 
206  } else {
207  ret = 3;
208  }
209 
210  break;
211 
213  if (byte == ST24_STX2) {
215 
216  } else {
218  }
219 
220  break;
221 
223 
224  /* ensure no data overflow failure or hack is possible */
225  if ((unsigned)byte <= sizeof(_rxpacket.length) + sizeof(_rxpacket.type) + sizeof(_rxpacket.st24_data)) {
226  _rxpacket.length = byte;
227  _rxlen = 0;
229 
230  } else {
232  }
233 
234  break;
235 
237  _rxpacket.type = byte;
238  _rxlen++;
240  break;
241 
243  _rxpacket.st24_data[_rxlen - 1] = byte;
244  _rxlen++;
245 
246  if (_rxlen == (_rxpacket.length - 1)) {
248  }
249 
250  break;
251 
253  _rxpacket.crc8 = byte;
254  _rxlen++;
255 
256  if (st24_common_crc8((uint8_t *) & (_rxpacket.length), _rxlen) == _rxpacket.crc8) {
257 
258  ret = 0;
259 
260  /* decode the actual packet */
261 
262  switch (_rxpacket.type) {
263 
265  ChannelData12 *d = (ChannelData12 *)_rxpacket.st24_data;
266 
267  *rssi = d->rssi;
268  *rx_count = d->packet_count;
269 
270  /* this can lead to rounding of the strides */
271  *channel_count = (max_chan_count < 12) ? max_chan_count : 12;
272 
273  unsigned stride_count = (*channel_count * 3) / 2;
274  unsigned chan_index = 0;
275 
276  for (unsigned i = 0; i < stride_count; i += 3) {
277  channels[chan_index] = ((uint16_t)d->channel[i] << 4);
278  channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
279  /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
280  channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
281  chan_index++;
282 
283  channels[chan_index] = ((uint16_t)d->channel[i + 2]);
284  channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
285  /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
286  channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
287  chan_index++;
288  }
289  }
290  break;
291 
293  ChannelData24 *d = (ChannelData24 *)&_rxpacket.st24_data;
294 
295  *rssi = d->rssi;
296  *rx_count = d->packet_count;
297 
298  /* this can lead to rounding of the strides */
299  *channel_count = (max_chan_count < 24) ? max_chan_count : 24;
300 
301  unsigned stride_count = (*channel_count * 3) / 2;
302  unsigned chan_index = 0;
303 
304  for (unsigned i = 0; i < stride_count; i += 3) {
305  channels[chan_index] = ((uint16_t)d->channel[i] << 4);
306  channels[chan_index] |= ((uint16_t)(0xF0 & d->channel[i + 1]) >> 4);
307  /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
308  channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
309  chan_index++;
310 
311  channels[chan_index] = ((uint16_t)d->channel[i + 2]);
312  channels[chan_index] |= (((uint16_t)(0x0F & d->channel[i + 1])) << 8);
313  /* convert values to 1000-2000 ppm encoding in a not too sloppy fashion */
314  channels[chan_index] = (uint16_t)(channels[chan_index] * ST24_SCALE_FACTOR + .5f) + ST24_SCALE_OFFSET;
315  chan_index++;
316  }
317  }
318  break;
319 
321 
322  // ReceiverFcPacket* d = (ReceiverFcPacket*)&_rxpacket.st24_data;
323  /* we silently ignore this data for now, as it is unused */
324  ret = 2;
325  }
326  break;
327 
328  default:
329  ret = 2;
330  break;
331  }
332 
333  } else {
334  /* decoding failed */
335  ret = 4;
336  }
337 
339  break;
340  }
341 
342  return ret;
343 }
int16_t yaw
0.01 degree resolution
Definition: st24.cpp:135
uint8_t st24_data[ST24_DATA_LEN_MAX]
Definition: st24.cpp:66
uint8_t length
length includes type, data, and crc = sizeof(type)+sizeof(data[payload_len])+sizeof(crc8) ...
Definition: st24.cpp:64
int32_t lat
lattitude (degrees) +/- 90 deg
Definition: st24.cpp:128
static uint8_t _rxlen
Definition: st24.cpp:164
uint16_t t
packet counter or clock
Definition: st24.cpp:76
int32_t alt
0.01m resolution, altitude (meters)
Definition: st24.cpp:130
uint16_t t
packet counter or clock
Definition: st24.cpp:87
uint8_t nsat
number of satellites
Definition: st24.cpp:132
int16_t vz
velocity 0.01m res, +/-320.00 North-East- Down
Definition: st24.cpp:131
#define ST24_SCALE_OFFSET
Definition: st24.cpp:161
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
static uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len)
Definition: st24.cpp:168
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
static enum ST24_DECODE_STATE _decode_state
Definition: st24.cpp:163
uint8_t imuStatus
inertial measurement unit status
Definition: st24.cpp:137
uint8_t rssi
signal strength
Definition: st24.cpp:77
uint8_t current
0.5A resolution
Definition: st24.cpp:134
#define f(i)
uint8_t byte
Definition: compat.h:8
uint8_t header2
0x55 for a valid packet
Definition: st24.cpp:63
uint8_t channel[36]
channel data, 24 channels (12 bit numbers)
Definition: st24.cpp:90
uint8_t header1
0x55 for a valid packet
Definition: st24.cpp:62
ST24_DECODE_STATE
Definition: st24.cpp:143
uint8_t packet_count
Number of UART packets sent since reception of last RF frame (this tells something about age / rate) ...
Definition: st24.cpp:89
uint8_t pressCompassStatus
baro / compass status
Definition: st24.cpp:138
#define ST24_STX1
Definition: st24.cpp:51
uint8_t crc8
crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data ...
Definition: st24.cpp:67
uint16_t t
packet counter or clock
Definition: st24.cpp:127
static ReceiverFcPacket _rxpacket
Definition: st24.cpp:166
uint8_t channel[18]
channel data, 12 channels (12 bit numbers)
Definition: st24.cpp:79
int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Definition: st24.cpp:195
uint8_t rssi
signal strength
Definition: st24.cpp:88
#define ST24_STX2
Definition: st24.cpp:52
uint8_t packet_count
Number of UART packets sent since reception of last RF frame (this tells something about age / rate) ...
Definition: st24.cpp:78
ST24_PACKET_TYPE
Definition: st24.cpp:54
uint8_t voltage
25.4V voltage = 5 + 255*0.1 = 30.5V, min=5V
Definition: st24.cpp:133
uint8_t motorStatus
1 bit per motor for status 1=good, 0= fail
Definition: st24.cpp:136
int32_t lon
longitude (degrees) +/- 180 deg
Definition: st24.cpp:129
#define ST24_DATA_LEN_MAX
Definition: st24.cpp:50
#define ST24_SCALE_FACTOR
Definition: st24.cpp:160
uint8_t type
from enum ST24_PACKET_TYPE
Definition: st24.cpp:65