3 #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 182
15 #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN 12
16 #define MAVLINK_MSG_ID_182_LEN 12
18 #define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC 29
19 #define MAVLINK_MSG_ID_182_CRC 29
23 #define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS { \
24 "WATCHDOG_PROCESS_STATUS", \
26 { { "pid", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_watchdog_process_status_t, pid) }, \
27 { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_watchdog_process_status_t, watchdog_id) }, \
28 { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_watchdog_process_status_t, process_id) }, \
29 { "crashes", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_watchdog_process_status_t, crashes) }, \
30 { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_watchdog_process_status_t, state) }, \
31 { "muted", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_watchdog_process_status_t, muted) }, \
50 static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51 uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t
pid, uint16_t crashes)
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
97 static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98 mavlink_message_t* msg,
99 uint16_t watchdog_id,uint16_t process_id,uint8_t state,uint8_t muted,int32_t
pid,uint16_t crashes)
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
117 packet.
state = state;
118 packet.
muted = muted;
124 #if MAVLINK_CRC_EXTRA
139 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)
141 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);
153 static inline uint16_t mavlink_msg_watchdog_process_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_watchdog_process_status_t* watchdog_process_status)
155 return mavlink_msg_watchdog_process_status_pack_chan(system_id, component_id, chan, 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);
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
171 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)
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
182 #if MAVLINK_CRC_EXTRA
193 packet.
state = state;
194 packet.
muted = muted;
196 #if MAVLINK_CRC_EXTRA
204 #if MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
212 static inline void mavlink_msg_watchdog_process_status_send_buf(mavlink_message_t *msgbuf,
mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes)
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215 char *buf = (
char *)msgbuf;
223 #if MAVLINK_CRC_EXTRA
234 packet->
state = state;
235 packet->
muted = muted;
237 #if MAVLINK_CRC_EXTRA
256 static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(
const mavlink_message_t* msg)
258 return _MAV_RETURN_uint16_t(msg, 4);
266 static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(
const mavlink_message_t* msg)
268 return _MAV_RETURN_uint16_t(msg, 6);
276 static inline uint8_t mavlink_msg_watchdog_process_status_get_state(
const mavlink_message_t* msg)
286 static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(
const mavlink_message_t* msg)
296 static inline int32_t mavlink_msg_watchdog_process_status_get_pid(
const mavlink_message_t* msg)
298 return _MAV_RETURN_int32_t(msg, 0);
306 static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(
const mavlink_message_t* msg)
308 return _MAV_RETURN_uint16_t(msg, 8);
319 #if MAVLINK_NEED_BYTE_SWAP
320 watchdog_process_status->
pid = mavlink_msg_watchdog_process_status_get_pid(msg);
321 watchdog_process_status->
watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg);
322 watchdog_process_status->
process_id = mavlink_msg_watchdog_process_status_get_process_id(msg);
323 watchdog_process_status->
crashes = mavlink_msg_watchdog_process_status_get_crashes(msg);
324 watchdog_process_status->
state = mavlink_msg_watchdog_process_status_get_state(msg);
325 watchdog_process_status->
muted = mavlink_msg_watchdog_process_status_get_muted(msg);
uint8_t muted
Is muted.
Definition: mavlink_msg_watchdog_process_status.h:12
Definition: mavlink_msg_watchdog_process_status.h:5
uint16_t watchdog_id
Watchdog ID.
Definition: mavlink_msg_watchdog_process_status.h:8
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:238
#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN
Definition: mavlink_msg_watchdog_process_status.h:15
uint8_t state
Is running / finished / suspended / crashed.
Definition: mavlink_msg_watchdog_process_status.h:11
#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC
Definition: mavlink_msg_watchdog_process_status.h:18
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t length)
Finalize a MAVLink message with MAVLINK_COMM_0 as default channel.
Definition: mavlink_helpers.h:105
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:134
#define _mav_put_int32_t(buf, wire_offset, b)
Definition: protocol.h:142
#define _MAV_PAYLOAD_NON_CONST(msg)
Definition: mavlink_types.h:172
struct pid_config pid
Definition: config.h:92
uint16_t crashes
Number of crashes.
Definition: mavlink_msg_watchdog_process_status.h:10
mavlink_channel_t
Definition: mavlink_types.h:178
#define _MAV_PAYLOAD(msg)
Definition: mavlink_types.h:171
uint16_t process_id
Process ID.
Definition: mavlink_msg_watchdog_process_status.h:9
struct __mavlink_watchdog_process_status_t mavlink_watchdog_process_status_t
int32_t pid
PID.
Definition: mavlink_msg_watchdog_process_status.h:7
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:139
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t *msg, uint8_t system_id, uint8_t component_id, uint8_t chan, uint8_t length)
Finalize a MAVLink message with channel assignment.
Definition: mavlink_helpers.h:71
#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS
Definition: mavlink_msg_watchdog_process_status.h:3