mavlink_msg_heartbeat.h 9.37 KB
Newer Older
LM's avatar
LM committed
1 2 3 4
// MESSAGE HEARTBEAT PACKING

#define MAVLINK_MSG_ID_HEARTBEAT 0

lm's avatar
lm committed
5
typedef struct __mavlink_heartbeat_t
LM's avatar
LM committed
6
{
lm's avatar
lm committed
7
 uint32_t custom_mode; ///< Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
lm's avatar
lm committed
8 9
 uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
 uint8_t autopilot; ///< Autopilot type / class. defined in MAV_CLASS ENUM
lm's avatar
lm committed
10 11
 uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
 uint8_t system_status; ///< System status flag, see MAV_STATUS ENUM
lm's avatar
lm committed
12
 uint8_t mavlink_version; ///< MAVLink version
LM's avatar
LM committed
13 14
} mavlink_heartbeat_t;

lm's avatar
lm committed
15 16
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
#define MAVLINK_MSG_ID_0_LEN 9
lm's avatar
lm committed
17 18 19 20 21



#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
	"HEARTBEAT", \
lm's avatar
lm committed
22 23 24 25 26 27 28
	6, \
	{  { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
         { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
         { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
         { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
         { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
         { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
lm's avatar
lm committed
29 30 31 32
         } \
}


LM's avatar
LM committed
33 34 35 36 37 38 39
/**
 * @brief Pack a heartbeat message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
40
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
lm's avatar
lm committed
41 42 43
 * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
 * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
 * @param system_status System status flag, see MAV_STATUS ENUM
LM's avatar
LM committed
44 45
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
46
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
lm's avatar
lm committed
47
						       uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
LM's avatar
LM committed
48
{
LM's avatar
LM committed
49
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
50 51 52 53 54 55 56 57
	char buf[9];
	_mav_put_uint32_t(buf, 0, custom_mode);
	_mav_put_uint8_t(buf, 4, type);
	_mav_put_uint8_t(buf, 5, autopilot);
	_mav_put_uint8_t(buf, 6, base_mode);
	_mav_put_uint8_t(buf, 7, system_status);
	_mav_put_uint8_t(buf, 8, 2);

58
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
LM's avatar
LM committed
59 60
#else
	mavlink_heartbeat_t packet;
lm's avatar
lm committed
61
	packet.custom_mode = custom_mode;
LM's avatar
LM committed
62 63
	packet.type = type;
	packet.autopilot = autopilot;
lm's avatar
lm committed
64 65
	packet.base_mode = base_mode;
	packet.system_status = system_status;
LM's avatar
LM committed
66
	packet.mavlink_version = 2;
LM's avatar
LM committed
67

68
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
LM's avatar
LM committed
69
#endif
LM's avatar
LM committed
70

LM's avatar
LM committed
71
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
lm's avatar
lm committed
72
	return mavlink_finalize_message(msg, system_id, component_id, 9, 50);
LM's avatar
LM committed
73 74 75
}

/**
lm's avatar
lm committed
76
 * @brief Pack a heartbeat message on a channel
LM's avatar
LM committed
77 78 79 80 81
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message was sent over
 * @param msg The MAVLink message to compress the data into
 * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
82
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
lm's avatar
lm committed
83 84 85
 * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
 * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
 * @param system_status System status flag, see MAV_STATUS ENUM
LM's avatar
LM committed
86 87
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
88 89
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
lm's avatar
lm committed
90
						           uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status)
LM's avatar
LM committed
91
{
LM's avatar
LM committed
92
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
93 94 95 96 97 98 99 100
	char buf[9];
	_mav_put_uint32_t(buf, 0, custom_mode);
	_mav_put_uint8_t(buf, 4, type);
	_mav_put_uint8_t(buf, 5, autopilot);
	_mav_put_uint8_t(buf, 6, base_mode);
	_mav_put_uint8_t(buf, 7, system_status);
	_mav_put_uint8_t(buf, 8, 2);

101
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
LM's avatar
LM committed
102 103
#else
	mavlink_heartbeat_t packet;
lm's avatar
lm committed
104
	packet.custom_mode = custom_mode;
LM's avatar
LM committed
105 106
	packet.type = type;
	packet.autopilot = autopilot;
lm's avatar
lm committed
107 108
	packet.base_mode = base_mode;
	packet.system_status = system_status;
LM's avatar
LM committed
109
	packet.mavlink_version = 2;
LM's avatar
LM committed
110

111
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
LM's avatar
LM committed
112 113 114
#endif

	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
lm's avatar
lm committed
115
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 50);
LM's avatar
LM committed
116 117 118 119 120 121 122 123 124 125 126 127
}

/**
 * @brief Encode a heartbeat struct into a message
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param heartbeat C-struct to read the message contents from
 */
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)
{
lm's avatar
lm committed
128
	return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
LM's avatar
LM committed
129 130 131 132 133 134 135
}

/**
 * @brief Send a heartbeat message
 * @param chan MAVLink channel to send the message
 *
 * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
136
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
lm's avatar
lm committed
137 138 139
 * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
 * @param custom_mode Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
 * @param system_status System status flag, see MAV_STATUS ENUM
LM's avatar
LM committed
140
 */
lm's avatar
lm committed
141 142
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

lm's avatar
lm committed
143
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)
lm's avatar
lm committed
144
{
LM's avatar
LM committed
145
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
lm's avatar
lm committed
146 147 148 149 150 151 152 153 154
	char buf[9];
	_mav_put_uint32_t(buf, 0, custom_mode);
	_mav_put_uint8_t(buf, 4, type);
	_mav_put_uint8_t(buf, 5, autopilot);
	_mav_put_uint8_t(buf, 6, base_mode);
	_mav_put_uint8_t(buf, 7, system_status);
	_mav_put_uint8_t(buf, 8, 2);

	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 9, 50);
LM's avatar
LM committed
155 156
#else
	mavlink_heartbeat_t packet;
lm's avatar
lm committed
157
	packet.custom_mode = custom_mode;
LM's avatar
LM committed
158 159
	packet.type = type;
	packet.autopilot = autopilot;
lm's avatar
lm committed
160 161
	packet.base_mode = base_mode;
	packet.system_status = system_status;
LM's avatar
LM committed
162
	packet.mavlink_version = 2;
LM's avatar
LM committed
163

lm's avatar
lm committed
164
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 9, 50);
LM's avatar
LM committed
165
#endif
LM's avatar
LM committed
166 167 168
}

#endif
lm's avatar
lm committed
169

LM's avatar
LM committed
170 171
// MESSAGE HEARTBEAT UNPACKING

lm's avatar
lm committed
172

LM's avatar
LM committed
173 174 175 176 177 178 179
/**
 * @brief Get field type from heartbeat message
 *
 * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
 */
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
lm's avatar
lm committed
180
	return _MAV_RETURN_uint8_t(msg,  4);
LM's avatar
LM committed
181 182 183 184 185
}

