• Home
  • Features
  • Pricing
  • Docs
  • Announcements
  • Sign In

mavlink / MAVSDK / 9232636745

25 May 2024 03:36AM UTC coverage: 37.012% (+0.1%) from 36.883%
9232636745

push

github

web-flow
Merge pull request #2297 from mavlink/pr-warnings-take-2

Fix warnings (take two)

110 of 112 new or added lines in 9 files covered. (98.21%)

1 existing line in 1 file now uncovered.

10919 of 29501 relevant lines covered (37.01%)

119.87 hits per line

Source File
Press 'n' to go to next uncovered line, 'b' for previous

65.0
/src/mavsdk/plugins/component_metadata/component_metadata_impl.cpp
1
#include "component_metadata_impl.h"
2
#include "callback_list.tpp"
3
#include "fs_utils.h"
4
#include "inflate_lzma.h"
5
#include "unused.h"
6

7
#include <utility>
8
#include <filesystem>
9
#include <fstream>
10
#include <random>
11
#include <regex>
12

13
#ifdef WINDOWS
14
#define strncasecmp(x, y, z) _strnicmp(x, y, z)
15
#endif
16

17
namespace mavsdk {
18

19
namespace fs = std::filesystem;
20

21
ComponentMetadataImpl::ComponentMetadataImpl(System& system) : PluginImplBase(system)
×
22
{
23
    _system_impl->register_plugin(this);
×
24
    init_object();
×
25
}
×
26

27
ComponentMetadataImpl::ComponentMetadataImpl(std::shared_ptr<System> system) :
1✔
28
    PluginImplBase(std::move(system))
1✔
29
{
30
    _system_impl->register_plugin(this);
1✔
31
    init_object();
1✔
32
}
1✔
33

34
void ComponentMetadataImpl::init_object()
1✔
35
{
36
    if (const char* env_p = std::getenv("MAVSDK_COMPONENT_METADATA_DEBUGGING")) {
1✔
37
        if (std::string(env_p) == "1") {
1✔
38
            LogDebug() << "Verbose component metadata logging is on";
1✔
39
            _verbose_debugging = true;
1✔
40
        }
41
    }
42

43
    const auto cache_dir_option = get_cache_directory();
2✔
44
    if (cache_dir_option) {
1✔
45
        _file_cache.emplace(
2✔
46
            cache_dir_option.value() / "component_metadata", 50, _verbose_debugging);
1✔
47
    } else {
48
        LogErr() << "Failed to get cache directory";
×
49
    }
50

51
    const auto tmp_option = create_tmp_directory("mavsdk-component-metadata");
4✔
52
    if (tmp_option) {
1✔
53
        _tmp_download_path = tmp_option.value();
1✔
54
    } else {
55
        _tmp_download_path = "./mavsdk-component-metadata";
×
56
        std::error_code err;
×
57
        std::filesystem::create_directory(_tmp_download_path, err);
×
58
    }
59
}
1✔
60

61
ComponentMetadataImpl::~ComponentMetadataImpl()
1✔
62
{
63
    _system_impl->unregister_plugin(this);
1✔
64
    std::error_code ec;
1✔
65
    std::filesystem::remove_all(_tmp_download_path, ec);
1✔
66
    if (ec) {
1✔
67
        LogErr() << "failed to remove directory: " << ec.message();
×
68
    }
69
}
1✔
70

71
void ComponentMetadataImpl::init() {}
1✔
72

73
void ComponentMetadataImpl::deinit() {}
1✔
74

75
void ComponentMetadataImpl::enable()
1✔
76
{
77
    const std::lock_guard lg{_mavlink_components_mutex};
1✔
78
    _mavlink_components.clear();
1✔
79
    request_componenents();
1✔
80
    _is_enabled = true;
1✔
81
}
1✔
82

83
void ComponentMetadataImpl::disable()
1✔
84
{
85
    // TODO: stop ongoing downloads?
86
    _is_enabled = false;
1✔
87
}
1✔
88

89
void ComponentMetadataImpl::request_componenents()
2✔
90
{
91
    const std::lock_guard lg{_mavlink_components_mutex};
4✔
92
    for (const auto& component : _components_to_request) {
3✔
93
        if (_mavlink_components.find(component) == _mavlink_components.end()) {
1✔
94
            _mavlink_components[component] = MavlinkComponent{};
1✔
95
            _system_impl->request_message().request(
2✔
96
                MAVLINK_MSG_ID_COMPONENT_METADATA,
97
                component,
1✔
98
                [this](auto&& result, auto&& message) {
1✔
99
                    receive_component_metadata(result, message);
1✔
100
                });
1✔
101
        }
102
    }
103
}
2✔
104

105
void ComponentMetadataImpl::request_component(uint32_t compid)
1✔
106
{
107
    _components_to_request.insert(compid);
1✔
108
    if (_is_enabled) {
1✔
109
        request_componenents();
1✔
110
    }
111
}
1✔
112

113
void ComponentMetadataImpl::receive_component_metadata(
1✔
114
    MavlinkCommandSender::Result result, const mavlink_message_t& message)
115
{
116
    const std::lock_guard lg{_mavlink_components_mutex};
1✔
117
    if (_mavlink_components.find(message.compid) == _mavlink_components.end()) {
1✔
118
        LogWarn() << "Unexpected component ID " << static_cast<int>(message.compid);
×
119
        return;
×
120
    }
121

122
    // Store the result if the command failed
123
    if (result != MavlinkCommandSender::Result::Success) {
1✔
124
        switch (result) {
×
125
            case MavlinkCommandSender::Result::ConnectionError:
×
126
                _mavlink_components[message.compid].result =
×
127
                    ComponentMetadata::Result::ConnectionError;
×
128
                break;
×
129
            case MavlinkCommandSender::Result::Denied:
×
130
                _mavlink_components[message.compid].result = ComponentMetadata::Result::Denied;
×
131
                break;
×
132
            case MavlinkCommandSender::Result::Unsupported:
×
133
                _mavlink_components[message.compid].result = ComponentMetadata::Result::Unsupported;
×
134
                break;
×
135
            case MavlinkCommandSender::Result::Timeout:
×
136
                _mavlink_components[message.compid].result = ComponentMetadata::Result::Timeout;
×
137
                break;
×
138
            default:
×
139
                _mavlink_components[message.compid].result = ComponentMetadata::Result::Failed;
×
140
                break;
×
141
        }
142
        LogWarn() << "Requesting component metadata failed with " << static_cast<int>(result);
×
143
        on_all_types_completed(message.compid);
×
144
        return;
×
145
    }
146

147
    mavlink_component_metadata_t component_metadata;
1✔
148
    mavlink_msg_component_metadata_decode(&message, &component_metadata);
1✔
149

150
    component_metadata.uri[sizeof(component_metadata.uri) - 1] = '\0';
1✔
151
    _mavlink_components[message.compid].components.insert(std::make_pair(
4✔
152
        COMP_METADATA_TYPE_GENERAL,
2✔
153
        MetadataComponent{{component_metadata.uri, component_metadata.file_crc}}));
4✔
154

155
    retrieve_metadata(message.compid, COMP_METADATA_TYPE_GENERAL);
1✔
156
}
157

158
std::string ComponentMetadataImpl::get_file_cache_tag(
3✔
159
    uint8_t compid, int comp_info_type, uint32_t crc, bool is_translation)
160
{
161
    char buf[255];
3✔
162
    snprintf(
3✔
163
        buf,
164
        sizeof(buf),
165
        "compid-%03i_crc-%08x_type-%02i_trans-%i",
166
        compid,
167
        crc,
168
        comp_info_type,
169
        (int)is_translation);
170
    return buf;
3✔
171
}
172
bool ComponentMetadataImpl::uri_is_mavlinkftp(
6✔
173
    const std::string& uri, std::string& download_path, uint8_t& target_compid)
174
{
175
    // Case insensitiv check if uri starts with "mftp://"
176
    if (strncasecmp(uri.c_str(), "mftp://", 7) == 0) {
6✔
177
        download_path = uri.substr(7);
5✔
178
        // Extract optional [;comp=<compid>] prefix
179
        std::regex compid_regex(R"(^(?:\[\;comp\=(\d+)\])(.*))");
10✔
180
        std::smatch match;
5✔
181
        if (std::regex_search(download_path, match, compid_regex)) {
5✔
182
            target_compid = std::stoi(match[1]);
1✔
183
            download_path = match[2];
1✔
184
        }
185
        return true;
5✔
186
    }
187
    return false;
1✔
188
}
189

190
void ComponentMetadataImpl::retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE type)
6✔
191
{
192
    if (_verbose_debugging) {
6✔
193
        LogDebug() << "ComponentMetadataImpl::retrieve_metadata for compid "
12✔
194
                   << static_cast<int>(compid) << ", type " << static_cast<int>(type);
12✔
195
    }
196

197
    const std::lock_guard lg{_mavlink_components_mutex};
6✔
198
    auto& component = _mavlink_components[compid].components[type];
6✔
199
    bool crc_valid;
6✔
200
    uint32_t crc;
6✔
201
    bool is_translation;
6✔
202
    std::string uri;
6✔
203

204
    if (component.get_next_uri(crc_valid, crc, is_translation, uri)) {
6✔
205
        // If translation locale is not set, skip translations
206
        if (is_translation && !_translation_locale) {
3✔
207
            retrieve_metadata(compid, type);
×
208
            return;
×
209
        }
210

211
        std::optional<std::filesystem::path> cached_file_option{};
6✔
212
        std::string file_cache_tag{};
6✔
213
        if (_file_cache && crc_valid) {
3✔
214
            file_cache_tag = get_file_cache_tag(compid, type, crc, is_translation);
3✔
215
            cached_file_option = _file_cache->access(file_cache_tag);
3✔
216
        }
217

218
        if (cached_file_option) {
3✔
219
            if (_verbose_debugging) {
×
220
                LogDebug() << "Using cached file " << cached_file_option.value();
×
221
            }
222
            component.current_metadata_path() = cached_file_option.value();
×
223
            retrieve_metadata(compid, type);
×
224
        } else {
225
            if (_verbose_debugging) {
3✔
226
                LogDebug() << "Downloading json " << uri;
3✔
227
            }
228
            std::string download_path;
6✔
229
            uint8_t target_compid = compid;
3✔
230

231
            if (uri_is_mavlinkftp(uri, download_path, target_compid)) {
3✔
232
                // Create compid-specific tmp subdir, to ensure multiple components don't overwrite
233
                // files from each other
234
                const std::filesystem::path tmp_download_path =
3✔
235
                    _tmp_download_path / std::to_string(compid);
12✔
236
                if (!std::filesystem::exists(tmp_download_path)) {
3✔
237
                    std::error_code err;
1✔
238
                    std::filesystem::create_directory(tmp_download_path, err);
1✔
239
                }
240

241
                const std::filesystem::path local_path =
3✔
242
                    tmp_download_path / std::filesystem::path(download_path).filename();
12✔
243
                _system_impl->mavlink_ftp_client().download_async(
9✔
244
                    download_path,
245
                    tmp_download_path.string(),
6✔
246
                    true,
247
                    [this, &component, local_path, compid, type, file_cache_tag](
19✔
248
                        MavlinkFtpClient::ClientResult download_result,
249
                        MavlinkFtpClient::ProgressData progress_data) {
28✔
250
                        if (download_result == MavlinkFtpClient::ClientResult::Next) {
19✔
251
                            if (_verbose_debugging) {
16✔
252
                                LogDebug()
32✔
253
                                    << "File download progress: " << progress_data.bytes_transferred
16✔
254
                                    << '/' << progress_data.total_bytes;
32✔
255
                            }
256
                            // TODO: detect slow link (e.g. telemetry), and cancel download
257
                            // (fallback to http) e.g. by estimating the remaining download time,
258
                            // and cancel if >40s
259
                        } else {
260
                            if (_verbose_debugging) {
3✔
261
                                LogDebug() << "File download ended with result " << download_result;
3✔
262
                            }
263
                            if (download_result == MavlinkFtpClient::ClientResult::Success) {
3✔
264
                                component.current_metadata_path() =
6✔
265
                                    extract_and_cache_file(local_path, file_cache_tag);
6✔
266
                            }
267
                            // Move on to the next uri or type
268
                            retrieve_metadata(compid, type);
3✔
269
                        }
270
                    },
19✔
271
                    target_compid);
272

273
            } else {
274
                // http(s) download
275
#if BUILD_WITHOUT_CURL == 1
276
                LogErr() << "HTTP disabled at build time, skipping download of " << uri;
277
                retrieve_metadata(compid, type);
278
#else
279
                const std::string base_filename = filename_from_uri(uri);
×
280
                const std::filesystem::path tmp_download_path =
×
281
                    _tmp_download_path / ("http-" + std::to_string(compid) + "-" +
×
282
                                          std::to_string(type) + "-" + base_filename);
×
283
                _http_loader.download_async(
×
284
                    uri,
285
                    tmp_download_path.string(),
×
286
                    [this, &component, tmp_download_path, compid, type, file_cache_tag](
×
287
                        int progress, Status status, CURLcode curl_code) -> int {
×
NEW
288
                        UNUSED(progress);
×
289
                        if (status == Status::Error) {
×
290
                            LogErr() << "File download failed with result " << curl_code;
×
291
                            // Move on to the next uri or type
292
                            retrieve_metadata(compid, type);
×
293
                        } else if (status == Status::Finished) {
×
294
                            if (_verbose_debugging) {
×
295
                                LogDebug() << "File download finished " << tmp_download_path;
×
296
                            }
297
                            component.current_metadata_path() =
×
298
                                extract_and_cache_file(tmp_download_path, file_cache_tag);
×
299
                            // Move on to the next uri or type
300
                            retrieve_metadata(compid, type);
×
301
                        }
302
                        return 0;
×
303
                    });
304
#endif
305
            }
306
        }
307
    } else {
308
        // Move on to next type
309
        handle_metadata_type_completed(compid, type);
3✔
310
    }
311
}
312

