3 #define MAVLINK_MSG_ID_BOOT 197
10 #define MAVLINK_MSG_ID_BOOT_LEN 4
11 #define MAVLINK_MSG_ID_197_LEN 4
13 #define MAVLINK_MSG_ID_BOOT_CRC 39
14 #define MAVLINK_MSG_ID_197_CRC 39
18 #define MAVLINK_MESSAGE_INFO_BOOT { \
21 { { "version", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_boot_t, version) }, \
35 static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
38 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
67 static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
68 mavlink_message_t* msg,
71 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
99 static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_boot_t* boot)
101 return mavlink_msg_boot_pack(system_id, component_id, msg, boot->
version);
113 static inline uint16_t mavlink_msg_boot_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_boot_t* boot)
115 return mavlink_msg_boot_pack_chan(system_id, component_id, chan, msg, boot->
version);
124 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
126 static inline void mavlink_msg_boot_send(
mavlink_channel_t chan, uint32_t version)
128 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
132 #if MAVLINK_CRC_EXTRA
141 #if MAVLINK_CRC_EXTRA
149 #if MAVLINK_MSG_ID_BOOT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
157 static inline void mavlink_msg_boot_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint32_t version)
159 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
160 char *buf = (
char *)msgbuf;
163 #if MAVLINK_CRC_EXTRA
172 #if MAVLINK_CRC_EXTRA
191 static inline uint32_t mavlink_msg_boot_get_version(
const mavlink_message_t* msg)
193 return _MAV_RETURN_uint32_t(msg, 0);
202 static inline void mavlink_msg_boot_decode(
const mavlink_message_t* msg,
mavlink_boot_t* boot)
204 #if MAVLINK_NEED_BYTE_SWAP
205 boot->
version = mavlink_msg_boot_get_version(msg);
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.
Definition: mavlink_helpers.h:105
#define MAVLINK_MSG_ID_BOOT
Definition: mavlink_msg_boot.h:3
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
struct __mavlink_boot_t mavlink_boot_t
#define MAVLINK_MSG_ID_BOOT_CRC
Definition: mavlink_msg_boot.h:13
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint32_t version
The onboard software version.
Definition: mavlink_msg_boot.h:7
Definition: mavlink_msg_boot.h:5
#define MAVLINK_MSG_ID_BOOT_LEN
Definition: mavlink_msg_boot.h:10
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.
Definition: mavlink_helpers.h:71
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:141