1 // MESSAGE SERIAL_CONTROL PACKING
3 #define MAVLINK_MSG_ID_SERIAL_CONTROL 126
5 typedef struct __mavlink_serial_control_t
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
13 } mavlink_serial_control_t
;
15 #define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79
16 #define MAVLINK_MSG_ID_126_LEN 79
18 #define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220
19 #define MAVLINK_MSG_ID_126_CRC 220
21 #define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70
23 #define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \
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) }, \
37 * @brief Pack a serial_control message
38 * @param system_id ID of this system
39 * @param component_id ID of this component (e.g. 200 for IMU)
40 * @param msg The MAVLink message to compress the data into
42 * @param device See SERIAL_CONTROL_DEV enum
43 * @param flags See SERIAL_CONTROL_FLAG enum
44 * @param timeout Timeout for reply data in milliseconds
45 * @param baudrate Baudrate of transfer. Zero means no change.
46 * @param count how many bytes in this transfer
47 * @param data serial data
48 * @return length of the message in bytes (excluding serial stream start sign)
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
)
53 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
54 char buf
[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
];
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);
61 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
63 mavlink_serial_control_t packet
;
64 packet
.baudrate
= baudrate
;
65 packet
.timeout
= timeout
;
66 packet
.device
= device
;
69 mav_array_memcpy(packet
.data
, data
, sizeof(uint8_t)*70);
70 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
73 msg
->msgid
= MAVLINK_MSG_ID_SERIAL_CONTROL
;
75 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC
);
77 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
82 * @brief Pack a serial_control message on a channel
83 * @param system_id ID of this system
84 * @param component_id ID of this component (e.g. 200 for IMU)
85 * @param chan The MAVLink channel this message will be sent over
86 * @param msg The MAVLink message to compress the data into
87 * @param device See SERIAL_CONTROL_DEV enum
88 * @param flags See SERIAL_CONTROL_FLAG enum
89 * @param timeout Timeout for reply data in milliseconds
90 * @param baudrate Baudrate of transfer. Zero means no change.
91 * @param count how many bytes in this transfer
92 * @param data serial data
93 * @return length of the message in bytes (excluding serial stream start sign)
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
)
99 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
100 char buf
[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
];
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);
107 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
109 mavlink_serial_control_t packet
;
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);
116 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
119 msg
->msgid
= MAVLINK_MSG_ID_SERIAL_CONTROL
;
120 #if MAVLINK_CRC_EXTRA
121 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC
);
123 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
128 * @brief Encode a serial_control struct
130 * @param system_id ID of this system
131 * @param component_id ID of this component (e.g. 200 for IMU)
132 * @param msg The MAVLink message to compress the data into
133 * @param serial_control C-struct to read the message contents from
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
)
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
);
141 * @brief Encode a serial_control struct on a channel
143 * @param system_id ID of this system
144 * @param component_id ID of this component (e.g. 200 for IMU)
145 * @param chan The MAVLink channel this message will be sent over
146 * @param msg The MAVLink message to compress the data into
147 * @param serial_control C-struct to read the message contents from
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
)
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
);
155 * @brief Send a serial_control message
156 * @param chan MAVLink channel to send the message
158 * @param device See SERIAL_CONTROL_DEV enum
159 * @param flags See SERIAL_CONTROL_FLAG enum
160 * @param timeout Timeout for reply data in milliseconds
161 * @param baudrate Baudrate of transfer. Zero means no change.
162 * @param count how many bytes in this transfer
163 * @param data serial data
165 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
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
)
169 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
170 char buf
[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
];
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
178 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SERIAL_CONTROL
, buf
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC
);
180 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SERIAL_CONTROL
, buf
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
183 mavlink_serial_control_t packet
;
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
);
193 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SERIAL_CONTROL
, (const char *)&packet
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
198 #if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
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.
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
)
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
217 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SERIAL_CONTROL
, buf
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC
);
219 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SERIAL_CONTROL
, buf
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
222 mavlink_serial_control_t
*packet
= (mavlink_serial_control_t
*)msgbuf
;
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
);
232 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_SERIAL_CONTROL
, (const char *)packet
, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);
240 // MESSAGE SERIAL_CONTROL UNPACKING
244 * @brief Get field device from serial_control message
246 * @return See SERIAL_CONTROL_DEV enum
248 static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t
* msg
)
250 return _MAV_RETURN_uint8_t(msg
, 6);
254 * @brief Get field flags from serial_control message
256 * @return See SERIAL_CONTROL_FLAG enum
258 static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t
* msg
)
260 return _MAV_RETURN_uint8_t(msg
, 7);
264 * @brief Get field timeout from serial_control message
266 * @return Timeout for reply data in milliseconds
268 static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t
* msg
)
270 return _MAV_RETURN_uint16_t(msg
, 4);
274 * @brief Get field baudrate from serial_control message
276 * @return Baudrate of transfer. Zero means no change.
278 static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t
* msg
)
280 return _MAV_RETURN_uint32_t(msg
, 0);
284 * @brief Get field count from serial_control message
286 * @return how many bytes in this transfer
288 static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t
* msg
)
290 return _MAV_RETURN_uint8_t(msg
, 8);
294 * @brief Get field data from serial_control message
296 * @return serial data
298 static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t
* msg
, uint8_t *data
)
300 return _MAV_RETURN_uint8_t_array(msg
, data
, 70, 9);
304 * @brief Decode a serial_control message into a struct
306 * @param msg The message to decode
307 * @param serial_control C-struct to decode the message contents into
309 static inline void mavlink_msg_serial_control_decode(const mavlink_message_t
* msg
, mavlink_serial_control_t
* serial_control
)
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
);
319 memcpy(serial_control
, _MAV_PAYLOAD(msg
), MAVLINK_MSG_ID_SERIAL_CONTROL_LEN
);