1 #ifndef MAVLINK_TYPES_H_ 2 #define MAVLINK_TYPES_H_ 171 #ifndef MAVLINK_MAX_PAYLOAD_LEN 173 #define MAVLINK_MAX_PAYLOAD_LEN 255 176 #define MAVLINK_CORE_HEADER_LEN 5 177 #define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) 178 #define MAVLINK_NUM_CHECKSUM_BYTES 2 179 #define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) 181 #define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) 183 #define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 184 #define MAVLINK_EXTENDED_HEADER_LEN 14 186 #if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__) 188 #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 191 #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 194 #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) 249 #define MAVLINK_MAX_FIELDS 64 268 #define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) 269 #define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) 272 #define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) 273 #define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) 287 #ifndef MAVLINK_COMM_NUM_BUFFERS 288 #if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) 289 # define MAVLINK_COMM_NUM_BUFFERS 16 291 # define MAVLINK_COMM_NUM_BUFFERS 4 320 #define MAVLINK_BIG_ENDIAN 0 321 #define MAVLINK_LITTLE_ENDIAN 1
uint8_t magic
sent at end of packet
unsigned int array_length
ArduPilotMega / ArduCopter, http://diydrones.com.
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN
System is in undefined state.
uint8_t msgid
ID of message in payload.
Motors are blocked, system is safe.
Generic test mode, for custom use.
Generic autopilot supporting the full mission command set.
int32_t extended_payload_len
Length of extended payload if any.
uint8_t seq
Sequence of packet.
struct __mavlink_extended_message mavlink_extended_message_t
uint8_t sysid
Used by the MAVLink message_xx_send() convenience function.
#define MAVLINK_MAX_FIELDS
struct __mavlink_system mavlink_system_t
uint8_t msg_received
Number of received messages.
mavlink_parse_state_t parse_state
Parsing state machine.
mavlink_message_type_t type
struct __mavlink_field_info mavlink_field_info_t
uint8_t type
Unused, can be used by user to store the system's type.
uint8_t nav_mode
Unused, can be used by user to store the system's navigation mode.
uint8_t parse_error
Number of parse errors.
System is blocked, only RC valued are read and reported back.
#define MAVLINK_MAX_PAYLOAD_LEN
Maximum payload length.
Generic autopilot only supporting simple waypoints.
uint16_t packet_rx_drop_count
Number of packet drops.
#define MAVLINK_NUM_CHECKSUM_BYTES
mavlink_message_t base_msg
const char * print_format
uint16_t packet_rx_success_count
Received packets.
System is allowed to be active, under autonomous control, manual setpoint.
Number of autopilot classes.
uint8_t state
Unused, can be used by user to store the system's state.
uint8_t sysid
ID of message sender system/aircraft.
uint8_t compid
ID of the message sender component.
System is allowed to be active, under manual (RC) control.
struct __mavlink_status mavlink_status_t
uint8_t packet_idx
Index in current packet.
struct __mavlink_message_info mavlink_message_info_t
uint8_t len
Length of payload.
struct __mavlink_message mavlink_message_t
uint8_t current_rx_seq
Sequence number of last packet received.
unsigned int structure_offset
System is ready, motors are unblocked, but controllers are inactive.
Generic test mode, for custom use.
Generic test mode, for custom use.
Generic autopilot supporting waypoints and other simple navigation commands.
struct param_union mavlink_param_union_t
uint8_t buffer_overrun
Number of buffer overruns.
System is allowed to be active, under autonomous control and navigation.
SLUGS autopilot, http://slugsuav.soe.ucsc.edu.
Generic autopilot, full support for everything.
uint8_t current_tx_seq
Sequence number of last packet sent.
uint8_t compid
Used by the MAVLink message_xx_send() convenience function.
uint8_t mode
Unused, can be used by user to store the system's mode.
OpenPilot, http://openpilot.org.
PIXHAWK autopilot, http://pixhawk.ethz.ch.