313
void ComponentMetadataImpl::handle_metadata_type_completed(uint8_t compid, COMP_METADATA_TYPE type)
3✔
314
{
315
    const std::lock_guard lg{_mavlink_components_mutex};
6✔
316
    auto& component = _mavlink_components[compid].components[type];
3✔
317
    assert(component.is_completed());
3✔
318

319
    // TODO: handle translations. For that we need to parse the translation summary json file
320
    // component.json_translation() and then download the locale-specific translation file.
321
    // See
322
    // https://github.com/mavlink/qgroundcontrol/blob/master/src/Vehicle/ComponentInformationTranslation.cc
323

324
    if (type == COMP_METADATA_TYPE_GENERAL && component.json_metadata()) {
3✔
325
        parse_component_metadata_general(compid, *component.json_metadata());
1✔
326
    }
327

328
    // Call user callbacks
329
    if (component.json_metadata()) {
3✔
330
        auto metadata_type = get_metadata_type(type);
3✔
331
        if (metadata_type) {
3✔
332
            const std::lock_guard lg_callbacks{_notification_callbacks_mutex};
4✔
333
            _notification_callbacks.queue(
6✔
334
                ComponentMetadata::MetadataUpdate{
4✔
335
                    compid, metadata_type.value(), component.json_metadata().value()},
2✔
336
                [this](const auto& func) { _system_impl->call_user_callback(func); });
2✔
337
        }
338
    }
339

340
    // Retrieve next remaining metadata type
341
    bool all_completed = true;
3✔
342
    for (const auto& [next_type, next_component] : _mavlink_components[compid].components) {
9✔
343
        if (!next_component.is_completed()) {
8✔
344
            retrieve_metadata(compid, next_type);
2✔
345
            all_completed = false;
2✔
346
            break;
2✔
347
        }
348
    }
349
    if (all_completed) {
3✔
350
        LogDebug() << "All metadata types completed for compid " << static_cast<int>(compid);
1✔
351
        _mavlink_components[compid].result = ComponentMetadata::Result::Success;
1✔
352
        on_all_types_completed(compid);
1✔
353
    }
354
}
3✔
355

