aboutsummaryrefslogtreecommitdiff
path: root/src/lib/rc/st24.h
diff options
context:
space:
mode:
Diffstat (limited to 'src/lib/rc/st24.h')
-rw-r--r--src/lib/rc/st24.h46
1 files changed, 28 insertions, 18 deletions
diff --git a/src/lib/rc/st24.h b/src/lib/rc/st24.h
index 3621e8506..24dbf8e51 100644
--- a/src/lib/rc/st24.h
+++ b/src/lib/rc/st24.h
@@ -39,22 +39,30 @@
* @author Lorenz Meier <lm@inf.ethz.ch>
*/
+#pragma once
+
+#include <stdint.h>
+
+__BEGIN_DECLS
+
#define ST24_DATA_LEN_MAX 64
+#define ST24_STX1 0x55
+#define ST24_STX2 0x55
-enum {
+enum ST24_PACKET_TYPE {
ST24_PACKET_TYPE_CHANNELDATA12 = 0,
ST24_PACKET_TYPE_CHANNELDATA24,
ST24_PACKET_TYPE_TRANSMITTERGPSDATA
-} ST24_PACKET_TYPE;
+};
#pragma pack(push, 1)
typedef struct {
- uint8_t header1; ///< 0x55 for a valid packet
- uint8_t header2; ///< 0x55 for a valid packet
+ uint8_t header1; ///< 0x55 for a valid packet
+ uint8_t header2; ///< 0x55 for a valid packet
uint8_t length; ///< length includes type, data, and crc = sizeof(type)+sizeof(data[payload_len])+sizeof(crc8)
- uint8_t type; ///< from enum ST24_PACKET_TYPE
+ uint8_t type; ///< from enum ST24_PACKET_TYPE
uint8_t st24_data[ST24_DATA_LEN_MAX];
- uint8_t crc8; ///< crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data
+ uint8_t crc8; ///< crc8 checksum, calculated by st24_common_crc8 and including fields length, type and st24_data
} ReceiverFcPacket;
/**
@@ -63,8 +71,8 @@ typedef struct {
* This is incoming from the ST24
*/
typedef struct {
- uint16_t t; ///< packet counter or clock
- uint8_t rssi ///< signal strength
+ uint16_t t; ///< packet counter or clock
+ uint8_t rssi; ///< signal strength
uint8_t packet_count; ///< Number of UART packets sent since reception of last RF frame (this tells something about age / rate)
uint8_t channel[18]; ///< channel data, 12 channels (12 bit numbers)
} ChannelData12;
@@ -74,8 +82,8 @@ typedef struct {
*
*/
typedef struct {
- uint16_t t; ///< packet counter or clock
- uint8_t rssi ///< signal strength
+ uint16_t t; ///< packet counter or clock
+ uint8_t rssi; ///< signal strength
uint8_t packet_count; ///< Number of UART packets sent since reception of last RF frame (this tells something about age / rate)
uint8_t channel[36]; ///< channel data, 24 channels (12 bit numbers)
} ChannelData24;
@@ -114,17 +122,17 @@ typedef struct {
*
*/
typedef struct {
- uint16_t t; ///< packet counter or clock
- int32_t lat; ///< lattitude (degrees) +/- 90 deg
- int32_t lon; ///< longitude (degrees) +/- 180 deg
- int32_t alt; ///< 0.01m resolution, altitude (meters)
+ uint16_t t; ///< packet counter or clock
+ int32_t lat; ///< lattitude (degrees) +/- 90 deg
+ int32_t lon; ///< longitude (degrees) +/- 180 deg
+ int32_t alt; ///< 0.01m resolution, altitude (meters)
int16_t vx, vy, vz; ///< velocity 0.01m res, +/-320.00 North-East- Down
- uint8_t nsat; ///<number of satellites
- uint8_t voltage; ///< 25.4V voltage = 5 + 255*0.1 = 30.5V, min=5V
- uint8_t current; ///< 0.5A resolution
+ uint8_t nsat; ///<number of satellites
+ uint8_t voltage; ///< 25.4V voltage = 5 + 255*0.1 = 30.5V, min=5V
+ uint8_t current; ///< 0.5A resolution
int16_t roll, pitch, yaw; ///< 0.01 degree resolution
uint8_t motorStatus; ///< 1 bit per motor for status 1=good, 0= fail
- uint8_t imuStatus; ///< inertial measurement unit status
+ uint8_t imuStatus; ///< inertial measurement unit status
uint8_t pressCompassStatus; ///< baro / compass status
} TelemetryData;
@@ -150,3 +158,5 @@ uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len);
* @return 0 for success (a decoded packet), 1 for no packet yet (accumulating), 3 for out of sync, 4 for checksum error
*/
__EXPORT uint8_t st24_decode(uint8_t byte, uint8_t *rssi, uint8_t* rx_count, uint16_t *channels, uint16_t max_chan_count);
+
+__END_DECLS