Subversion Repositories Projects

Rev

Details | Last modification | View Log | RSS feed

Rev Author Line No. Line
1702 - 1
// MESSAGE CHANGE_OPERATOR_CONTROL PACKING
2
 
3
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
4
 
5
typedef struct __mavlink_change_operator_control_t
6
{
7
 uint8_t target_system; ///< System the GCS requests control for
8
 uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
9
 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.
10
 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 "!?,.-"
11
} mavlink_change_operator_control_t;
12
 
13
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
14
#define MAVLINK_MSG_ID_5_LEN 28
15
 
16
#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
17
 
18
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \
19
        "CHANGE_OPERATOR_CONTROL", \
20
        4, \
21
        {  { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \
22
         { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \
23
         { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \
24
         { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \
25
         } \
26
}
27
 
28
 
29
/**
30
 * @brief Pack a change_operator_control message
31
 * @param system_id ID of this system
32
 * @param component_id ID of this component (e.g. 200 for IMU)
33
 * @param msg The MAVLink message to compress the data into
34
 *
35
 * @param target_system System the GCS requests control for
36
 * @param control_request 0: request control of this MAV, 1: Release control of this MAV
37
 * @param 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.
38
 * @param passkey 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 "!?,.-"
39
 * @return length of the message in bytes (excluding serial stream start sign)
40
 */
41
static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
42
                                                       uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
43
{
44
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
45
        char buf[28];
46
        _mav_put_uint8_t(buf, 0, target_system);
47
        _mav_put_uint8_t(buf, 1, control_request);
48
        _mav_put_uint8_t(buf, 2, version);
49
        _mav_put_char_array(buf, 3, passkey, 25);
50
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
51
#else
52
        mavlink_change_operator_control_t packet;
53
        packet.target_system = target_system;
54
        packet.control_request = control_request;
55
        packet.version = version;
56
        mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
57
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
58
#endif
59
 
60
        msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
61
        return mavlink_finalize_message(msg, system_id, component_id, 28);
62
}
63
 
64
/**
65
 * @brief Pack a change_operator_control message on a channel
66
 * @param system_id ID of this system
67
 * @param component_id ID of this component (e.g. 200 for IMU)
68
 * @param chan The MAVLink channel this message was sent over
69
 * @param msg The MAVLink message to compress the data into
70
 * @param target_system System the GCS requests control for
71
 * @param control_request 0: request control of this MAV, 1: Release control of this MAV
72
 * @param 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.
73
 * @param passkey 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 "!?,.-"
74
 * @return length of the message in bytes (excluding serial stream start sign)
75
 */
76
static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
77
                                                           mavlink_message_t* msg,
78
                                                           uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey)
79
{
80
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
81
        char buf[28];
82
        _mav_put_uint8_t(buf, 0, target_system);
83
        _mav_put_uint8_t(buf, 1, control_request);
84
        _mav_put_uint8_t(buf, 2, version);
85
        _mav_put_char_array(buf, 3, passkey, 25);
86
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
87
#else
88
        mavlink_change_operator_control_t packet;
89
        packet.target_system = target_system;
90
        packet.control_request = control_request;
91
        packet.version = version;
92
        mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
93
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
94
#endif
95
 
96
        msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
97
        return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28);
98
}
99
 
100
/**
101
 * @brief Encode a change_operator_control struct into a message
102
 *
103
 * @param system_id ID of this system
104
 * @param component_id ID of this component (e.g. 200 for IMU)
105
 * @param msg The MAVLink message to compress the data into
106
 * @param change_operator_control C-struct to read the message contents from
107
 */
108
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)
109
{
110
        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);
111
}
112
 
113
/**
114
 * @brief Send a change_operator_control message
115
 * @param chan MAVLink channel to send the message
116
 *
117
 * @param target_system System the GCS requests control for
118
 * @param control_request 0: request control of this MAV, 1: Release control of this MAV
119
 * @param 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.
120
 * @param passkey 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 "!?,.-"
121
 */
122
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
123
 
124
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)
125
{
126
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
127
        char buf[28];
128
        _mav_put_uint8_t(buf, 0, target_system);
129
        _mav_put_uint8_t(buf, 1, control_request);
130
        _mav_put_uint8_t(buf, 2, version);
131
        _mav_put_char_array(buf, 3, passkey, 25);
132
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, 28);
133
#else
134
        mavlink_change_operator_control_t packet;
135
        packet.target_system = target_system;
136
        packet.control_request = control_request;
137
        packet.version = version;
138
        mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
139
        _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, 28);
140
#endif
141
}
142
 
143
#endif
144
 
145
// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
146
 
147
 
148
/**
149
 * @brief Get field target_system from change_operator_control message
150
 *
151
 * @return System the GCS requests control for
152
 */
153
static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
154
{
155
        return _MAV_RETURN_uint8_t(msg,  0);
156
}
157
 
158
/**
159
 * @brief Get field control_request from change_operator_control message
160
 *
161
 * @return 0: request control of this MAV, 1: Release control of this MAV
162
 */
163
static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
164
{
165
        return _MAV_RETURN_uint8_t(msg,  1);
166
}
167
 
168
/**
169
 * @brief Get field version from change_operator_control message
170
 *
171
 * @return 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.
172
 */
173
static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
174
{
175
        return _MAV_RETURN_uint8_t(msg,  2);
176
}
177
 
178
/**
179
 * @brief Get field passkey from change_operator_control message
180
 *
181
 * @return 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 "!?,.-"
182
 */
183
static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey)
184
{
185
        return _MAV_RETURN_char_array(msg, passkey, 25,  3);
186
}
187
 
188
/**
189
 * @brief Decode a change_operator_control message into a struct
190
 *
191
 * @param msg The message to decode
192
 * @param change_operator_control C-struct to decode the message contents into
193
 */
194
static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control)
195
{
196
#if MAVLINK_NEED_BYTE_SWAP
197
        change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg);
198
        change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg);
199
        change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
200
        mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
201
#else
202
        memcpy(change_operator_control, _MAV_PAYLOAD(msg), 28);
203
#endif
204
}