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
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
#pragma once
// MESSAGE STORAGE_INFORMATION PACKING
 
#define MAVLINK_MSG_ID_STORAGE_INFORMATION 261
 
 
typedef struct __mavlink_storage_information_t {
 uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
 float total_capacity; /*< [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.*/
 float used_capacity; /*< [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.*/
 float available_capacity; /*< [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.*/
 float read_speed; /*< [MiB/s] Read speed.*/
 float write_speed; /*< [MiB/s] Write speed.*/
 uint8_t storage_id; /*<  Storage ID (1 for first, 2 for second, etc.)*/
 uint8_t storage_count; /*<  Number of storage devices*/
 uint8_t status; /*<  Status of storage*/
 uint8_t type; /*<  Type of storage*/
 char name[32]; /*<  Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.*/
 uint8_t storage_usage; /*<  Flags indicating whether this instance is preferred storage for photos, videos, etc.
        Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported).
        This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE.
        If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.*/
} mavlink_storage_information_t;
 
#define MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN 61
#define MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN 27
#define MAVLINK_MSG_ID_261_LEN 61
#define MAVLINK_MSG_ID_261_MIN_LEN 27
 
#define MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC 179
#define MAVLINK_MSG_ID_261_CRC 179
 
#define MAVLINK_MSG_STORAGE_INFORMATION_FIELD_NAME_LEN 32
 
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION { \
    261, \
    "STORAGE_INFORMATION", \
    12, \
    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storage_information_t, time_boot_ms) }, \
         { "storage_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_storage_information_t, storage_id) }, \
         { "storage_count", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_storage_information_t, storage_count) }, \
         { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_storage_information_t, status) }, \
         { "total_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storage_information_t, total_capacity) }, \
         { "used_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storage_information_t, used_capacity) }, \
         { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storage_information_t, available_capacity) }, \
         { "read_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storage_information_t, read_speed) }, \
         { "write_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storage_information_t, write_speed) }, \
         { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_storage_information_t, type) }, \
         { "name", NULL, MAVLINK_TYPE_CHAR, 32, 28, offsetof(mavlink_storage_information_t, name) }, \
         { "storage_usage", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_storage_information_t, storage_usage) }, \
         } \
}
#else
#define MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION { \
    "STORAGE_INFORMATION", \
    12, \
    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storage_information_t, time_boot_ms) }, \
         { "storage_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_storage_information_t, storage_id) }, \
         { "storage_count", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_storage_information_t, storage_count) }, \
         { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_storage_information_t, status) }, \
         { "total_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storage_information_t, total_capacity) }, \
         { "used_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storage_information_t, used_capacity) }, \
         { "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storage_information_t, available_capacity) }, \
         { "read_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storage_information_t, read_speed) }, \
         { "write_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storage_information_t, write_speed) }, \
         { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_storage_information_t, type) }, \
         { "name", NULL, MAVLINK_TYPE_CHAR, 32, 28, offsetof(mavlink_storage_information_t, name) }, \
         { "storage_usage", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_storage_information_t, storage_usage) }, \
         } \
}
#endif
 
