2 // MESSAGE PROTOCOL_VERSION PACKING
4 #define MAVLINK_MSG_ID_PROTOCOL_VERSION 300
7 typedef struct __mavlink_protocol_version_t
{
8 uint16_t version
; /*< Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.*/
9 uint16_t min_version
; /*< Minimum MAVLink version supported*/
10 uint16_t max_version
; /*< Maximum MAVLink version supported (set to the same value as version by default)*/
11 uint8_t spec_version_hash
[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/
12 uint8_t library_version_hash
[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/
13 } mavlink_protocol_version_t
;
15 #define MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN 22
16 #define MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN 22
17 #define MAVLINK_MSG_ID_300_LEN 22
18 #define MAVLINK_MSG_ID_300_MIN_LEN 22
20 #define MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC 217
21 #define MAVLINK_MSG_ID_300_CRC 217
23 #define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_SPEC_VERSION_HASH_LEN 8
24 #define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_LIBRARY_VERSION_HASH_LEN 8
26 #if MAVLINK_COMMAND_24BIT
27 #define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \
31 { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \
32 { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \
33 { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \
34 { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \
35 { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \
39 #define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \
42 { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \
43 { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \
44 { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \
45 { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \
46 { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \
52 * @brief Pack a protocol_version message
53 * @param system_id ID of this system
54 * @param component_id ID of this component (e.g. 200 for IMU)
55 * @param msg The MAVLink message to compress the data into
57 * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
58 * @param min_version Minimum MAVLink version supported
59 * @param max_version Maximum MAVLink version supported (set to the same value as version by default)
60 * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
61 * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
62 * @return length of the message in bytes (excluding serial stream start sign)
64 static inline uint16_t mavlink_msg_protocol_version_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
65 uint16_t version
, uint16_t min_version
, uint16_t max_version
, const uint8_t *spec_version_hash
, const uint8_t *library_version_hash
)
67 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
68 char buf
[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
];
69 _mav_put_uint16_t(buf
, 0, version
);
70 _mav_put_uint16_t(buf
, 2, min_version
);
71 _mav_put_uint16_t(buf
, 4, max_version
);
72 _mav_put_uint8_t_array(buf
, 6, spec_version_hash
, 8);
73 _mav_put_uint8_t_array(buf
, 14, library_version_hash
, 8);
74 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
);
76 mavlink_protocol_version_t packet
;
77 packet
.version
= version
;
78 packet
.min_version
= min_version
;
79 packet
.max_version
= max_version
;
80 mav_array_memcpy(packet
.spec_version_hash
, spec_version_hash
, sizeof(uint8_t)*8);
81 mav_array_memcpy(packet
.library_version_hash
, library_version_hash
, sizeof(uint8_t)*8);
82 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
);
85 msg
->msgid
= MAVLINK_MSG_ID_PROTOCOL_VERSION
;
86 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC
);
90 * @brief Pack a protocol_version message on a channel
91 * @param system_id ID of this system
92 * @param component_id ID of this component (e.g. 200 for IMU)
93 * @param chan The MAVLink channel this message will be sent over
94 * @param msg The MAVLink message to compress the data into
95 * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
96 * @param min_version Minimum MAVLink version supported
97 * @param max_version Maximum MAVLink version supported (set to the same value as version by default)
98 * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
99 * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
100 * @return length of the message in bytes (excluding serial stream start sign)
102 static inline uint16_t mavlink_msg_protocol_version_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
103 mavlink_message_t
* msg
,
104 uint16_t version
,uint16_t min_version
,uint16_t max_version
,const uint8_t *spec_version_hash
,const uint8_t *library_version_hash
)
106 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107 char buf
[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
];
108 _mav_put_uint16_t(buf
, 0, version
);
109 _mav_put_uint16_t(buf
, 2, min_version
);
110 _mav_put_uint16_t(buf
, 4, max_version
);
111 _mav_put_uint8_t_array(buf
, 6, spec_version_hash
, 8);
112 _mav_put_uint8_t_array(buf
, 14, library_version_hash
, 8);
113 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
);
115 mavlink_protocol_version_t packet
;
116 packet
.version
= version
;
117 packet
.min_version
= min_version
;
118 packet
.max_version
= max_version
;
119 mav_array_memcpy(packet
.spec_version_hash
, spec_version_hash
, sizeof(uint8_t)*8);
120 mav_array_memcpy(packet
.library_version_hash
, library_version_hash
, sizeof(uint8_t)*8);
121 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
);
124 msg
->msgid
= MAVLINK_MSG_ID_PROTOCOL_VERSION
;
125 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC
);
129 * @brief Encode a protocol_version struct
131 * @param system_id ID of this system
132 * @param component_id ID of this component (e.g. 200 for IMU)
133 * @param msg The MAVLink message to compress the data into
134 * @param protocol_version C-struct to read the message contents from
136 static inline uint16_t mavlink_msg_protocol_version_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_protocol_version_t
* protocol_version
)
138 return mavlink_msg_protocol_version_pack(system_id
, component_id
, msg
, protocol_version
->version
, protocol_version
->min_version
, protocol_version
->max_version
, protocol_version
->spec_version_hash
, protocol_version
->library_version_hash
);
142 * @brief Encode a protocol_version struct on a channel
144 * @param system_id ID of this system
145 * @param component_id ID of this component (e.g. 200 for IMU)
146 * @param chan The MAVLink channel this message will be sent over
147 * @param msg The MAVLink message to compress the data into
148 * @param protocol_version C-struct to read the message contents from
150 static inline uint16_t mavlink_msg_protocol_version_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_protocol_version_t
* protocol_version
)
152 return mavlink_msg_protocol_version_pack_chan(system_id
, component_id
, chan
, msg
, protocol_version
->version
, protocol_version
->min_version
, protocol_version
->max_version
, protocol_version
->spec_version_hash
, protocol_version
->library_version_hash
);
156 * @brief Send a protocol_version message
157 * @param chan MAVLink channel to send the message
159 * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
160 * @param min_version Minimum MAVLink version supported
161 * @param max_version Maximum MAVLink version supported (set to the same value as version by default)
162 * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
163 * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
165 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
167 static inline void mavlink_msg_protocol_version_send(mavlink_channel_t chan
, uint16_t version
, uint16_t min_version
, uint16_t max_version
, const uint8_t *spec_version_hash
, const uint8_t *library_version_hash
)
169 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
170 char buf
[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
];
171 _mav_put_uint16_t(buf
, 0, version
);
172 _mav_put_uint16_t(buf
, 2, min_version
);
173 _mav_put_uint16_t(buf
, 4, max_version
);
174 _mav_put_uint8_t_array(buf
, 6, spec_version_hash
, 8);
175 _mav_put_uint8_t_array(buf
, 14, library_version_hash
, 8);
176 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PROTOCOL_VERSION
, buf
, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC
);
178 mavlink_protocol_version_t packet
;
179 packet
.version
= version
;
180 packet
.min_version
= min_version
;
181 packet
.max_version
= max_version
;
182 mav_array_memcpy(packet
.spec_version_hash
, spec_version_hash
, sizeof(uint8_t)*8);
183 mav_array_memcpy(packet
.library_version_hash
, library_version_hash
, sizeof(uint8_t)*8);
184 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PROTOCOL_VERSION
, (const char *)&packet
, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC
);
189 * @brief Send a protocol_version message
190 * @param chan MAVLink channel to send the message
191 * @param struct The MAVLink struct to serialize
193 static inline void mavlink_msg_protocol_version_send_struct(mavlink_channel_t chan
, const mavlink_protocol_version_t
* protocol_version
)
195 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
196 mavlink_msg_protocol_version_send(chan
, protocol_version
->version
, protocol_version
->min_version
, protocol_version
->max_version
, protocol_version
->spec_version_hash
, protocol_version
->library_version_hash
);
198 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PROTOCOL_VERSION
, (const char *)protocol_version
, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC
);
202 #if MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
204 This varient of _send() can be used to save stack space by re-using
205 memory from the receive buffer. The caller provides a
206 mavlink_message_t which is the size of a full mavlink message. This
207 is usually the receive buffer for the channel, and allows a reply to an
208 incoming message with minimum stack space usage.
210 static inline void mavlink_msg_protocol_version_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint16_t version
, uint16_t min_version
, uint16_t max_version
, const uint8_t *spec_version_hash
, const uint8_t *library_version_hash
)
212 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 char *buf
= (char *)msgbuf
;
214 _mav_put_uint16_t(buf
, 0, version
);
215 _mav_put_uint16_t(buf
, 2, min_version
);
216 _mav_put_uint16_t(buf
, 4, max_version
);
217 _mav_put_uint8_t_array(buf
, 6, spec_version_hash
, 8);
218 _mav_put_uint8_t_array(buf
, 14, library_version_hash
, 8);
219 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PROTOCOL_VERSION
, buf
, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC
);
221 mavlink_protocol_version_t
*packet
= (mavlink_protocol_version_t
*)msgbuf
;
222 packet
->version
= version
;
223 packet
->min_version
= min_version
;
224 packet
->max_version
= max_version
;
225 mav_array_memcpy(packet
->spec_version_hash
, spec_version_hash
, sizeof(uint8_t)*8);
226 mav_array_memcpy(packet
->library_version_hash
, library_version_hash
, sizeof(uint8_t)*8);
227 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_PROTOCOL_VERSION
, (const char *)packet
, MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
, MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC
);
234 // MESSAGE PROTOCOL_VERSION UNPACKING
238 * @brief Get field version from protocol_version message
240 * @return Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
242 static inline uint16_t mavlink_msg_protocol_version_get_version(const mavlink_message_t
* msg
)
244 return _MAV_RETURN_uint16_t(msg
, 0);
248 * @brief Get field min_version from protocol_version message
250 * @return Minimum MAVLink version supported
252 static inline uint16_t mavlink_msg_protocol_version_get_min_version(const mavlink_message_t
* msg
)
254 return _MAV_RETURN_uint16_t(msg
, 2);
258 * @brief Get field max_version from protocol_version message
260 * @return Maximum MAVLink version supported (set to the same value as version by default)
262 static inline uint16_t mavlink_msg_protocol_version_get_max_version(const mavlink_message_t
* msg
)
264 return _MAV_RETURN_uint16_t(msg
, 4);
268 * @brief Get field spec_version_hash from protocol_version message
270 * @return The first 8 bytes (not characters printed in hex!) of the git hash.
272 static inline uint16_t mavlink_msg_protocol_version_get_spec_version_hash(const mavlink_message_t
* msg
, uint8_t *spec_version_hash
)
274 return _MAV_RETURN_uint8_t_array(msg
, spec_version_hash
, 8, 6);
278 * @brief Get field library_version_hash from protocol_version message
280 * @return The first 8 bytes (not characters printed in hex!) of the git hash.
282 static inline uint16_t mavlink_msg_protocol_version_get_library_version_hash(const mavlink_message_t
* msg
, uint8_t *library_version_hash
)
284 return _MAV_RETURN_uint8_t_array(msg
, library_version_hash
, 8, 14);
288 * @brief Decode a protocol_version message into a struct
290 * @param msg The message to decode
291 * @param protocol_version C-struct to decode the message contents into
293 static inline void mavlink_msg_protocol_version_decode(const mavlink_message_t
* msg
, mavlink_protocol_version_t
* protocol_version
)
295 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
296 protocol_version
->version
= mavlink_msg_protocol_version_get_version(msg
);
297 protocol_version
->min_version
= mavlink_msg_protocol_version_get_min_version(msg
);
298 protocol_version
->max_version
= mavlink_msg_protocol_version_get_max_version(msg
);
299 mavlink_msg_protocol_version_get_spec_version_hash(msg
, protocol_version
->spec_version_hash
);
300 mavlink_msg_protocol_version_get_library_version_hash(msg
, protocol_version
->library_version_hash
);
302 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
? msg
->len
: MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
;
303 memset(protocol_version
, 0, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN
);
304 memcpy(protocol_version
, _MAV_PAYLOAD(msg
), len
);