mavlink_msg_autopilot_version.h
Go to the documentation of this file.
1 // MESSAGE AUTOPILOT_VERSION PACKING
2 
3 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148
4 
6 {
7  uint64_t capabilities; /*< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)*/
8  uint64_t uid; /*< UID if provided by hardware*/
9  uint32_t flight_sw_version; /*< Firmware version number*/
10  uint32_t middleware_sw_version; /*< Middleware version number*/
11  uint32_t os_sw_version; /*< Operating system version number*/
12  uint32_t board_version; /*< HW / board version (last 8 bytes should be silicon ID, if any)*/
13  uint16_t vendor_id; /*< ID of the board vendor*/
14  uint16_t product_id; /*< ID of the product*/
15  uint8_t flight_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
16  uint8_t middleware_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
17  uint8_t os_custom_version[8]; /*< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.*/
19 
20 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60
21 #define MAVLINK_MSG_ID_148_LEN 60
22 
23 #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178
24 #define MAVLINK_MSG_ID_148_CRC 178
25 
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
29 
30 #define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
31  "AUTOPILOT_VERSION", \
32  11, \
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) }, \
44  } \
45 }
46 
47 
67 static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
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)
69 {
70 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
72  _mav_put_uint64_t(buf, 0, capabilities);
73  _mav_put_uint64_t(buf, 8, uid);
74  _mav_put_uint32_t(buf, 16, flight_sw_version);
75  _mav_put_uint32_t(buf, 20, middleware_sw_version);
76  _mav_put_uint32_t(buf, 24, os_sw_version);
77  _mav_put_uint32_t(buf, 28, board_version);
78  _mav_put_uint16_t(buf, 32, vendor_id);
79  _mav_put_uint16_t(buf, 34, product_id);
80  _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
81  _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
82  _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
84 #else
86  packet.capabilities = capabilities;
87  packet.uid = uid;
92  packet.vendor_id = vendor_id;
93  packet.product_id = product_id;
94  mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
95  mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
96  mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
98 #endif
99 
101 #if MAVLINK_CRC_EXTRA
103 #else
104  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
105 #endif
106 }
107 
127 static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
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)
130 {
131 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
133  _mav_put_uint64_t(buf, 0, capabilities);
134  _mav_put_uint64_t(buf, 8, uid);
135  _mav_put_uint32_t(buf, 16, flight_sw_version);
136  _mav_put_uint32_t(buf, 20, middleware_sw_version);
137  _mav_put_uint32_t(buf, 24, os_sw_version);
138  _mav_put_uint32_t(buf, 28, board_version);
139  _mav_put_uint16_t(buf, 32, vendor_id);
140  _mav_put_uint16_t(buf, 34, product_id);
141  _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
142  _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
143  _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
145 #else
147  packet.capabilities = capabilities;
148  packet.uid = uid;
151  packet.os_sw_version = os_sw_version;
152  packet.board_version = board_version;
153  packet.vendor_id = vendor_id;
154  packet.product_id = product_id;
155  mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
156  mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
157  mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
159 #endif
160 
162 #if MAVLINK_CRC_EXTRA
164 #else
165  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
166 #endif
167 }
168 
177 static inline 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)
178 {
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);
180 }
181 
191 static inline 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)
192 {
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);
194 }
195 
212 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
213 
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)
215 {
216 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
219  _mav_put_uint64_t(buf, 8, uid);
224  _mav_put_uint16_t(buf, 32, vendor_id);
225  _mav_put_uint16_t(buf, 34, product_id);
229 #if MAVLINK_CRC_EXTRA
231 #else
232  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
233 #endif
234 #else
236  packet.capabilities = capabilities;
237  packet.uid = uid;
240  packet.os_sw_version = os_sw_version;
241  packet.board_version = board_version;
242  packet.vendor_id = vendor_id;
243  packet.product_id = product_id;
246  mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
247 #if MAVLINK_CRC_EXTRA
248  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
249 #else
250  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
251 #endif
252 #endif
253 }
254 
255 #if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
256 /*
257  This varient of _send() can be used to save stack space by re-using
258  memory from the receive buffer. The caller provides a
259  mavlink_message_t which is the size of a full mavlink message. This
260  is usually the receive buffer for the channel, and allows a reply to an
261  incoming message with minimum stack space usage.
262  */
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)
264 {
265 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
266  char *buf = (char *)msgbuf;
268  _mav_put_uint64_t(buf, 8, uid);
273  _mav_put_uint16_t(buf, 32, vendor_id);
274  _mav_put_uint16_t(buf, 34, product_id);
278 #if MAVLINK_CRC_EXTRA
280 #else
281  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
282 #endif
283 #else
285  packet->capabilities = capabilities;
286  packet->uid = uid;
289  packet->os_sw_version = os_sw_version;
290  packet->board_version = board_version;
291  packet->vendor_id = vendor_id;
292  packet->product_id = product_id;
293  mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
295  mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8);
296 #if MAVLINK_CRC_EXTRA
297  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
298 #else
299  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
300 #endif
301 #endif
302 }
303 #endif
304 
305 #endif
306 
307 // MESSAGE AUTOPILOT_VERSION UNPACKING
308 
309 
315 static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg)
316 {
317  return _MAV_RETURN_uint64_t(msg, 0);
318 }
319 
325 static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg)
326 {
327  return _MAV_RETURN_uint32_t(msg, 16);
328 }
329 
335 static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg)
336 {
337  return _MAV_RETURN_uint32_t(msg, 20);
338 }
339 
345 static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg)
346 {
347  return _MAV_RETURN_uint32_t(msg, 24);
348 }
349 
355 static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg)
356 {
357  return _MAV_RETURN_uint32_t(msg, 28);
358 }
359 
365 static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version)
366 {
367  return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36);
368 }
369 
375 static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version)
376 {
377  return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44);
378 }
379 
385 static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version)
386 {
387  return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52);
388 }
389 
395 static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg)
396 {
397  return _MAV_RETURN_uint16_t(msg, 32);
398 }
399 
405 static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg)
406 {
407  return _MAV_RETURN_uint16_t(msg, 34);
408 }
409 
415 static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg)
416 {
417  return _MAV_RETURN_uint64_t(msg, 8);
418 }
419 
426 static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version)
427 {
428 #if MAVLINK_NEED_BYTE_SWAP
430  autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg);
435  autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg);
440 #else
441  memcpy(autopilot_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
442 #endif
443 }
static void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
Definition: protocol.h:197
#define _mav_put_uint64_t(buf, wire_offset, b)
Definition: protocol.h:149
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:295
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:24