mavlink_msg_heartbeat.h 13.5 KB
Newer Older
James Goppert's avatar
James Goppert 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
James Goppert's avatar
James Goppert 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 system_mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 uint8_t flight_mode; ///< Navigation mode, see MAV_FLIGHT_MODE ENUM
 uint8_t system_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
James Goppert's avatar
James Goppert 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) }, \
         { "system_mode", MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_heartbeat_t, system_mode) }, \
         { "flight_mode", MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_heartbeat_t, flight_mode) }, \
         { "system_status", MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, system_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) }, \
         } \
}


James Goppert's avatar
James Goppert 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 system_mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 * @param flight_mode Navigation mode, see MAV_FLIGHT_MODE ENUM
 * @param system_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
James Goppert's avatar
James Goppert 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 system_mode, uint8_t flight_mode, uint8_t system_status, uint8_t safety_status, uint8_t link_status)
James Goppert's avatar
James Goppert committed
54 55 56
{
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

lm's avatar
lm committed
57 58 59 60 61 62 63 64
	put_uint8_t_by_index(msg, 0, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
	put_uint8_t_by_index(msg, 1, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM
	put_uint8_t_by_index(msg, 2, system_mode); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
	put_uint8_t_by_index(msg, 3, flight_mode); // Navigation mode, see MAV_FLIGHT_MODE ENUM
	put_uint8_t_by_index(msg, 4, system_status); // System status flag, see MAV_STATUS ENUM
	put_uint8_t_by_index(msg, 5, safety_status); // System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
	put_uint8_t_by_index(msg, 6, 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
	put_uint8_t_by_index(msg, 7, 3); // MAVLink version
James Goppert's avatar
James Goppert committed
65

lm's avatar
lm committed
66
	return mavlink_finalize_message(msg, system_id, component_id, 8, 153);
James Goppert's avatar
James Goppert committed
67 68 69
}

/**
lm's avatar
lm committed
70
 * @brief Pack a heartbeat message on a channel
James Goppert's avatar
James Goppert committed
71 72 73 74 75
 * @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)
76 77 78 79 80 81
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
 * @param system_mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 * @param flight_mode Navigation mode, see MAV_FLIGHT_MODE ENUM
 * @param system_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
James Goppert's avatar
James Goppert committed
82 83
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
84 85 86
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 system_mode,uint8_t flight_mode,uint8_t system_status,uint8_t safety_status,uint8_t link_status)
James Goppert's avatar
James Goppert committed
87 88 89
{
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

lm's avatar
lm committed
90 91 92 93 94 95 96 97
	put_uint8_t_by_index(msg, 0, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
	put_uint8_t_by_index(msg, 1, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM
	put_uint8_t_by_index(msg, 2, system_mode); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
	put_uint8_t_by_index(msg, 3, flight_mode); // Navigation mode, see MAV_FLIGHT_MODE ENUM
	put_uint8_t_by_index(msg, 4, system_status); // System status flag, see MAV_STATUS ENUM
	put_uint8_t_by_index(msg, 5, safety_status); // System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
	put_uint8_t_by_index(msg, 6, 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
	put_uint8_t_by_index(msg, 7, 3); // MAVLink version
James Goppert's avatar
James Goppert committed
98

lm's avatar
lm committed
99
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 153);
James Goppert's avatar
James Goppert committed
100 101
}

lm's avatar
lm committed
102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

/**
 * @brief Pack a heartbeat message on a channel and send
 * @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)
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
 * @param system_mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 * @param flight_mode Navigation mode, see MAV_FLIGHT_MODE ENUM
 * @param system_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
 */
static inline void mavlink_msg_heartbeat_pack_chan_send(mavlink_channel_t chan,
							   mavlink_message_t* msg,
						           uint8_t type,uint8_t autopilot,uint8_t system_mode,uint8_t flight_mode,uint8_t system_status,uint8_t safety_status,uint8_t link_status)
{
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

	put_uint8_t_by_index(msg, 0, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
	put_uint8_t_by_index(msg, 1, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM
	put_uint8_t_by_index(msg, 2, system_mode); // System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
	put_uint8_t_by_index(msg, 3, flight_mode); // Navigation mode, see MAV_FLIGHT_MODE ENUM
	put_uint8_t_by_index(msg, 4, system_status); // System status flag, see MAV_STATUS ENUM
	put_uint8_t_by_index(msg, 5, safety_status); // System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
	put_uint8_t_by_index(msg, 6, 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
	put_uint8_t_by_index(msg, 7, 3); // MAVLink version

	mavlink_finalize_message_chan_send(msg, chan, 8, 153);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS


James Goppert's avatar
James Goppert committed
136 137 138 139 140 141 142 143 144 145
/**
 * @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)
{
146
	return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->system_mode, heartbeat->flight_mode, heartbeat->system_status, heartbeat->safety_status, heartbeat->link_status);
James Goppert's avatar
James Goppert committed
147 148 149 150 151 152 153
}

/**
 * @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)
154 155 156 157 158 159
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
 * @param system_mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
 * @param flight_mode Navigation mode, see MAV_FLIGHT_MODE ENUM
 * @param system_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
James Goppert's avatar
James Goppert committed
160
 */
lm's avatar
lm committed
161 162
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

163
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t system_mode, uint8_t flight_mode, uint8_t system_status, uint8_t safety_status, uint8_t link_status)
lm's avatar
lm committed
164
{
lm's avatar
lm committed
165 166
	MAVLINK_ALIGNED_MESSAGE(msg, 8);
	mavlink_msg_heartbeat_pack_chan_send(chan, msg, type, autopilot, system_mode, flight_mode, system_status, safety_status, link_status);
James Goppert's avatar
James Goppert committed
167 168 169
}

#endif
lm's avatar
lm committed
170

James Goppert's avatar
James Goppert committed
171 172
// MESSAGE HEARTBEAT UNPACKING

lm's avatar
lm committed
173

James Goppert's avatar
James Goppert committed
174 175 176 177 178 179 180
/**
 * @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
181
	return MAVLINK_MSG_RETURN_uint8_t(msg,  0);
James Goppert's avatar
James Goppert committed
182 183 184 185 186
}

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

194 195 196 197 198 199 200
/**
 * @brief Get field system_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_system_mode(const mavlink_message_t* msg)
{
lm's avatar
lm committed
201
	return MAVLINK_MSG_RETURN_uint8_t(msg,  2);
202 203 204 205 206 207 208 209 210
}

/**
 * @brief Get field flight_mode from heartbeat message
 *
 * @return Navigation mode, see MAV_FLIGHT_MODE ENUM
 */
static inline uint8_t mavlink_msg_heartbeat_get_flight_mode(const mavlink_message_t* msg)
{
lm's avatar
lm committed
211
	return MAVLINK_MSG_RETURN_uint8_t(msg,  3);
212 213 214 215 216 217 218 219 220
}

/**
 * @brief Get field system_status from heartbeat message
 *
 * @return System status flag, see MAV_STATUS ENUM
 */
static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
{
lm's avatar
lm committed
221
	return MAVLINK_MSG_RETURN_uint8_t(msg,  4);
222 223 224 225 226 227 228 229 230
}

/**
 * @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
231
	return MAVLINK_MSG_RETURN_uint8_t(msg,  5);
232 233 234 235 236 237 238 239 240
}

/**
 * @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
241
	return MAVLINK_MSG_RETURN_uint8_t(msg,  6);
242 243
}

James Goppert's avatar
James Goppert committed
244 245 246 247 248 249 250
/**
 * @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
251
	return MAVLINK_MSG_RETURN_uint8_t(msg,  7);
James Goppert's avatar
James Goppert committed
252 253 254 255 256 257 258 259 260 261
}

/**
 * @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
262 263 264 265 266 267 268 269 270 271 272 273
#if MAVLINK_NEED_BYTE_SWAP
	heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
	heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
	heartbeat->system_mode = mavlink_msg_heartbeat_get_system_mode(msg);
	heartbeat->flight_mode = mavlink_msg_heartbeat_get_flight_mode(msg);
	heartbeat->system_status = mavlink_msg_heartbeat_get_system_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
	memcpy(heartbeat, MAVLINK_PAYLOAD(msg), 8);
#endif
James Goppert's avatar
James Goppert committed
274
}