#include <stdint.h>
Go to the source code of this file.
|
enum | mavlink_message_type_t {
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
} |
|
enum | mavlink_channel_t { MAVLINK_COMM_0,
MAVLINK_COMM_1,
MAVLINK_COMM_2,
MAVLINK_COMM_3
} |
|
enum | mavlink_parse_state_t {
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
} |
|
|
| MAVPACKED (typedef struct param_union{union{float param_float;int32_t param_int32;uint32_t param_uint32;int16_t param_int16;uint16_t param_uint16;int8_t param_int8;uint8_t param_uint8;uint8_t bytes[4];};uint8_t type;}) mavlink_param_union_t |
|
| MAVPACKED (typedef struct param_union_extended{union{struct{uint8_t is_double:1;uint8_t mavlink_type:7;union{char c;uint8_t uint8;int8_t int8;uint16_t uint16;int16_t int16;uint32_t uint32;int32_t int32;float f;uint8_t align[7];};};uint8_t data[8];};}) mavlink_param_union_double_t |
|
| MAVPACKED (typedef struct __mavlink_system{uint8_t sysid;uint8_t compid;}) mavlink_system_t |
|
| MAVPACKED (typedef struct __mavlink_message{uint16_t checksum;uint8_t magic;uint8_t len;uint8_t seq;uint8_t sysid;uint8_t compid;uint8_t msgid;uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];}) mavlink_message_t |
|
| MAVPACKED (typedef struct __mavlink_extended_message{mavlink_message_t base_msg;int32_t extended_payload_len;uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];}) mavlink_extended_message_t |
|
#define _MAV_PAYLOAD |
( |
|
msg | ) |
((const char *)(&((msg)->payload64[0]))) |
#define _MAV_PAYLOAD_NON_CONST |
( |
|
msg | ) |
((char *)(&((msg)->payload64[0]))) |
#define MAVLINK_BIG_ENDIAN 0 |
#define MAVLINK_COMM_NUM_BUFFERS 4 |
#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_EXTENDED_HEADER_LEN 14 |
#define MAVLINK_LITTLE_ENDIAN 1 |
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 |
#define MAVLINK_MAX_FIELDS 64 |
#define MAVLINK_MAX_PAYLOAD_LEN 255 |
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 |
#define MAVLINK_NUM_CHECKSUM_BYTES 2 |
Length of all header bytes, including core and checksum.
#define MAVPACKED |
( |
|
__Declaration__ | ) |
__pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) |
Enumerator |
---|
MAVLINK_COMM_0 |
|
MAVLINK_COMM_1 |
|
MAVLINK_COMM_2 |
|
MAVLINK_COMM_3 |
|
Enumerator |
---|
MAVLINK_TYPE_CHAR |
|
MAVLINK_TYPE_UINT8_T |
|
MAVLINK_TYPE_INT8_T |
|
MAVLINK_TYPE_UINT16_T |
|
MAVLINK_TYPE_INT16_T |
|
MAVLINK_TYPE_UINT32_T |
|
MAVLINK_TYPE_INT32_T |
|
MAVLINK_TYPE_UINT64_T |
|
MAVLINK_TYPE_INT64_T |
|
MAVLINK_TYPE_FLOAT |
|
MAVLINK_TYPE_DOUBLE |
|
Enumerator |
---|
MAVLINK_PARSE_STATE_UNINIT |
|
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 |
|
MAVPACKED |
( |
typedef struct param_union{union{float param_float;int32_t param_int32;uint32_t param_uint32;int16_t param_int16;uint16_t param_uint16;int8_t param_int8;uint8_t param_uint8;uint8_t bytes[4];};uint8_t type;} |
| ) |
|
Old-style 4 byte param union
This struct is the data format to be used when sending parameters. The parameter should be copied to the native type (without type conversion) and re-instanted on the receiving side using the native type as well.
MAVPACKED |
( |
typedef struct param_union_extended{union{struct{uint8_t is_double:1;uint8_t mavlink_type:7;union{char c;uint8_t uint8;int8_t int8;uint16_t uint16;int16_t int16;uint32_t uint32;int32_t int32;float f;uint8_t align[7];};};uint8_t data[8];};} |
| ) |
|
New-style 8 byte param union mavlink_param_union_double_t will be 8 bytes long, and treated as needing 8 byte alignment for the purposes of MAVLink 1.0 field ordering. The mavlink_param_union_double_t will be treated as a little-endian structure.
If is_double is 1 then the type is a double, and the remaining 63 bits are the double, with the lowest bit of the mantissa zero. The intention is that by replacing the is_double bit with 0 the type can be directly used as a double (as the is_double bit corresponds to the lowest mantissa bit of a double). If is_double is 0 then mavlink_type gives the type in the union. The mavlink_types.h header will also need to have shifts/masks to define the bit boundaries in the above, as bitfield ordering isn’t consistent between platforms. The above is intended to be for gcc on x86, which should be the same as gcc on little-endian arm. When using shifts/masks the value will be treated as a 64 bit unsigned number, and the bits pulled out using the shifts/masks.
MAVPACKED |
( |
typedef struct __mavlink_system{uint8_t sysid;uint8_t compid;} |
| ) |
|
This structure is required to make the mavlink_send_xxx convenience functions work, as it tells the library what the current system and component ID are.
MAVPACKED |
( |
typedef struct __mavlink_extended_message{mavlink_message_t base_msg;int32_t extended_payload_len;uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];} |
| ) |
|