mavlink_msg_autopilot_version.h 28 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483
  1. #pragma once
  2. // MESSAGE AUTOPILOT_VERSION PACKING
  3. #define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148
  4. typedef struct __mavlink_autopilot_version_t {
  5. uint64_t capabilities; /*< Bitmap of capabilities*/
  6. uint64_t uid; /*< UID if provided by hardware (see uid2)*/
  7. uint32_t flight_sw_version; /*< Firmware version number*/
  8. uint32_t middleware_sw_version; /*< Middleware version number*/
  9. uint32_t os_sw_version; /*< Operating system version number*/
  10. uint32_t board_version; /*< HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt*/
  11. uint16_t vendor_id; /*< ID of the board vendor*/
  12. uint16_t product_id; /*< ID of the product*/
  13. 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.*/
  14. 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.*/
  15. 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.*/
  16. uint8_t uid2[18]; /*< UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)*/
  17. } mavlink_autopilot_version_t;
  18. #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 78
  19. #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN 60
  20. #define MAVLINK_MSG_ID_148_LEN 78
  21. #define MAVLINK_MSG_ID_148_MIN_LEN 60
  22. #define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178
  23. #define MAVLINK_MSG_ID_148_CRC 178
  24. #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8
  25. #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8
  26. #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8
  27. #define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN 18
  28. #if MAVLINK_COMMAND_24BIT
  29. #define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
  30. 148, \
  31. "AUTOPILOT_VERSION", \
  32. 12, \
  33. { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
  34. { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \
  35. { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \
  36. { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \
  37. { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \
  38. { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \
  39. { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \
  40. { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \
  41. { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
  42. { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
  43. { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
  44. { "uid2", NULL, MAVLINK_TYPE_UINT8_T, 18, 60, offsetof(mavlink_autopilot_version_t, uid2) }, \
  45. } \
  46. }
  47. #else
  48. #define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
  49. "AUTOPILOT_VERSION", \
  50. 12, \
  51. { { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
  52. { "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \
  53. { "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \
  54. { "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \
  55. { "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \
  56. { "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \
  57. { "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \
  58. { "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \
  59. { "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
  60. { "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
  61. { "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
  62. { "uid2", NULL, MAVLINK_TYPE_UINT8_T, 18, 60, offsetof(mavlink_autopilot_version_t, uid2) }, \
  63. } \
  64. }
  65. #endif
  66. /**
  67. * @brief Pack a autopilot_version message
  68. * @param system_id ID of this system
  69. * @param component_id ID of this component (e.g. 200 for IMU)
  70. * @param msg The MAVLink message to compress the data into
  71. *
  72. * @param capabilities Bitmap of capabilities
  73. * @param flight_sw_version Firmware version number
  74. * @param middleware_sw_version Middleware version number
  75. * @param os_sw_version Operating system version number
  76. * @param board_version HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt
  77. * @param flight_custom_version 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.
  78. * @param middleware_custom_version 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.
  79. * @param os_custom_version 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.
  80. * @param vendor_id ID of the board vendor
  81. * @param product_id ID of the product
  82. * @param uid UID if provided by hardware (see uid2)
  83. * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  84. * @return length of the message in bytes (excluding serial stream start sign)
  85. */
  86. static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  87. 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, const uint8_t *uid2)
  88. {
  89. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  90. char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
  91. _mav_put_uint64_t(buf, 0, capabilities);
  92. _mav_put_uint64_t(buf, 8, uid);
  93. _mav_put_uint32_t(buf, 16, flight_sw_version);
  94. _mav_put_uint32_t(buf, 20, middleware_sw_version);
  95. _mav_put_uint32_t(buf, 24, os_sw_version);
  96. _mav_put_uint32_t(buf, 28, board_version);
  97. _mav_put_uint16_t(buf, 32, vendor_id);
  98. _mav_put_uint16_t(buf, 34, product_id);
  99. _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
  100. _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
  101. _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
  102. _mav_put_uint8_t_array(buf, 60, uid2, 18);
  103. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  104. #else
  105. mavlink_autopilot_version_t packet;
  106. packet.capabilities = capabilities;
  107. packet.uid = uid;
  108. packet.flight_sw_version = flight_sw_version;
  109. packet.middleware_sw_version = middleware_sw_version;
  110. packet.os_sw_version = os_sw_version;
  111. packet.board_version = board_version;
  112. packet.vendor_id = vendor_id;
  113. packet.product_id = product_id;
  114. mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
  115. mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
  116. mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
  117. mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
  118. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  119. #endif
  120. msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
  121. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  122. }
  123. /**
  124. * @brief Pack a autopilot_version message on a channel
  125. * @param system_id ID of this system
  126. * @param component_id ID of this component (e.g. 200 for IMU)
  127. * @param chan The MAVLink channel this message will be sent over
  128. * @param msg The MAVLink message to compress the data into
  129. * @param capabilities Bitmap of capabilities
  130. * @param flight_sw_version Firmware version number
  131. * @param middleware_sw_version Middleware version number
  132. * @param os_sw_version Operating system version number
  133. * @param board_version HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt
  134. * @param flight_custom_version 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.
  135. * @param middleware_custom_version 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.
  136. * @param os_custom_version 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.
  137. * @param vendor_id ID of the board vendor
  138. * @param product_id ID of the product
  139. * @param uid UID if provided by hardware (see uid2)
  140. * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  141. * @return length of the message in bytes (excluding serial stream start sign)
  142. */
  143. static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  144. mavlink_message_t* msg,
  145. 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,const uint8_t *uid2)
  146. {
  147. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  148. char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
  149. _mav_put_uint64_t(buf, 0, capabilities);
  150. _mav_put_uint64_t(buf, 8, uid);
  151. _mav_put_uint32_t(buf, 16, flight_sw_version);
  152. _mav_put_uint32_t(buf, 20, middleware_sw_version);
  153. _mav_put_uint32_t(buf, 24, os_sw_version);
  154. _mav_put_uint32_t(buf, 28, board_version);
  155. _mav_put_uint16_t(buf, 32, vendor_id);
  156. _mav_put_uint16_t(buf, 34, product_id);
  157. _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
  158. _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
  159. _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
  160. _mav_put_uint8_t_array(buf, 60, uid2, 18);
  161. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  162. #else
  163. mavlink_autopilot_version_t packet;
  164. packet.capabilities = capabilities;
  165. packet.uid = uid;
  166. packet.flight_sw_version = flight_sw_version;
  167. packet.middleware_sw_version = middleware_sw_version;
  168. packet.os_sw_version = os_sw_version;
  169. packet.board_version = board_version;
  170. packet.vendor_id = vendor_id;
  171. packet.product_id = product_id;
  172. mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
  173. mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
  174. mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
  175. mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
  176. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  177. #endif
  178. msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
  179. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  180. }
  181. /**
  182. * @brief Encode a autopilot_version struct
  183. *
  184. * @param system_id ID of this system
  185. * @param component_id ID of this component (e.g. 200 for IMU)
  186. * @param msg The MAVLink message to compress the data into
  187. * @param autopilot_version C-struct to read the message contents from
  188. */
  189. 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)
  190. {
  191. 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, autopilot_version->uid2);
  192. }
  193. /**
  194. * @brief Encode a autopilot_version struct on a channel
  195. *
  196. * @param system_id ID of this system
  197. * @param component_id ID of this component (e.g. 200 for IMU)
  198. * @param chan The MAVLink channel this message will be sent over
  199. * @param msg The MAVLink message to compress the data into
  200. * @param autopilot_version C-struct to read the message contents from
  201. */
  202. 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)
  203. {
  204. 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, autopilot_version->uid2);
  205. }
  206. /**
  207. * @brief Send a autopilot_version message
  208. * @param chan MAVLink channel to send the message
  209. *
  210. * @param capabilities Bitmap of capabilities
  211. * @param flight_sw_version Firmware version number
  212. * @param middleware_sw_version Middleware version number
  213. * @param os_sw_version Operating system version number
  214. * @param board_version HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt
  215. * @param flight_custom_version 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.
  216. * @param middleware_custom_version 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.
  217. * @param os_custom_version 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.
  218. * @param vendor_id ID of the board vendor
  219. * @param product_id ID of the product
  220. * @param uid UID if provided by hardware (see uid2)
  221. * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  222. */
  223. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  224. 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, const uint8_t *uid2)
  225. {
  226. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  227. char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
  228. _mav_put_uint64_t(buf, 0, capabilities);
  229. _mav_put_uint64_t(buf, 8, uid);
  230. _mav_put_uint32_t(buf, 16, flight_sw_version);
  231. _mav_put_uint32_t(buf, 20, middleware_sw_version);
  232. _mav_put_uint32_t(buf, 24, os_sw_version);
  233. _mav_put_uint32_t(buf, 28, board_version);
  234. _mav_put_uint16_t(buf, 32, vendor_id);
  235. _mav_put_uint16_t(buf, 34, product_id);
  236. _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
  237. _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
  238. _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
  239. _mav_put_uint8_t_array(buf, 60, uid2, 18);
  240. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  241. #else
  242. mavlink_autopilot_version_t packet;
  243. packet.capabilities = capabilities;
  244. packet.uid = uid;
  245. packet.flight_sw_version = flight_sw_version;
  246. packet.middleware_sw_version = middleware_sw_version;
  247. packet.os_sw_version = os_sw_version;
  248. packet.board_version = board_version;
  249. packet.vendor_id = vendor_id;
  250. packet.product_id = product_id;
  251. mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
  252. mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
  253. mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
  254. mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
  255. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  256. #endif
  257. }
  258. /**
  259. * @brief Send a autopilot_version message
  260. * @param chan MAVLink channel to send the message
  261. * @param struct The MAVLink struct to serialize
  262. */
  263. static inline void mavlink_msg_autopilot_version_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_t* autopilot_version)
  264. {
  265. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  266. mavlink_msg_autopilot_version_send(chan, 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, autopilot_version->uid2);
  267. #else
  268. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)autopilot_version, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  269. #endif
  270. }
  271. #if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  272. /*
  273. This variant of _send() can be used to save stack space by re-using
  274. memory from the receive buffer. The caller provides a
  275. mavlink_message_t which is the size of a full mavlink message. This
  276. is usually the receive buffer for the channel, and allows a reply to an
  277. incoming message with minimum stack space usage.
  278. */
  279. 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, const uint8_t *uid2)
  280. {
  281. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  282. char *buf = (char *)msgbuf;
  283. _mav_put_uint64_t(buf, 0, capabilities);
  284. _mav_put_uint64_t(buf, 8, uid);
  285. _mav_put_uint32_t(buf, 16, flight_sw_version);
  286. _mav_put_uint32_t(buf, 20, middleware_sw_version);
  287. _mav_put_uint32_t(buf, 24, os_sw_version);
  288. _mav_put_uint32_t(buf, 28, board_version);
  289. _mav_put_uint16_t(buf, 32, vendor_id);
  290. _mav_put_uint16_t(buf, 34, product_id);
  291. _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
  292. _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
  293. _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
  294. _mav_put_uint8_t_array(buf, 60, uid2, 18);
  295. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  296. #else
  297. mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf;
  298. packet->capabilities = capabilities;
  299. packet->uid = uid;
  300. packet->flight_sw_version = flight_sw_version;
  301. packet->middleware_sw_version = middleware_sw_version;
  302. packet->os_sw_version = os_sw_version;
  303. packet->board_version = board_version;
  304. packet->vendor_id = vendor_id;
  305. packet->product_id = product_id;
  306. mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
  307. mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
  308. mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8);
  309. mav_array_memcpy(packet->uid2, uid2, sizeof(uint8_t)*18);
  310. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  311. #endif
  312. }
  313. #endif
  314. #endif
  315. // MESSAGE AUTOPILOT_VERSION UNPACKING
  316. /**
  317. * @brief Get field capabilities from autopilot_version message
  318. *
  319. * @return Bitmap of capabilities
  320. */
  321. static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg)
  322. {
  323. return _MAV_RETURN_uint64_t(msg, 0);
  324. }
  325. /**
  326. * @brief Get field flight_sw_version from autopilot_version message
  327. *
  328. * @return Firmware version number
  329. */
  330. static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg)
  331. {
  332. return _MAV_RETURN_uint32_t(msg, 16);
  333. }
  334. /**
  335. * @brief Get field middleware_sw_version from autopilot_version message
  336. *
  337. * @return Middleware version number
  338. */
  339. static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg)
  340. {
  341. return _MAV_RETURN_uint32_t(msg, 20);
  342. }
  343. /**
  344. * @brief Get field os_sw_version from autopilot_version message
  345. *
  346. * @return Operating system version number
  347. */
  348. static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg)
  349. {
  350. return _MAV_RETURN_uint32_t(msg, 24);
  351. }
  352. /**
  353. * @brief Get field board_version from autopilot_version message
  354. *
  355. * @return HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt
  356. */
  357. static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg)
  358. {
  359. return _MAV_RETURN_uint32_t(msg, 28);
  360. }
  361. /**
  362. * @brief Get field flight_custom_version from autopilot_version message
  363. *
  364. * @return 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.
  365. */
  366. static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version)
  367. {
  368. return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36);
  369. }
  370. /**
  371. * @brief Get field middleware_custom_version from autopilot_version message
  372. *
  373. * @return 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.
  374. */
  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. /**
  380. * @brief Get field os_custom_version from autopilot_version message
  381. *
  382. * @return 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.
  383. */
  384. static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version)
  385. {
  386. return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52);
  387. }
  388. /**
  389. * @brief Get field vendor_id from autopilot_version message
  390. *
  391. * @return ID of the board vendor
  392. */
  393. static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg)
  394. {
  395. return _MAV_RETURN_uint16_t(msg, 32);
  396. }
  397. /**
  398. * @brief Get field product_id from autopilot_version message
  399. *
  400. * @return ID of the product
  401. */
  402. static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg)
  403. {
  404. return _MAV_RETURN_uint16_t(msg, 34);
  405. }
  406. /**
  407. * @brief Get field uid from autopilot_version message
  408. *
  409. * @return UID if provided by hardware (see uid2)
  410. */
  411. static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg)
  412. {
  413. return _MAV_RETURN_uint64_t(msg, 8);
  414. }
  415. /**
  416. * @brief Get field uid2 from autopilot_version message
  417. *
  418. * @return UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  419. */
  420. static inline uint16_t mavlink_msg_autopilot_version_get_uid2(const mavlink_message_t* msg, uint8_t *uid2)
  421. {
  422. return _MAV_RETURN_uint8_t_array(msg, uid2, 18, 60);
  423. }
  424. /**
  425. * @brief Decode a autopilot_version message into a struct
  426. *
  427. * @param msg The message to decode
  428. * @param autopilot_version C-struct to decode the message contents into
  429. */
  430. static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version)
  431. {
  432. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  433. autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg);
  434. autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg);
  435. autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg);
  436. autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg);
  437. autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg);
  438. autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg);
  439. autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg);
  440. autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg);
  441. mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version);
  442. mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version);
  443. mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version);
  444. mavlink_msg_autopilot_version_get_uid2(msg, autopilot_version->uid2);
  445. #else
  446. uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN;
  447. memset(autopilot_version, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  448. memcpy(autopilot_version, _MAV_PAYLOAD(msg), len);
  449. #endif
  450. }