mavlink_msg_auth_key.h
Go to the documentation of this file.
00001 // MESSAGE AUTH_KEY PACKING
00002 
00003 #define MAVLINK_MSG_ID_AUTH_KEY 7
00004 
00005 typedef struct __mavlink_auth_key_t
00006 {
00007  char key[32]; /*< key*/
00008 } mavlink_auth_key_t;
00009 
00010 #define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
00011 #define MAVLINK_MSG_ID_7_LEN 32
00012 
00013 #define MAVLINK_MSG_ID_AUTH_KEY_CRC 119
00014 #define MAVLINK_MSG_ID_7_CRC 119
00015 
00016 #define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
00017 
00018 #define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
00019         "AUTH_KEY", \
00020         1, \
00021         {  { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
00022          } \
00023 }
00024 
00025 
00035 static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00036                                                        const char *key)
00037 {
00038 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00039         char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
00040 
00041         _mav_put_char_array(buf, 0, key, 32);
00042         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00043 #else
00044         mavlink_auth_key_t packet;
00045 
00046         mav_array_memcpy(packet.key, key, sizeof(char)*32);
00047         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00048 #endif
00049 
00050         msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
00051 #if MAVLINK_CRC_EXTRA
00052     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
00053 #else
00054     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00055 #endif
00056 }
00057 
00067 static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00068                                                            mavlink_message_t* msg,
00069                                                            const char *key)
00070 {
00071 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00072         char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
00073 
00074         _mav_put_char_array(buf, 0, key, 32);
00075         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00076 #else
00077         mavlink_auth_key_t packet;
00078 
00079         mav_array_memcpy(packet.key, key, sizeof(char)*32);
00080         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00081 #endif
00082 
00083         msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
00084 #if MAVLINK_CRC_EXTRA
00085     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
00086 #else
00087     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00088 #endif
00089 }
00090 
00099 static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
00100 {
00101         return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
00102 }
00103 
00113 static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
00114 {
00115         return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key);
00116 }
00117 
00124 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00125 
00126 static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key)
00127 {
00128 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00129         char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN];
00130 
00131         _mav_put_char_array(buf, 0, key, 32);
00132 #if MAVLINK_CRC_EXTRA
00133     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
00134 #else
00135     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00136 #endif
00137 #else
00138         mavlink_auth_key_t packet;
00139 
00140         mav_array_memcpy(packet.key, key, sizeof(char)*32);
00141 #if MAVLINK_CRC_EXTRA
00142     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
00143 #else
00144     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00145 #endif
00146 #endif
00147 }
00148 
00149 #if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00150 /*
00151   This varient of _send() can be used to save stack space by re-using
00152   memory from the receive buffer.  The caller provides a
00153   mavlink_message_t which is the size of a full mavlink message. This
00154   is usually the receive buffer for the channel, and allows a reply to an
00155   incoming message with minimum stack space usage.
00156  */
00157 static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  const char *key)
00158 {
00159 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00160         char *buf = (char *)msgbuf;
00161 
00162         _mav_put_char_array(buf, 0, key, 32);
00163 #if MAVLINK_CRC_EXTRA
00164     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
00165 #else
00166     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00167 #endif
00168 #else
00169         mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf;
00170 
00171         mav_array_memcpy(packet->key, key, sizeof(char)*32);
00172 #if MAVLINK_CRC_EXTRA
00173     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
00174 #else
00175     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
00176 #endif
00177 #endif
00178 }
00179 #endif
00180 
00181 #endif
00182 
00183 // MESSAGE AUTH_KEY UNPACKING
00184 
00185 
00191 static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key)
00192 {
00193         return _MAV_RETURN_char_array(msg, key, 32,  0);
00194 }
00195 
00202 static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
00203 {
00204 #if MAVLINK_NEED_BYTE_SWAP
00205         mavlink_msg_auth_key_get_key(msg, auth_key->key);
00206 #else
00207         memcpy(auth_key, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTH_KEY_LEN);
00208 #endif
00209 }


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