mavlink_msg_serial_control.h
Go to the documentation of this file.
1 // MESSAGE SERIAL_CONTROL PACKING
2 
3 #define MAVLINK_MSG_ID_SERIAL_CONTROL 126
4 
6 {
7  uint32_t baudrate; /*< Baudrate of transfer. Zero means no change.*/
8  uint16_t timeout; /*< Timeout for reply data in milliseconds*/
9  uint8_t device; /*< See SERIAL_CONTROL_DEV enum*/
10  uint8_t flags; /*< See SERIAL_CONTROL_FLAG enum*/
11  uint8_t count; /*< how many bytes in this transfer*/
12  uint8_t data[70]; /*< serial data*/
14 
15 #define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79
16 #define MAVLINK_MSG_ID_126_LEN 79
17 
18 #define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220
19 #define MAVLINK_MSG_ID_126_CRC 220
20 
21 #define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70
22 
23 #define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \
24  "SERIAL_CONTROL", \
25  6, \
26  { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \
27  { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \
28  { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \
29  { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \
30  { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \
31  { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \
32  } \
33 }
34 
35 
50 static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
51  uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
52 {
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
55  _mav_put_uint32_t(buf, 0, baudrate);
56  _mav_put_uint16_t(buf, 4, timeout);
57  _mav_put_uint8_t(buf, 6, device);
58  _mav_put_uint8_t(buf, 7, flags);
59  _mav_put_uint8_t(buf, 8, count);
60  _mav_put_uint8_t_array(buf, 9, data, 70);
62 #else
64  packet.baudrate = baudrate;
65  packet.timeout = timeout;
66  packet.device = device;
67  packet.flags = flags;
68  packet.count = count;
69  mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
71 #endif
72 
73  msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL;
74 #if MAVLINK_CRC_EXTRA
76 #else
77  return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
78 #endif
79 }
80 
95 static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
96  mavlink_message_t* msg,
97  uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data)
98 {
99 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
101  _mav_put_uint32_t(buf, 0, baudrate);
102  _mav_put_uint16_t(buf, 4, timeout);
103  _mav_put_uint8_t(buf, 6, device);
104  _mav_put_uint8_t(buf, 7, flags);
105  _mav_put_uint8_t(buf, 8, count);
106  _mav_put_uint8_t_array(buf, 9, data, 70);
108 #else
110  packet.baudrate = baudrate;
111  packet.timeout = timeout;
112  packet.device = device;
113  packet.flags = flags;
114  packet.count = count;
115  mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
117 #endif
118 
119  msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL;
120 #if MAVLINK_CRC_EXTRA
122 #else
123  return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
124 #endif
125 }
126 
135 static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control)
136 {
137  return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data);
138 }
139 
149 static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control)
150 {
151  return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data);
152 }
153 
165 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
166 
167 static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
168 {
169 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
171  _mav_put_uint32_t(buf, 0, baudrate);
172  _mav_put_uint16_t(buf, 4, timeout);
173  _mav_put_uint8_t(buf, 6, device);
174  _mav_put_uint8_t(buf, 7, flags);
175  _mav_put_uint8_t(buf, 8, count);
176  _mav_put_uint8_t_array(buf, 9, data, 70);
177 #if MAVLINK_CRC_EXTRA
179 #else
180  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
181 #endif
182 #else
184  packet.baudrate = baudrate;
185  packet.timeout = timeout;
186  packet.device = device;
187  packet.flags = flags;
188  packet.count = count;
189  mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
190 #if MAVLINK_CRC_EXTRA
191  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
192 #else
193  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
194 #endif
195 #endif
196 }
197 
198 #if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
199 /*
200  This varient of _send() can be used to save stack space by re-using
201  memory from the receive buffer. The caller provides a
202  mavlink_message_t which is the size of a full mavlink message. This
203  is usually the receive buffer for the channel, and allows a reply to an
204  incoming message with minimum stack space usage.
205  */
206 static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
207 {
208 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
209  char *buf = (char *)msgbuf;
210  _mav_put_uint32_t(buf, 0, baudrate);
211  _mav_put_uint16_t(buf, 4, timeout);
212  _mav_put_uint8_t(buf, 6, device);
213  _mav_put_uint8_t(buf, 7, flags);
214  _mav_put_uint8_t(buf, 8, count);
215  _mav_put_uint8_t_array(buf, 9, data, 70);
216 #if MAVLINK_CRC_EXTRA
218 #else
219  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
220 #endif
221 #else
223  packet->baudrate = baudrate;
224  packet->timeout = timeout;
225  packet->device = device;
226  packet->flags = flags;
227  packet->count = count;
228  mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70);
229 #if MAVLINK_CRC_EXTRA
230  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
231 #else
232  _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
233 #endif
234 #endif
235 }
236 #endif
237 
238 #endif
239 
240 // MESSAGE SERIAL_CONTROL UNPACKING
241 
242 
248 static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg)
249 {
250  return _MAV_RETURN_uint8_t(msg, 6);
251 }
252 
258 static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg)
259 {
260  return _MAV_RETURN_uint8_t(msg, 7);
261 }
262 
268 static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg)
269 {
270  return _MAV_RETURN_uint16_t(msg, 4);
271 }
272 
278 static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg)
279 {
280  return _MAV_RETURN_uint32_t(msg, 0);
281 }
282 
288 static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg)
289 {
290  return _MAV_RETURN_uint8_t(msg, 8);
291 }
292 
298 static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data)
299 {
300  return _MAV_RETURN_uint8_t_array(msg, data, 70, 9);
301 }
302 
309 static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control)
310 {
311 #if MAVLINK_NEED_BYTE_SWAP
312  serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg);
313  serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg);
314  serial_control->device = mavlink_msg_serial_control_get_device(msg);
315  serial_control->flags = mavlink_msg_serial_control_get_flags(msg);
316  serial_control->count = mavlink_msg_serial_control_get_count(msg);
317  mavlink_msg_serial_control_get_data(msg, serial_control->data);
318 #else
319  memcpy(serial_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
320 #endif
321 }
#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_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
Definition: protocol.h:197
static void mav_array_memcpy(void *dest, const void *src, size_t n)
Definition: protocol.h:176
static uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value, uint8_t array_length, uint8_t wire_offset)
Definition: protocol.h:295
#define _mav_put_uint16_t(buf, wire_offset, b)
Definition: protocol.h:145
#define _mav_put_uint32_t(buf, wire_offset, b)
Definition: protocol.h:147


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