mavlink_msg_watchdog_process_status.h 9.34 KB
Newer Older
James Goppert's avatar
James Goppert committed
1 2 3
// MESSAGE WATCHDOG_PROCESS_STATUS PACKING

#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 152
lm's avatar
lm committed
4 5
#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN 12
#define MAVLINK_MSG_152_LEN 12
James Goppert's avatar
James Goppert committed
6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33

typedef struct __mavlink_watchdog_process_status_t 
{
	uint16_t watchdog_id; ///< Watchdog ID
	uint16_t process_id; ///< Process ID
	uint8_t state; ///< Is running / finished / suspended / crashed
	uint8_t muted; ///< Is muted
	int32_t pid; ///< PID
	uint16_t crashes; ///< Number of crashes

} mavlink_watchdog_process_status_t;

/**
 * @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID
 * @param process_id Process ID
 * @param state Is running / finished / suspended / crashed
 * @param muted Is muted
 * @param pid PID
 * @param crashes Number of crashes
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
{
lm's avatar
lm committed
34
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
35 36
	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;

lm's avatar
lm committed
37 38 39 40 41 42
	p->watchdog_id = watchdog_id; // uint16_t:Watchdog ID
	p->process_id = process_id; // uint16_t:Process ID
	p->state = state; // uint8_t:Is running / finished / suspended / crashed
	p->muted = muted; // uint8_t:Is muted
	p->pid = pid; // int32_t:PID
	p->crashes = crashes; // uint16_t:Number of crashes
James Goppert's avatar
James Goppert committed
43

lm's avatar
lm committed
44
	return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN);
James Goppert's avatar
James Goppert committed
45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62
}

/**
 * @brief Pack a watchdog_process_status 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 watchdog_id Watchdog ID
 * @param process_id Process ID
 * @param state Is running / finished / suspended / crashed
 * @param muted Is muted
 * @param pid PID
 * @param crashes Number of crashes
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
{
lm's avatar
lm committed
63
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
James Goppert's avatar
James Goppert committed
64 65
	msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;

lm's avatar
lm committed
66 67 68 69 70 71
	p->watchdog_id = watchdog_id; // uint16_t:Watchdog ID
	p->process_id = process_id; // uint16_t:Process ID
	p->state = state; // uint8_t:Is running / finished / suspended / crashed
	p->muted = muted; // uint8_t:Is muted
	p->pid = pid; // int32_t:PID
	p->crashes = crashes; // uint16_t:Number of crashes
James Goppert's avatar
James Goppert committed
72

lm's avatar
lm committed
73
	return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN);
James Goppert's avatar
James Goppert committed
74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103
}

/**
 * @brief Encode a watchdog_process_status 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 watchdog_process_status C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status)
{
	return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes);
}

/**
 * @brief Send a watchdog_process_status message
 * @param chan MAVLink channel to send the message
 *
 * @param watchdog_id Watchdog ID
 * @param process_id Process ID
 * @param state Is running / finished / suspended / crashed
 * @param muted Is muted
 * @param pid PID
 * @param crashes Number of crashes
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
{
	mavlink_message_t msg;
lm's avatar
lm committed
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 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161
	uint16_t checksum;
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg.payload[0];

	p->watchdog_id = watchdog_id; // uint16_t:Watchdog ID
	p->process_id = process_id; // uint16_t:Process ID
	p->state = state; // uint8_t:Is running / finished / suspended / crashed
	p->muted = muted; // uint8_t:Is muted
	p->pid = pid; // int32_t:PID
	p->crashes = crashes; // uint16_t:Number of crashes

	msg.STX = MAVLINK_STX;
	msg.len = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN;
	msg.msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
	msg.sysid = mavlink_system.sysid;
	msg.compid = mavlink_system.compid;
	msg.seq = mavlink_get_channel_status(chan)->current_tx_seq;
	mavlink_get_channel_status(chan)->current_tx_seq = msg.seq + 1;
	checksum = crc_calculate_msg(&msg, msg.len + MAVLINK_CORE_HEADER_LEN);
	msg.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	msg.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_msg(chan, &msg);
}

#endif

#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS_SMALL
static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
{
	mavlink_header_t hdr;
	mavlink_watchdog_process_status_t payload;
	uint16_t checksum;
	mavlink_watchdog_process_status_t *p = &payload;

	p->watchdog_id = watchdog_id; // uint16_t:Watchdog ID
	p->process_id = process_id; // uint16_t:Process ID
	p->state = state; // uint8_t:Is running / finished / suspended / crashed
	p->muted = muted; // uint8_t:Is muted
	p->pid = pid; // int32_t:PID
	p->crashes = crashes; // uint16_t:Number of crashes

	hdr.STX = MAVLINK_STX;
	hdr.len = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN;
	hdr.msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS;
	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 );

	crc_init(&checksum);
	checksum = crc_calculate_mem((uint8_t *)&hdr.len, &checksum, MAVLINK_CORE_HEADER_LEN);
	checksum = crc_calculate_mem((uint8_t *)&payload, &checksum, hdr.len );
	hdr.ck_a = (uint8_t)(checksum & 0xFF); ///< Low byte
	hdr.ck_b = (uint8_t)(checksum >> 8); ///< High byte

	mavlink_send_mem(chan, (uint8_t *)&payload, hdr.len);
	mavlink_send_mem(chan, (uint8_t *)&hdr.ck_a, MAVLINK_NUM_CHECKSUM_BYTES);
James Goppert's avatar
James Goppert committed
162 163 164 165 166 167 168 169 170 171 172 173
}

#endif
// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING

/**
 * @brief Get field watchdog_id from watchdog_process_status message
 *
 * @return Watchdog ID
 */
