mavlink_msg_heartbeat.h 9.51 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
{
7
 uint16_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
10
 uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
lm's avatar
lm committed
11 12
 uint8_t system_status; ///< System status flag, see MAV_STATUS ENUM
 uint8_t mavlink_version; ///< MAVLink version
James Goppert's avatar
James Goppert committed
13 14
} mavlink_heartbeat_t;

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



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


James Goppert's avatar
James Goppert 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
41 42
 * @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.
43
 * @param system_status System status flag, see MAV_STATUS ENUM
James Goppert's avatar
James Goppert 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,
47
						       uint8_t type, uint8_t autopilot, uint8_t base_mode, uint16_t custom_mode, uint8_t system_status)
James Goppert's avatar
James Goppert committed
48 49 50
{
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

51 52 53 54 55 56
	put_uint16_t_by_index(msg, 0, custom_mode); // Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
	put_uint8_t_by_index(msg, 2, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
	put_uint8_t_by_index(msg, 3, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM
	put_uint8_t_by_index(msg, 4, base_mode); // System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
	put_uint8_t_by_index(msg, 5, system_status); // System status flag, see MAV_STATUS ENUM
	put_uint8_t_by_index(msg, 6, 3); // MAVLink version
James Goppert's avatar
James Goppert committed
57

58
	return mavlink_finalize_message(msg, system_id, component_id, 7, 88);
James Goppert's avatar
James Goppert committed
59 60 61
}

/**
lm's avatar
lm committed
62
 * @brief Pack a heartbeat message on a channel
James Goppert's avatar
James Goppert committed
63 64 65 66 67
 * @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)
68
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
69 70
 * @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.
71
 * @param system_status System status flag, see MAV_STATUS ENUM
James Goppert's avatar
James Goppert committed
72 73
 * @return length of the message in bytes (excluding serial stream start sign)
 */
lm's avatar
lm committed
74 75
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
							   mavlink_message_t* msg,
76
						           uint8_t type,uint8_t autopilot,uint8_t base_mode,uint16_t custom_mode,uint8_t system_status)
James Goppert's avatar
James Goppert committed
77 78 79
{
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

80 81 82 83 84 85
	put_uint16_t_by_index(msg, 0, custom_mode); // Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
	put_uint8_t_by_index(msg, 2, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
	put_uint8_t_by_index(msg, 3, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM
	put_uint8_t_by_index(msg, 4, base_mode); // System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
	put_uint8_t_by_index(msg, 5, system_status); // System status flag, see MAV_STATUS ENUM
	put_uint8_t_by_index(msg, 6, 3); // MAVLink version
James Goppert's avatar
James Goppert committed
86

87
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 7, 88);
James Goppert's avatar
James Goppert committed
88 89 90 91 92 93 94 95 96 97 98 99
}

/**
 * @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)
{
100
	return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
James Goppert's avatar
James Goppert committed
101 102 103 104 105 106 107
}

/**
 * @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)
108
 * @param autopilot Autopilot type / class. defined in MAV_CLASS ENUM
109 110
 * @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.
111
 * @param system_status System status flag, see MAV_STATUS ENUM
James Goppert's avatar
James Goppert committed
112
 */
lm's avatar
lm committed
113 114
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS

115
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint16_t custom_mode, uint8_t system_status)
lm's avatar
lm committed
116
{
117
	MAVLINK_ALIGNED_MESSAGE(msg, 7);
LM's avatar
LM committed
118 119
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

120 121 122 123 124 125
	put_uint16_t_by_index(msg, 0, custom_mode); // Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
	put_uint8_t_by_index(msg, 2, type); // Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
	put_uint8_t_by_index(msg, 3, autopilot); // Autopilot type / class. defined in MAV_CLASS ENUM
	put_uint8_t_by_index(msg, 4, base_mode); // System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
	put_uint8_t_by_index(msg, 5, system_status); // System status flag, see MAV_STATUS ENUM
	put_uint8_t_by_index(msg, 6, 3); // MAVLink version
LM's avatar
LM committed
126

127
	mavlink_finalize_message_chan_send(msg, chan, 7, 88);
James Goppert's avatar
James Goppert committed
128 129 130
}

#endif
lm's avatar
lm committed
131

James Goppert's avatar
James Goppert committed
132 133
// MESSAGE HEARTBEAT UNPACKING

lm's avatar
lm committed
134

James Goppert's avatar
James Goppert committed
135 136 137 138 139 140 141
/**
 * @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)
{
142
	return MAVLINK_MSG_RETURN_uint8_t(msg,  2);
James Goppert's avatar
James Goppert committed
143 144 145 146 147
}

/**
 * @brief Get field autopilot from heartbeat message
 *
148
 * @return Autopilot type / class. defined in MAV_CLASS ENUM
James Goppert's avatar
James Goppert committed
149 150 151
 */
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
152
	return MAVLINK_MSG_RETURN_uint8_t(msg,  3);
James Goppert's avatar
James Goppert committed
153 154
}

155
/**
156
 * @brief Get field base_mode from heartbeat message
157
 *
158
 * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
159
 */
160
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
161
{
162
	return MAVLINK_MSG_RETURN_uint8_t(msg,  4);
163 164 165
}

/**
166
 * @brief Get field custom_mode from heartbeat message
167
 *
168
 * @return Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific.
169
 */
170
static inline uint16_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
171
{
172
	return MAVLINK_MSG_RETURN_uint16_t(msg,  0);
173 174 175 176 177 178 179 180 181
}

/**
 * @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
182
	return MAVLINK_MSG_RETURN_uint8_t(msg,  5);
183 184
}

James Goppert's avatar
James Goppert committed
185 186 187 188 189 190 191
/**
 * @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)
{
192
	return MAVLINK_MSG_RETURN_uint8_t(msg,  6);
James Goppert's avatar
James Goppert committed
193 194 195 196 197 198 199 200 201 202
}

/**
 * @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
203
#if MAVLINK_NEED_BYTE_SWAP
204
	heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg);
lm's avatar
lm committed
205 206
	heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
	heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
207
	heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg);
lm's avatar
lm committed
208 209 210
	heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
	heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else
211
	memcpy(heartbeat, MAVLINK_PAYLOAD(msg), 7);
lm's avatar
lm committed
212
#endif
James Goppert's avatar
James Goppert committed
213
}