mavlink_msg_heartbeat.h 11.3 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 8 9 10 11 12 13 14
 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
 uint8_t mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 uint8_t nav_mode; ///< Navigation mode, see MAV_NAV_MODE ENUM
 uint8_t status; ///< System status flag, see MAV_STATUS ENUM
 uint8_t safety_status; ///< System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
 uint8_t link_status; ///< Bitmask showing which links are ok / enabled. 0 for disabled/non functional, 1: enabled Indices: 0: RC, 1: UART1, 2: UART2, 3: UART3, 4: UART4, 5: UART5, 6: I2C, 7: CAN
 uint8_t mavlink_version; ///< MAVLink version
LM's avatar
LM committed
15 16
} mavlink_heartbeat_t;

lm's avatar
lm committed
17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 8
#define MAVLINK_MSG_ID_0_LEN 8



#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
	"HEARTBEAT", \
	8, \
	{  { "type", MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_heartbeat_t, type) }, \
         { "autopilot", MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_heartbeat_t, autopilot) }, \
         { "mode", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_heartbeat_t, mode) }, \
         { "nav_mode", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_heartbeat_t, nav_mode) }, \
         { "status", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, status) }, \
         { "safety_status", MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, safety_status) }, \
         { "link_status", MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, link_status) }, \
         { "mavlink_version", MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
         } \
}


LM's avatar
LM committed
37 38 39 40 41 42 43
/**
 * @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)
44 45 46 47 48 49
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
 * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
 * @param status System status flag, see MAV_STATUS ENUM
 * @param safety_status System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
 * @param link_status Bitmask showing which links are ok / enabled. 0 for disabled/non functional, 1: enabled Indices: 0: RC, 1: UART1, 2: UART2, 3: UART3, 4: UART4, 5: UART5, 6: I2C, 7: CAN
LM's avatar
LM committed
50 51
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
52 53
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
						       uint8_t type, uint8_t autopilot, uint8_t mode, uint8_t nav_mode, uint8_t status, uint8_t safety_status, uint8_t link_status)
LM's avatar
LM committed
54
{
LM's avatar
LM committed
55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[8];
	_mav_put_uint8_t(buf, 0, type);
	_mav_put_uint8_t(buf, 1, autopilot);
	_mav_put_uint8_t(buf, 2, mode);
	_mav_put_uint8_t(buf, 3, nav_mode);
	_mav_put_uint8_t(buf, 4, status);
	_mav_put_uint8_t(buf, 5, safety_status);
	_mav_put_uint8_t(buf, 6, link_status);
	_mav_put_uint8_t(buf, 7, 2);

        memcpy(_MAV_PAYLOAD(msg), buf, 8);
#else
	mavlink_heartbeat_t packet;
	packet.type = type;
	packet.autopilot = autopilot;
	packet.mode = mode;
	packet.nav_mode = nav_mode;
	packet.status = status;
	packet.safety_status = safety_status;
	packet.link_status = link_status;
	packet.mavlink_version = 2;
LM's avatar
LM committed
77

LM's avatar
LM committed
78 79
        memcpy(_MAV_PAYLOAD(msg), &packet, 8);
#endif
LM's avatar
LM committed
80

LM's avatar
LM committed
81
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
lm's avatar
lm committed
82
	return mavlink_finalize_message(msg, system_id, component_id, 8, 11);
LM's avatar
LM committed
83 84 85
}

/**
lm's avatar
lm committed
86
 * @brief Pack a heartbeat message on a channel
LM's avatar
LM committed
87 88 89 90 91
 * @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)
92 93 94 95 96 97
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
 * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
 * @param status System status flag, see MAV_STATUS ENUM
 * @param safety_status System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
 * @param link_status Bitmask showing which links are ok / enabled. 0 for disabled/non functional, 1: enabled Indices: 0: RC, 1: UART1, 2: UART2, 3: UART3, 4: UART4, 5: UART5, 6: I2C, 7: CAN
LM's avatar
LM committed
98 99
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
100 101 102
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
						           uint8_t type,uint8_t autopilot,uint8_t mode,uint8_t nav_mode,uint8_t status,uint8_t safety_status,uint8_t link_status)
LM's avatar
LM committed
103
{
LM's avatar
LM committed
104 105 106 107 108 109 110 111 112 113
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[8];
	_mav_put_uint8_t(buf, 0, type);
	_mav_put_uint8_t(buf, 1, autopilot);
	_mav_put_uint8_t(buf, 2, mode);
	_mav_put_uint8_t(buf, 3, nav_mode);
	_mav_put_uint8_t(buf, 4, status);
	_mav_put_uint8_t(buf, 5, safety_status);
	_mav_put_uint8_t(buf, 6, link_status);
	_mav_put_uint8_t(buf, 7, 2);
LM's avatar
LM committed
114

LM's avatar
LM committed
115 116 117 118 119 120 121 122 123 124 125
        memcpy(_MAV_PAYLOAD(msg), buf, 8);
#else
	mavlink_heartbeat_t packet;
	packet.type = type;
	packet.autopilot = autopilot;
	packet.mode = mode;
	packet.nav_mode = nav_mode;
	packet.status = status;
	packet.safety_status = safety_status;
	packet.link_status = link_status;
	packet.mavlink_version = 2;
LM's avatar
LM committed
126

LM's avatar
LM committed
127 128 129 130
        memcpy(_MAV_PAYLOAD(msg), &packet, 8);
#endif

	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
lm's avatar
lm committed
131
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 11);
LM's avatar
LM committed
132 133 134 135 136 137 138 139 140 141 142 143
}

/**
 * @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)
{
144
	return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->mode, heartbeat->nav_mode, heartbeat->status, heartbeat->safety_status, heartbeat->link_status);
LM's avatar
LM committed
145 146 147 148 149 150 151
}

/**
 * @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)
152 153 154 155 156 157
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
 * @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 * @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
 * @param status System status flag, see MAV_STATUS ENUM
 * @param safety_status System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
 * @param link_status Bitmask showing which links are ok / enabled. 0 for disabled/non functional, 1: enabled Indices: 0: RC, 1: UART1, 2: UART2, 3: UART3, 4: UART4, 5: UART5, 6: I2C, 7: CAN
LM's avatar
LM committed
158
 */