static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg)
{
lm's avatar
lm committed
174 175
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
	return (uint16_t)(p->watchdog_id);
James Goppert's avatar
James Goppert committed
176 177 178 179 180 181 182 183 184
}

/**
 * @brief Get field process_id from watchdog_process_status message
 *
 * @return Process ID
 */
static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg)
{
lm's avatar
lm committed
185 186
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
	return (uint16_t)(p->process_id);
James Goppert's avatar
James Goppert committed
187 188 189 190 191 192 193 194 195
}

/**
 * @brief Get field state from watchdog_process_status message
 *
 * @return Is running / finished / suspended / crashed
 */
static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg)
{
lm's avatar
lm committed
196 197
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
	return (uint8_t)(p->state);
James Goppert's avatar
James Goppert committed
198 199 200 201 202 203 204 205 206
}

/**
 * @brief Get field muted from watchdog_process_status message
 *
 * @return Is muted
 */
static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg)
{
lm's avatar
lm committed
207 208
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
	return (uint8_t)(p->muted);
James Goppert's avatar
James Goppert committed
209 210 211 212 213 214 215 216 217
}

/**
 * @brief Get field pid from watchdog_process_status message
 *
 * @return PID
 */
static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg)
{
lm's avatar
lm committed
218 219
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
	return (int32_t)(p->pid);
James Goppert's avatar
James Goppert committed
220 221 222 223 224 225 226 227 228
}

/**
 * @brief Get field crashes from watchdog_process_status message
 *
 * @return Number of crashes
 */
static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg)
{
lm's avatar
lm committed
229 230
	mavlink_watchdog_process_status_t *p = (mavlink_watchdog_process_status_t *)&msg->payload[0];
	return (uint16_t)(p->crashes);
James Goppert's avatar
James Goppert committed
231 232 233 234 235 236 237 238 239 240
}

/**
 * @brief Decode a watchdog_process_status message into a struct
 *
 * @param msg The message to decode
 * @param watchdog_process_status C-struct to decode the message contents into
 */
static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status)
{
lm's avatar
lm committed
241
	memcpy( watchdog_process_status, msg->payload, sizeof(mavlink_watchdog_process_status_t));
James Goppert's avatar
James Goppert committed
242
}