tarask
6 days ago 532005c6573d95199ce0ffbc33df4c7a0a4c3ef9
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
#pragma once
// MESSAGE WIFI_NETWORK_INFO PACKING
 
#define MAVLINK_MSG_ID_WIFI_NETWORK_INFO 298
 
 
typedef struct __mavlink_wifi_network_info_t {
 uint16_t data_rate; /*< [MiB/s] WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.*/
 char ssid[32]; /*<  Name of Wi-Fi network (SSID).*/
 uint8_t channel_id; /*<  WiFi network operating channel ID. Set to 0 if unknown or unidentified.*/
 uint8_t signal_quality; /*< [%] WiFi network signal quality.*/
 uint8_t security; /*<  WiFi network security type.*/
} mavlink_wifi_network_info_t;
 
#define MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN 37
#define MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN 37
#define MAVLINK_MSG_ID_298_LEN 37
#define MAVLINK_MSG_ID_298_MIN_LEN 37
 
#define MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC 237
#define MAVLINK_MSG_ID_298_CRC 237
 
#define MAVLINK_MSG_WIFI_NETWORK_INFO_FIELD_SSID_LEN 32
 
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_WIFI_NETWORK_INFO { \
    298, \
    "WIFI_NETWORK_INFO", \
    5, \
    {  { "ssid", NULL, MAVLINK_TYPE_CHAR, 32, 2, offsetof(mavlink_wifi_network_info_t, ssid) }, \
         { "channel_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_wifi_network_info_t, channel_id) }, \
         { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_wifi_network_info_t, signal_quality) }, \
         { "data_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_wifi_network_info_t, data_rate) }, \
         { "security", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_wifi_network_info_t, security) }, \
         } \
}
#else
#define MAVLINK_MESSAGE_INFO_WIFI_NETWORK_INFO { \
    "WIFI_NETWORK_INFO", \
    5, \
    {  { "ssid", NULL, MAVLINK_TYPE_CHAR, 32, 2, offsetof(mavlink_wifi_network_info_t, ssid) }, \
         { "channel_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_wifi_network_info_t, channel_id) }, \
         { "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_wifi_network_info_t, signal_quality) }, \
         { "data_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_wifi_network_info_t, data_rate) }, \
         { "security", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_wifi_network_info_t, security) }, \
         } \
}
#endif
 
/**
 * @brief Pack a wifi_network_info message
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 *
 * @param ssid  Name of Wi-Fi network (SSID).
 * @param channel_id  WiFi network operating channel ID. Set to 0 if unknown or unidentified.
 * @param signal_quality [%] WiFi network signal quality.
 * @param data_rate [MiB/s] WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.
 * @param security  WiFi network security type.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_wifi_network_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               const char *ssid, uint8_t channel_id, uint8_t signal_quality, uint16_t data_rate, uint8_t security)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN];
    _mav_put_uint16_t(buf, 0, data_rate);
    _mav_put_uint8_t(buf, 34, channel_id);
    _mav_put_uint8_t(buf, 35, signal_quality);
    _mav_put_uint8_t(buf, 36, security);
    _mav_put_char_array(buf, 2, ssid, 32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN);
#else
    mavlink_wifi_network_info_t packet;
    packet.data_rate = data_rate;
    packet.channel_id = channel_id;
    packet.signal_quality = signal_quality;
    packet.security = security;
    mav_array_memcpy(packet.ssid, ssid, sizeof(char)*32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_WIFI_NETWORK_INFO;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC);
}
 
/**
 * @brief Pack a wifi_network_info message on a channel
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param ssid  Name of Wi-Fi network (SSID).
 * @param channel_id  WiFi network operating channel ID. Set to 0 if unknown or unidentified.
 * @param signal_quality [%] WiFi network signal quality.
 * @param data_rate [MiB/s] WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.
 * @param security  WiFi network security type.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_wifi_network_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                               mavlink_message_t* msg,
                                   const char *ssid,uint8_t channel_id,uint8_t signal_quality,uint16_t data_rate,uint8_t security)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN];
    _mav_put_uint16_t(buf, 0, data_rate);
    _mav_put_uint8_t(buf, 34, channel_id);
    _mav_put_uint8_t(buf, 35, signal_quality);
    _mav_put_uint8_t(buf, 36, security);
    _mav_put_char_array(buf, 2, ssid, 32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN);
#else
    mavlink_wifi_network_info_t packet;
    packet.data_rate = data_rate;
    packet.channel_id = channel_id;
    packet.signal_quality = signal_quality;
    packet.security = security;
    mav_array_memcpy(packet.ssid, ssid, sizeof(char)*32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_WIFI_NETWORK_INFO;
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC);
}
 
/**
 * @brief Encode a wifi_network_info struct
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param msg The MAVLink message to compress the data into
 * @param wifi_network_info C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_wifi_network_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wifi_network_info_t* wifi_network_info)
{
    return mavlink_msg_wifi_network_info_pack(system_id, component_id, msg, wifi_network_info->ssid, wifi_network_info->channel_id, wifi_network_info->signal_quality, wifi_network_info->data_rate, wifi_network_info->security);
}
 
/**
 * @brief Encode a wifi_network_info struct on a channel
 *
 * @param system_id ID of this system
 * @param component_id ID of this component (e.g. 200 for IMU)
 * @param chan The MAVLink channel this message will be sent over
 * @param msg The MAVLink message to compress the data into
 * @param wifi_network_info C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_wifi_network_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wifi_network_info_t* wifi_network_info)
{
    return mavlink_msg_wifi_network_info_pack_chan(system_id, component_id, chan, msg, wifi_network_info->ssid, wifi_network_info->channel_id, wifi_network_info->signal_quality, wifi_network_info->data_rate, wifi_network_info->security);
}
 
/**
 * @brief Send a wifi_network_info message
 * @param chan MAVLink channel to send the message
 *
 * @param ssid  Name of Wi-Fi network (SSID).
 * @param channel_id  WiFi network operating channel ID. Set to 0 if unknown or unidentified.
 * @param signal_quality [%] WiFi network signal quality.
 * @param data_rate [MiB/s] WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.
 * @param security  WiFi network security type.
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_wifi_network_info_send(mavlink_channel_t chan, const char *ssid, uint8_t channel_id, uint8_t signal_quality, uint16_t data_rate, uint8_t security)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN];
    _mav_put_uint16_t(buf, 0, data_rate);
    _mav_put_uint8_t(buf, 34, channel_id);
    _mav_put_uint8_t(buf, 35, signal_quality);
    _mav_put_uint8_t(buf, 36, security);
    _mav_put_char_array(buf, 2, ssid, 32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_NETWORK_INFO, buf, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC);
#else
    mavlink_wifi_network_info_t packet;
    packet.data_rate = data_rate;
    packet.channel_id = channel_id;
    packet.signal_quality = signal_quality;
    packet.security = security;
    mav_array_memcpy(packet.ssid, ssid, sizeof(char)*32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_NETWORK_INFO, (const char *)&packet, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC);
#endif
}
 
/**
 * @brief Send a wifi_network_info message
 * @param chan MAVLink channel to send the message
 * @param struct The MAVLink struct to serialize
 */
static inline void mavlink_msg_wifi_network_info_send_struct(mavlink_channel_t chan, const mavlink_wifi_network_info_t* wifi_network_info)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    mavlink_msg_wifi_network_info_send(chan, wifi_network_info->ssid, wifi_network_info->channel_id, wifi_network_info->signal_quality, wifi_network_info->data_rate, wifi_network_info->security);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_NETWORK_INFO, (const char *)wifi_network_info, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC);
#endif
}
 
