mavlink_msg_offboard_control.h
Go to the documentation of this file.
1 // MESSAGE OFFBOARD_CONTROL PACKING
2 
3 #define MAVLINK_MSG_ID_OFFBOARD_CONTROL 180
4 
6 {
7  float x; /*< x control channel interpreted according to mode*/
8  float y; /*< y control channel, interpreted according to mode*/
9  float z; /*< z control channel, interpreted according to mode*/
10  float F; /*< F control channel, interpreted according to mode*/
11  uint8_t mode; /*< Offboard control mode, see OFFBOARD_CONTROL_MODE*/
12  uint8_t ignore; /*< Bitfield specifying which fields should be ignored, see OFFBOARD_CONTROL_IGNORE*/
14 
15 #define MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN 18
16 #define MAVLINK_MSG_ID_180_LEN 18
17 
18 #define MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC 93
19 #define MAVLINK_MSG_ID_180_CRC 93
20 
21 
22 
23 #define MAVLINK_MESSAGE_INFO_OFFBOARD_CONTROL { \
24  "OFFBOARD_CONTROL", \
25  6, \
26  { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_offboard_control_t, x) }, \
27  { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_offboard_control_t, y) }, \
28  { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_offboard_control_t, z) }, \
29  { "F", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_offboard_control_t, F) }, \
30  { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_offboard_control_t, mode) }, \
31  { "ignore", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_offboard_control_t, ignore) }, \
32  } \
33 }
34 
35 
50 static inline uint16_t mavlink_msg_offboard_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51  uint8_t mode, uint8_t ignore, float x, float y, float z, float F)
52 {
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55  _mav_put_float(buf, 0, x);
56  _mav_put_float(buf, 4, y);
57  _mav_put_float(buf, 8, z);
58  _mav_put_float(buf, 12, F);
59  _mav_put_uint8_t(buf, 16, mode);
60  _mav_put_uint8_t(buf, 17, ignore);
61 
63 #else
65  packet.x = x;
66  packet.y = y;
67  packet.z = z;
68  packet.F = F;
69  packet.mode = mode;
70  packet.ignore = ignore;
71 
73 #endif
74 
76 #if MAVLINK_CRC_EXTRA
78 #else
79  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN);
80 #endif
81 }
82 
97 static inline uint16_t mavlink_msg_offboard_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
98  mavlink_message_t* msg,
99  uint8_t mode,uint8_t ignore,float x,float y,float z,float F)
100 {
101 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
103  _mav_put_float(buf, 0, x);
104  _mav_put_float(buf, 4, y);
105  _mav_put_float(buf, 8, z);
106  _mav_put_float(buf, 12, F);
107  _mav_put_uint8_t(buf, 16, mode);
108  _mav_put_uint8_t(buf, 17, ignore);
109 
111 #else
113  packet.x = x;
114  packet.y = y;
115  packet.z = z;
116  packet.F = F;
117  packet.mode = mode;
118  packet.ignore = ignore;
119 
121 #endif
122 
123  msg->msgid = MAVLINK_MSG_ID_OFFBOARD_CONTROL;
124 #if MAVLINK_CRC_EXTRA
126 #else
127  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN);
128 #endif
129 }
130 
139 static inline uint16_t mavlink_msg_offboard_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_offboard_control_t* offboard_control)
140 {
141  return mavlink_msg_offboard_control_pack(system_id, component_id, msg, offboard_control->mode, offboard_control->ignore, offboard_control->x, offboard_control->y, offboard_control->z, offboard_control->F);
142 }
143 
153 static inline uint16_t mavlink_msg_offboard_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_offboard_control_t* offboard_control)
154 {
155  return mavlink_msg_offboard_control_pack_chan(system_id, component_id, chan, msg, offboard_control->mode, offboard_control->ignore, offboard_control->x, offboard_control->y, offboard_control->z, offboard_control->F);
156 }
157 
169 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
170 
171 static inline void mavlink_msg_offboard_control_send(mavlink_channel_t chan, uint8_t mode, uint8_t ignore, float x, float y, float z, float F)
172 {
173 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
175  _mav_put_float(buf, 0, x);
176  _mav_put_float(buf, 4, y);
177  _mav_put_float(buf, 8, z);
178  _mav_put_float(buf, 12, F);
179  _mav_put_uint8_t(buf, 16, mode);
180  _mav_put_uint8_t(buf, 17, ignore);
181 
182 #if MAVLINK_CRC_EXTRA
184 #else
185  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN);
186 #endif
187 #else
189  packet.x = x;
190  packet.y = y;
191  packet.z = z;
192  packet.F = F;
193  packet.mode = mode;
194  packet.ignore = ignore;
195 
196 #if MAVLINK_CRC_EXTRA
197  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC);
198 #else
199  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN);
200 #endif
201 #endif
202 }
203 
204 #if MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
205 /*
206  This varient of _send() can be used to save stack space by re-using
207  memory from the receive buffer. The caller provides a
208  mavlink_message_t which is the size of a full mavlink message. This
209  is usually the receive buffer for the channel, and allows a reply to an
210  incoming message with minimum stack space usage.
211  */
212 static inline void mavlink_msg_offboard_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t mode, uint8_t ignore, float x, float y, float z, float F)
213 {
214 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
215  char *buf = (char *)msgbuf;
216  _mav_put_float(buf, 0, x);
217  _mav_put_float(buf, 4, y);
218  _mav_put_float(buf, 8, z);
219  _mav_put_float(buf, 12, F);
220  _mav_put_uint8_t(buf, 16, mode);
221  _mav_put_uint8_t(buf, 17, ignore);
222 
223 #if MAVLINK_CRC_EXTRA
225 #else
226  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, buf, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN);
227 #endif
228 #else
230  packet->x = x;
231  packet->y = y;
232  packet->z = z;
233  packet->F = F;
234  packet->mode = mode;
235  packet->ignore = ignore;
236 
237 #if MAVLINK_CRC_EXTRA
238  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN, MAVLINK_MSG_ID_OFFBOARD_CONTROL_CRC);
239 #else
240  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OFFBOARD_CONTROL, (const char *)packet, MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN);
241 #endif
242 #endif
243 }
244 #endif
245 
246 #endif
247 
248 // MESSAGE OFFBOARD_CONTROL UNPACKING
249 
250 
256 static inline uint8_t mavlink_msg_offboard_control_get_mode(const mavlink_message_t* msg)
257 {
258  return _MAV_RETURN_uint8_t(msg, 16);
259 }
260 
266 static inline uint8_t mavlink_msg_offboard_control_get_ignore(const mavlink_message_t* msg)
267 {
268  return _MAV_RETURN_uint8_t(msg, 17);
269 }
270 
276 static inline float mavlink_msg_offboard_control_get_x(const mavlink_message_t* msg)
277 {
278  return _MAV_RETURN_float(msg, 0);
279 }
280 
286 static inline float mavlink_msg_offboard_control_get_y(const mavlink_message_t* msg)
287 {
288  return _MAV_RETURN_float(msg, 4);
289 }
290 
296 static inline float mavlink_msg_offboard_control_get_z(const mavlink_message_t* msg)
297 {
298  return _MAV_RETURN_float(msg, 8);
299 }
300 
306 static inline float mavlink_msg_offboard_control_get_F(const mavlink_message_t* msg)
307 {
308  return _MAV_RETURN_float(msg, 12);
309 }
310 
317 static inline void mavlink_msg_offboard_control_decode(const mavlink_message_t* msg, mavlink_offboard_control_t* offboard_control)
318 {
319 #if MAVLINK_NEED_BYTE_SWAP
320  offboard_control->x = mavlink_msg_offboard_control_get_x(msg);
321  offboard_control->y = mavlink_msg_offboard_control_get_y(msg);
322  offboard_control->z = mavlink_msg_offboard_control_get_z(msg);
323  offboard_control->F = mavlink_msg_offboard_control_get_F(msg);
324  offboard_control->mode = mavlink_msg_offboard_control_get_mode(msg);
325  offboard_control->ignore = mavlink_msg_offboard_control_get_ignore(msg);
326 #else
327  memcpy(offboard_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OFFBOARD_CONTROL_LEN);
328 #endif
329 }
#define _mav_put_float(buf, wire_offset, b)
Definition: protocol.h:151
#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


rosflight
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 20:00:13