356
std::optional<std::filesystem::path> ComponentMetadataImpl::extract_and_cache_file(
3✔
357
    const std::filesystem::path& path, const std::string& file_cache_tag)
358
{
359
    std::filesystem::path returned_path = path;
6✔
360
    // Decompress if needed
361
    if (path.extension() == ".lzma" || path.extension() == ".xz") {
3✔
362
        returned_path.replace_extension(".extracted");
×
363
        if (InflateLZMA::inflateLZMAFile(path, returned_path)) {
×
364
            std::filesystem::remove(path);
×
365
        } else {
366
            LogErr() << "Inflate of compressed json failed " << path;
×
367
            return std::nullopt;
×
368
        }
369
    }
370

371
    if (_file_cache && !file_cache_tag.empty()) {
3✔
372
        // Cache the file (this will move/remove the temp file as well)
373
        returned_path = _file_cache->insert(file_cache_tag, returned_path).value_or(returned_path);
3✔
374
    }
375
    return returned_path;
3✔
376
}
377
std::string ComponentMetadataImpl::filename_from_uri(const std::string& uri)
2✔
378
{
379
    // Extract the base name from an uri
380
    const auto last_slash = uri.find_last_of('/');
2✔
381
    std::string base_filename = "downloaded_file.json";
4✔
382
    if (last_slash != std::string::npos) {
2✔
383
        base_filename = uri.substr(last_slash + 1);
2✔
384
    }
385
    const auto parameter_index = base_filename.find('?');
2✔
386
    if (parameter_index != std::string::npos) {
2✔
387
        base_filename = base_filename.substr(0, parameter_index);
1✔
388
    }
389
    return base_filename;
2✔
390
}
391
std::optional<ComponentMetadata::MetadataType>
392
ComponentMetadataImpl::get_metadata_type(COMP_METADATA_TYPE type)
3✔
393
{
394
    switch (type) {
3✔
395
        case COMP_METADATA_TYPE_PARAMETER:
1✔
396
            return ComponentMetadata::MetadataType::Parameter;
1✔
397
        case COMP_METADATA_TYPE_EVENTS:
1✔
398
            return ComponentMetadata::MetadataType::Events;
1✔
399
        case COMP_METADATA_TYPE_ACTUATORS:
×
400
            return ComponentMetadata::MetadataType::Actuators;
×
401
        default:
1✔
402
            break;
1✔
403
    }
404

405
    return std::nullopt;
1✔
406
}
407
std::pair<ComponentMetadata::Result, ComponentMetadata::MetadataData>
408
ComponentMetadataImpl::get_metadata(uint32_t compid, ComponentMetadata::MetadataType type)
×
409
{
410
    COMP_METADATA_TYPE metadata_type{COMP_METADATA_TYPE_GENERAL};
×
411
    switch (type) {
×
412
        case ComponentMetadata::MetadataType::Parameter:
×
413
            metadata_type = COMP_METADATA_TYPE_PARAMETER;
×
414
            break;
×
415
        case ComponentMetadata::MetadataType::Events:
×
416
            metadata_type = COMP_METADATA_TYPE_EVENTS;
×
417
            break;
×
418
        case ComponentMetadata::MetadataType::Actuators:
×
419
            metadata_type = COMP_METADATA_TYPE_ACTUATORS;
×
420
            break;
×
421
        case ComponentMetadata::MetadataType::AllCompleted:
×
422
            return std::make_pair(
423
                ComponentMetadata::Result::Failed, ComponentMetadata::MetadataData{});
×
424
    }
425
    const std::lock_guard lg{_mavlink_components_mutex};
×
426
    const auto comp_iter = _mavlink_components.find(compid);
×
427
    if (comp_iter != _mavlink_components.end()) {
×
428
        const auto type_iter = comp_iter->second.components.find(metadata_type);
×
429
        if (type_iter != comp_iter->second.components.end() && type_iter->second.json_metadata()) {
×
430
            return std::make_pair(
431
                ComponentMetadata::Result::Success,
×
432
                ComponentMetadata::MetadataData{*type_iter->second.json_metadata()});
×
433
        }
434
        if (!comp_iter->second.result ||
×
435
            *comp_iter->second.result == ComponentMetadata::Result::Success) {
×
436
            return std::make_pair(
437
                ComponentMetadata::Result::NotAvailable, ComponentMetadata::MetadataData{""});
×
438
        } else {
439
            return std::make_pair(*comp_iter->second.result, ComponentMetadata::MetadataData{""});
×
440
        }
441
    }
442
    return std::make_pair(
443
        ComponentMetadata::Result::NotRequested, ComponentMetadata::MetadataData{""});
×
444
}
445
void ComponentMetadataImpl::parse_component_metadata_general(
1✔
446
    uint8_t compid, const std::string& json_metadata)