lm's avatar
lm committed
159 160
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

161
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t mode, uint8_t nav_mode, uint8_t status, uint8_t safety_status, uint8_t link_status)
lm's avatar
lm committed
162
{
LM's avatar
LM committed
163 164 165 166 167 168 169 170 171 172
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
	char buf[8];
	_mav_put_uint8_t(buf, 0, type);
	_mav_put_uint8_t(buf, 1, autopilot);
	_mav_put_uint8_t(buf, 2, mode);
	_mav_put_uint8_t(buf, 3, nav_mode);
	_mav_put_uint8_t(buf, 4, status);
	_mav_put_uint8_t(buf, 5, safety_status);
	_mav_put_uint8_t(buf, 6, link_status);
	_mav_put_uint8_t(buf, 7, 2);
LM's avatar
LM committed
173

LM's avatar
LM committed
174 175 176 177 178 179 180 181 182 183 184
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 8, 11);
#else
	mavlink_heartbeat_t packet;
	packet.type = type;
	packet.autopilot = autopilot;
	packet.mode = mode;
	packet.nav_mode = nav_mode;
	packet.status = status;
	packet.safety_status = safety_status;
	packet.link_status = link_status;
	packet.mavlink_version = 2;
LM's avatar
LM committed
185

LM's avatar
LM committed
186 187
	_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 8, 11);
#endif
LM's avatar
LM committed
188 189 190
}

#endif
lm's avatar
lm committed
191

LM's avatar
LM committed
192 193
// MESSAGE HEARTBEAT UNPACKING

lm's avatar
lm committed
194

LM's avatar
LM committed
195 196 197 198 199 200 201
/**
 * @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
202
	return _MAV_RETURN_uint8_t(msg,  0);
LM's avatar
LM committed
203 204 205 206 207
}

/**
 * @brief Get field autopilot from heartbeat message
 *
208
 * @return Autopilot type / class. defined in MAV_CLASS ENUM
LM's avatar
LM committed
209 210 211
 */
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
LM's avatar
LM committed
212
	return _MAV_RETURN_uint8_t(msg,  1);
LM's avatar
LM committed
213 214
}

215 216 217 218 219 220 221
/**
 * @brief Get field mode from heartbeat message
 *
 * @return System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 */
static inline uint8_t mavlink_msg_heartbeat_get_mode(const mavlink_message_t* msg)
{
LM's avatar
LM committed
222
	return _MAV_RETURN_uint8_t(msg,  2);
223 224 225 226 227 228 229 230 231
}

/**
 * @brief Get field nav_mode from heartbeat message
 *
 * @return Navigation mode, see MAV_NAV_MODE ENUM
 */
static inline uint8_t mavlink_msg_heartbeat_get_nav_mode(const mavlink_message_t* msg)
{
LM's avatar
LM committed
232
	return _MAV_RETURN_uint8_t(msg,  3);
233 234 235 236 237 238 239 240 241
}

/**
 * @brief Get field status from heartbeat message
 *
 * @return System status flag, see MAV_STATUS ENUM
 */
static inline uint8_t mavlink_msg_heartbeat_get_status(const mavlink_message_t* msg)
{
LM's avatar
LM committed
242
	return _MAV_RETURN_uint8_t(msg,  4);
243 244 245 246 247 248 249 250 251
}

/**
 * @brief Get field safety_status from heartbeat message
 *
 * @return System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
 */
static inline uint8_t mavlink_msg_heartbeat_get_safety_status(const mavlink_message_t* msg)
{
LM's avatar
LM committed
252
	return _MAV_RETURN_uint8_t(msg,  5);
253 254 255 256 257 258 259 260 261
}

/**
 * @brief Get field link_status from heartbeat message
 *
 * @return Bitmask showing which links are ok / enabled. 0 for disabled/non functional, 1: enabled Indices: 0: RC, 1: UART1, 2: UART2, 3: UART3, 4: UART4, 5: UART5, 6: I2C, 7: CAN
 */
static inline uint8_t mavlink_msg_heartbeat_get_link_status(const mavlink_message_t* msg)
{
LM's avatar
LM committed
262
	return _MAV_RETURN_uint8_t(msg,  6);
263 264
}

LM's avatar
LM committed
265 266 267 268 269 270 271
/**
 * @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
272
	return _MAV_RETURN_uint8_t(msg,  7);
LM's avatar
LM committed
273 274 275 276 277 278 279 280 281 282
}

/**
 * @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
283 284 285 286 287 288 289 290 291 292
#if MAVLINK_NEED_BYTE_SWAP
	heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
	heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
	heartbeat->mode = mavlink_msg_heartbeat_get_mode(msg);
	heartbeat->nav_mode = mavlink_msg_heartbeat_get_nav_mode(msg);
	heartbeat->status = mavlink_msg_heartbeat_get_status(msg);
	heartbeat->safety_status = mavlink_msg_heartbeat_get_safety_status(msg);
	heartbeat->link_status = mavlink_msg_heartbeat_get_link_status(msg);
	heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else
LM's avatar
LM committed
293
	memcpy(heartbeat, _MAV_PAYLOAD(msg), 8);
lm's avatar
lm committed
294
#endif
LM's avatar
LM committed
295
}