/**
 * @brief Pack a storage_information 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 time_boot_ms [ms] Timestamp (time since system boot).
 * @param storage_id  Storage ID (1 for first, 2 for second, etc.)
 * @param storage_count  Number of storage devices
 * @param status  Status of storage
 * @param total_capacity [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param used_capacity [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param available_capacity [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param read_speed [MiB/s] Read speed.
 * @param write_speed [MiB/s] Write speed.
 * @param type  Type of storage
 * @param name  Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.
 * @param storage_usage  Flags indicating whether this instance is preferred storage for photos, videos, etc.
        Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported).
        This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE.
        If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_storage_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
                               uint32_t time_boot_ms, uint8_t storage_id, uint8_t storage_count, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed, uint8_t type, const char *name, uint8_t storage_usage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN];
    _mav_put_uint32_t(buf, 0, time_boot_ms);
    _mav_put_float(buf, 4, total_capacity);
    _mav_put_float(buf, 8, used_capacity);
    _mav_put_float(buf, 12, available_capacity);
    _mav_put_float(buf, 16, read_speed);
    _mav_put_float(buf, 20, write_speed);
    _mav_put_uint8_t(buf, 24, storage_id);
    _mav_put_uint8_t(buf, 25, storage_count);
    _mav_put_uint8_t(buf, 26, status);
    _mav_put_uint8_t(buf, 27, type);
    _mav_put_uint8_t(buf, 60, storage_usage);
    _mav_put_char_array(buf, 28, name, 32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN);
#else
    mavlink_storage_information_t packet;
    packet.time_boot_ms = time_boot_ms;
    packet.total_capacity = total_capacity;
    packet.used_capacity = used_capacity;
    packet.available_capacity = available_capacity;
    packet.read_speed = read_speed;
    packet.write_speed = write_speed;
    packet.storage_id = storage_id;
    packet.storage_count = storage_count;
    packet.status = status;
    packet.type = type;
    packet.storage_usage = storage_usage;
    mav_array_memcpy(packet.name, name, sizeof(char)*32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_STORAGE_INFORMATION;
    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC);
}
 
/**
 * @brief Pack a storage_information 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 time_boot_ms [ms] Timestamp (time since system boot).
 * @param storage_id  Storage ID (1 for first, 2 for second, etc.)
 * @param storage_count  Number of storage devices
 * @param status  Status of storage
 * @param total_capacity [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param used_capacity [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param available_capacity [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param read_speed [MiB/s] Read speed.
 * @param write_speed [MiB/s] Write speed.
 * @param type  Type of storage
 * @param name  Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.
 * @param storage_usage  Flags indicating whether this instance is preferred storage for photos, videos, etc.
        Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported).
        This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE.
        If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.
 * @return length of the message in bytes (excluding serial stream start sign)
 */
static inline uint16_t mavlink_msg_storage_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                               mavlink_message_t* msg,
                                   uint32_t time_boot_ms,uint8_t storage_id,uint8_t storage_count,uint8_t status,float total_capacity,float used_capacity,float available_capacity,float read_speed,float write_speed,uint8_t type,const char *name,uint8_t storage_usage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN];
    _mav_put_uint32_t(buf, 0, time_boot_ms);
    _mav_put_float(buf, 4, total_capacity);
    _mav_put_float(buf, 8, used_capacity);
    _mav_put_float(buf, 12, available_capacity);
    _mav_put_float(buf, 16, read_speed);
    _mav_put_float(buf, 20, write_speed);
    _mav_put_uint8_t(buf, 24, storage_id);
    _mav_put_uint8_t(buf, 25, storage_count);
    _mav_put_uint8_t(buf, 26, status);
    _mav_put_uint8_t(buf, 27, type);
    _mav_put_uint8_t(buf, 60, storage_usage);
    _mav_put_char_array(buf, 28, name, 32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN);
#else
    mavlink_storage_information_t packet;
    packet.time_boot_ms = time_boot_ms;
    packet.total_capacity = total_capacity;
    packet.used_capacity = used_capacity;
    packet.available_capacity = available_capacity;
    packet.read_speed = read_speed;
    packet.write_speed = write_speed;
    packet.storage_id = storage_id;
    packet.storage_count = storage_count;
    packet.status = status;
    packet.type = type;
    packet.storage_usage = storage_usage;
    mav_array_memcpy(packet.name, name, sizeof(char)*32);
        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN);
#endif
 
    msg->msgid = MAVLINK_MSG_ID_STORAGE_INFORMATION;
    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC);
}
 
/**
 * @brief Encode a storage_information 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 storage_information C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_storage_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storage_information_t* storage_information)
{
    return mavlink_msg_storage_information_pack(system_id, component_id, msg, storage_information->time_boot_ms, storage_information->storage_id, storage_information->storage_count, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed, storage_information->type, storage_information->name, storage_information->storage_usage);
}
 
/**
 * @brief Encode a storage_information 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 storage_information C-struct to read the message contents from
 */
static inline uint16_t mavlink_msg_storage_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storage_information_t* storage_information)
{
    return mavlink_msg_storage_information_pack_chan(system_id, component_id, chan, msg, storage_information->time_boot_ms, storage_information->storage_id, storage_information->storage_count, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed, storage_information->type, storage_information->name, storage_information->storage_usage);
}
 
