mavlink_msg_rosflight_status.h
Go to the documentation of this file.
1 // MESSAGE ROSFLIGHT_STATUS PACKING
2 
3 #define MAVLINK_MSG_ID_ROSFLIGHT_STATUS 191
4 
6 {
7  int16_t num_errors; /*< */
8  int16_t loop_time_us; /*< */
9  uint8_t armed; /*< */
10  uint8_t failsafe; /*< */
11  uint8_t rc_override; /*< */
12  uint8_t offboard; /*< */
13  uint8_t error_code; /*< */
14  uint8_t control_mode; /*< */
16 
17 #define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN 10
18 #define MAVLINK_MSG_ID_191_LEN 10
19 
20 #define MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC 183
21 #define MAVLINK_MSG_ID_191_CRC 183
22 
23 
24 
25 #define MAVLINK_MESSAGE_INFO_ROSFLIGHT_STATUS { \
26  "ROSFLIGHT_STATUS", \
27  8, \
28  { { "num_errors", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_rosflight_status_t, num_errors) }, \
29  { "loop_time_us", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_rosflight_status_t, loop_time_us) }, \
30  { "armed", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_rosflight_status_t, armed) }, \
31  { "failsafe", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_rosflight_status_t, failsafe) }, \
32  { "rc_override", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_rosflight_status_t, rc_override) }, \
33  { "offboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_rosflight_status_t, offboard) }, \
34  { "error_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_rosflight_status_t, error_code) }, \
35  { "control_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_rosflight_status_t, control_mode) }, \
36  } \
37 }
38 
39 
56 static inline uint16_t mavlink_msg_rosflight_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
57  uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us)
58 {
59 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
61  _mav_put_int16_t(buf, 0, num_errors);
62  _mav_put_int16_t(buf, 2, loop_time_us);
63  _mav_put_uint8_t(buf, 4, armed);
64  _mav_put_uint8_t(buf, 5, failsafe);
65  _mav_put_uint8_t(buf, 6, rc_override);
66  _mav_put_uint8_t(buf, 7, offboard);
67  _mav_put_uint8_t(buf, 8, error_code);
68  _mav_put_uint8_t(buf, 9, control_mode);
69 
71 #else
73  packet.num_errors = num_errors;
74  packet.loop_time_us = loop_time_us;
75  packet.armed = armed;
76  packet.failsafe = failsafe;
77  packet.rc_override = rc_override;
78  packet.offboard = offboard;
79  packet.error_code = error_code;
80  packet.control_mode = control_mode;
81 
83 #endif
84 
86 #if MAVLINK_CRC_EXTRA
88 #else
89  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN);
90 #endif
91 }
92 
109 static inline uint16_t mavlink_msg_rosflight_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
110  mavlink_message_t* msg,
111  uint8_t armed,uint8_t failsafe,uint8_t rc_override,uint8_t offboard,uint8_t error_code,uint8_t control_mode,int16_t num_errors,int16_t loop_time_us)
112 {
113 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115  _mav_put_int16_t(buf, 0, num_errors);
116  _mav_put_int16_t(buf, 2, loop_time_us);
117  _mav_put_uint8_t(buf, 4, armed);
118  _mav_put_uint8_t(buf, 5, failsafe);
119  _mav_put_uint8_t(buf, 6, rc_override);
120  _mav_put_uint8_t(buf, 7, offboard);
121  _mav_put_uint8_t(buf, 8, error_code);
122  _mav_put_uint8_t(buf, 9, control_mode);
123 
125 #else
127  packet.num_errors = num_errors;
128  packet.loop_time_us = loop_time_us;
129  packet.armed = armed;
130  packet.failsafe = failsafe;
131  packet.rc_override = rc_override;
132  packet.offboard = offboard;
133  packet.error_code = error_code;
134  packet.control_mode = control_mode;
135 
137 #endif
138 
139  msg->msgid = MAVLINK_MSG_ID_ROSFLIGHT_STATUS;
140 #if MAVLINK_CRC_EXTRA
142 #else
143  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN);
144 #endif
145 }
146 
155 static inline uint16_t mavlink_msg_rosflight_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rosflight_status_t* rosflight_status)
156 {
157  return mavlink_msg_rosflight_status_pack(system_id, component_id, msg, rosflight_status->armed, rosflight_status->failsafe, rosflight_status->rc_override, rosflight_status->offboard, rosflight_status->error_code, rosflight_status->control_mode, rosflight_status->num_errors, rosflight_status->loop_time_us);
158 }
159 
169 static inline uint16_t mavlink_msg_rosflight_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rosflight_status_t* rosflight_status)
170 {
171  return mavlink_msg_rosflight_status_pack_chan(system_id, component_id, chan, msg, rosflight_status->armed, rosflight_status->failsafe, rosflight_status->rc_override, rosflight_status->offboard, rosflight_status->error_code, rosflight_status->control_mode, rosflight_status->num_errors, rosflight_status->loop_time_us);
172 }
173 
187 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
188 
189 static inline void mavlink_msg_rosflight_status_send(mavlink_channel_t chan, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us)
190 {
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
193  _mav_put_int16_t(buf, 0, num_errors);
194  _mav_put_int16_t(buf, 2, loop_time_us);
195  _mav_put_uint8_t(buf, 4, armed);
196  _mav_put_uint8_t(buf, 5, failsafe);
197  _mav_put_uint8_t(buf, 6, rc_override);
198  _mav_put_uint8_t(buf, 7, offboard);
199  _mav_put_uint8_t(buf, 8, error_code);
201 
202 #if MAVLINK_CRC_EXTRA
204 #else
205  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN);
206 #endif
207 #else
209  packet.num_errors = num_errors;
210  packet.loop_time_us = loop_time_us;
211  packet.armed = armed;
212  packet.failsafe = failsafe;
213  packet.rc_override = rc_override;
214  packet.offboard = offboard;
215  packet.error_code = error_code;
216  packet.control_mode = control_mode;
217 
218 #if MAVLINK_CRC_EXTRA
219  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC);
220 #else
221  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN);
222 #endif
223 #endif
224 }
225 
226 #if MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
227 /*
228  This varient of _send() can be used to save stack space by re-using
229  memory from the receive buffer. The caller provides a
230  mavlink_message_t which is the size of a full mavlink message. This
231  is usually the receive buffer for the channel, and allows a reply to an
232  incoming message with minimum stack space usage.
233  */
234 static inline void mavlink_msg_rosflight_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t armed, uint8_t failsafe, uint8_t rc_override, uint8_t offboard, uint8_t error_code, uint8_t control_mode, int16_t num_errors, int16_t loop_time_us)
235 {
236 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
237  char *buf = (char *)msgbuf;
238  _mav_put_int16_t(buf, 0, num_errors);
239  _mav_put_int16_t(buf, 2, loop_time_us);
240  _mav_put_uint8_t(buf, 4, armed);
241  _mav_put_uint8_t(buf, 5, failsafe);
242  _mav_put_uint8_t(buf, 6, rc_override);
243  _mav_put_uint8_t(buf, 7, offboard);
244  _mav_put_uint8_t(buf, 8, error_code);
246 
247 #if MAVLINK_CRC_EXTRA
249 #else
250  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, buf, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN);
251 #endif
252 #else
254  packet->num_errors = num_errors;
255  packet->loop_time_us = loop_time_us;
256  packet->armed = armed;
257  packet->failsafe = failsafe;
258  packet->rc_override = rc_override;
259  packet->offboard = offboard;
260  packet->error_code = error_code;
261  packet->control_mode = control_mode;
262 
263 #if MAVLINK_CRC_EXTRA
264  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_CRC);
265 #else
266  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROSFLIGHT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN);
267 #endif
268 #endif
269 }
270 #endif
271 
272 #endif
273 
274 // MESSAGE ROSFLIGHT_STATUS UNPACKING
275 
276 
282 static inline uint8_t mavlink_msg_rosflight_status_get_armed(const mavlink_message_t* msg)
283 {
284  return _MAV_RETURN_uint8_t(msg, 4);
285 }
286 
292 static inline uint8_t mavlink_msg_rosflight_status_get_failsafe(const mavlink_message_t* msg)
293 {
294  return _MAV_RETURN_uint8_t(msg, 5);
295 }
296 
302 static inline uint8_t mavlink_msg_rosflight_status_get_rc_override(const mavlink_message_t* msg)
303 {
304  return _MAV_RETURN_uint8_t(msg, 6);
305 }
306 
312 static inline uint8_t mavlink_msg_rosflight_status_get_offboard(const mavlink_message_t* msg)
313 {
314  return _MAV_RETURN_uint8_t(msg, 7);
315 }
316 
322 static inline uint8_t mavlink_msg_rosflight_status_get_error_code(const mavlink_message_t* msg)
323 {
324  return _MAV_RETURN_uint8_t(msg, 8);
325 }
326 
332 static inline uint8_t mavlink_msg_rosflight_status_get_control_mode(const mavlink_message_t* msg)
333 {
334  return _MAV_RETURN_uint8_t(msg, 9);
335 }
336 
342 static inline int16_t mavlink_msg_rosflight_status_get_num_errors(const mavlink_message_t* msg)
343 {
344  return _MAV_RETURN_int16_t(msg, 0);
345 }
346 
352 static inline int16_t mavlink_msg_rosflight_status_get_loop_time_us(const mavlink_message_t* msg)
353 {
354  return _MAV_RETURN_int16_t(msg, 2);
355 }
356 
363 static inline void mavlink_msg_rosflight_status_decode(const mavlink_message_t* msg, mavlink_rosflight_status_t* rosflight_status)
364 {
365 #if MAVLINK_NEED_BYTE_SWAP
368  rosflight_status->armed = mavlink_msg_rosflight_status_get_armed(msg);
369  rosflight_status->failsafe = mavlink_msg_rosflight_status_get_failsafe(msg);
371  rosflight_status->offboard = mavlink_msg_rosflight_status_get_offboard(msg);
374 #else
375  memcpy(rosflight_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROSFLIGHT_STATUS_LEN);
376 #endif
377 }
#define _MAV_RETURN_uint8_t(msg, wire_offset)
Definition: protocol.h:244
#define _mav_put_uint8_t(buf, wire_offset, b)
Definition: protocol.h:140
#define _mav_put_int16_t(buf, wire_offset, b)
Definition: protocol.h:146


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:25