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

#define MAVLINK_MSG_ID_HEARTBEAT 0
4 5 6 7
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 8
#define MAVLINK_MSG_0_LEN 8
#define MAVLINK_MSG_ID_HEARTBEAT_KEY 0xB3
#define MAVLINK_MSG_0_KEY 0xB3
LM's avatar
LM committed
8 9 10

typedef struct __mavlink_heartbeat_t 
{
lm's avatar
lm committed
11
	uint8_t type;	///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
12 13 14 15 16 17
	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
lm's avatar
lm committed
18
	uint8_t mavlink_version;	///< MAVLink version
LM's avatar
LM committed
19 20 21 22 23 24 25 26 27 28

} mavlink_heartbeat_t;

/**
 * @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)
29 30 31 32 33 34
 * @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
35 36
 * @return length of the message in bytes (excluding serial stream start sign)
 */
37
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
38
{
lm's avatar
lm committed
39
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
LM's avatar
LM committed
40 41
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

lm's avatar
lm committed
42
	p->type = type;	// uint8_t:Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
43 44 45 46 47 48
	p->autopilot = autopilot;	// uint8_t:Autopilot type / class. defined in MAV_CLASS ENUM
	p->mode = mode;	// uint8_t:System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
	p->nav_mode = nav_mode;	// uint8_t:Navigation mode, see MAV_NAV_MODE ENUM
	p->status = status;	// uint8_t:System status flag, see MAV_STATUS ENUM
	p->safety_status = safety_status;	// uint8_t:System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
	p->link_status = link_status;	// uint8_t: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
49

lm's avatar
lm committed
50
	p->mavlink_version = MAVLINK_VERSION;	// uint8_t_mavlink_version:MAVLink version
lm's avatar
lm committed
51
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN);
LM's avatar
LM committed
52 53 54 55 56 57 58 59 60
}

/**
 * @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 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)
61 62 63 64 65 66
 * @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
67 68
 * @return length of the message in bytes (excluding serial stream start sign)
 */
69
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
70
{
lm's avatar
lm committed
71
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
LM's avatar
LM committed
72 73
	msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;

lm's avatar
lm committed
74
	p->type = type;	// uint8_t:Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
75 76 77 78 79 80
	p->autopilot = autopilot;	// uint8_t:Autopilot type / class. defined in MAV_CLASS ENUM
	p->mode = mode;	// uint8_t:System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
	p->nav_mode = nav_mode;	// uint8_t:Navigation mode, see MAV_NAV_MODE ENUM
	p->status = status;	// uint8_t:System status flag, see MAV_STATUS ENUM
	p->safety_status = safety_status;	// uint8_t:System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
	p->link_status = link_status;	// uint8_t: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
81

lm's avatar
lm committed
82
	p->mavlink_version = MAVLINK_VERSION;	// uint8_t_mavlink_version:MAVLink version
lm's avatar
lm committed
83
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN);
LM's avatar
LM committed
84 85 86 87 88 89 90 91 92 93 94 95
}

/**
 * @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)
{
96
	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
97 98
}

lm's avatar
lm committed
99 100

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
LM's avatar
LM committed
101 102 103 104 105
/**
 * @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)
106 107 108 109 110 111
 * @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
112
 */
113
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
114 115 116 117
{
	mavlink_header_t hdr;
	mavlink_heartbeat_t payload;

lm's avatar
lm committed
118 119
	MAVLINK_BUFFER_CHECK_START( chan, MAVLINK_MSG_ID_HEARTBEAT_LEN )
	payload.type = type;	// uint8_t:Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
120 121 122 123 124 125
	payload.autopilot = autopilot;	// uint8_t:Autopilot type / class. defined in MAV_CLASS ENUM
	payload.mode = mode;	// uint8_t:System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
	payload.nav_mode = nav_mode;	// uint8_t:Navigation mode, see MAV_NAV_MODE ENUM
	payload.status = status;	// uint8_t:System status flag, see MAV_STATUS ENUM
	payload.safety_status = safety_status;	// uint8_t:System safety lock state, see MAV_SAFETY enum. Also indicates HIL operation
	payload.link_status = link_status;	// uint8_t: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
126

lm's avatar
lm committed
127
	payload.mavlink_version = MAVLINK_VERSION;	// uint8_t_mavlink_version:MAVLink version
lm's avatar
lm committed
128 129 130 131 132 133 134 135
	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_HEARTBEAT_LEN;
	hdr.msgid = MAVLINK_MSG_ID_HEARTBEAT;
	hdr.sysid = mavlink_system.sysid;
	hdr.compid = mavlink_system.compid;
	hdr.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = hdr.seq + 1;
	mavlink_send_mem(chan, (uint8_t *)&hdr.STX, MAVLINK_NUM_HEADER_BYTES );
136
	mavlink_send_mem(chan, (uint8_t *)&payload, sizeof(payload) );
lm's avatar
lm committed
137

lm's avatar
lm committed
138 139 140
	crc_init(&hdr.ck);
	crc_calculate_mem((uint8_t *)&hdr.len, &hdr.ck, MAVLINK_CORE_HEADER_LEN);
	crc_calculate_mem((uint8_t *)&payload, &hdr.ck, hdr.len );
141
	crc_accumulate( 0xB3, &hdr.ck); /// include key in X25 checksum
lm's avatar
lm committed
142 143
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck, MAVLINK_NUM_CHECKSUM_BYTES);
	MAVLINK_BUFFER_CHECK_END
LM's avatar
LM committed
144 145 146 147 148 149 150 151 152 153 154 155
}

#endif
// MESSAGE HEARTBEAT UNPACKING

/**
 * @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
156 157
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->type);
LM's avatar
LM committed
158 159 160 161 162
}

/**
 * @brief Get field autopilot from heartbeat message
 *
163
 * @return Autopilot type / class. defined in MAV_CLASS ENUM
LM's avatar
LM committed
164 165 166
 */
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
lm's avatar
lm committed
167 168
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->autopilot);
LM's avatar
LM committed
169 170
}

171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225
/**
 * @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)
{
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->mode);
}

/**
 * @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)
{
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->nav_mode);
}

/**
 * @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)
{
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->status);
}

/**
 * @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)
{
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->safety_status);
}

/**
 * @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)
{
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->link_status);
}

LM's avatar
LM committed
226 227 228 229 230 231 232
/**
 * @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
233 234
	mavlink_heartbeat_t *p = (mavlink_heartbeat_t *)&msg->payload[0];
	return (uint8_t)(p->mavlink_version);
LM's avatar
LM committed
235 236 237 238 239 240 241 242 243 244
}

/**
 * @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
245
	memcpy( heartbeat, msg->payload, sizeof(mavlink_heartbeat_t));
LM's avatar
LM committed
246
}