mavlink_msg_serial_control.h
Go to the documentation of this file.
00001 // MESSAGE SERIAL_CONTROL PACKING
00002 
00003 #define MAVLINK_MSG_ID_SERIAL_CONTROL 126
00004 
00005 typedef struct __mavlink_serial_control_t
00006 {
00007  uint32_t baudrate; /*< Baudrate of transfer. Zero means no change.*/
00008  uint16_t timeout; /*< Timeout for reply data in milliseconds*/
00009  uint8_t device; /*< See SERIAL_CONTROL_DEV enum*/
00010  uint8_t flags; /*< See SERIAL_CONTROL_FLAG enum*/
00011  uint8_t count; /*< how many bytes in this transfer*/
00012  uint8_t data[70]; /*< serial data*/
00013 } mavlink_serial_control_t;
00014 
00015 #define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79
00016 #define MAVLINK_MSG_ID_126_LEN 79
00017 
00018 #define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220
00019 #define MAVLINK_MSG_ID_126_CRC 220
00020 
00021 #define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70
00022 
00023 #define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \
00024         "SERIAL_CONTROL", \
00025         6, \
00026         {  { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \
00027          { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \
00028          { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \
00029          { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \
00030          { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \
00031          { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \
00032          } \
00033 }
00034 
00035 
00050 static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00051                                                        uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data)
00052 {
00053 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00054         char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN];
00055         _mav_put_uint32_t(buf, 0, baudrate);
00056         _mav_put_uint16_t(buf, 4, timeout);
00057         _mav_put_uint8_t(buf, 6, device);
00058         _mav_put_uint8_t(buf, 7, flags);
00059         _mav_put_uint8_t(buf, 8, count);
00060         _mav_put_uint8_t_array(buf, 9, data, 70);
00061         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00062 #else
00063         mavlink_serial_control_t packet;
00064         packet.baudrate = baudrate;
00065         packet.timeout = timeout;
00066         packet.device = device;
00067         packet.flags = flags;
00068         packet.count = count;
00069         mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
00070         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00071 #endif
00072 
00073         msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL;
00074 #if MAVLINK_CRC_EXTRA
00075     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
00076 #else
00077     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00078 #endif
00079 }
00080 
00095 static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00096                                                            mavlink_message_t* msg,
00097                                                            uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data)
00098 {
00099 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00100         char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN];
00101         _mav_put_uint32_t(buf, 0, baudrate);
00102         _mav_put_uint16_t(buf, 4, timeout);
00103         _mav_put_uint8_t(buf, 6, device);
00104         _mav_put_uint8_t(buf, 7, flags);
00105         _mav_put_uint8_t(buf, 8, count);
00106         _mav_put_uint8_t_array(buf, 9, data, 70);
00107         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00108 #else
00109         mavlink_serial_control_t packet;
00110         packet.baudrate = baudrate;
00111         packet.timeout = timeout;
00112         packet.device = device;
00113         packet.flags = flags;
00114         packet.count = count;
00115         mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
00116         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00117 #endif
00118 
00119         msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL;
00120 #if MAVLINK_CRC_EXTRA
00121     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
00122 #else
00123     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00124 #endif
00125 }
00126 
00135 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)
00136 {
00137         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);
00138 }
00139 
00149 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)
00150 {
00151         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);
00152 }
00153 
00165 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00166 
00167 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)
00168 {
00169 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00170         char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN];
00171         _mav_put_uint32_t(buf, 0, baudrate);
00172         _mav_put_uint16_t(buf, 4, timeout);
00173         _mav_put_uint8_t(buf, 6, device);
00174         _mav_put_uint8_t(buf, 7, flags);
00175         _mav_put_uint8_t(buf, 8, count);
00176         _mav_put_uint8_t_array(buf, 9, data, 70);
00177 #if MAVLINK_CRC_EXTRA
00178     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
00179 #else
00180     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00181 #endif
00182 #else
00183         mavlink_serial_control_t packet;
00184         packet.baudrate = baudrate;
00185         packet.timeout = timeout;
00186         packet.device = device;
00187         packet.flags = flags;
00188         packet.count = count;
00189         mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70);
00190 #if MAVLINK_CRC_EXTRA
00191     _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);
00192 #else
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00194 #endif
00195 #endif
00196 }
00197 
00198 #if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00199 /*
00200   This varient of _send() can be used to save stack space by re-using
00201   memory from the receive buffer.  The caller provides a
00202   mavlink_message_t which is the size of a full mavlink message. This
00203   is usually the receive buffer for the channel, and allows a reply to an
00204   incoming message with minimum stack space usage.
00205  */
00206 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)
00207 {
00208 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00209         char *buf = (char *)msgbuf;
00210         _mav_put_uint32_t(buf, 0, baudrate);
00211         _mav_put_uint16_t(buf, 4, timeout);
00212         _mav_put_uint8_t(buf, 6, device);
00213         _mav_put_uint8_t(buf, 7, flags);
00214         _mav_put_uint8_t(buf, 8, count);
00215         _mav_put_uint8_t_array(buf, 9, data, 70);
00216 #if MAVLINK_CRC_EXTRA
00217     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC);
00218 #else
00219     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00220 #endif
00221 #else
00222         mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf;
00223         packet->baudrate = baudrate;
00224         packet->timeout = timeout;
00225         packet->device = device;
00226         packet->flags = flags;
00227         packet->count = count;
00228         mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70);
00229 #if MAVLINK_CRC_EXTRA
00230     _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);
00231 #else
00232     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00233 #endif
00234 #endif
00235 }
00236 #endif
00237 
00238 #endif
00239 
00240 // MESSAGE SERIAL_CONTROL UNPACKING
00241 
00242 
00248 static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg)
00249 {
00250         return _MAV_RETURN_uint8_t(msg,  6);
00251 }
00252 
00258 static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg)
00259 {
00260         return _MAV_RETURN_uint8_t(msg,  7);
00261 }
00262 
00268 static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg)
00269 {
00270         return _MAV_RETURN_uint16_t(msg,  4);
00271 }
00272 
00278 static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg)
00279 {
00280         return _MAV_RETURN_uint32_t(msg,  0);
00281 }
00282 
00288 static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg)
00289 {
00290         return _MAV_RETURN_uint8_t(msg,  8);
00291 }
00292 
00298 static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data)
00299 {
00300         return _MAV_RETURN_uint8_t_array(msg, data, 70,  9);
00301 }
00302 
00309 static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control)
00310 {
00311 #if MAVLINK_NEED_BYTE_SWAP
00312         serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg);
00313         serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg);
00314         serial_control->device = mavlink_msg_serial_control_get_device(msg);
00315         serial_control->flags = mavlink_msg_serial_control_get_flags(msg);
00316         serial_control->count = mavlink_msg_serial_control_get_count(msg);
00317         mavlink_msg_serial_control_get_data(msg, serial_control->data);
00318 #else
00319         memcpy(serial_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_CONTROL_LEN);
00320 #endif
00321 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35