/**
 * @brief Send a storage_information message
 * @param chan MAVLink channel to send the message
 *
 * @param time_boot_ms [ms] Timestamp (time since system boot).
 * @param storage_id  Storage ID (1 for first, 2 for second, etc.)
 * @param storage_count  Number of storage devices
 * @param status  Status of storage
 * @param total_capacity [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param used_capacity [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param available_capacity [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 * @param read_speed [MiB/s] Read speed.
 * @param write_speed [MiB/s] Write speed.
 * @param type  Type of storage
 * @param name  Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.
 * @param storage_usage  Flags indicating whether this instance is preferred storage for photos, videos, etc.
        Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported).
        This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE.
        If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.
 */
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_storage_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t storage_id, uint8_t storage_count, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed, uint8_t type, const char *name, uint8_t storage_usage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char buf[MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN];
    _mav_put_uint32_t(buf, 0, time_boot_ms);
    _mav_put_float(buf, 4, total_capacity);
    _mav_put_float(buf, 8, used_capacity);
    _mav_put_float(buf, 12, available_capacity);
    _mav_put_float(buf, 16, read_speed);
    _mav_put_float(buf, 20, write_speed);
    _mav_put_uint8_t(buf, 24, storage_id);
    _mav_put_uint8_t(buf, 25, storage_count);
    _mav_put_uint8_t(buf, 26, status);
    _mav_put_uint8_t(buf, 27, type);
    _mav_put_uint8_t(buf, 60, storage_usage);
    _mav_put_char_array(buf, 28, name, 32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC);
#else
    mavlink_storage_information_t packet;
    packet.time_boot_ms = time_boot_ms;
    packet.total_capacity = total_capacity;
    packet.used_capacity = used_capacity;
    packet.available_capacity = available_capacity;
    packet.read_speed = read_speed;
    packet.write_speed = write_speed;
    packet.storage_id = storage_id;
    packet.storage_count = storage_count;
    packet.status = status;
    packet.type = type;
    packet.storage_usage = storage_usage;
    mav_array_memcpy(packet.name, name, sizeof(char)*32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC);
#endif
}
 
/**
 * @brief Send a storage_information message
 * @param chan MAVLink channel to send the message
 * @param struct The MAVLink struct to serialize
 */
static inline void mavlink_msg_storage_information_send_struct(mavlink_channel_t chan, const mavlink_storage_information_t* storage_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    mavlink_msg_storage_information_send(chan, storage_information->time_boot_ms, storage_information->storage_id, storage_information->storage_count, storage_information->status, storage_information->total_capacity, storage_information->used_capacity, storage_information->available_capacity, storage_information->read_speed, storage_information->write_speed, storage_information->type, storage_information->name, storage_information->storage_usage);
#else
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)storage_information, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC);
#endif
}
 
#if MAVLINK_MSG_ID_STORAGE_INFORMATION_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_storage_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t storage_id, uint8_t storage_count, uint8_t status, float total_capacity, float used_capacity, float available_capacity, float read_speed, float write_speed, uint8_t type, const char *name, uint8_t storage_usage)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    char *buf = (char *)msgbuf;
    _mav_put_uint32_t(buf, 0, time_boot_ms);
    _mav_put_float(buf, 4, total_capacity);
    _mav_put_float(buf, 8, used_capacity);
    _mav_put_float(buf, 12, available_capacity);
    _mav_put_float(buf, 16, read_speed);
    _mav_put_float(buf, 20, write_speed);
    _mav_put_uint8_t(buf, 24, storage_id);
    _mav_put_uint8_t(buf, 25, storage_count);
    _mav_put_uint8_t(buf, 26, status);
    _mav_put_uint8_t(buf, 27, type);
    _mav_put_uint8_t(buf, 60, storage_usage);
    _mav_put_char_array(buf, 28, name, 32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, buf, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC);
#else
    mavlink_storage_information_t *packet = (mavlink_storage_information_t *)msgbuf;
    packet->time_boot_ms = time_boot_ms;
    packet->total_capacity = total_capacity;
    packet->used_capacity = used_capacity;
    packet->available_capacity = available_capacity;
    packet->read_speed = read_speed;
    packet->write_speed = write_speed;
    packet->storage_id = storage_id;
    packet->storage_count = storage_count;
    packet->status = status;
    packet->type = type;
    packet->storage_usage = storage_usage;
    mav_array_memcpy(packet->name, name, sizeof(char)*32);
    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORAGE_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_STORAGE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN, MAVLINK_MSG_ID_STORAGE_INFORMATION_CRC);
#endif
}
#endif
 
#endif
 
