3 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148 20 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60 21 #define MAVLINK_MSG_ID_148_LEN 60 23 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178 24 #define MAVLINK_MSG_ID_148_CRC 178 26 #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8 27 #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8 28 #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8 30 #define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \ 31 "AUTOPILOT_VERSION", \ 33 { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \ 34 { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \ 35 { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \ 36 { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \ 37 { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \ 38 { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \ 39 { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \ 40 { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \ 41 { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \ 42 { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \ 43 { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \ 68 uint64_t
capabilities, uint32_t
flight_sw_version, uint32_t
middleware_sw_version, uint32_t
os_sw_version, uint32_t
board_version,
const uint8_t *
flight_custom_version,
const uint8_t *
middleware_custom_version,
const uint8_t *
os_custom_version, uint16_t
vendor_id, uint16_t
product_id, uint64_t
uid)
70 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 101 #if MAVLINK_CRC_EXTRA 128 mavlink_message_t* msg,
129 uint64_t
capabilities,uint32_t
flight_sw_version,uint32_t
middleware_sw_version,uint32_t
os_sw_version,uint32_t
board_version,
const uint8_t *
flight_custom_version,
const uint8_t *
middleware_custom_version,
const uint8_t *
os_custom_version,uint16_t
vendor_id,uint16_t
product_id,uint64_t
uid)
131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 162 #if MAVLINK_CRC_EXTRA 179 return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->
capabilities, autopilot_version->
flight_sw_version, autopilot_version->
middleware_sw_version, autopilot_version->
os_sw_version, autopilot_version->
board_version, autopilot_version->
flight_custom_version, autopilot_version->
middleware_custom_version, autopilot_version->
os_custom_version, autopilot_version->
vendor_id, autopilot_version->
product_id, autopilot_version->
uid);
193 return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->
capabilities, autopilot_version->
flight_sw_version, autopilot_version->
middleware_sw_version, autopilot_version->
os_sw_version, autopilot_version->
board_version, autopilot_version->
flight_custom_version, autopilot_version->
middleware_custom_version, autopilot_version->
os_custom_version, autopilot_version->
vendor_id, autopilot_version->
product_id, autopilot_version->
uid);
212 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS 214 static inline void mavlink_msg_autopilot_version_send(
mavlink_channel_t chan, uint64_t
capabilities, uint32_t
flight_sw_version, uint32_t
middleware_sw_version, uint32_t
os_sw_version, uint32_t
board_version,
const uint8_t *
flight_custom_version,
const uint8_t *
middleware_custom_version,
const uint8_t *
os_custom_version, uint16_t
vendor_id, uint16_t
product_id, uint64_t
uid)
216 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 229 #if MAVLINK_CRC_EXTRA 247 #if MAVLINK_CRC_EXTRA 255 #if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN 263 static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint64_t
capabilities, uint32_t
flight_sw_version, uint32_t
middleware_sw_version, uint32_t
os_sw_version, uint32_t
board_version,
const uint8_t *
flight_custom_version,
const uint8_t *
middleware_custom_version,
const uint8_t *
os_custom_version, uint16_t
vendor_id, uint16_t
product_id, uint64_t
uid)
265 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS 266 char *buf = (
char *)msgbuf;
278 #if MAVLINK_CRC_EXTRA 296 #if MAVLINK_CRC_EXTRA 317 return _MAV_RETURN_uint64_t(msg, 0);
327 return _MAV_RETURN_uint32_t(msg, 16);
337 return _MAV_RETURN_uint32_t(msg, 20);
347 return _MAV_RETURN_uint32_t(msg, 24);
357 return _MAV_RETURN_uint32_t(msg, 28);
397 return _MAV_RETURN_uint16_t(msg, 32);
407 return _MAV_RETURN_uint16_t(msg, 34);
417 return _MAV_RETURN_uint64_t(msg, 8);
428 #if MAVLINK_NEED_BYTE_SWAP uint32_t middleware_sw_version
static uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_autopilot_version_t *autopilot_version)
Encode a autopilot_version struct on a channel.
static uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t *msg)
Get field middleware_sw_version from autopilot_version message.
uint8_t middleware_custom_version[8]
static uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t *msg)
Get field vendor_id from autopilot_version message.
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN
static void mavlink_msg_autopilot_version_decode(const mavlink_message_t *msg, mavlink_autopilot_version_t *autopilot_version)
Decode a autopilot_version message into a struct.
static uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t *msg)
Get field uid from autopilot_version message.
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
#define _mav_put_uint64_t(buf, wire_offset, b)
static uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t *msg)
Send a autopilot_version message.
#define _MAV_PAYLOAD_NON_CONST(msg)
static uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_autopilot_version_t *autopilot_version)
Encode a autopilot_version struct.
static uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
Pack a autopilot_version message.
static uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t *msg)
Get field os_sw_version from autopilot_version message.
static uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t *msg)
Get field flight_sw_version from autopilot_version message.
#define _MAV_PAYLOAD(msg)
uint8_t os_custom_version[8]
uint32_t flight_sw_version
static uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
Pack a autopilot_version message on a channel.
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION
struct __mavlink_autopilot_version_t mavlink_autopilot_version_t
static uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t *msg)
Get field board_version from autopilot_version message.
static uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t *msg, uint8_t *os_custom_version)
Get field os_custom_version from autopilot_version message.
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC
static uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t *msg)
Get field product_id from autopilot_version message.
static uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t *msg, uint8_t *middleware_custom_version)
Get field middleware_custom_version from autopilot_version message.
static void mav_array_memcpy(void *dest, const void *src, size_t n)
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
uint8_t flight_custom_version[8]
#define _mav_put_uint16_t(buf, wire_offset, b)
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
static uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t *msg, uint8_t *flight_custom_version)
Get field flight_custom_version from autopilot_version message.
#define _mav_put_uint32_t(buf, wire_offset, b)