447
{
448
    Json::Value metadata;
1✔
449
    Json::Reader reader;
1✔
450
    bool parsing_successful = reader.parse(json_metadata, metadata);
1✔
451
    if (!parsing_successful) {
1✔
452
        LogErr() << "Failed to parse" << reader.getFormattedErrorMessages();
×
453
        return;
×
454
    }
455

456
    if (!metadata.isMember("version")) {
1✔
457
        LogErr() << "version not found";
×
458
        return;
×
459
    }
460

461
    if (metadata["version"].asInt() != 1) {
1✔
462
        LogWarn() << "version " << metadata["version"].asInt() << " not supported";
×
463
        return;
×
464
    }
465

466
    if (!metadata.isMember("metadataTypes")) {
1✔
467
        LogErr() << "metadataTypes not found";
×
468
        return;
×
469
    }
470

471
    for (const auto& metadata_type : metadata["metadataTypes"]) {
3✔
472
        if (!metadata_type.isMember("type")) {
2✔
473
            LogErr() << "type missing";
×
474
            continue;
×
475
        }
476
        auto type = static_cast<COMP_METADATA_TYPE>(metadata_type["type"].asInt());
2✔
477
        auto& components = _mavlink_components[compid].components;
2✔
478
        if (components.find(type) != components.end()) {
2✔
479
            LogErr() << "component type already added: " << type;
×
480
            continue;
×
481
        }
482
        if (!metadata_type.isMember("uri")) {
2✔
483
            LogErr() << "uri missing";
×
484
            continue;
×
485
        }
486

487
        components.emplace(type, MetadataComponent{MetadataComponentUris{metadata_type}});
2✔
488
    }
489
}
490
void ComponentMetadataImpl::unsubscribe_metadata_available(
×
491
    ComponentMetadata::MetadataAvailableHandle handle)
