mavlink_msg_protocol_version.h 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306
  1. #pragma once
  2. // MESSAGE PROTOCOL_VERSION PACKING
  3. #define MAVLINK_MSG_ID_PROTOCOL_VERSION 300
  4. typedef struct __mavlink_protocol_version_t {
  5. uint16_t version; /*< Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.*/
  6. uint16_t min_version; /*< Minimum MAVLink version supported*/
  7. uint16_t max_version; /*< Maximum MAVLink version supported (set to the same value as version by default)*/
  8. uint8_t spec_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/
  9. uint8_t library_version_hash[8]; /*< The first 8 bytes (not characters printed in hex!) of the git hash.*/
  10. } mavlink_protocol_version_t;
  11. #define MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN 22
  12. #define MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN 22
  13. #define MAVLINK_MSG_ID_300_LEN 22
  14. #define MAVLINK_MSG_ID_300_MIN_LEN 22
  15. #define MAVLINK_MSG_ID_PROTOCOL_VERSION_CRC 217
  16. #define MAVLINK_MSG_ID_300_CRC 217
  17. #define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_SPEC_VERSION_HASH_LEN 8
  18. #define MAVLINK_MSG_PROTOCOL_VERSION_FIELD_LIBRARY_VERSION_HASH_LEN 8
  19. #if MAVLINK_COMMAND_24BIT
  20. #define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \
  21. 300, \
  22. "PROTOCOL_VERSION", \
  23. 5, \
  24. { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \
  25. { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \
  26. { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \
  27. { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \
  28. { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \
  29. } \
  30. }
  31. #else
  32. #define MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION { \
  33. "PROTOCOL_VERSION", \
  34. 5, \
  35. { { "version", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_protocol_version_t, version) }, \
  36. { "min_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_protocol_version_t, min_version) }, \
  37. { "max_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_protocol_version_t, max_version) }, \
  38. { "spec_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 6, offsetof(mavlink_protocol_version_t, spec_version_hash) }, \
  39. { "library_version_hash", NULL, MAVLINK_TYPE_UINT8_T, 8, 14, offsetof(mavlink_protocol_version_t, library_version_hash) }, \
  40. } \
  41. }
  42. #endif
  43. /**
  44. * @brief Pack a protocol_version message
  45. * @param system_id ID of this system
  46. * @param component_id ID of this component (e.g. 200 for IMU)
  47. * @param msg The MAVLink message to compress the data into
  48. *
  49. * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
  50. * @param min_version Minimum MAVLink version supported
  51. * @param max_version Maximum MAVLink version supported (set to the same value as version by default)
  52. * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
  53. * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
  54. * @return length of the message in bytes (excluding serial stream start sign)
  55. */
  56. static inline uint16_t mavlink_msg_protocol_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  57. uint16_t version, uint16_t min_version, uint16_t max_version, const uint8_t *spec_version_hash, const uint8_t *library_version_hash)
  58. {
  59. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  60. char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN];
  61. _mav_put_uint16_t(buf, 0, version);
  62. _mav_put_uint16_t(buf, 2, min_version);
  63. _mav_put_uint16_t(buf, 4, max_version);
  64. _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
  65. _mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
  66. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
  67. #else
  68. mavlink_protocol_version_t packet;
  69. packet.version = version;
  70. packet.min_version = min_version;
  71. packet.max_version = max_version;
  72. mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
  73. mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8);
  74. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
  75. #endif
  76. msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION;
  77. 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);
  78. }
  79. /**
  80. * @brief Pack a protocol_version message on a channel
  81. * @param system_id ID of this system
  82. * @param component_id ID of this component (e.g. 200 for IMU)
  83. * @param chan The MAVLink channel this message will be sent over
  84. * @param msg The MAVLink message to compress the data into
  85. * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
  86. * @param min_version Minimum MAVLink version supported
  87. * @param max_version Maximum MAVLink version supported (set to the same value as version by default)
  88. * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
  89. * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
  90. * @return length of the message in bytes (excluding serial stream start sign)
  91. */
  92. static inline uint16_t mavlink_msg_protocol_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  93. mavlink_message_t* msg,
  94. uint16_t version,uint16_t min_version,uint16_t max_version,const uint8_t *spec_version_hash,const uint8_t *library_version_hash)
  95. {
  96. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  97. char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN];
  98. _mav_put_uint16_t(buf, 0, version);
  99. _mav_put_uint16_t(buf, 2, min_version);
  100. _mav_put_uint16_t(buf, 4, max_version);
  101. _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
  102. _mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
  103. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
  104. #else
  105. mavlink_protocol_version_t packet;
  106. packet.version = version;
  107. packet.min_version = min_version;
  108. packet.max_version = max_version;
  109. mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
  110. mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8);
  111. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
  112. #endif
  113. msg->msgid = MAVLINK_MSG_ID_PROTOCOL_VERSION;
  114. 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);
  115. }
  116. /**
  117. * @brief Encode a protocol_version struct
  118. *
  119. * @param system_id ID of this system
  120. * @param component_id ID of this component (e.g. 200 for IMU)
  121. * @param msg The MAVLink message to compress the data into
  122. * @param protocol_version C-struct to read the message contents from
  123. */
  124. 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)
  125. {
  126. 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);
  127. }
  128. /**
  129. * @brief Encode a protocol_version struct on a channel
  130. *
  131. * @param system_id ID of this system
  132. * @param component_id ID of this component (e.g. 200 for IMU)
  133. * @param chan The MAVLink channel this message will be sent over
  134. * @param msg The MAVLink message to compress the data into
  135. * @param protocol_version C-struct to read the message contents from
  136. */
  137. 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)
  138. {
  139. 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);
  140. }
  141. /**
  142. * @brief Send a protocol_version message
  143. * @param chan MAVLink channel to send the message
  144. *
  145. * @param version Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
  146. * @param min_version Minimum MAVLink version supported
  147. * @param max_version Maximum MAVLink version supported (set to the same value as version by default)
  148. * @param spec_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
  149. * @param library_version_hash The first 8 bytes (not characters printed in hex!) of the git hash.
  150. */
  151. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  152. 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)
  153. {
  154. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  155. char buf[MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN];
  156. _mav_put_uint16_t(buf, 0, version);
  157. _mav_put_uint16_t(buf, 2, min_version);
  158. _mav_put_uint16_t(buf, 4, max_version);
  159. _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
  160. _mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
  161. _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);
  162. #else
  163. mavlink_protocol_version_t packet;
  164. packet.version = version;
  165. packet.min_version = min_version;
  166. packet.max_version = max_version;
  167. mav_array_memcpy(packet.spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
  168. mav_array_memcpy(packet.library_version_hash, library_version_hash, sizeof(uint8_t)*8);
  169. _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);
  170. #endif
  171. }
  172. /**
  173. * @brief Send a protocol_version message
  174. * @param chan MAVLink channel to send the message
  175. * @param struct The MAVLink struct to serialize
  176. */
  177. static inline void mavlink_msg_protocol_version_send_struct(mavlink_channel_t chan, const mavlink_protocol_version_t* protocol_version)
  178. {
  179. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  180. 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);
  181. #else
  182. _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);
  183. #endif
  184. }
  185. #if MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  186. /*
  187. This variant of _send() can be used to save stack space by re-using
  188. memory from the receive buffer. The caller provides a
  189. mavlink_message_t which is the size of a full mavlink message. This
  190. is usually the receive buffer for the channel, and allows a reply to an
  191. incoming message with minimum stack space usage.
  192. */
  193. 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)
  194. {
  195. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  196. char *buf = (char *)msgbuf;
  197. _mav_put_uint16_t(buf, 0, version);
  198. _mav_put_uint16_t(buf, 2, min_version);
  199. _mav_put_uint16_t(buf, 4, max_version);
  200. _mav_put_uint8_t_array(buf, 6, spec_version_hash, 8);
  201. _mav_put_uint8_t_array(buf, 14, library_version_hash, 8);
  202. _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);
  203. #else
  204. mavlink_protocol_version_t *packet = (mavlink_protocol_version_t *)msgbuf;
  205. packet->version = version;
  206. packet->min_version = min_version;
  207. packet->max_version = max_version;
  208. mav_array_memcpy(packet->spec_version_hash, spec_version_hash, sizeof(uint8_t)*8);
  209. mav_array_memcpy(packet->library_version_hash, library_version_hash, sizeof(uint8_t)*8);
  210. _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);
  211. #endif
  212. }
  213. #endif
  214. #endif
  215. // MESSAGE PROTOCOL_VERSION UNPACKING
  216. /**
  217. * @brief Get field version from protocol_version message
  218. *
  219. * @return Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc.
  220. */
  221. static inline uint16_t mavlink_msg_protocol_version_get_version(const mavlink_message_t* msg)
  222. {
  223. return _MAV_RETURN_uint16_t(msg, 0);
  224. }
  225. /**
  226. * @brief Get field min_version from protocol_version message
  227. *
  228. * @return Minimum MAVLink version supported
  229. */
  230. static inline uint16_t mavlink_msg_protocol_version_get_min_version(const mavlink_message_t* msg)
  231. {
  232. return _MAV_RETURN_uint16_t(msg, 2);
  233. }
  234. /**
  235. * @brief Get field max_version from protocol_version message
  236. *
  237. * @return Maximum MAVLink version supported (set to the same value as version by default)
  238. */
  239. static inline uint16_t mavlink_msg_protocol_version_get_max_version(const mavlink_message_t* msg)
  240. {
  241. return _MAV_RETURN_uint16_t(msg, 4);
  242. }
  243. /**
  244. * @brief Get field spec_version_hash from protocol_version message
  245. *
  246. * @return The first 8 bytes (not characters printed in hex!) of the git hash.
  247. */
  248. static inline uint16_t mavlink_msg_protocol_version_get_spec_version_hash(const mavlink_message_t* msg, uint8_t *spec_version_hash)
  249. {
  250. return _MAV_RETURN_uint8_t_array(msg, spec_version_hash, 8, 6);
  251. }
  252. /**
  253. * @brief Get field library_version_hash from protocol_version message
  254. *
  255. * @return The first 8 bytes (not characters printed in hex!) of the git hash.
  256. */
  257. static inline uint16_t mavlink_msg_protocol_version_get_library_version_hash(const mavlink_message_t* msg, uint8_t *library_version_hash)
  258. {
  259. return _MAV_RETURN_uint8_t_array(msg, library_version_hash, 8, 14);
  260. }
  261. /**
  262. * @brief Decode a protocol_version message into a struct
  263. *
  264. * @param msg The message to decode
  265. * @param protocol_version C-struct to decode the message contents into
  266. */
  267. static inline void mavlink_msg_protocol_version_decode(const mavlink_message_t* msg, mavlink_protocol_version_t* protocol_version)
  268. {
  269. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  270. protocol_version->version = mavlink_msg_protocol_version_get_version(msg);
  271. protocol_version->min_version = mavlink_msg_protocol_version_get_min_version(msg);
  272. protocol_version->max_version = mavlink_msg_protocol_version_get_max_version(msg);
  273. mavlink_msg_protocol_version_get_spec_version_hash(msg, protocol_version->spec_version_hash);
  274. mavlink_msg_protocol_version_get_library_version_hash(msg, protocol_version->library_version_hash);
  275. #else
  276. uint8_t len = msg->len < MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN? msg->len : MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN;
  277. memset(protocol_version, 0, MAVLINK_MSG_ID_PROTOCOL_VERSION_LEN);
  278. memcpy(protocol_version, _MAV_PAYLOAD(msg), len);
  279. #endif
  280. }