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

mavlink / MAVSDK / 11767930807

10 Nov 2024 07:33PM UTC coverage: 38.608% (+0.7%) from 37.921%
11767930807

push

github

web-flow
Merge pull request #2394 from mavlink/pr-consolidate-ci

Consolidate CI

12030 of 31159 relevant lines covered (38.61%)

243.33 hits per line

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

62.87
/src/mavsdk/core/mavlink_component_metadata.cpp
1
#include "mavlink_component_metadata.h"
2
#include "callback_list.tpp"
3
#include "fs_utils.h"
4
#include "inflate_lzma.h"
5
#include "unused.h"
6
#include "system_impl.h"
7

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

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

18
namespace mavsdk {
19

20
namespace fs = std::filesystem;
21

22
MavlinkComponentMetadata::MavlinkComponentMetadata(SystemImpl& system_impl) :
69✔
23
    _system_impl(system_impl)
69✔
24
{
25
    if (const char* env_p = std::getenv("MAVSDK_COMPONENT_METADATA_DEBUGGING")) {
69✔
26
        if (std::string(env_p) == "1") {
66✔
27
            LogDebug() << "Verbose component metadata logging is on";
66✔
28
            _verbose_debugging = true;
66✔
29
        }
30
    }
31

32
    const auto cache_dir_option = get_cache_directory();
69✔
33
    if (cache_dir_option) {
69✔
34
        _file_cache.emplace(
69✔
35
            cache_dir_option.value() / "component_metadata", 50, _verbose_debugging);
138✔
36
    } else {
37
        LogErr() << "Failed to get cache directory";
×
38
    }
39

40
    const auto tmp_option = create_tmp_directory("mavsdk-component-metadata");
207✔
41
    if (tmp_option) {
69✔
42
        _tmp_download_path = tmp_option.value();
69✔
43
    } else {
44
        _tmp_download_path = "./mavsdk-component-metadata";
×
45
        std::error_code err;
×
46
        std::filesystem::create_directory(_tmp_download_path, err);
×
47
    }
48
}
69✔
49

50
MavlinkComponentMetadata::~MavlinkComponentMetadata()
138✔
51
{
52
    std::error_code ec;
69✔
53
    std::filesystem::remove_all(_tmp_download_path, ec);
69✔
54
    if (ec) {
69✔
55
        LogErr() << "failed to remove directory: " << ec.message();
×
56
    }
57
}
69✔
58

59
void MavlinkComponentMetadata::request_component(uint32_t compid)
1✔
60
{
61
    const std::lock_guard lg{_mavlink_components_mutex};
1✔
62
    if (_mavlink_components.find(compid) == _mavlink_components.end()) {
1✔
63
        _mavlink_components[compid] = MavlinkComponent{};
1✔
64
        _system_impl.mavlink_request_message().request(
1✔
65
            MAVLINK_MSG_ID_COMPONENT_METADATA, compid, [this](auto&& result, auto&& message) {
1✔
66
                receive_component_metadata(result, message);
1✔
67
            });
1✔
68
    }
69
}
1✔
70

71
void MavlinkComponentMetadata::receive_component_metadata(
1✔
72
    MavlinkCommandSender::Result result, const mavlink_message_t& message)
73
{
74
    const std::lock_guard lg{_mavlink_components_mutex};
1✔
75
    if (_mavlink_components.find(message.compid) == _mavlink_components.end()) {
1✔
76
        LogWarn() << "Unexpected component ID " << static_cast<int>(message.compid);
×
77
        return;
×
78
    }
79

80
    // Store the result if the command failed
81
    if (result != MavlinkCommandSender::Result::Success) {
1✔
82
        switch (result) {
×
83
            case MavlinkCommandSender::Result::ConnectionError:
×
84
                _mavlink_components[message.compid].result = Result::ConnectionError;
×
85
                break;
×
86
            case MavlinkCommandSender::Result::Denied:
×
87
                _mavlink_components[message.compid].result = Result::Denied;
×
88
                break;
×
89
            case MavlinkCommandSender::Result::Unsupported:
×
90
                _mavlink_components[message.compid].result = Result::Unsupported;
×
91
                break;
×
92
            case MavlinkCommandSender::Result::Timeout:
×
93
                _mavlink_components[message.compid].result = Result::Timeout;
×
94
                break;
×
95
            default:
×
96
                _mavlink_components[message.compid].result = Result::Failed;
×
97
                break;
×
98
        }
99
        LogWarn() << "Requesting component metadata failed with " << static_cast<int>(result);
×
100
        on_all_types_completed(message.compid);
×
101
        return;
×
102
    }
103

104
    mavlink_component_metadata_t component_metadata;
1✔
105
    mavlink_msg_component_metadata_decode(&message, &component_metadata);
1✔
106

107
    component_metadata.uri[sizeof(component_metadata.uri) - 1] = '\0';
1✔
108
    _mavlink_components[message.compid].components.insert(std::make_pair(
3✔
109
        COMP_METADATA_TYPE_GENERAL,
2✔
110
        MetadataComponent{{component_metadata.uri, component_metadata.file_crc}}));
2✔
111

112
    retrieve_metadata(message.compid, COMP_METADATA_TYPE_GENERAL);
1✔
113
}
1✔
114

115
std::string MavlinkComponentMetadata::get_file_cache_tag(
3✔
116
    uint8_t compid, int comp_info_type, uint32_t crc, bool is_translation)
117
{
118
    char buf[255];
3✔
119
    snprintf(
3✔
120
        buf,
121
        sizeof(buf),
122
        "compid-%03i_crc-%08x_type-%02i_trans-%i",
123
        compid,
124
        crc,
125
        comp_info_type,
126
        (int)is_translation);
127
    return buf;
3✔
128
}
129
bool MavlinkComponentMetadata::uri_is_mavlinkftp(
6✔
130
    const std::string& uri, std::string& download_path, uint8_t& target_compid)
131
{
132
    // Case insensitiv check if uri starts with "mftp://"
133
    if (strncasecmp(uri.c_str(), "mftp://", 7) == 0) {
6✔
134
        download_path = uri.substr(7);
5✔
135
        // Extract optional [;comp=<compid>] prefix
136
        std::regex compid_regex(R"(^(?:\[\;comp\=(\d+)\])(.*))");
5✔
137
        std::smatch match;
5✔
138
        if (std::regex_search(download_path, match, compid_regex)) {
5✔
139
            target_compid = std::stoi(match[1]);
1✔
140
            download_path = match[2];
1✔
141
        }
142
        return true;
5✔
143
    }
5✔
144
    return false;
1✔
145
}
146

147
void MavlinkComponentMetadata::retrieve_metadata(uint8_t compid, COMP_METADATA_TYPE type)
6✔
148
{
149
    if (_verbose_debugging) {
6✔
150
        LogDebug() << "MavlinkComponentMetadata::retrieve_metadata for compid "
12✔
151
                   << static_cast<int>(compid) << ", type " << static_cast<int>(type);
12✔
152
    }
153

154
    const std::lock_guard lg{_mavlink_components_mutex};
6✔
155
    auto& component = _mavlink_components[compid].components[type];
6✔
156
    bool crc_valid;
6✔
157
    uint32_t crc;
6✔
158
    bool is_translation;
6✔
159
    std::string uri;
6✔
160

161
    if (component.get_next_uri(crc_valid, crc, is_translation, uri)) {
6✔
162
        // If translation locale is not set, skip translations
163
        if (is_translation && !_translation_locale) {
3✔
164
            retrieve_metadata(compid, type);
×
165
            return;
×
166
        }
167

168
        std::optional<std::filesystem::path> cached_file_option{};
3✔
169
        std::string file_cache_tag{};
3✔
170
        if (_file_cache && crc_valid) {
3✔
171
            file_cache_tag = get_file_cache_tag(compid, type, crc, is_translation);
3✔
172
            cached_file_option = _file_cache->access(file_cache_tag);
3✔
173
        }
174

175
        if (cached_file_option) {
3✔
176
            if (_verbose_debugging) {
×
177
                LogDebug() << "Using cached file " << cached_file_option.value();
×
178
            }
179
            component.current_metadata_path() = cached_file_option.value();
×
180
            retrieve_metadata(compid, type);
×
181
        } else {
182
            if (_verbose_debugging) {
3✔
183
                LogDebug() << "Downloading json " << uri;
3✔
184
            }
185
            std::string download_path;
3✔
186
            uint8_t target_compid = compid;
3✔
187

188
            if (uri_is_mavlinkftp(uri, download_path, target_compid)) {
3✔
189
                // Create compid-specific tmp subdir, to ensure multiple components don't overwrite
190
                // files from each other
191
                const std::filesystem::path tmp_download_path =
3✔
192
                    _tmp_download_path / std::to_string(compid);
9✔
193
                if (!std::filesystem::exists(tmp_download_path)) {
3✔
194
                    std::error_code err;
1✔
195
                    std::filesystem::create_directory(tmp_download_path, err);
1✔
196
                }
197

198
                const std::filesystem::path local_path =
3✔
199
                    tmp_download_path / std::filesystem::path(download_path).filename();
9✔
200

201
                _system_impl.call_user_callback([this,
25✔
202
                                                 download_path,
203
                                                 tmp_download_path,
204
                                                 &component,
205
                                                 target_compid,
206
                                                 local_path,
207
                                                 compid,
208
                                                 type,
209
                                                 file_cache_tag]() {
210
                    _system_impl.mavlink_ftp_client().download_async(
211
                        download_path,
212
                        tmp_download_path.string(),
213
                        true,
214
                        [this, &component, local_path, compid, type, file_cache_tag](
215
                            MavlinkFtpClient::ClientResult download_result,
216
                            MavlinkFtpClient::ProgressData progress_data) {
217
                            if (download_result == MavlinkFtpClient::ClientResult::Next) {
218
                                if (_verbose_debugging) {
219
                                    LogDebug() << "File download progress: "
220
                                               << progress_data.bytes_transferred << '/'
221
                                               << progress_data.total_bytes;
222
                                }
223
                                // TODO: detect slow link (e.g. telemetry), and cancel download
224
                                // (fallback to http) e.g. by estimating the remaining download
225
                                // time, and cancel if >40s
226
                            } else {
227
                                if (_verbose_debugging) {
228
                                    LogDebug()
229
                                        << "File download ended with result " << download_result;
230
                                }
231
                                if (download_result == MavlinkFtpClient::ClientResult::Success) {
232
                                    component.current_metadata_path() =
233
                                        extract_and_cache_file(local_path, file_cache_tag);
234
                                }
235
                                // Move on to the next uri or type
236
                                retrieve_metadata(compid, type);
237
                            }
238
                        },
239
                        target_compid);
240
                });
241

242
            } else {
3✔
243
                // http(s) download
244
#if BUILD_WITHOUT_CURL == 1
245
                LogErr() << "HTTP disabled at build time, skipping download of " << uri;
246
                retrieve_metadata(compid, type);
247
#else
248
                const std::string base_filename = filename_from_uri(uri);
×
249
                const std::filesystem::path tmp_download_path =
×
250
                    _tmp_download_path / ("http-" + std::to_string(compid) + "-" +
×
251
                                          std::to_string(type) + "-" + base_filename);
×
252
                _http_loader.download_async(
×
253
                    uri,
254
                    tmp_download_path.string(),
×
255
                    [this, &component, tmp_download_path, compid, type, file_cache_tag](
×
256
                        int progress, HttpStatus status, CURLcode curl_code) -> int {
×
257
                        UNUSED(progress);
×
258
                        if (status == HttpStatus::Error) {
×
259
                            LogErr() << "File download failed with result " << curl_code;
×
260
                            // Move on to the next uri or type
261
                            retrieve_metadata(compid, type);
×
262
                        } else if (status == HttpStatus::Finished) {
×
263
                            if (_verbose_debugging) {
×
264
                                LogDebug() << "File download finished " << tmp_download_path;
×
265
                            }
266
                            component.current_metadata_path() =
×
267
                                extract_and_cache_file(tmp_download_path, file_cache_tag);
×
268
                            // Move on to the next uri or type
269
                            retrieve_metadata(compid, type);
×
270
                        }
271
                        return 0;
×
272
                    });
273
#endif
274
            }
×
275
        }
3✔
276
    } else {
3✔
277
        // Move on to next type
278
        handle_metadata_type_completed(compid, type);
3✔
279
    }
280
}
6✔
281

282
void MavlinkComponentMetadata::handle_metadata_type_completed(
3✔
283
    uint8_t compid, COMP_METADATA_TYPE type)
284
{
285
    const std::lock_guard lg{_mavlink_components_mutex};
3✔
286
    auto& component = _mavlink_components[compid].components[type];
3✔
287
    assert(component.is_completed());
3✔
288

289
    // TODO: handle translations. For that we need to parse the translation summary json file
290
    // component.json_translation() and then download the locale-specific translation file.
291
    // See
292
    // https://github.com/mavlink/qgroundcontrol/blob/master/src/Vehicle/ComponentInformationTranslation.cc
293

294
    if (type == COMP_METADATA_TYPE_GENERAL && component.json_metadata()) {
3✔
295
        parse_component_metadata_general(compid, *component.json_metadata());
1✔
296
    }
297

298
    // Call user callbacks
299
    if (component.json_metadata()) {
3✔
300
        auto metadata_type = get_metadata_type(type);
3✔
301
        if (metadata_type) {
3✔
302
            const std::lock_guard lg_callbacks{_notification_callbacks_mutex};
2✔
303
            _notification_callbacks.queue(
6✔
304
                MetadataUpdate{compid, metadata_type.value(), component.json_metadata().value()},
4✔
305
                [this](const auto& func) { _system_impl.call_user_callback(func); });
2✔
306
        }
2✔
307
    }
308

309
    // Retrieve next remaining metadata type
310
    bool all_completed = true;
3✔
311
    for (const auto& [next_type, next_component] : _mavlink_components[compid].components) {
9✔
312
        if (!next_component.is_completed()) {
8✔
313
            retrieve_metadata(compid, next_type);
2✔
314
            all_completed = false;
2✔
315
            break;
2✔
316
        }
317
    }
318
    if (all_completed) {
3✔
319
        LogDebug() << "All metadata types completed for compid " << static_cast<int>(compid);
1✔
320
        _mavlink_components[compid].result = Result::Success;
1✔
321
        on_all_types_completed(compid);
1✔
322
    }
323
}
3✔
324

325
std::optional<std::filesystem::path> MavlinkComponentMetadata::extract_and_cache_file(
3✔
326
    const std::filesystem::path& path, const std::string& file_cache_tag)
327
{
328
    std::filesystem::path returned_path = path;
3✔
329
    // Decompress if needed
330
    if (path.extension() == ".lzma" || path.extension() == ".xz") {
3✔
331
        returned_path.replace_extension(".extracted");
×
332
        if (InflateLZMA::inflateLZMAFile(path, returned_path)) {
×
333
            std::filesystem::remove(path);
×
334
        } else {
335
            LogErr() << "Inflate of compressed json failed " << path;
×
336
            return std::nullopt;
×
337
        }
338
    }
339

340
    if (_file_cache && !file_cache_tag.empty()) {
3✔
341
        // Cache the file (this will move/remove the temp file as well)
342
        returned_path = _file_cache->insert(file_cache_tag, returned_path).value_or(returned_path);
3✔
343
    }
344
    return returned_path;
3✔
345
}
3✔
346
std::string MavlinkComponentMetadata::filename_from_uri(const std::string& uri)
2✔
347
{
348
    // Extract the base name from an uri
349
    const auto last_slash = uri.find_last_of('/');
2✔
350
    std::string base_filename = "downloaded_file.json";
4✔
351
    if (last_slash != std::string::npos) {
2✔
352
        base_filename = uri.substr(last_slash + 1);
2✔
353
    }
354
    const auto parameter_index = base_filename.find('?');
2✔
355
    if (parameter_index != std::string::npos) {
2✔
356
        base_filename = base_filename.substr(0, parameter_index);
1✔
357
    }
358
    return base_filename;
2✔
359
}
360
std::optional<MavlinkComponentMetadata::MetadataType>
361
MavlinkComponentMetadata::get_metadata_type(COMP_METADATA_TYPE type)
3✔
362
{
363
    switch (type) {
3✔
364
        case COMP_METADATA_TYPE_PARAMETER:
1✔
365
            return MetadataType::Parameter;
1✔
366
        case COMP_METADATA_TYPE_EVENTS:
1✔
367
            return MetadataType::Events;
1✔
368
        case COMP_METADATA_TYPE_ACTUATORS:
×
369
            return MetadataType::Actuators;
×
370
        default:
1✔
371
            break;
1✔
372
    }
373

374
    return std::nullopt;
1✔
375
}
376
std::pair<MavlinkComponentMetadata::Result, MavlinkComponentMetadata::MetadataData>
377
MavlinkComponentMetadata::get_metadata(uint32_t compid, MetadataType type)
×
378
{
379
    COMP_METADATA_TYPE metadata_type{COMP_METADATA_TYPE_GENERAL};
×
380
    switch (type) {
×
381
        case MetadataType::Parameter:
×
382
            metadata_type = COMP_METADATA_TYPE_PARAMETER;
×
383
            break;
×
384
        case MetadataType::Events:
×
385
            metadata_type = COMP_METADATA_TYPE_EVENTS;
×
386
            break;
×
387
        case MetadataType::Actuators:
×
388
            metadata_type = COMP_METADATA_TYPE_ACTUATORS;
×
389
            break;
×
390
        case MetadataType::AllCompleted:
×
391
            return std::make_pair(Result::Failed, MetadataData{});
×
392
    }
393
    const std::lock_guard lg{_mavlink_components_mutex};
×
394
    const auto comp_iter = _mavlink_components.find(compid);
×
395
    if (comp_iter != _mavlink_components.end()) {
×
396
        const auto type_iter = comp_iter->second.components.find(metadata_type);
×
397
        if (type_iter != comp_iter->second.components.end() && type_iter->second.json_metadata()) {
×
398
            return std::make_pair(
399
                Result::Success, MetadataData{*type_iter->second.json_metadata()});
×
400
        }
401
        if (!comp_iter->second.result || *comp_iter->second.result == Result::Success) {
×
402
            return std::make_pair(Result::NotAvailable, MetadataData{""});
×
403
        } else {
404
            return std::make_pair(*comp_iter->second.result, MetadataData{""});
×
405
        }
406
    }
407
    return std::make_pair(Result::NotRequested, MetadataData{""});
×
408
}
×
409
void MavlinkComponentMetadata::parse_component_metadata_general(
1✔
410
    uint8_t compid, const std::string& json_metadata)
411
{
412
    Json::Value metadata;
1✔
413
    Json::Reader reader;
1✔
414
    bool parsing_successful = reader.parse(json_metadata, metadata);
1✔
415
    if (!parsing_successful) {
1✔
416
        LogErr() << "Failed to parse" << reader.getFormattedErrorMessages();
×
417
        return;
×
418
    }
419

420
    if (!metadata.isMember("version")) {
1✔
421
        LogErr() << "version not found";
×
422
        return;
×
423
    }
424

425
    if (metadata["version"].asInt() != 1) {
1✔
426
        LogWarn() << "version " << metadata["version"].asInt() << " not supported";
×
427
        return;
×
428
    }
429

430
    if (!metadata.isMember("metadataTypes")) {
1✔
431
        LogErr() << "metadataTypes not found";
×
432
        return;
×
433
    }
434

435
    for (const auto& metadata_type : metadata["metadataTypes"]) {
3✔
436
        if (!metadata_type.isMember("type")) {
2✔
437
            LogErr() << "type missing";
×
438
            continue;
×
439
        }
440
        auto type = static_cast<COMP_METADATA_TYPE>(metadata_type["type"].asInt());
2✔
441
        auto& components = _mavlink_components[compid].components;
2✔
442
        if (components.find(type) != components.end()) {
2✔
443
            LogErr() << "component type already added: " << type;
×
444
            continue;
×
445
        }
446
        if (!metadata_type.isMember("uri")) {
2✔
447
            LogErr() << "uri missing";
×
448
            continue;
×
449
        }
450

451
        components.emplace(type, MetadataComponent{MetadataComponentUris{metadata_type}});
2✔
452
    }
453
}
1✔
454
void MavlinkComponentMetadata::unsubscribe_metadata_available(MetadataAvailableHandle handle)
×
455
{
456
    const std::lock_guard lg{_notification_callbacks_mutex};
×
457
    _notification_callbacks.unsubscribe(handle);
×
458
}
×
459
MavlinkComponentMetadata::MetadataAvailableHandle
460
MavlinkComponentMetadata::subscribe_metadata_available(const MetadataAvailableCallback& callback)
1✔
461
{
462
    const std::lock_guard lg_components{_mavlink_components_mutex}; // Take this mutex first
1✔
463
    const std::lock_guard lg_callbacks{_notification_callbacks_mutex};
1✔
464
    const auto handle = _notification_callbacks.subscribe(callback);
1✔
465

466
    // Immediately call the callback for all already existing metadata (with the mutexes locked)
467
    for (const auto& [compid, component] : _mavlink_components) {
2✔
468
        for (const auto& [type, metadata] : component.components) {
1✔
469
            auto metadata_type = get_metadata_type(type);
×
470
            if (metadata.is_completed() && metadata.json_metadata() && metadata_type) {
×
471
                _system_impl.call_user_callback([temp_callback = callback,
×
472
                                                 metadata_type = metadata_type.value(),
473
                                                 temp_compid = compid,
474
                                                 json_metadata = metadata.json_metadata().value()] {
475
                    temp_callback(MetadataUpdate{temp_compid, metadata_type, json_metadata});
476
                });
477
            }
478
        }
479
        if (component.result) {
1✔
480
            _system_impl.call_user_callback([temp_callback = callback, temp_compid = compid] {
×
481
                temp_callback(MetadataUpdate{temp_compid, MetadataType::AllCompleted, ""});
482
            });
483
        }
484
    }
485
    return handle;
2✔
486
}
1✔
487

488
void MavlinkComponentMetadata::on_all_types_completed(uint8_t compid)
1✔
489
{
490
    const std::lock_guard lg_callbacks{_notification_callbacks_mutex};
1✔
491
    _notification_callbacks.queue(
3✔
492
        MetadataUpdate{compid, MetadataType::AllCompleted, ""},
2✔
493
        [this](const auto& func) { _system_impl.call_user_callback(func); });
1✔
494
}
1✔
495

496
MetadataComponentUris::MetadataComponentUris(const Json::Value& value)
2✔
497
{
498
    if (value["uri"].isString()) {
2✔
499
        _uri_metadata = value["uri"].asString();
2✔
500
    }
501
    if (value["fileCrc"].isUInt()) {
2✔
502
        _crc_metadata = value["fileCrc"].asUInt();
2✔
503
        _crc_metadata_valid = true;
2✔
504
    }
505
    if (value["uriFallback"].isString()) {
2✔
506
        _uri_metadata_fallback = value["uriFallback"].asString();
×
507
    }
508
    if (value["fileCrcFallback"].isUInt()) {
2✔
509
        _crc_metadata_fallback = value["fileCrcFallback"].asUInt();
×
510
        _crc_metadata_fallback_valid = true;
×
511
    }
512
    if (value["translationUri"].isString()) {
2✔
513
        _uri_translation = value["translationUri"].asString();
×
514
    }
515
    if (value["translationUriFallback"].isString()) {
2✔
516
        _uri_translation_fallback = value["translationUriFallback"].asString();
×
517
    }
518
}
2✔
519

520
bool MetadataComponent::get_next_uri(
6✔
521
    bool& crc_valid, uint32_t& crc, bool& is_translation, std::string& uri)
522
{
523
    // Skip fallback if we have valid data already
524
    switch (_state) {
6✔
525
        case State::Metadata:
3✔
526
            if (_metadata) {
3✔
527
                _state = State::MetadataFallback;
3✔
528
            }
529
            break;
3✔
530
        case State::Translation:
×
531
            if (_translation) {
×
532
                _state = State::TranslationFallback;
×
533
            }
534
            break;
×
535
        default:
3✔
536
            break;
3✔
537
    }
538

539
    uri = "";
6✔
540
    while (uri.empty() && _state != State::Done) {
18✔
541
        switch (_state) {
12✔
542
            case State::Init:
3✔
543
                crc_valid = _metadata_uris.crc_meta_data_valid();
3✔
544
                crc = _metadata_uris.crc_meta_data();
3✔
545
                uri = _metadata_uris.uri_metadata();
3✔
546
                is_translation = false;
3✔
547
                _state = State::Metadata;
3✔
548
                break;
3✔
549
            case State::Metadata:
×
550
                crc_valid = _metadata_uris.crc_meta_data_fallback_valid();
×
551
                crc = _metadata_uris.crc_meta_data_fallback();
×
552
                uri = _metadata_uris.uri_metadata_fallback();
×
553
                is_translation = false;
×
554
                _state = State::MetadataFallback;
×
555
                break;
×
556
            case State::MetadataFallback:
3✔
557
                crc_valid = false;
3✔
558
                crc = 0;
3✔
559
                uri = _metadata_uris.uri_translation();
3✔
560
                is_translation = true;
3✔
561
                _state = State::Translation;
3✔
562
                break;
3✔
563
            case State::Translation:
3✔
564
                crc_valid = false;
3✔
565
                crc = 0;
3✔
566
                uri = _metadata_uris.uri_translation_fallback();
3✔
567
                is_translation = true;
3✔
568
                _state = State::TranslationFallback;
3✔
569
                break;
3✔
570
            case State::TranslationFallback:
3✔
571
                // Read files if available
572
                if (_metadata) {
3✔
573
                    std::ifstream file(*_metadata);
3✔
574
                    if (file) {
3✔
575
                        std::stringstream buffer;
3✔
576
                        buffer << file.rdbuf();
3✔
577
                        _json_metadata.emplace(buffer.str());
3✔
578
                    }
3✔
579
                }
3✔
580
                if (_translation) {
3✔
581
                    std::ifstream file(*_translation);
×
582
                    if (file) {
×
583
                        std::stringstream buffer;
×
584
                        buffer << file.rdbuf();
×
585
                        _json_translation.emplace(buffer.str());
×
586
                    }
×
587
                }
×
588
                _state = State::Done;
3✔
589
                break;
3✔
590
            case State::Done:
×
591
                break;
×
592
        }
593
    }
594
    return _state != State::Done;
6✔
595
}
596
std::optional<std::filesystem::path>& MetadataComponent::current_metadata_path()
3✔
597
{
598
    switch (_state) {
3✔
599
        case State::Metadata:
3✔
600
        case State::MetadataFallback:
601
            return _metadata;
3✔
602
        case State::Translation:
×
603
        case State::TranslationFallback:
604
            return _translation;
×
605
        case State::Done:
×
606
        case State::Init:
607
            break;
×
608
    }
609
    LogErr() << "current_metadata_path() called in invalid state";
×
610
    return _metadata;
×
611
}
612
} // 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