492
{
493
    const std::lock_guard lg{_notification_callbacks_mutex};
×
494
    _notification_callbacks.unsubscribe(handle);
×
495
}
×
496
ComponentMetadata::MetadataAvailableHandle ComponentMetadataImpl::subscribe_metadata_available(
1✔
497
    const ComponentMetadata::MetadataAvailableCallback& callback)
498
{
499
    const std::lock_guard lg_components{_mavlink_components_mutex}; // Take this mutex first
2✔
500
    const std::lock_guard lg_callbacks{_notification_callbacks_mutex};
1✔
501
    const auto handle = _notification_callbacks.subscribe(callback);
1✔
502

503
    // Immediately call the callback for all already existing metadata (with the mutexes locked)
504
    for (const auto& [compid, component] : _mavlink_components) {
2✔
505
        for (const auto& [type, metadata] : component.components) {
1✔
506
            auto metadata_type = get_metadata_type(type);
×
507
            if (metadata.is_completed() && metadata.json_metadata() && metadata_type) {
×
508
                _system_impl->call_user_callback(
×
509
                    [temp_callback = callback,
510
                     metadata_type = metadata_type.value(),
511
                     temp_compid = compid,
512
                     json_metadata = metadata.json_metadata().value()] {
513
                        temp_callback(ComponentMetadata::MetadataUpdate{
514
                            temp_compid, metadata_type, json_metadata});
515
                    });
516
            }
517
        }
518
        if (component.result) {
1✔
519
            _system_impl->call_user_callback([temp_callback = callback, temp_compid = compid] {
×
520
                temp_callback(ComponentMetadata::MetadataUpdate{
521
                    temp_compid, ComponentMetadata::MetadataType::AllCompleted, ""});
522
            });
523
        }
524
    }
525
    return handle;
1✔
526
}
527

