PX4 Firmware
PX4 Autopilot Software http://px4.io
st24.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2014 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file st24.h
36  *
37  * RC protocol definition for Yuneec ST24 transmitter
38  *
39  * @author Lorenz Meier <lm@inf.ethz.ch>
40  */
41 
42 #pragma once
43 
44 #include <stdint.h>
45 
47 
48 #define ST24_DATA_LEN_MAX 64
49 #define ST24_STX1 0x55
50 #define ST24_STX2 0x55
51 
56 };
57 
65 };
66 
67 #pragma pack(push, 1)
68 typedef struct {
69  uint8_t header1; ///< 0x55 for a valid packet
70  uint8_t header2; ///< 0x55 for a valid packet
71  uint8_t length; ///< length includes type, data, and crc = sizeof(type)+sizeof(data[payload_len])+sizeof(crc8)
72  uint8_t type; ///< from enum ST24_PACKET_TYPE
73  uint8_t st24_data[ST24_DATA_LEN_MAX];
74  uint8_t crc8; ///< crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data
76 
77 /**
78  * RC Channel data (12 channels).
79  *
80  * This is incoming from the ST24
81  */
82 typedef struct {
83  uint16_t t; ///< packet counter or clock
84  uint8_t rssi; ///< signal strength
85  uint8_t lost_count; ///< Number of UART packets sent since reception of last RF frame (100 frame means RC timeout of 1s)
86  uint8_t channel[18]; ///< channel data, 12 channels (12 bit numbers)
88 
89 /**
90  * RC Channel data (12 channels).
91  *
92  */
93 typedef struct {
94  uint16_t t; ///< packet counter or clock
95  uint8_t rssi; ///< signal strength
96  uint8_t lost_count; ///< Number of UART packets sent since reception of last RF frame (100 frame means RC timeout of 1s)
97  uint8_t channel[36]; ///< channel data, 24 channels (12 bit numbers)
99 
100 /**
101  * Telemetry packet
102  *
103  * This is outgoing to the ST24
104  *
105  * imuStatus:
106  * 8 bit total
107  * bits 0-2 for status
108  * - value 0 is FAILED
109  * - value 1 is INITIALIZING
110  * - value 2 is RUNNING
111  * - values 3 through 7 are reserved
112  * bits 3-7 are status for sensors (0 or 1)
113  * - mpu6050
114  * - accelerometer
115  * - primary gyro x
116  * - primary gyro y
117  * - primary gyro z
118  *
119  * pressCompassStatus
120  * 8 bit total
121  * bits 0-3 for compass status
122  * - value 0 is FAILED
123  * - value 1 is INITIALIZING
124  * - value 2 is RUNNING
125  * - value 3 - 15 are reserved
126  * bits 4-7 for pressure status
127  * - value 0 is FAILED
128  * - value 1 is INITIALIZING
129  * - value 2 is RUNNING
130  * - value 3 - 15 are reserved
131  *
132  */
133 typedef struct {
134  uint16_t t; ///< packet counter or clock
135  int32_t lat; ///< lattitude (degrees) +/- 90 deg
136  int32_t lon; ///< longitude (degrees) +/- 180 deg
137  int32_t alt; ///< 0.01m resolution, altitude (meters)
138  int16_t vx, vy, vz; ///< velocity 0.01m res, +/-320.00 North-East- Down
139  uint8_t nsat; ///<number of satellites
140  uint8_t voltage; ///< 25.4V voltage = 5 + 255*0.1 = 30.5V, min=5V
141  uint8_t current; ///< 0.5A resolution
142  int16_t roll, pitch, yaw; ///< 0.01 degree resolution
143  uint8_t motorStatus; ///< 1 bit per motor for status 1=good, 0= fail
144  uint8_t imuStatus; ///< inertial measurement unit status
145  uint8_t pressCompassStatus; ///< baro / compass status
146 } TelemetryData;
147 
148 #pragma pack(pop)
149 
150 /**
151  * CRC8 implementation for ST24 protocol
152  *
153  * @param prt Pointer to the data to CRC
154  * @param len number of bytes to accumulate in the checksum
155  * @return the checksum of these bytes over len
156  */
157 uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len);
158 
159 /**
160  * Decoder for ST24 protocol
161  *
162  * @param byte current char to read
163  * @param rssi pointer to a byte where the RSSI value is written back to
164  * @param lost_count pointer to a byte where the receive count of packets since last wireless frame is written back to ( > 0 if RC is lost)
165  * @param channels pointer to a datastructure of size max_chan_count where channel values (12 bit) are written back to
166  * @param max_chan_count maximum channels to decode - if more channels are decoded, the last n are skipped and success (0) is returned
167  * @return 0 for success (a decoded packet), 1 for no packet yet (accumulating), 2 for unknown packet, 3 for out of sync, 4 for checksum error
168  */
169 __EXPORT int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *lost_count, uint16_t *channel_count,
170  uint16_t *channels, uint16_t max_chan_count);
171 
uint8_t motorStatus
1 bit per motor for status 1=good, 0= fail
Definition: st24.h:143
uint16_t t
packet counter or clock
Definition: st24.h:134
uint8_t pressCompassStatus
baro / compass status
Definition: st24.h:145
uint8_t lost_count
Number of UART packets sent since reception of last RF frame (100 frame means RC timeout of 1s) ...
Definition: st24.h:96
#define __END_DECLS
Definition: visibility.h:59
uint16_t t
packet counter or clock
Definition: st24.h:94
uint8_t byte
Definition: sbus.cpp:559
ST24_PACKET_TYPE
Definition: st24.h:52
uint8_t type
from enum ST24_PACKET_TYPE
Definition: st24.h:72
Definition: I2C.hpp:51
uint8_t header2
0x55 for a valid packet
Definition: st24.h:70
uint8_t nsat
number of satellites
Definition: st24.h:139
int32_t lon
longitude (degrees) +/- 180 deg
Definition: st24.h:136
uint16_t t
packet counter or clock
Definition: st24.h:83
uint8_t rssi
signal strength
Definition: st24.h:84
ST24_DECODE_STATE
Definition: st24.h:58
#define ST24_DATA_LEN_MAX
Definition: st24.h:48
RC Channel data (12 channels).
Definition: st24.h:82
uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len)
CRC8 implementation for ST24 protocol.
Definition: st24.cpp:71
int16_t vz
velocity 0.01m res, +/-320.00 North-East- Down
Definition: st24.h:138
uint8_t voltage
25.4V voltage = 5 + 255*0.1 = 30.5V, min=5V
Definition: st24.h:140
uint8_t imuStatus
inertial measurement unit status
Definition: st24.h:144
uint8_t crc8
crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data ...
Definition: st24.h:74
#define __BEGIN_DECLS
Definition: visibility.h:58
RC Channel data (12 channels).
Definition: st24.h:93
uint8_t rssi
signal strength
Definition: st24.h:95
int16_t yaw
0.01 degree resolution
Definition: st24.h:142
int32_t alt
0.01m resolution, altitude (meters)
Definition: st24.h:137
int32_t lat
lattitude (degrees) +/- 90 deg
Definition: st24.h:135
__EXPORT int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *lost_count, uint16_t *channel_count, uint16_t *channels, uint16_t max_chan_count)
Decoder for ST24 protocol.
Definition: st24.cpp:98
uint8_t current
0.5A resolution
Definition: st24.h:141
uint8_t header1
0x55 for a valid packet
Definition: st24.h:69
uint8_t length
length includes type, data, and crc = sizeof(type)+sizeof(data[payload_len])+sizeof(crc8) ...
Definition: st24.h:71
Telemetry packet.
Definition: st24.h:133
uint8_t lost_count
Number of UART packets sent since reception of last RF frame (100 frame means RC timeout of 1s) ...
Definition: st24.h:85