mavlink_types.h
Go to the documentation of this file.
00001 #ifndef MAVLINK_TYPES_H_
00002 #define MAVLINK_TYPES_H_
00003 
00004 // Visual Studio versions before 2010 don't have stdint.h, so we just error out.
00005 #if (defined _MSC_VER) && (_MSC_VER < 1600)
00006 #error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
00007 #endif
00008 
00009 #include <stdint.h>
00010 
00011 // Macro to define packed structures
00012 #ifdef __GNUC__
00013   #define MAVPACKED( __Declaration__ ) __Declaration__ __attribute__((packed))
00014 #else
00015   #define MAVPACKED( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
00016 #endif
00017 
00018 #ifndef MAVLINK_MAX_PAYLOAD_LEN
00019 // it is possible to override this, but be careful!
00020 #define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
00021 #endif
00022 
00023 #define MAVLINK_CORE_HEADER_LEN 9 ///< Length of core header (of the comm. layer)
00024 #define MAVLINK_CORE_HEADER_MAVLINK1_LEN 5 ///< Length of MAVLink1 core header (of the comm. layer)
00025 #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and stx
00026 #define MAVLINK_NUM_CHECKSUM_BYTES 2
00027 #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
00028 
00029 #define MAVLINK_SIGNATURE_BLOCK_LEN 13
00030 
00031 #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES + MAVLINK_SIGNATURE_BLOCK_LEN) ///< Maximum packet length
00032 
00042 MAVPACKED(
00043 typedef struct param_union {
00044         union {
00045                 float param_float;
00046                 int32_t param_int32;
00047                 uint32_t param_uint32;
00048                 int16_t param_int16;
00049                 uint16_t param_uint16;
00050                 int8_t param_int8;
00051                 uint8_t param_uint8;
00052                 uint8_t bytes[4];
00053         };
00054         uint8_t type;
00055 }) mavlink_param_union_t;
00056 
00057 
00071 MAVPACKED(
00072 typedef struct param_union_extended {
00073     union {
00074     struct {
00075         uint8_t is_double:1;
00076         uint8_t mavlink_type:7;
00077         union {
00078             char c;
00079             uint8_t uint8;
00080             int8_t int8;
00081             uint16_t uint16;
00082             int16_t int16;
00083             uint32_t uint32;
00084             int32_t int32;
00085             float f;
00086             uint8_t align[7];
00087         };
00088     };
00089     uint8_t data[8];
00090     };
00091 }) mavlink_param_union_double_t;
00092 
00097 MAVPACKED(
00098 typedef struct __mavlink_system {
00099     uint8_t sysid;   
00100     uint8_t compid;  
00101 }) mavlink_system_t;
00102 
00103 MAVPACKED(
00104 typedef struct __mavlink_message {
00105         uint16_t checksum;      
00106         uint8_t magic;          
00107         uint8_t len;            
00108         uint8_t incompat_flags; 
00109         uint8_t compat_flags;   
00110         uint8_t seq;            
00111         uint8_t sysid;          
00112         uint8_t compid;         
00113         uint32_t msgid:24;      
00114         uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
00115         uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
00116 }) mavlink_message_t;
00117 
00118 typedef enum {
00119         MAVLINK_TYPE_CHAR     = 0,
00120         MAVLINK_TYPE_UINT8_T  = 1,
00121         MAVLINK_TYPE_INT8_T   = 2,
00122         MAVLINK_TYPE_UINT16_T = 3,
00123         MAVLINK_TYPE_INT16_T  = 4,
00124         MAVLINK_TYPE_UINT32_T = 5,
00125         MAVLINK_TYPE_INT32_T  = 6,
00126         MAVLINK_TYPE_UINT64_T = 7,
00127         MAVLINK_TYPE_INT64_T  = 8,
00128         MAVLINK_TYPE_FLOAT    = 9,
00129         MAVLINK_TYPE_DOUBLE   = 10
00130 } mavlink_message_type_t;
00131 
00132 #define MAVLINK_MAX_FIELDS 64
00133 
00134 typedef struct __mavlink_field_info {
00135         const char *name;                 // name of this field
00136         const char *print_format;         // printing format hint, or NULL
00137         mavlink_message_type_t type;      // type of this field
00138         unsigned int array_length;        // if non-zero, field is an array
00139         unsigned int wire_offset;         // offset of each field in the payload
00140         unsigned int structure_offset;    // offset in a C structure
00141 } mavlink_field_info_t;
00142 
00143 // note that in this structure the order of fields is the order
00144 // in the XML file, not necessary the wire order
00145 typedef struct __mavlink_message_info {
00146         uint32_t msgid;                                        // message ID
00147         const char *name;                                      // name of the message
00148         unsigned num_fields;                                   // how many fields in this message
00149         mavlink_field_info_t fields[MAVLINK_MAX_FIELDS];       // field information
00150 } mavlink_message_info_t;
00151 
00152 #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
00153 #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
00154 
00155 // checksum is immediately after the payload bytes
00156 #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
00157 #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
00158 
00159 typedef enum {
00160     MAVLINK_COMM_0,
00161     MAVLINK_COMM_1,
00162     MAVLINK_COMM_2,
00163     MAVLINK_COMM_3
00164 } mavlink_channel_t;
00165 
00166 /*
00167  * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
00168  * of buffers they will use. If more are used, then the result will be
00169  * a stack overrun
00170  */
00171 #ifndef MAVLINK_COMM_NUM_BUFFERS
00172 #if (defined linux) | (defined __linux) | (defined  __MACH__) | (defined _WIN32)
00173 # define MAVLINK_COMM_NUM_BUFFERS 16
00174 #else
00175 # define MAVLINK_COMM_NUM_BUFFERS 4
00176 #endif
00177 #endif
00178 
00179 typedef enum {
00180     MAVLINK_PARSE_STATE_UNINIT=0,
00181     MAVLINK_PARSE_STATE_IDLE,
00182     MAVLINK_PARSE_STATE_GOT_STX,
00183     MAVLINK_PARSE_STATE_GOT_LENGTH,
00184     MAVLINK_PARSE_STATE_GOT_INCOMPAT_FLAGS,
00185     MAVLINK_PARSE_STATE_GOT_COMPAT_FLAGS,
00186     MAVLINK_PARSE_STATE_GOT_SEQ,
00187     MAVLINK_PARSE_STATE_GOT_SYSID,
00188     MAVLINK_PARSE_STATE_GOT_COMPID,
00189     MAVLINK_PARSE_STATE_GOT_MSGID1,
00190     MAVLINK_PARSE_STATE_GOT_MSGID2,
00191     MAVLINK_PARSE_STATE_GOT_MSGID3,
00192     MAVLINK_PARSE_STATE_GOT_PAYLOAD,
00193     MAVLINK_PARSE_STATE_GOT_CRC1,
00194     MAVLINK_PARSE_STATE_GOT_BAD_CRC1,
00195     MAVLINK_PARSE_STATE_SIGNATURE_WAIT
00196 } mavlink_parse_state_t; 
00197 
00198 typedef enum {
00199     MAVLINK_FRAMING_INCOMPLETE=0,
00200     MAVLINK_FRAMING_OK=1,
00201     MAVLINK_FRAMING_BAD_CRC=2,
00202     MAVLINK_FRAMING_BAD_SIGNATURE=3
00203 } mavlink_framing_t;
00204 
00205 #define MAVLINK_STATUS_FLAG_IN_MAVLINK1  1 // last incoming packet was MAVLink1
00206 #define MAVLINK_STATUS_FLAG_OUT_MAVLINK1 2 // generate MAVLink1 by default
00207 #define MAVLINK_STATUS_FLAG_IN_SIGNED    4 // last incoming packet was signed and validated
00208 #define MAVLINK_STATUS_FLAG_IN_BADSIG    8 // last incoming packet had a bad signature
00209 
00210 #define MAVLINK_STX_MAVLINK1 0xFE          // marker for old protocol
00211 
00212 typedef struct __mavlink_status {
00213     uint8_t msg_received;               
00214     uint8_t buffer_overrun;             
00215     uint8_t parse_error;                
00216     mavlink_parse_state_t parse_state;  
00217     uint8_t packet_idx;                 
00218     uint8_t current_rx_seq;             
00219     uint8_t current_tx_seq;             
00220     uint16_t packet_rx_success_count;   
00221     uint16_t packet_rx_drop_count;      
00222     uint8_t flags;                      
00223     uint8_t signature_wait;             
00224     struct __mavlink_signing *signing;  
00225     struct __mavlink_signing_streams *signing_streams; 
00226 } mavlink_status_t;
00227 
00228 /*
00229   a callback function to allow for accepting unsigned packets
00230  */
00231 typedef bool (*mavlink_accept_unsigned_t)(const mavlink_status_t *status, uint32_t msgid);
00232 
00233 /*
00234   flags controlling signing
00235  */
00236 #define MAVLINK_SIGNING_FLAG_SIGN_OUTGOING 1
00237 
00238 /*
00239   state of MAVLink signing for this channel
00240  */
00241 typedef struct __mavlink_signing {
00242     uint8_t flags;                     
00243     uint8_t link_id;
00244     uint64_t timestamp;
00245     uint8_t secret_key[32];
00246     mavlink_accept_unsigned_t accept_unsigned_callback;
00247 } mavlink_signing_t;
00248 
00249 /*
00250   timestamp state of each logical signing stream. This needs to be the same structure for all
00251   connections in order to be secure
00252  */
00253 #ifndef MAVLINK_MAX_SIGNING_STREAMS
00254 #define MAVLINK_MAX_SIGNING_STREAMS 16
00255 #endif
00256 typedef struct __mavlink_signing_streams {
00257     uint16_t num_signing_streams;
00258     struct __mavlink_signing_stream {
00259         uint8_t link_id;
00260         uint8_t sysid;
00261         uint8_t compid;
00262         uint8_t timestamp_bytes[6];
00263     } stream[MAVLINK_MAX_SIGNING_STREAMS];
00264 } mavlink_signing_streams_t;
00265 
00266 
00267 #define MAVLINK_BIG_ENDIAN 0
00268 #define MAVLINK_LITTLE_ENDIAN 1
00269 
00270 #define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM    1
00271 #define MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT 2
00272 
00273 /*
00274   entry in table of information about each message type
00275  */
00276 typedef struct __mavlink_msg_entry {
00277         uint32_t msgid;
00278         uint8_t crc_extra;
00279         uint8_t msg_len;
00280         uint8_t flags;             // MAV_MSG_ENTRY_FLAG_*
00281         uint8_t target_system_ofs; // payload offset to target_system, or 0
00282         uint8_t target_component_ofs; // payload offset to target_component, or 0
00283 } mavlink_msg_entry_t;
00284 
00285 /*
00286   incompat_flags bits
00287  */
00288 #define MAVLINK_IFLAG_SIGNED  0x01
00289 #define MAVLINK_IFLAG_MASK    0x01 // mask of all understood bits
00290 
00291 #endif /* MAVLINK_TYPES_H_ */


mavlink
Author(s): Lorenz Meier
autogenerated on Thu Jun 6 2019 19:01:57