【类 型】:
【原 因】: 【过 程】: 【影 响】:
This commit is contained in:
parent
ceba245d46
commit
805b83f143
@ -5,7 +5,7 @@
|
|||||||
|
|
||||||
#ifndef MAVLINK_MAX_PAYLOAD_LEN
|
#ifndef MAVLINK_MAX_PAYLOAD_LEN
|
||||||
// it is possible to override this, but be careful!
|
// it is possible to override this, but be careful!
|
||||||
#define MAVLINK_MAX_PAYLOAD_LEN 100 ///< Maximum payload length 255
|
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length 255
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#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)
|
#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)
|
||||||
@ -19,17 +19,19 @@
|
|||||||
#define MAVLINK_EXTENDED_HEADER_LEN 14
|
#define MAVLINK_EXTENDED_HEADER_LEN 14
|
||||||
|
|
||||||
#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
|
#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
|
||||||
/* full fledged 32bit++ OS */
|
/* full fledged 32bit++ OS */
|
||||||
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
|
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
|
||||||
#else
|
#else
|
||||||
/* small microcontrollers */
|
/* small microcontrollers */
|
||||||
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
|
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
|
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
|
||||||
|
|
||||||
typedef struct param_union {
|
typedef struct param_union
|
||||||
union {
|
{
|
||||||
|
union
|
||||||
|
{
|
||||||
float param_float;
|
float param_float;
|
||||||
int32_t param_int32;
|
int32_t param_int32;
|
||||||
uint32_t param_uint32;
|
uint32_t param_uint32;
|
||||||
@ -39,7 +41,8 @@ typedef struct param_union {
|
|||||||
uint8_t type;
|
uint8_t type;
|
||||||
} mavlink_param_union_t;
|
} mavlink_param_union_t;
|
||||||
|
|
||||||
typedef struct __mavlink_system {
|
typedef struct __mavlink_system
|
||||||
|
{
|
||||||
uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
|
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 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 type; ///< Unused, can be used by user to store the system's type
|
||||||
@ -48,7 +51,8 @@ typedef struct __mavlink_system {
|
|||||||
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
|
||||||
} mavlink_system_t;
|
} mavlink_system_t;
|
||||||
|
|
||||||
typedef struct __mavlink_message {
|
typedef struct __mavlink_message
|
||||||
|
{
|
||||||
uint16_t checksum; /// sent at end of packet
|
uint16_t checksum; /// sent at end of packet
|
||||||
uint8_t magic; ///< protocol magic marker
|
uint8_t magic; ///< protocol magic marker
|
||||||
uint8_t len; ///< Length of payload
|
uint8_t len; ///< Length of payload
|
||||||
@ -56,18 +60,18 @@ typedef struct __mavlink_message {
|
|||||||
uint8_t sysid; ///< ID of message sender system/aircraft
|
uint8_t sysid; ///< ID of message sender system/aircraft
|
||||||
uint8_t compid; ///< ID of the message sender component
|
uint8_t compid; ///< ID of the message sender component
|
||||||
uint8_t msgid; ///< ID of message in payload
|
uint8_t msgid; ///< ID of message in payload
|
||||||
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
|
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_CHECKSUM_BYTES + 7) / 8];
|
||||||
} mavlink_message_t;
|
} mavlink_message_t;
|
||||||
|
|
||||||
|
typedef struct __mavlink_extended_message
|
||||||
typedef struct __mavlink_extended_message {
|
{
|
||||||
mavlink_message_t base_msg;
|
mavlink_message_t base_msg;
|
||||||
int32_t extended_payload_len; ///< Length of extended payload if any
|
int32_t extended_payload_len; ///< Length of extended payload if any
|
||||||
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
|
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
|
||||||
} mavlink_extended_message_t;
|
} mavlink_extended_message_t;
|
||||||
|
|
||||||
|
typedef enum
|
||||||
typedef enum {
|
{
|
||||||
MAVLINK_TYPE_CHAR = 0,
|
MAVLINK_TYPE_CHAR = 0,
|
||||||
MAVLINK_TYPE_UINT8_T = 1,
|
MAVLINK_TYPE_UINT8_T = 1,
|
||||||
MAVLINK_TYPE_INT8_T = 2,
|
MAVLINK_TYPE_INT8_T = 2,
|
||||||
@ -83,7 +87,8 @@ typedef enum {
|
|||||||
|
|
||||||
#define MAVLINK_MAX_FIELDS 64
|
#define MAVLINK_MAX_FIELDS 64
|
||||||
|
|
||||||
typedef struct __mavlink_field_info {
|
typedef struct __mavlink_field_info
|
||||||
|
{
|
||||||
const char *name; // name of this field
|
const char *name; // name of this field
|
||||||
const char *print_format; // printing format hint, or NULL
|
const char *print_format; // printing format hint, or NULL
|
||||||
mavlink_message_type_t type; // type of this field
|
mavlink_message_type_t type; // type of this field
|
||||||
@ -94,7 +99,8 @@ typedef struct __mavlink_field_info {
|
|||||||
|
|
||||||
// note that in this structure the order of fields is the order
|
// note that in this structure the order of fields is the order
|
||||||
// in the XML file, not necessary the wire order
|
// in the XML file, not necessary the wire order
|
||||||
typedef struct __mavlink_message_info {
|
typedef struct __mavlink_message_info
|
||||||
|
{
|
||||||
const char *name; // name of the message
|
const char *name; // name of the message
|
||||||
unsigned num_fields; // how many fields in this message
|
unsigned num_fields; // how many fields in this message
|
||||||
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
|
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
|
||||||
@ -105,9 +111,10 @@ typedef struct __mavlink_message_info {
|
|||||||
|
|
||||||
// checksum is immediately after the payload bytes
|
// checksum is immediately after the payload bytes
|
||||||
#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
|
#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))
|
#define mavlink_ck_b(msg) *(((msg)->len + (uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
|
||||||
|
|
||||||
typedef enum {
|
typedef enum
|
||||||
|
{
|
||||||
MAVLINK_COMM_0,
|
MAVLINK_COMM_0,
|
||||||
MAVLINK_COMM_1,
|
MAVLINK_COMM_1,
|
||||||
MAVLINK_COMM_2,
|
MAVLINK_COMM_2,
|
||||||
@ -121,14 +128,15 @@ typedef enum {
|
|||||||
*/
|
*/
|
||||||
#ifndef MAVLINK_COMM_NUM_BUFFERS
|
#ifndef MAVLINK_COMM_NUM_BUFFERS
|
||||||
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
|
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
|
||||||
# define MAVLINK_COMM_NUM_BUFFERS 16
|
#define MAVLINK_COMM_NUM_BUFFERS 16
|
||||||
#else
|
#else
|
||||||
# define MAVLINK_COMM_NUM_BUFFERS 4
|
#define MAVLINK_COMM_NUM_BUFFERS 4
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
typedef enum {
|
typedef enum
|
||||||
MAVLINK_PARSE_STATE_UNINIT=0,
|
{
|
||||||
|
MAVLINK_PARSE_STATE_UNINIT = 0,
|
||||||
MAVLINK_PARSE_STATE_IDLE,
|
MAVLINK_PARSE_STATE_IDLE,
|
||||||
MAVLINK_PARSE_STATE_GOT_STX,
|
MAVLINK_PARSE_STATE_GOT_STX,
|
||||||
MAVLINK_PARSE_STATE_GOT_SEQ,
|
MAVLINK_PARSE_STATE_GOT_SEQ,
|
||||||
@ -140,7 +148,8 @@ typedef enum {
|
|||||||
MAVLINK_PARSE_STATE_GOT_CRC1
|
MAVLINK_PARSE_STATE_GOT_CRC1
|
||||||
} mavlink_parse_state_t; ///< The state machine for the comm parser
|
} mavlink_parse_state_t; ///< The state machine for the comm parser
|
||||||
|
|
||||||
typedef struct __mavlink_status {
|
typedef struct __mavlink_status
|
||||||
|
{
|
||||||
uint8_t msg_received; ///< Number of received messages
|
uint8_t msg_received; ///< Number of received messages
|
||||||
uint8_t buffer_overrun; ///< Number of buffer overruns
|
uint8_t buffer_overrun; ///< Number of buffer overruns
|
||||||
uint8_t parse_error; ///< Number of parse errors
|
uint8_t parse_error; ///< Number of parse errors
|
||||||
|
Loading…
Reference in New Issue
Block a user