/**
 * @brief Get field autopilot from heartbeat message
 *
186
 * @return Autopilot type / class. defined in MAV_CLASS ENUM
LM's avatar
LM committed
187 188 189
 */
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
lm's avatar
lm committed
190
	return _MAV_RETURN_uint8_t(msg,  5);
LM's avatar
LM committed
191 192
}

193
/**
lm's avatar
lm committed
194
 * @brief Get field base_mode from heartbeat message
195
 *
lm's avatar
lm committed
196
 * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
197
 */
lm's avatar
lm committed
198
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
199
{
lm's avatar
lm committed
200
	return _MAV_RETURN_uint8_t(msg,  6);
201 202 203
}

/**
lm's avatar
lm committed
204
 * @brief Get field custom_mode from heartbeat message
205
 *
lm's avatar
lm committed
206
 * @return Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
207
 */
lm's avatar
lm committed
208
static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
209
{
lm's avatar
lm committed
210
	return _MAV_RETURN_uint32_t(msg,  0);
211 212 213
}

/**
lm's avatar
lm committed
214
 * @brief Get field system_status from heartbeat message
215 216 217
 *
 * @return System status flag, see MAV_STATUS ENUM
 */
lm's avatar
lm committed
218
static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
219
{
lm's avatar
lm committed
220
	return _MAV_RETURN_uint8_t(msg,  7);
221 222
}

LM's avatar
LM committed
223 224 225 226 227 228 229
/**
 * @brief Get field mavlink_version from heartbeat message
 *
 * @return MAVLink version
 */
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{
lm's avatar
lm committed
230
	return _MAV_RETURN_uint8_t(msg,  8);
LM's avatar
LM committed
231 232 233 234 235 236 237 238 239 240
}

/**
 * @brief Decode a heartbeat message into a struct
 *
 * @param msg The message to decode
 * @param heartbeat C-struct to decode the message contents into
 */
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
{
lm's avatar
lm committed
241
#if MAVLINK_NEED_BYTE_SWAP
lm's avatar
lm committed
242
	heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg);
lm's avatar
lm committed
243 244
	heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
	heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
lm's avatar
lm committed
245 246
	heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg);
	heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
lm's avatar
lm committed
247 248
	heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else
lm's avatar
lm committed
249
	memcpy(heartbeat, _MAV_PAYLOAD(msg), 9);
lm's avatar
lm committed
250
#endif
LM's avatar
LM committed
251
}