528
void ComponentMetadataImpl::on_all_types_completed(uint8_t compid)
1✔
529
{
530
    const std::lock_guard lg_callbacks{_notification_callbacks_mutex};
2✔
531
    _notification_callbacks.queue(
3✔
532
        ComponentMetadata::MetadataUpdate{
2✔
533
            compid, ComponentMetadata::MetadataType::AllCompleted, ""},
1✔
534
        [this](const auto& func) { _system_impl->call_user_callback(func); });
1✔
535
}
1✔
536

537
MetadataComponentUris::MetadataComponentUris(const Json::Value& value)
2✔
538
{
539
    if (value["uri"].isString()) {
2✔
540
        _uri_metadata = value["uri"].asString();
2✔
541
    }
542
    if (value["fileCrc"].isUInt()) {
2✔
543
        _crc_metadata = value["fileCrc"].asUInt();
2✔
544
        _crc_metadata_valid = true;
2✔
545
    }
546
    if (value["uriFallback"].isString()) {
2✔
547
        _uri_metadata_fallback = value["uriFallback"].asString();
×
548
    }
549
    if (value["fileCrcFallback"].isUInt()) {
2✔
550
        _crc_metadata_fallback = value["fileCrcFallback"].asUInt();
×
551
        _crc_metadata_fallback_valid = true;
×
552
    }
553
    if (value["translationUri"].isString()) {
2✔
554
        _uri_translation = value["translationUri"].asString();
×
555
    }
556
    if (value["translationUriFallback"].isString()) {
2✔
557
        _uri_translation_fallback = value["translationUriFallback"].asString();
×
558
    }
559
}
2✔
560

