mavlink_types.h 5.82 KB
Newer Older
lm's avatar
lm committed
1 2 3
#ifndef MAVLINK_TYPES_H_
#define MAVLINK_TYPES_H_

4 5 6 7
#include <inttypes.h>

#ifndef MAVLINK_MAX_PAYLOAD_LEN
// it is possible to override this, but be careful!
lm's avatar
lm committed
8
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
9
#endif
lm's avatar
lm committed
10 11

#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
lm's avatar
lm committed
12
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
lm's avatar
lm committed
13 14 15 16 17
#define MAVLINK_NUM_CHECKSUM_BYTES 2
#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)

#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length

18 19 20 21 22
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
#define MAVLINK_EXTENDED_HEADER_LEN 14
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)

lm's avatar
lm committed
23 24 25 26 27
typedef struct param_union {
	union {
		float param_float;
		int32_t param_int32;
		uint32_t param_uint32;
28 29
		uint8_t param_uint8;
		uint8_t bytes[4];
lm's avatar
lm committed
30 31 32 33 34
	};
	uint8_t type;
} mavlink_param_union_t;

typedef struct __mavlink_system {
lm's avatar
lm committed
35 36 37 38 39
    uint8_t sysid;   ///< Used by the MAVLink message_xx_send() convenience function
    uint8_t compid;  ///< Used by the MAVLink message_xx_send() convenience function
    uint8_t type;    ///< Unused, can be used by user to store the system's type
    uint8_t state;   ///< Unused, can be used by user to store the system's state
    uint8_t mode;    ///< Unused, can be used by user to store the system's mode
lm's avatar
lm committed
40
    uint8_t nav_mode;    ///< Unused, can be used by user to store the system's navigation mode
lm's avatar
lm committed
41 42
} mavlink_system_t;

lm's avatar
lm committed
43
typedef struct __mavlink_message {
LM's avatar
LM committed
44 45 46 47 48 49 50 51
	uint16_t checksum; /// sent at end of packet
	uint8_t magic;   ///< protocol magic marker
	uint8_t len;     ///< Length of payload
	uint8_t seq;     ///< Sequence of packet
	uint8_t sysid;   ///< ID of message sender system/aircraft
	uint8_t compid;  ///< ID of the message sender component
	uint8_t msgid;   ///< ID of message in payload
	uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
lm's avatar
lm committed
52 53
} mavlink_message_t;

54

55 56 57 58 59 60 61
typedef struct __mavlink_extended_message {
       mavlink_message_t base_msg;
       int32_t extended_payload_len;   ///< Length of extended payload if any
       uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t;


lm's avatar
lm committed
62 63 64 65 66 67 68 69 70 71 72 73 74
typedef enum {
	MAVLINK_TYPE_CHAR     = 0,
	MAVLINK_TYPE_UINT8_T  = 1,
	MAVLINK_TYPE_INT8_T   = 2,
	MAVLINK_TYPE_UINT16_T = 3,
	MAVLINK_TYPE_INT16_T  = 4,
	MAVLINK_TYPE_UINT32_T = 5,
	MAVLINK_TYPE_INT32_T  = 6,
	MAVLINK_TYPE_UINT64_T = 7,
	MAVLINK_TYPE_INT64_T  = 8,
	MAVLINK_TYPE_FLOAT    = 9,
	MAVLINK_TYPE_DOUBLE   = 10
} mavlink_message_type_t;
lm's avatar
lm committed
75

lm's avatar
lm committed
76 77 78
#define MAVLINK_MAX_FIELDS 64

typedef struct __mavlink_field_info {
79 80 81 82 83 84
        const char *name;                 // name of this field
        const char *print_format;         // printing format hint, or NULL
        mavlink_message_type_t type;      // type of this field
        unsigned int array_length;        // if non-zero, field is an array
        unsigned int wire_offset;         // offset of each field in the payload
        unsigned int structure_offset;    // offset in a C structure
lm's avatar
lm committed
85 86 87 88 89 90 91
} mavlink_field_info_t;

// note that in this structure the order of fields is the order
// in the XML file, not necessary the wire order
typedef struct __mavlink_message_info {
	const char *name;                                      // name of the message
	unsigned num_fields;                                   // how many fields in this message
lm's avatar
lm committed
92
	mavlink_field_info_t fields[MAVLINK_MAX_FIELDS];       // field information
lm's avatar
lm committed
93 94
} mavlink_message_info_t;

95 96
#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
lm's avatar
lm committed
97 98

// checksum is immediately after the payload bytes
99 100
#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
lm's avatar
lm committed
101 102

typedef enum {
lm's avatar
lm committed
103 104 105
    MAVLINK_COMM_0,
    MAVLINK_COMM_1,
    MAVLINK_COMM_2,
lm's avatar
lm committed
106
    MAVLINK_COMM_3
lm's avatar
lm committed
107 108
} mavlink_channel_t;

lm's avatar
lm committed
109 110 111 112 113 114 115 116 117 118 119 120 121 122
/*
 * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
 * of buffers they will use. If more are used, then the result will be
 * a stack overrun
 */
#ifndef MAVLINK_COMM_NUM_BUFFERS
#if (defined linux) | (defined __linux) | (defined  __MACH__) | (defined _WIN32)
# define MAVLINK_COMM_NUM_BUFFERS 16
#else
# define MAVLINK_COMM_NUM_BUFFERS 4
#endif
#endif

typedef enum {
lm's avatar
lm committed
123 124 125 126 127 128 129 130 131 132 133 134
    MAVLINK_PARSE_STATE_UNINIT=0,
    MAVLINK_PARSE_STATE_IDLE,
    MAVLINK_PARSE_STATE_GOT_STX,
    MAVLINK_PARSE_STATE_GOT_SEQ,
    MAVLINK_PARSE_STATE_GOT_LENGTH,
    MAVLINK_PARSE_STATE_GOT_SYSID,
    MAVLINK_PARSE_STATE_GOT_COMPID,
    MAVLINK_PARSE_STATE_GOT_MSGID,
    MAVLINK_PARSE_STATE_GOT_PAYLOAD,
    MAVLINK_PARSE_STATE_GOT_CRC1
} mavlink_parse_state_t; ///< The state machine for the comm parser

lm's avatar
lm committed
135
typedef struct __mavlink_status {
lm's avatar
lm committed
136 137 138 139 140 141 142 143 144 145 146
    uint8_t msg_received;               ///< Number of received messages
    uint8_t buffer_overrun;             ///< Number of buffer overruns
    uint8_t parse_error;                ///< Number of parse errors
    mavlink_parse_state_t parse_state;  ///< Parsing state machine
    uint8_t packet_idx;                 ///< Index in current packet
    uint8_t current_rx_seq;             ///< Sequence number of last packet received
    uint8_t current_tx_seq;             ///< Sequence number of last packet sent
    uint16_t packet_rx_success_count;   ///< Received packets
    uint16_t packet_rx_drop_count;      ///< Number of packet drops
} mavlink_status_t;

lm's avatar
lm committed
147 148 149
#define MAVLINK_BIG_ENDIAN 0
#define MAVLINK_LITTLE_ENDIAN 1

lm's avatar
lm committed
150
#endif /* MAVLINK_TYPES_H_ */