mavlink_msg_heartbeat.h 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335
  1. #pragma once
  2. // MESSAGE HEARTBEAT PACKING
  3. #define MAVLINK_MSG_ID_HEARTBEAT 0
  4. typedef struct __mavlink_heartbeat_t {
  5. uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags*/
  6. uint8_t type; /*< Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.*/
  7. uint8_t autopilot; /*< Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.*/
  8. uint8_t base_mode; /*< System mode bitmap.*/
  9. uint8_t system_status; /*< System status flag.*/
  10. uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/
  11. } mavlink_heartbeat_t;
  12. #define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
  13. #define MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN 9
  14. #define MAVLINK_MSG_ID_0_LEN 9
  15. #define MAVLINK_MSG_ID_0_MIN_LEN 9
  16. #define MAVLINK_MSG_ID_HEARTBEAT_CRC 50
  17. #define MAVLINK_MSG_ID_0_CRC 50
  18. #if MAVLINK_COMMAND_24BIT
  19. #define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
  20. 0, \
  21. "HEARTBEAT", \
  22. 6, \
  23. { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
  24. { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
  25. { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
  26. { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
  27. { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
  28. { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
  29. } \
  30. }
  31. #else
  32. #define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
  33. "HEARTBEAT", \
  34. 6, \
  35. { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
  36. { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
  37. { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
  38. { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
  39. { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
  40. { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
  41. } \
  42. }
  43. #endif
  44. /**
  45. * @brief Pack a heartbeat message
  46. * @param system_id ID of this system
  47. * @param component_id ID of this component (e.g. 200 for IMU)
  48. * @param msg The MAVLink message to compress the data into
  49. *
  50. * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
  51. * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
  52. * @param base_mode System mode bitmap.
  53. * @param custom_mode A bitfield for use for autopilot-specific flags
  54. * @param system_status System status flag.
  55. * @return length of the message in bytes (excluding serial stream start sign)
  56. */
  57. static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
  58. uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
  59. {
  60. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  61. char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
  62. _mav_put_uint32_t(buf, 0, custom_mode);
  63. _mav_put_uint8_t(buf, 4, type);
  64. _mav_put_uint8_t(buf, 5, autopilot);
  65. _mav_put_uint8_t(buf, 6, base_mode);
  66. _mav_put_uint8_t(buf, 7, system_status);
  67. _mav_put_uint8_t(buf, 8, 3);
  68. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
  69. #else
  70. mavlink_heartbeat_t packet;
  71. packet.custom_mode = custom_mode;
  72. packet.type = type;
  73. packet.autopilot = autopilot;
  74. packet.base_mode = base_mode;
  75. packet.system_status = system_status;
  76. packet.mavlink_version = 3;
  77. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
  78. #endif
  79. msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
  80. return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
  81. }
  82. /**
  83. * @brief Pack a heartbeat message on a channel
  84. * @param system_id ID of this system
  85. * @param component_id ID of this component (e.g. 200 for IMU)
  86. * @param chan The MAVLink channel this message will be sent over
  87. * @param msg The MAVLink message to compress the data into
  88. * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
  89. * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
  90. * @param base_mode System mode bitmap.
  91. * @param custom_mode A bitfield for use for autopilot-specific flags
  92. * @param system_status System status flag.
  93. * @return length of the message in bytes (excluding serial stream start sign)
  94. */
  95. static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  96. mavlink_message_t* msg,
  97. uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status)
  98. {
  99. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  100. char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
  101. _mav_put_uint32_t(buf, 0, custom_mode);
  102. _mav_put_uint8_t(buf, 4, type);
  103. _mav_put_uint8_t(buf, 5, autopilot);
  104. _mav_put_uint8_t(buf, 6, base_mode);
  105. _mav_put_uint8_t(buf, 7, system_status);
  106. _mav_put_uint8_t(buf, 8, 3);
  107. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
  108. #else
  109. mavlink_heartbeat_t packet;
  110. packet.custom_mode = custom_mode;
  111. packet.type = type;
  112. packet.autopilot = autopilot;
  113. packet.base_mode = base_mode;
  114. packet.system_status = system_status;
  115. packet.mavlink_version = 3;
  116. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
  117. #endif
  118. msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
  119. return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
  120. }
  121. /**
  122. * @brief Encode a heartbeat struct
  123. *
  124. * @param system_id ID of this system
  125. * @param component_id ID of this component (e.g. 200 for IMU)
  126. * @param msg The MAVLink message to compress the data into
  127. * @param heartbeat C-struct to read the message contents from
  128. */
  129. static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
  130. {
  131. return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
  132. }
  133. /**
  134. * @brief Encode a heartbeat struct on a channel
  135. *
  136. * @param system_id ID of this system
  137. * @param component_id ID of this component (e.g. 200 for IMU)
  138. * @param chan The MAVLink channel this message will be sent over
  139. * @param msg The MAVLink message to compress the data into
  140. * @param heartbeat C-struct to read the message contents from
  141. */
  142. static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
  143. {
  144. return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
  145. }
  146. /**
  147. * @brief Send a heartbeat message
  148. * @param chan MAVLink channel to send the message
  149. *
  150. * @param type Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
  151. * @param autopilot Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
  152. * @param base_mode System mode bitmap.
  153. * @param custom_mode A bitfield for use for autopilot-specific flags
  154. * @param system_status System status flag.
  155. */
  156. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  157. static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
  158. {
  159. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  160. char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN];
  161. _mav_put_uint32_t(buf, 0, custom_mode);
  162. _mav_put_uint8_t(buf, 4, type);
  163. _mav_put_uint8_t(buf, 5, autopilot);
  164. _mav_put_uint8_t(buf, 6, base_mode);
  165. _mav_put_uint8_t(buf, 7, system_status);
  166. _mav_put_uint8_t(buf, 8, 3);
  167. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
  168. #else
  169. mavlink_heartbeat_t packet;
  170. packet.custom_mode = custom_mode;
  171. packet.type = type;
  172. packet.autopilot = autopilot;
  173. packet.base_mode = base_mode;
  174. packet.system_status = system_status;
  175. packet.mavlink_version = 3;
  176. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
  177. #endif
  178. }
  179. /**
  180. * @brief Send a heartbeat message
  181. * @param chan MAVLink channel to send the message
  182. * @param struct The MAVLink struct to serialize
  183. */
  184. static inline void mavlink_msg_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_heartbeat_t* heartbeat)
  185. {
  186. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  187. mavlink_msg_heartbeat_send(chan, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
  188. #else
  189. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)heartbeat, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
  190. #endif
  191. }
  192. #if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  193. /*
  194. This variant of _send() can be used to save stack space by re-using
  195. memory from the receive buffer. The caller provides a
  196. mavlink_message_t which is the size of a full mavlink message. This
  197. is usually the receive buffer for the channel, and allows a reply to an
  198. incoming message with minimum stack space usage.
  199. */
  200. static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
  201. {
  202. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  203. char *buf = (char *)msgbuf;
  204. _mav_put_uint32_t(buf, 0, custom_mode);
  205. _mav_put_uint8_t(buf, 4, type);
  206. _mav_put_uint8_t(buf, 5, autopilot);
  207. _mav_put_uint8_t(buf, 6, base_mode);
  208. _mav_put_uint8_t(buf, 7, system_status);
  209. _mav_put_uint8_t(buf, 8, 3);
  210. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
  211. #else
  212. mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf;
  213. packet->custom_mode = custom_mode;
  214. packet->type = type;
  215. packet->autopilot = autopilot;
  216. packet->base_mode = base_mode;
  217. packet->system_status = system_status;
  218. packet->mavlink_version = 3;
  219. _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
  220. #endif
  221. }
  222. #endif
  223. #endif
  224. // MESSAGE HEARTBEAT UNPACKING
  225. /**
  226. * @brief Get field type from heartbeat message
  227. *
  228. * @return Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type.
  229. */
  230. static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
  231. {
  232. return _MAV_RETURN_uint8_t(msg, 4);
  233. }
  234. /**
  235. * @brief Get field autopilot from heartbeat message
  236. *
  237. * @return Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers.
  238. */
  239. static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
  240. {
  241. return _MAV_RETURN_uint8_t(msg, 5);
  242. }
  243. /**
  244. * @brief Get field base_mode from heartbeat message
  245. *
  246. * @return System mode bitmap.
  247. */
  248. static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
  249. {
  250. return _MAV_RETURN_uint8_t(msg, 6);
  251. }
  252. /**
  253. * @brief Get field custom_mode from heartbeat message
  254. *
  255. * @return A bitfield for use for autopilot-specific flags
  256. */
  257. static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
  258. {
  259. return _MAV_RETURN_uint32_t(msg, 0);
  260. }
  261. /**
  262. * @brief Get field system_status from heartbeat message
  263. *
  264. * @return System status flag.
  265. */
  266. static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
  267. {
  268. return _MAV_RETURN_uint8_t(msg, 7);
  269. }
  270. /**
  271. * @brief Get field mavlink_version from heartbeat message
  272. *
  273. * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
  274. */
  275. static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
  276. {
  277. return _MAV_RETURN_uint8_t(msg, 8);
  278. }
  279. /**
  280. * @brief Decode a heartbeat message into a struct
  281. *
  282. * @param msg The message to decode
  283. * @param heartbeat C-struct to decode the message contents into
  284. */
  285. static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
  286. {
  287. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  288. heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg);
  289. heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
  290. heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
  291. heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg);
  292. heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
  293. heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
  294. #else
  295. uint8_t len = msg->len < MAVLINK_MSG_ID_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_HEARTBEAT_LEN;
  296. memset(heartbeat, 0, MAVLINK_MSG_ID_HEARTBEAT_LEN);
  297. memcpy(heartbeat, _MAV_PAYLOAD(msg), len);
  298. #endif
  299. }