561
bool MetadataComponent::get_next_uri(
6✔
562
    bool& crc_valid, uint32_t& crc, bool& is_translation, std::string& uri)
563
{
564
    // Skip fallback if we have valid data already
565
    switch (_state) {
6✔
566
        case State::Metadata:
3✔
567
            if (_metadata) {
3✔
568
                _state = State::MetadataFallback;
3✔
569
            }
570
            break;
3✔
571
        case State::Translation:
×
572
            if (_translation) {
×
573
                _state = State::TranslationFallback;
×
574
            }
575
            break;
×
576
        default:
3✔
577
            break;
3✔
578
    }
579

580
    uri = "";
6✔
581
    while (uri.empty() && _state != State::Done) {
18✔
582
        switch (_state) {
12✔
583
            case State::Init:
3✔
584
                crc_valid = _metadata_uris.crc_meta_data_valid();
3✔
585
                crc = _metadata_uris.crc_meta_data();
3✔
586
                uri = _metadata_uris.uri_metadata();
3✔
587
                is_translation = false;
3✔
588
                _state = State::Metadata;
3✔
589
                break;
3✔
590
            case State::Metadata:
×
591
                crc_valid = _metadata_uris.crc_meta_data_fallback_valid();
×
592
                crc = _metadata_uris.crc_meta_data_fallback();
×
593
                uri = _metadata_uris.uri_metadata_fallback();
×
594
                is_translation = false;
×
595
                _state = State::MetadataFallback;
×
596
                break;
×
597
            case State::MetadataFallback:
3✔
598
                crc_valid = false;
3✔
599
                crc = 0;
3✔
600
                uri = _metadata_uris.uri_translation();
3✔
601
                is_translation = true;
3✔
602
                _state = State::Translation;
3✔
603
                break;
3✔
604
            case State::Translation:
3✔
605
                crc_valid = false;
3✔
606
                crc = 0;
3✔
607
                uri = _metadata_uris.uri_translation_fallback();
3✔
608
                is_translation = true;
3✔
609
                _state = State::TranslationFallback;
3✔
610
                break;
3✔
611
            case State::TranslationFallback:
3✔
612
                // Read files if available
613
                if (_metadata) {
3✔
614
                    std::ifstream file(*_metadata);
6✔
615
                    if (file) {
3✔
616
                        std::stringstream buffer;
6✔
617
                        buffer << file.rdbuf();
3✔
618
                        _json_metadata.emplace(buffer.str());
3✔
619
                    }
620
                }
621
                if (_translation) {
3✔
622
                    std::ifstream file(*_translation);
×
623
                    if (file) {
×
624
                        std::stringstream buffer;
×
625
                        buffer << file.rdbuf();
×
626
                        _json_translation.emplace(buffer.str());
×
627
                    }
628
                }
629
                _state = State::Done;
3✔
630
                break;
3✔
631
            case State::Done:
×
632
                break;
×
633
        }
634
    }
635
    return _state != State::Done;
6✔
636
}
637
std::optional<std::filesystem::path>& MetadataComponent::current_metadata_path()
3✔
638
{
639
    switch (_state) {
3✔
640
        case State::Metadata:
3✔
641
        case State::MetadataFallback:
642
            return _metadata;
3✔
643
        case State::Translation:
×
644
        case State::TranslationFallback:
645
            return _translation;
×
646
        case State::Done:
×
647
        case State::Init:
648
            break;
×
649
    }
650
    LogErr() << "current_metadata_path() called in invalid state";
×
651
    return _metadata;
×
652
}
653
} // namespace mavsdk
STATUS · Troubleshooting · Open an Issue · Sales · Support · CAREERS · ENTERPRISE · START FREE · SCHEDULE DEMO
ANNOUNCEMENTS · TWITTER · TOS & SLA · Supported CI Services · What's a CI service? · Automated Testing

© 2026 Coveralls, Inc