mavlink_msg_heartbeat.h
Go to the documentation of this file.
1 // MESSAGE HEARTBEAT PACKING
2 
3 #define MAVLINK_MSG_ID_HEARTBEAT 0
4 
5 typedef struct __mavlink_heartbeat_t
6 {
7  uint32_t custom_mode; /*< A bitfield for use for autopilot-specific flags.*/
8  uint8_t type; /*< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)*/
9  uint8_t autopilot; /*< Autopilot type / class. defined in MAV_AUTOPILOT ENUM*/
10  uint8_t base_mode; /*< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h*/
11  uint8_t system_status; /*< System status flag, see MAV_STATE ENUM*/
12  uint8_t mavlink_version; /*< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version*/
14 
15 #define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
16 #define MAVLINK_MSG_ID_0_LEN 9
17 
18 #define MAVLINK_MSG_ID_HEARTBEAT_CRC 50
19 #define MAVLINK_MSG_ID_0_CRC 50
20 
21 
22 
23 #define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
24  "HEARTBEAT", \
25  6, \
26  { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
27  { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
28  { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
29  { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
30  { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
31  { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
32  } \
33 }
34 
35 
49 static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
50  uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
51 {
52 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
54  _mav_put_uint32_t(buf, 0, custom_mode);
55  _mav_put_uint8_t(buf, 4, type);
56  _mav_put_uint8_t(buf, 5, autopilot);
57  _mav_put_uint8_t(buf, 6, base_mode);
58  _mav_put_uint8_t(buf, 7, system_status);
59  _mav_put_uint8_t(buf, 8, 3);
60 
62 #else
63  mavlink_heartbeat_t packet;
64  packet.custom_mode = custom_mode;
65  packet.type = type;
66  packet.autopilot = autopilot;
67  packet.base_mode = base_mode;
69  packet.mavlink_version = 3;
70 
72 #endif
73 
74  msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
75 #if MAVLINK_CRC_EXTRA
77 #else
78  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN);
79 #endif
80 }
81 
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
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 
109 #else
110  mavlink_heartbeat_t packet;
111  packet.custom_mode = custom_mode;
112  packet.type = type;
113  packet.autopilot = autopilot;
114  packet.base_mode = base_mode;
115  packet.system_status = system_status;
116  packet.mavlink_version = 3;
117 
119 #endif
120 
121  msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
122 #if MAVLINK_CRC_EXTRA
124 #else
125  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN);
126 #endif
127 }
128 
137 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)
138 {
139  return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
140 }
141 
151 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)
152 {
153  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);
154 }
155 
166 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
167 
168 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)
169 {
170 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
173  _mav_put_uint8_t(buf, 4, type);
174  _mav_put_uint8_t(buf, 5, autopilot);
175  _mav_put_uint8_t(buf, 6, base_mode);
176  _mav_put_uint8_t(buf, 7, system_status);
177  _mav_put_uint8_t(buf, 8, 3);
178 
179 #if MAVLINK_CRC_EXTRA
180  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
181 #else
182  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
183 #endif
184 #else
185  mavlink_heartbeat_t packet;
186  packet.custom_mode = custom_mode;
187  packet.type = type;
188  packet.autopilot = autopilot;
189  packet.base_mode = base_mode;
190  packet.system_status = system_status;
191  packet.mavlink_version = 3;
192 
193 #if MAVLINK_CRC_EXTRA
194  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
195 #else
196  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
197 #endif
198 #endif
199 }
200 
201 #if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
202 /*
203  This varient of _send() can be used to save stack space by re-using
204  memory from the receive buffer. The caller provides a
205  mavlink_message_t which is the size of a full mavlink message. This
206  is usually the receive buffer for the channel, and allows a reply to an
207  incoming message with minimum stack space usage.
208  */
209 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)
210 {
211 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
212  char *buf = (char *)msgbuf;
214  _mav_put_uint8_t(buf, 4, type);
215  _mav_put_uint8_t(buf, 5, autopilot);
216  _mav_put_uint8_t(buf, 6, base_mode);
217  _mav_put_uint8_t(buf, 7, system_status);
218  _mav_put_uint8_t(buf, 8, 3);
219 
220 #if MAVLINK_CRC_EXTRA
221  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
222 #else
223  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
224 #endif
225 #else
226  mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf;
227  packet->custom_mode = custom_mode;
228  packet->type = type;
229  packet->autopilot = autopilot;
230  packet->base_mode = base_mode;
231  packet->system_status = system_status;
232  packet->mavlink_version = 3;
233 
234 #if MAVLINK_CRC_EXTRA
235  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
236 #else
237  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
238 #endif
239 #endif
240 }
241 #endif
242 
243 #endif
244 
245 // MESSAGE HEARTBEAT UNPACKING
246 
247 
253 static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
254 {
255  return _MAV_RETURN_uint8_t(msg, 4);
256 }
257 
263 static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
264 {
265  return _MAV_RETURN_uint8_t(msg, 5);
266 }
267 
273 static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
274 {
275  return _MAV_RETURN_uint8_t(msg, 6);
276 }
277 
283 static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
284 {
285  return _MAV_RETURN_uint32_t(msg, 0);
286 }
287 
293 static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
294 {
295  return _MAV_RETURN_uint8_t(msg, 7);
296 }
297 
303 static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
304 {
305  return _MAV_RETURN_uint8_t(msg, 8);
306 }
307 
314 static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
315 {
316 #if MAVLINK_NEED_BYTE_SWAP
318  heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
323 #else
324  memcpy(heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HEARTBEAT_LEN);
325 #endif
326 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13