// MESSAGE STORAGE_INFORMATION UNPACKING
 
 
/**
 * @brief Get field time_boot_ms from storage_information message
 *
 * @return [ms] Timestamp (time since system boot).
 */
static inline uint32_t mavlink_msg_storage_information_get_time_boot_ms(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint32_t(msg,  0);
}
 
/**
 * @brief Get field storage_id from storage_information message
 *
 * @return  Storage ID (1 for first, 2 for second, etc.)
 */
static inline uint8_t mavlink_msg_storage_information_get_storage_id(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  24);
}
 
/**
 * @brief Get field storage_count from storage_information message
 *
 * @return  Number of storage devices
 */
static inline uint8_t mavlink_msg_storage_information_get_storage_count(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  25);
}
 
/**
 * @brief Get field status from storage_information message
 *
 * @return  Status of storage
 */
static inline uint8_t mavlink_msg_storage_information_get_status(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  26);
}
 
/**
 * @brief Get field total_capacity from storage_information message
 *
 * @return [MiB] Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 */
static inline float mavlink_msg_storage_information_get_total_capacity(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  4);
}
 
/**
 * @brief Get field used_capacity from storage_information message
 *
 * @return [MiB] Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 */
static inline float mavlink_msg_storage_information_get_used_capacity(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  8);
}
 
/**
 * @brief Get field available_capacity from storage_information message
 *
 * @return [MiB] Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored.
 */
static inline float mavlink_msg_storage_information_get_available_capacity(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  12);
}
 
/**
 * @brief Get field read_speed from storage_information message
 *
 * @return [MiB/s] Read speed.
 */
static inline float mavlink_msg_storage_information_get_read_speed(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  16);
}
 
/**
 * @brief Get field write_speed from storage_information message
 *
 * @return [MiB/s] Write speed.
 */
static inline float mavlink_msg_storage_information_get_write_speed(const mavlink_message_t* msg)
{
    return _MAV_RETURN_float(msg,  20);
}
 
/**
 * @brief Get field type from storage_information message
 *
 * @return  Type of storage
 */
static inline uint8_t mavlink_msg_storage_information_get_type(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  27);
}
 
/**
 * @brief Get field name from storage_information message
 *
 * @return  Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user.
 */
static inline uint16_t mavlink_msg_storage_information_get_name(const mavlink_message_t* msg, char *name)
{
    return _MAV_RETURN_char_array(msg, name, 32,  28);
}
 
/**
 * @brief Get field storage_usage from storage_information message
 *
 * @return  Flags indicating whether this instance is preferred storage for photos, videos, etc.
        Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported).
        This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE.
        If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types.
 */
static inline uint8_t mavlink_msg_storage_information_get_storage_usage(const mavlink_message_t* msg)
{
    return _MAV_RETURN_uint8_t(msg,  60);
}
 
/**
 * @brief Decode a storage_information message into a struct
 *
 * @param msg The message to decode
 * @param storage_information C-struct to decode the message contents into
 */
static inline void mavlink_msg_storage_information_decode(const mavlink_message_t* msg, mavlink_storage_information_t* storage_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
    storage_information->time_boot_ms = mavlink_msg_storage_information_get_time_boot_ms(msg);
    storage_information->total_capacity = mavlink_msg_storage_information_get_total_capacity(msg);
    storage_information->used_capacity = mavlink_msg_storage_information_get_used_capacity(msg);
    storage_information->available_capacity = mavlink_msg_storage_information_get_available_capacity(msg);
    storage_information->read_speed = mavlink_msg_storage_information_get_read_speed(msg);
    storage_information->write_speed = mavlink_msg_storage_information_get_write_speed(msg);
    storage_information->storage_id = mavlink_msg_storage_information_get_storage_id(msg);
    storage_information->storage_count = mavlink_msg_storage_information_get_storage_count(msg);
    storage_information->status = mavlink_msg_storage_information_get_status(msg);
    storage_information->type = mavlink_msg_storage_information_get_type(msg);
    mavlink_msg_storage_information_get_name(msg, storage_information->name);
    storage_information->storage_usage = mavlink_msg_storage_information_get_storage_usage(msg);
#else
        uint8_t len = msg->len < MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN;
        memset(storage_information, 0, MAVLINK_MSG_ID_STORAGE_INFORMATION_LEN);
    memcpy(storage_information, _MAV_PAYLOAD(msg), len);
#endif
}