mavlink_msg_named_command_struct.h
Go to the documentation of this file.
1 // MESSAGE NAMED_COMMAND_STRUCT PACKING
2 
3 #define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT 186
4 
6 {
7  float x; /*< x value in the command struct*/
8  float y; /*< y value in the command struct*/
9  float z; /*< z value in the command struct*/
10  float F; /*< F value in the command struct*/
11  char name[10]; /*< Name of the command struct*/
12  uint8_t type; /*< Type of command struct*/
13  uint8_t ignore; /*< Type of command struct*/
15 
16 #define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN 28
17 #define MAVLINK_MSG_ID_186_LEN 28
18 
19 #define MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_CRC 169
20 #define MAVLINK_MSG_ID_186_CRC 169
21 
22 #define MAVLINK_MSG_NAMED_COMMAND_STRUCT_FIELD_NAME_LEN 10
23 
24 #define MAVLINK_MESSAGE_INFO_NAMED_COMMAND_STRUCT { \
25  "NAMED_COMMAND_STRUCT", \
26  7, \
27  { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_named_command_struct_t, x) }, \
28  { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_command_struct_t, y) }, \
29  { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_named_command_struct_t, z) }, \
30  { "F", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_named_command_struct_t, F) }, \
31  { "name", NULL, MAVLINK_TYPE_CHAR, 10, 16, offsetof(mavlink_named_command_struct_t, name) }, \
32  { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_named_command_struct_t, type) }, \
33  { "ignore", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_named_command_struct_t, ignore) }, \
34  } \
35 }
36 
37 
53 static inline uint16_t mavlink_msg_named_command_struct_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
54  const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F)
55 {
56 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
58  _mav_put_float(buf, 0, x);
59  _mav_put_float(buf, 4, y);
60  _mav_put_float(buf, 8, z);
61  _mav_put_float(buf, 12, F);
62  _mav_put_uint8_t(buf, 26, type);
63  _mav_put_uint8_t(buf, 27, ignore);
64  _mav_put_char_array(buf, 16, name, 10);
66 #else
68  packet.x = x;
69  packet.y = y;
70  packet.z = z;
71  packet.F = F;
72  packet.type = type;
73  packet.ignore = ignore;
74  mav_array_memcpy(packet.name, name, sizeof(char)*10);
76 #endif
77 
79 #if MAVLINK_CRC_EXTRA
81 #else
82  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN);
83 #endif
84 }
85 
101 static inline uint16_t mavlink_msg_named_command_struct_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
102  mavlink_message_t* msg,
103  const char *name,uint8_t type,uint8_t ignore,float x,float y,float z,float F)
104 {
105 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
107  _mav_put_float(buf, 0, x);
108  _mav_put_float(buf, 4, y);
109  _mav_put_float(buf, 8, z);
110  _mav_put_float(buf, 12, F);
111  _mav_put_uint8_t(buf, 26, type);
112  _mav_put_uint8_t(buf, 27, ignore);
113  _mav_put_char_array(buf, 16, name, 10);
115 #else
117  packet.x = x;
118  packet.y = y;
119  packet.z = z;
120  packet.F = F;
121  packet.type = type;
122  packet.ignore = ignore;
123  mav_array_memcpy(packet.name, name, sizeof(char)*10);
125 #endif
126 
128 #if MAVLINK_CRC_EXTRA
130 #else
131  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN);
132 #endif
133 }
134 
143 static inline uint16_t mavlink_msg_named_command_struct_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_command_struct_t* named_command_struct)
144 {
145  return mavlink_msg_named_command_struct_pack(system_id, component_id, msg, named_command_struct->name, named_command_struct->type, named_command_struct->ignore, named_command_struct->x, named_command_struct->y, named_command_struct->z, named_command_struct->F);
146 }
147 
157 static inline uint16_t mavlink_msg_named_command_struct_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_command_struct_t* named_command_struct)
158 {
159  return mavlink_msg_named_command_struct_pack_chan(system_id, component_id, chan, msg, named_command_struct->name, named_command_struct->type, named_command_struct->ignore, named_command_struct->x, named_command_struct->y, named_command_struct->z, named_command_struct->F);
160 }
161 
174 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
175 
176 static inline void mavlink_msg_named_command_struct_send(mavlink_channel_t chan, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F)
177 {
178 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
180  _mav_put_float(buf, 0, x);
181  _mav_put_float(buf, 4, y);
182  _mav_put_float(buf, 8, z);
183  _mav_put_float(buf, 12, F);
184  _mav_put_uint8_t(buf, 26, type);
185  _mav_put_uint8_t(buf, 27, ignore);
186  _mav_put_char_array(buf, 16, name, 10);
187 #if MAVLINK_CRC_EXTRA
189 #else
190  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN);
191 #endif
192 #else
194  packet.x = x;
195  packet.y = y;
196  packet.z = z;
197  packet.F = F;
198  packet.type = type;
199  packet.ignore = ignore;
200  mav_array_memcpy(packet.name, name, sizeof(char)*10);
201 #if MAVLINK_CRC_EXTRA
203 #else
204  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN);
205 #endif
206 #endif
207 }
208 
209 #if MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
210 /*
211  This varient of _send() can be used to save stack space by re-using
212  memory from the receive buffer. The caller provides a
213  mavlink_message_t which is the size of a full mavlink message. This
214  is usually the receive buffer for the channel, and allows a reply to an
215  incoming message with minimum stack space usage.
216  */
217 static inline void mavlink_msg_named_command_struct_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint8_t type, uint8_t ignore, float x, float y, float z, float F)
218 {
219 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
220  char *buf = (char *)msgbuf;
221  _mav_put_float(buf, 0, x);
222  _mav_put_float(buf, 4, y);
223  _mav_put_float(buf, 8, z);
224  _mav_put_float(buf, 12, F);
225  _mav_put_uint8_t(buf, 26, type);
226  _mav_put_uint8_t(buf, 27, ignore);
227  _mav_put_char_array(buf, 16, name, 10);
228 #if MAVLINK_CRC_EXTRA
230 #else
231  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, buf, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN);
232 #endif
233 #else
235  packet->x = x;
236  packet->y = y;
237  packet->z = z;
238  packet->F = F;
239  packet->type = type;
240  packet->ignore = ignore;
241  mav_array_memcpy(packet->name, name, sizeof(char)*10);
242 #if MAVLINK_CRC_EXTRA
244 #else
245  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT, (const char *)packet, MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN);
246 #endif
247 #endif
248 }
249 #endif
250 
251 #endif
252 
253 // MESSAGE NAMED_COMMAND_STRUCT UNPACKING
254 
255 
261 static inline uint16_t mavlink_msg_named_command_struct_get_name(const mavlink_message_t* msg, char *name)
262 {
263  return _MAV_RETURN_char_array(msg, name, 10, 16);
264 }
265 
271 static inline uint8_t mavlink_msg_named_command_struct_get_type(const mavlink_message_t* msg)
272 {
273  return _MAV_RETURN_uint8_t(msg, 26);
274 }
275 
281 static inline uint8_t mavlink_msg_named_command_struct_get_ignore(const mavlink_message_t* msg)
282 {
283  return _MAV_RETURN_uint8_t(msg, 27);
284 }
285 
291 static inline float mavlink_msg_named_command_struct_get_x(const mavlink_message_t* msg)
292 {
293  return _MAV_RETURN_float(msg, 0);
294 }
295 
301 static inline float mavlink_msg_named_command_struct_get_y(const mavlink_message_t* msg)
302 {
303  return _MAV_RETURN_float(msg, 4);
304 }
305 
311 static inline float mavlink_msg_named_command_struct_get_z(const mavlink_message_t* msg)
312 {
313  return _MAV_RETURN_float(msg, 8);
314 }
315 
321 static inline float mavlink_msg_named_command_struct_get_F(const mavlink_message_t* msg)
322 {
323  return _MAV_RETURN_float(msg, 12);
324 }
325 
332 static inline void mavlink_msg_named_command_struct_decode(const mavlink_message_t* msg, mavlink_named_command_struct_t* named_command_struct)
333 {
334 #if MAVLINK_NEED_BYTE_SWAP
335  named_command_struct->x = mavlink_msg_named_command_struct_get_x(msg);
336  named_command_struct->y = mavlink_msg_named_command_struct_get_y(msg);
337  named_command_struct->z = mavlink_msg_named_command_struct_get_z(msg);
338  named_command_struct->F = mavlink_msg_named_command_struct_get_F(msg);
339  mavlink_msg_named_command_struct_get_name(msg, named_command_struct->name);
340  named_command_struct->type = mavlink_msg_named_command_struct_get_type(msg);
341  named_command_struct->ignore = mavlink_msg_named_command_struct_get_ignore(msg);
342 #else
343  memcpy(named_command_struct, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_COMMAND_STRUCT_LEN);
344 #endif
345 }
#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
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:288
static void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
Definition: protocol.h:188


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:47