4#define MAVLINK_MSG_ID_LIMITS_STATUS 167
7typedef struct __mavlink_limits_status_t {
10 uint32_t last_recovery;
12 uint16_t breach_count;
15 uint8_t mods_required;
16 uint8_t mods_triggered;
17}) mavlink_limits_status_t;
19#define MAVLINK_MSG_ID_LIMITS_STATUS_LEN 22
20#define MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN 22
21#define MAVLINK_MSG_ID_167_LEN 22
22#define MAVLINK_MSG_ID_167_MIN_LEN 22
24#define MAVLINK_MSG_ID_LIMITS_STATUS_CRC 144
25#define MAVLINK_MSG_ID_167_CRC 144
29#if MAVLINK_COMMAND_24BIT
30#define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \
34 { { "limits_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_limits_status_t, limits_state) }, \
35 { "last_trigger", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_limits_status_t, last_trigger) }, \
36 { "last_action", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_limits_status_t, last_action) }, \
37 { "last_recovery", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_limits_status_t, last_recovery) }, \
38 { "last_clear", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_limits_status_t, last_clear) }, \
39 { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_limits_status_t, breach_count) }, \
40 { "mods_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_limits_status_t, mods_enabled) }, \
41 { "mods_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_limits_status_t, mods_required) }, \
42 { "mods_triggered", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_limits_status_t, mods_triggered) }, \
46#define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \
49 { { "limits_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_limits_status_t, limits_state) }, \
50 { "last_trigger", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_limits_status_t, last_trigger) }, \
51 { "last_action", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_limits_status_t, last_action) }, \
52 { "last_recovery", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_limits_status_t, last_recovery) }, \
53 { "last_clear", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_limits_status_t, last_clear) }, \
54 { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_limits_status_t, breach_count) }, \
55 { "mods_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_limits_status_t, mods_enabled) }, \
56 { "mods_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_limits_status_t, mods_required) }, \
57 { "mods_triggered", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_limits_status_t, mods_triggered) }, \
79static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
80 uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
82#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
83 char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
84 _mav_put_uint32_t(buf, 0, last_trigger);
85 _mav_put_uint32_t(buf, 4, last_action);
86 _mav_put_uint32_t(buf, 8, last_recovery);
87 _mav_put_uint32_t(buf, 12, last_clear);
88 _mav_put_uint16_t(buf, 16, breach_count);
89 _mav_put_uint8_t(buf, 18, limits_state);
90 _mav_put_uint8_t(buf, 19, mods_enabled);
91 _mav_put_uint8_t(buf, 20, mods_required);
92 _mav_put_uint8_t(buf, 21, mods_triggered);
94 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
96 mavlink_limits_status_t packet;
97 packet.last_trigger = last_trigger;
98 packet.last_action = last_action;
99 packet.last_recovery = last_recovery;
100 packet.last_clear = last_clear;
101 packet.breach_count = breach_count;
102 packet.limits_state = limits_state;
103 packet.mods_enabled = mods_enabled;
104 packet.mods_required = mods_required;
105 packet.mods_triggered = mods_triggered;
107 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
110 msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS;
111 return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
131static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
132 mavlink_message_t* msg,
133 uint8_t limits_state,uint32_t last_trigger,uint32_t last_action,uint32_t last_recovery,uint32_t last_clear,uint16_t breach_count,uint8_t mods_enabled,uint8_t mods_required,uint8_t mods_triggered)
135#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
136 char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
137 _mav_put_uint32_t(buf, 0, last_trigger);
138 _mav_put_uint32_t(buf, 4, last_action);
139 _mav_put_uint32_t(buf, 8, last_recovery);
140 _mav_put_uint32_t(buf, 12, last_clear);
141 _mav_put_uint16_t(buf, 16, breach_count);
142 _mav_put_uint8_t(buf, 18, limits_state);
143 _mav_put_uint8_t(buf, 19, mods_enabled);
144 _mav_put_uint8_t(buf, 20, mods_required);
145 _mav_put_uint8_t(buf, 21, mods_triggered);
147 memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
149 mavlink_limits_status_t packet;
150 packet.last_trigger = last_trigger;
151 packet.last_action = last_action;
152 packet.last_recovery = last_recovery;
153 packet.last_clear = last_clear;
154 packet.breach_count = breach_count;
155 packet.limits_state = limits_state;
156 packet.mods_enabled = mods_enabled;
157 packet.mods_required = mods_required;
158 packet.mods_triggered = mods_triggered;
160 memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
163 msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS;
164 return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
175static inline uint16_t mavlink_msg_limits_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const mavlink_limits_status_t* limits_status)
177 return mavlink_msg_limits_status_pack(system_id, component_id, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
189static inline uint16_t mavlink_msg_limits_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg,
const mavlink_limits_status_t* limits_status)
191 return mavlink_msg_limits_status_pack_chan(system_id, component_id, chan, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
208#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
210static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
212#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
213 char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
214 _mav_put_uint32_t(buf, 0, last_trigger);
215 _mav_put_uint32_t(buf, 4, last_action);
216 _mav_put_uint32_t(buf, 8, last_recovery);
217 _mav_put_uint32_t(buf, 12, last_clear);
218 _mav_put_uint16_t(buf, 16, breach_count);
219 _mav_put_uint8_t(buf, 18, limits_state);
220 _mav_put_uint8_t(buf, 19, mods_enabled);
221 _mav_put_uint8_t(buf, 20, mods_required);
222 _mav_put_uint8_t(buf, 21, mods_triggered);
224 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
226 mavlink_limits_status_t packet;
227 packet.last_trigger = last_trigger;
228 packet.last_action = last_action;
229 packet.last_recovery = last_recovery;
230 packet.last_clear = last_clear;
231 packet.breach_count = breach_count;
232 packet.limits_state = limits_state;
233 packet.mods_enabled = mods_enabled;
234 packet.mods_required = mods_required;
235 packet.mods_triggered = mods_triggered;
237 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (
const char *)&packet, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
246static inline void mavlink_msg_limits_status_send_struct(mavlink_channel_t chan,
const mavlink_limits_status_t* limits_status)
248#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
249 mavlink_msg_limits_status_send(chan, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
251 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (
const char *)limits_status, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
255#if MAVLINK_MSG_ID_LIMITS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
263static inline void mavlink_msg_limits_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
265#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
266 char *buf = (
char *)msgbuf;
267 _mav_put_uint32_t(buf, 0, last_trigger);
268 _mav_put_uint32_t(buf, 4, last_action);
269 _mav_put_uint32_t(buf, 8, last_recovery);
270 _mav_put_uint32_t(buf, 12, last_clear);
271 _mav_put_uint16_t(buf, 16, breach_count);
272 _mav_put_uint8_t(buf, 18, limits_state);
273 _mav_put_uint8_t(buf, 19, mods_enabled);
274 _mav_put_uint8_t(buf, 20, mods_required);
275 _mav_put_uint8_t(buf, 21, mods_triggered);
277 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
279 mavlink_limits_status_t *packet = (mavlink_limits_status_t *)msgbuf;
280 packet->last_trigger = last_trigger;
281 packet->last_action = last_action;
282 packet->last_recovery = last_recovery;
283 packet->last_clear = last_clear;
284 packet->breach_count = breach_count;
285 packet->limits_state = limits_state;
286 packet->mods_enabled = mods_enabled;
287 packet->mods_required = mods_required;
288 packet->mods_triggered = mods_triggered;
290 _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (
const char *)packet, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
305static inline uint8_t mavlink_msg_limits_status_get_limits_state(
const mavlink_message_t* msg)
307 return _MAV_RETURN_uint8_t(msg, 18);
315static inline uint32_t mavlink_msg_limits_status_get_last_trigger(
const mavlink_message_t* msg)
317 return _MAV_RETURN_uint32_t(msg, 0);
325static inline uint32_t mavlink_msg_limits_status_get_last_action(
const mavlink_message_t* msg)
327 return _MAV_RETURN_uint32_t(msg, 4);
335static inline uint32_t mavlink_msg_limits_status_get_last_recovery(
const mavlink_message_t* msg)
337 return _MAV_RETURN_uint32_t(msg, 8);
345static inline uint32_t mavlink_msg_limits_status_get_last_clear(
const mavlink_message_t* msg)
347 return _MAV_RETURN_uint32_t(msg, 12);
355static inline uint16_t mavlink_msg_limits_status_get_breach_count(
const mavlink_message_t* msg)
357 return _MAV_RETURN_uint16_t(msg, 16);
365static inline uint8_t mavlink_msg_limits_status_get_mods_enabled(
const mavlink_message_t* msg)
367 return _MAV_RETURN_uint8_t(msg, 19);
375static inline uint8_t mavlink_msg_limits_status_get_mods_required(
const mavlink_message_t* msg)
377 return _MAV_RETURN_uint8_t(msg, 20);
385static inline uint8_t mavlink_msg_limits_status_get_mods_triggered(
const mavlink_message_t* msg)
387 return _MAV_RETURN_uint8_t(msg, 21);
396static inline void mavlink_msg_limits_status_decode(
const mavlink_message_t* msg, mavlink_limits_status_t* limits_status)
398#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
399 limits_status->last_trigger = mavlink_msg_limits_status_get_last_trigger(msg);
400 limits_status->last_action = mavlink_msg_limits_status_get_last_action(msg);
401 limits_status->last_recovery = mavlink_msg_limits_status_get_last_recovery(msg);
402 limits_status->last_clear = mavlink_msg_limits_status_get_last_clear(msg);
403 limits_status->breach_count = mavlink_msg_limits_status_get_breach_count(msg);
404 limits_status->limits_state = mavlink_msg_limits_status_get_limits_state(msg);
405 limits_status->mods_enabled = mavlink_msg_limits_status_get_mods_enabled(msg);
406 limits_status->mods_required = mavlink_msg_limits_status_get_mods_required(msg);
407 limits_status->mods_triggered = mavlink_msg_limits_status_get_mods_triggered(msg);
409 uint8_t len = msg->len < MAVLINK_MSG_ID_LIMITS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_LIMITS_STATUS_LEN;
410 memset(limits_status, 0, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
411 memcpy(limits_status, _MAV_PAYLOAD(msg), len);