mavlink_msg_autopilot_version.h 34 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561
  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
  125. * @param system_id ID of this system
  126. * @param component_id ID of this component (e.g. 200 for IMU)
  127. * @param status MAVLink status structure
  128. * @param msg The MAVLink message to compress the data into
  129. *
  130. * @param capabilities Bitmap of capabilities
  131. * @param flight_sw_version Firmware version number
  132. * @param middleware_sw_version Middleware version number
  133. * @param os_sw_version Operating system version number
  134. * @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
  135. * @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.
  136. * @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.
  137. * @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.
  138. * @param vendor_id ID of the board vendor
  139. * @param product_id ID of the product
  140. * @param uid UID if provided by hardware (see uid2)
  141. * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  142. * @return length of the message in bytes (excluding serial stream start sign)
  143. */
  144. static inline uint16_t mavlink_msg_autopilot_version_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, 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. #if MAVLINK_CRC_EXTRA
  180. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
  181. #else
  182. return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  183. #endif
  184. }
  185. /**
  186. * @brief Pack a autopilot_version message on a channel
  187. * @param system_id ID of this system
  188. * @param component_id ID of this component (e.g. 200 for IMU)
  189. * @param chan The MAVLink channel this message will be sent over
  190. * @param msg The MAVLink message to compress the data into
  191. * @param capabilities Bitmap of capabilities
  192. * @param flight_sw_version Firmware version number
  193. * @param middleware_sw_version Middleware version number
  194. * @param os_sw_version Operating system version number
  195. * @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
  196. * @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.
  197. * @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.
  198. * @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.
  199. * @param vendor_id ID of the board vendor
  200. * @param product_id ID of the product
  201. * @param uid UID if provided by hardware (see uid2)
  202. * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  203. * @return length of the message in bytes (excluding serial stream start sign)
  204. */
  205. static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  206. mavlink_message_t* msg,
  207. 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)
  208. {
  209. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  210. char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
  211. _mav_put_uint64_t(buf, 0, capabilities);
  212. _mav_put_uint64_t(buf, 8, uid);
  213. _mav_put_uint32_t(buf, 16, flight_sw_version);
  214. _mav_put_uint32_t(buf, 20, middleware_sw_version);
  215. _mav_put_uint32_t(buf, 24, os_sw_version);
  216. _mav_put_uint32_t(buf, 28, board_version);
  217. _mav_put_uint16_t(buf, 32, vendor_id);
  218. _mav_put_uint16_t(buf, 34, product_id);
  219. _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
  220. _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
  221. _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
  222. _mav_put_uint8_t_array(buf, 60, uid2, 18);
  223. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  224. #else
  225. mavlink_autopilot_version_t packet;
  226. packet.capabilities = capabilities;
  227. packet.uid = uid;
  228. packet.flight_sw_version = flight_sw_version;
  229. packet.middleware_sw_version = middleware_sw_version;
  230. packet.os_sw_version = os_sw_version;
  231. packet.board_version = board_version;
  232. packet.vendor_id = vendor_id;
  233. packet.product_id = product_id;
  234. mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
  235. mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
  236. mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
  237. mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
  238. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  239. #endif
  240. msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
  241. 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);
  242. }
  243. /**
  244. * @brief Encode a autopilot_version struct
  245. *
  246. * @param system_id ID of this system
  247. * @param component_id ID of this component (e.g. 200 for IMU)
  248. * @param msg The MAVLink message to compress the data into
  249. * @param autopilot_version C-struct to read the message contents from
  250. */
  251. 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)
  252. {
  253. 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);
  254. }
  255. /**
  256. * @brief Encode a autopilot_version struct on a channel
  257. *
  258. * @param system_id ID of this system
  259. * @param component_id ID of this component (e.g. 200 for IMU)
  260. * @param chan The MAVLink channel this message will be sent over
  261. * @param msg The MAVLink message to compress the data into
  262. * @param autopilot_version C-struct to read the message contents from
  263. */
  264. 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)
  265. {
  266. 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);
  267. }
  268. /**
  269. * @brief Encode a autopilot_version struct with provided status structure
  270. *
  271. * @param system_id ID of this system
  272. * @param component_id ID of this component (e.g. 200 for IMU)
  273. * @param status MAVLink status structure
  274. * @param msg The MAVLink message to compress the data into
  275. * @param autopilot_version C-struct to read the message contents from
  276. */
  277. static inline uint16_t mavlink_msg_autopilot_version_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version)
  278. {
  279. return mavlink_msg_autopilot_version_pack_status(system_id, component_id, _status, 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);
  280. }
  281. /**
  282. * @brief Send a autopilot_version message
  283. * @param chan MAVLink channel to send the message
  284. *
  285. * @param capabilities Bitmap of capabilities
  286. * @param flight_sw_version Firmware version number
  287. * @param middleware_sw_version Middleware version number
  288. * @param os_sw_version Operating system version number
  289. * @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
  290. * @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.
  291. * @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.
  292. * @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.
  293. * @param vendor_id ID of the board vendor
  294. * @param product_id ID of the product
  295. * @param uid UID if provided by hardware (see uid2)
  296. * @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  297. */
  298. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  299. 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)
  300. {
  301. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  302. char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
  303. _mav_put_uint64_t(buf, 0, capabilities);
  304. _mav_put_uint64_t(buf, 8, uid);
  305. _mav_put_uint32_t(buf, 16, flight_sw_version);
  306. _mav_put_uint32_t(buf, 20, middleware_sw_version);
  307. _mav_put_uint32_t(buf, 24, os_sw_version);
  308. _mav_put_uint32_t(buf, 28, board_version);
  309. _mav_put_uint16_t(buf, 32, vendor_id);
  310. _mav_put_uint16_t(buf, 34, product_id);
  311. _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
  312. _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
  313. _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
  314. _mav_put_uint8_t_array(buf, 60, uid2, 18);
  315. _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);
  316. #else
  317. mavlink_autopilot_version_t packet;
  318. packet.capabilities = capabilities;
  319. packet.uid = uid;
  320. packet.flight_sw_version = flight_sw_version;
  321. packet.middleware_sw_version = middleware_sw_version;
  322. packet.os_sw_version = os_sw_version;
  323. packet.board_version = board_version;
  324. packet.vendor_id = vendor_id;
  325. packet.product_id = product_id;
  326. mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
  327. mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
  328. mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
  329. mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
  330. _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);
  331. #endif
  332. }
  333. /**
  334. * @brief Send a autopilot_version message
  335. * @param chan MAVLink channel to send the message
  336. * @param struct The MAVLink struct to serialize
  337. */
  338. static inline void mavlink_msg_autopilot_version_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_t* autopilot_version)
  339. {
  340. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  341. 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);
  342. #else
  343. _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);
  344. #endif
  345. }
  346. #if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  347. /*
  348. This variant of _send() can be used to save stack space by re-using
  349. memory from the receive buffer. The caller provides a
  350. mavlink_message_t which is the size of a full mavlink message. This
  351. is usually the receive buffer for the channel, and allows a reply to an
  352. incoming message with minimum stack space usage.
  353. */
  354. 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)
  355. {
  356. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  357. char *buf = (char *)msgbuf;
  358. _mav_put_uint64_t(buf, 0, capabilities);
  359. _mav_put_uint64_t(buf, 8, uid);
  360. _mav_put_uint32_t(buf, 16, flight_sw_version);
  361. _mav_put_uint32_t(buf, 20, middleware_sw_version);
  362. _mav_put_uint32_t(buf, 24, os_sw_version);
  363. _mav_put_uint32_t(buf, 28, board_version);
  364. _mav_put_uint16_t(buf, 32, vendor_id);
  365. _mav_put_uint16_t(buf, 34, product_id);
  366. _mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
  367. _mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
  368. _mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
  369. _mav_put_uint8_t_array(buf, 60, uid2, 18);
  370. _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);
  371. #else
  372. mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf;
  373. packet->capabilities = capabilities;
  374. packet->uid = uid;
  375. packet->flight_sw_version = flight_sw_version;
  376. packet->middleware_sw_version = middleware_sw_version;
  377. packet->os_sw_version = os_sw_version;
  378. packet->board_version = board_version;
  379. packet->vendor_id = vendor_id;
  380. packet->product_id = product_id;
  381. mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
  382. mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
  383. mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8);
  384. mav_array_memcpy(packet->uid2, uid2, sizeof(uint8_t)*18);
  385. _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);
  386. #endif
  387. }
  388. #endif
  389. #endif
  390. // MESSAGE AUTOPILOT_VERSION UNPACKING
  391. /**
  392. * @brief Get field capabilities from autopilot_version message
  393. *
  394. * @return Bitmap of capabilities
  395. */
  396. static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg)
  397. {
  398. return _MAV_RETURN_uint64_t(msg, 0);
  399. }
  400. /**
  401. * @brief Get field flight_sw_version from autopilot_version message
  402. *
  403. * @return Firmware version number
  404. */
  405. static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg)
  406. {
  407. return _MAV_RETURN_uint32_t(msg, 16);
  408. }
  409. /**
  410. * @brief Get field middleware_sw_version from autopilot_version message
  411. *
  412. * @return Middleware version number
  413. */
  414. static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg)
  415. {
  416. return _MAV_RETURN_uint32_t(msg, 20);
  417. }
  418. /**
  419. * @brief Get field os_sw_version from autopilot_version message
  420. *
  421. * @return Operating system version number
  422. */
  423. static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg)
  424. {
  425. return _MAV_RETURN_uint32_t(msg, 24);
  426. }
  427. /**
  428. * @brief Get field board_version from autopilot_version message
  429. *
  430. * @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
  431. */
  432. static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg)
  433. {
  434. return _MAV_RETURN_uint32_t(msg, 28);
  435. }
  436. /**
  437. * @brief Get field flight_custom_version from autopilot_version message
  438. *
  439. * @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.
  440. */
  441. static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version)
  442. {
  443. return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36);
  444. }
  445. /**
  446. * @brief Get field middleware_custom_version from autopilot_version message
  447. *
  448. * @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.
  449. */
  450. static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version)
  451. {
  452. return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44);
  453. }
  454. /**
  455. * @brief Get field os_custom_version from autopilot_version message
  456. *
  457. * @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.
  458. */
  459. static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version)
  460. {
  461. return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52);
  462. }
  463. /**
  464. * @brief Get field vendor_id from autopilot_version message
  465. *
  466. * @return ID of the board vendor
  467. */
  468. static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg)
  469. {
  470. return _MAV_RETURN_uint16_t(msg, 32);
  471. }
  472. /**
  473. * @brief Get field product_id from autopilot_version message
  474. *
  475. * @return ID of the product
  476. */
  477. static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg)
  478. {
  479. return _MAV_RETURN_uint16_t(msg, 34);
  480. }
  481. /**
  482. * @brief Get field uid from autopilot_version message
  483. *
  484. * @return UID if provided by hardware (see uid2)
  485. */
  486. static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg)
  487. {
  488. return _MAV_RETURN_uint64_t(msg, 8);
  489. }
  490. /**
  491. * @brief Get field uid2 from autopilot_version message
  492. *
  493. * @return UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
  494. */
  495. static inline uint16_t mavlink_msg_autopilot_version_get_uid2(const mavlink_message_t* msg, uint8_t *uid2)
  496. {
  497. return _MAV_RETURN_uint8_t_array(msg, uid2, 18, 60);
  498. }
  499. /**
  500. * @brief Decode a autopilot_version message into a struct
  501. *
  502. * @param msg The message to decode
  503. * @param autopilot_version C-struct to decode the message contents into
  504. */
  505. static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version)
  506. {
  507. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  508. autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg);
  509. autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg);
  510. autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg);
  511. autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg);
  512. autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg);
  513. autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg);
  514. autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg);
  515. autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg);
  516. mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version);
  517. mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version);
  518. mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version);
  519. mavlink_msg_autopilot_version_get_uid2(msg, autopilot_version->uid2);
  520. #else
  521. uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN;
  522. memset(autopilot_version, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
  523. memcpy(autopilot_version, _MAV_PAYLOAD(msg), len);
  524. #endif
  525. }