mavlink_msg_change_operator_control.h
Go to the documentation of this file.
00001 // MESSAGE CHANGE_OPERATOR_CONTROL PACKING
00002 
00003 #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
00004 
00005 typedef struct __mavlink_change_operator_control_t
00006 {
00007  uint8_t target_system; /*< System the GCS requests control for*/
00008  uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/
00009  uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/
00010  char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/
00011 } mavlink_change_operator_control_t;
00012 
00013 #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
00014 #define MAVLINK_MSG_ID_5_LEN 28
00015 
00016 #define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217
00017 #define MAVLINK_MSG_ID_5_CRC 217
00018 
00019 #define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
00020 
00021 #define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \
00022         "CHANGE_OPERATOR_CONTROL", \
00023         4, \
00024         {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \
00025          { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \
00026          { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \
00027          { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \
00028          } \
00029 }
00030 
00031 
00044 static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00045                                                        uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
00046 {
00047 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00048         char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN];
00049         _mav_put_uint8_t(buf, 0, target_system);
00050         _mav_put_uint8_t(buf, 1, control_request);
00051         _mav_put_uint8_t(buf, 2, version);
00052         _mav_put_char_array(buf, 3, passkey, 25);
00053         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00054 #else
00055         mavlink_change_operator_control_t packet;
00056         packet.target_system = target_system;
00057         packet.control_request = control_request;
00058         packet.version = version;
00059         mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
00060         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00061 #endif
00062 
00063         msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
00064 #if MAVLINK_CRC_EXTRA
00065     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
00066 #else
00067     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00068 #endif
00069 }
00070 
00083 static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00084                                                            mavlink_message_t* msg,
00085                                                            uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey)
00086 {
00087 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00088         char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN];
00089         _mav_put_uint8_t(buf, 0, target_system);
00090         _mav_put_uint8_t(buf, 1, control_request);
00091         _mav_put_uint8_t(buf, 2, version);
00092         _mav_put_char_array(buf, 3, passkey, 25);
00093         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00094 #else
00095         mavlink_change_operator_control_t packet;
00096         packet.target_system = target_system;
00097         packet.control_request = control_request;
00098         packet.version = version;
00099         mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
00100         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00101 #endif
00102 
00103         msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
00104 #if MAVLINK_CRC_EXTRA
00105     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
00106 #else
00107     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00108 #endif
00109 }
00110 
00119 static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
00120 {
00121         return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
00122 }
00123 
00133 static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
00134 {
00135         return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
00136 }
00137 
00147 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00148 
00149 static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
00150 {
00151 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00152         char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN];
00153         _mav_put_uint8_t(buf, 0, target_system);
00154         _mav_put_uint8_t(buf, 1, control_request);
00155         _mav_put_uint8_t(buf, 2, version);
00156         _mav_put_char_array(buf, 3, passkey, 25);
00157 #if MAVLINK_CRC_EXTRA
00158     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
00159 #else
00160     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00161 #endif
00162 #else
00163         mavlink_change_operator_control_t packet;
00164         packet.target_system = target_system;
00165         packet.control_request = control_request;
00166         packet.version = version;
00167         mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
00168 #if MAVLINK_CRC_EXTRA
00169     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
00170 #else
00171     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00172 #endif
00173 #endif
00174 }
00175 
00176 #if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00177 /*
00178   This varient of _send() can be used to save stack space by re-using
00179   memory from the receive buffer.  The caller provides a
00180   mavlink_message_t which is the size of a full mavlink message. This
00181   is usually the receive buffer for the channel, and allows a reply to an
00182   incoming message with minimum stack space usage.
00183  */
00184 static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
00185 {
00186 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00187         char *buf = (char *)msgbuf;
00188         _mav_put_uint8_t(buf, 0, target_system);
00189         _mav_put_uint8_t(buf, 1, control_request);
00190         _mav_put_uint8_t(buf, 2, version);
00191         _mav_put_char_array(buf, 3, passkey, 25);
00192 #if MAVLINK_CRC_EXTRA
00193     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
00194 #else
00195     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00196 #endif
00197 #else
00198         mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf;
00199         packet->target_system = target_system;
00200         packet->control_request = control_request;
00201         packet->version = version;
00202         mav_array_memcpy(packet->passkey, passkey, sizeof(char)*25);
00203 #if MAVLINK_CRC_EXTRA
00204     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
00205 #else
00206     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00207 #endif
00208 #endif
00209 }
00210 #endif
00211 
00212 #endif
00213 
00214 // MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
00215 
00216 
00222 static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
00223 {
00224         return _MAV_RETURN_uint8_t(msg,  0);
00225 }
00226 
00232 static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
00233 {
00234         return _MAV_RETURN_uint8_t(msg,  1);
00235 }
00236 
00242 static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
00243 {
00244         return _MAV_RETURN_uint8_t(msg,  2);
00245 }
00246 
00252 static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey)
00253 {
00254         return _MAV_RETURN_char_array(msg, passkey, 25,  3);
00255 }
00256 
00263 static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control)
00264 {
00265 #if MAVLINK_NEED_BYTE_SWAP
00266         change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg);
00267         change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg);
00268         change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
00269         mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
00270 #else
00271         memcpy(change_operator_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
00272 #endif
00273 }


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