#if MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
  This variant of _send() can be used to save stack space by re-using
  memory from the receive buffer.  The caller provides a
  mavlink_message_t which is the size of a full mavlink message. This
  is usually the receive buffer for the channel, and allows a reply to an
  incoming message with minimum stack space usage.
 */
static inline void mavlink_msg_wifi_network_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  const char *ssid, uint8_t channel_id, uint8_t signal_quality, uint16_t data_rate, uint8_t security)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char *buf = (char *)msgbuf;
    _mav_put_uint16_t(buf, 0, data_rate);
    _mav_put_uint8_t(buf, 34, channel_id);
    _mav_put_uint8_t(buf, 35, signal_quality);
    _mav_put_uint8_t(buf, 36, security);
    _mav_put_char_array(buf, 2, ssid, 32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_NETWORK_INFO, buf, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC);
#else
    mavlink_wifi_network_info_t *packet = (mavlink_wifi_network_info_t *)msgbuf;
    packet->data_rate = data_rate;
    packet->channel_id = channel_id;
    packet->signal_quality = signal_quality;
    packet->security = security;
    mav_array_memcpy(packet->ssid, ssid, sizeof(char)*32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIFI_NETWORK_INFO, (const char *)packet, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_MIN_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_CRC);
#endif
}
#endif
 
#endif
 
// MESSAGE WIFI_NETWORK_INFO UNPACKING
 
 
/**
 * @brief Get field ssid from wifi_network_info message
 *
 * @return  Name of Wi-Fi network (SSID).
 */
static inline uint16_t mavlink_msg_wifi_network_info_get_ssid(const mavlink_message_t* msg, char *ssid)
{
    return _MAV_RETURN_char_array(msg, ssid, 32,  2);
}
 
/**
 * @brief Get field channel_id from wifi_network_info message
 *
 * @return  WiFi network operating channel ID. Set to 0 if unknown or unidentified.
 */
static inline uint8_t mavlink_msg_wifi_network_info_get_channel_id(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  34);
}
 
/**
 * @brief Get field signal_quality from wifi_network_info message
 *
 * @return [%] WiFi network signal quality.
 */
static inline uint8_t mavlink_msg_wifi_network_info_get_signal_quality(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  35);
}
 
/**
 * @brief Get field data_rate from wifi_network_info message
 *
 * @return [MiB/s] WiFi network data rate. Set to UINT16_MAX if data_rate information is not supplied.
 */
static inline uint16_t mavlink_msg_wifi_network_info_get_data_rate(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint16_t(msg,  0);
}
 
/**
 * @brief Get field security from wifi_network_info message
 *
 * @return  WiFi network security type.
 */
static inline uint8_t mavlink_msg_wifi_network_info_get_security(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  36);
}
 
/**
 * @brief Decode a wifi_network_info message into a struct
 *
 * @param msg The message to decode
 * @param wifi_network_info C-struct to decode the message contents into
 */
static inline void mavlink_msg_wifi_network_info_decode(const mavlink_message_t* msg, mavlink_wifi_network_info_t* wifi_network_info)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    wifi_network_info->data_rate = mavlink_msg_wifi_network_info_get_data_rate(msg);
    mavlink_msg_wifi_network_info_get_ssid(msg, wifi_network_info->ssid);
    wifi_network_info->channel_id = mavlink_msg_wifi_network_info_get_channel_id(msg);
    wifi_network_info->signal_quality = mavlink_msg_wifi_network_info_get_signal_quality(msg);
    wifi_network_info->security = mavlink_msg_wifi_network_info_get_security(msg);
#else
        uint8_t len = msg->len < MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN? msg->len : MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN;
        memset(wifi_network_info, 0, MAVLINK_MSG_ID_WIFI_NETWORK_INFO_LEN);
    memcpy(wifi_network_info, _MAV_PAYLOAD(msg), len);
#endif
}