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

mavlink / MAVSDK / 19218039190

10 Nov 2025 01:44AM UTC coverage: 48.216% (-0.08%) from 48.296%
19218039190

push

github

web-flow
Merge pull request #2654 from mavlink/pr-logfiles-fixup

LogFiles fixup

0 of 91 new or added lines in 1 file covered. (0.0%)

4 existing lines in 2 files now uncovered.

17632 of 36569 relevant lines covered (48.22%)

465.54 hits per line

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

0.0
/src/mavsdk/plugins/log_files/log_files_impl.cpp
1
#include "log_files_impl.h"
2
#include "mavlink_address.h"
3
#include "mavsdk_impl.h"
4

5
#include <algorithm>
6
#include <cmath>
7
#include <ctime>
8
#include <filesystem>
9

10
namespace mavsdk {
11

12
namespace fs = std::filesystem;
13

14
LogData::LogData(
×
15
    const LogFiles::Entry& e, const std::string& filepath, LogFiles::DownloadLogFileCallback cb) :
×
16
    entry(e),
×
17
    file_path(filepath),
×
18
    user_callback(cb)
×
19
{
20
    // Reset the table
21
    chunk_bin_table = std::vector<bool>(bins_in_chunk(), false);
×
22
    file.open(file_path, std::ios::out | std::ios::binary);
×
23
}
×
24

25
bool LogData::file_is_open()
×
26
{
27
    // TODO: any other checks?
28
    return !(file.rdstate() & std::ofstream::failbit); // Ensure file is writable
×
29
}
30

31
uint32_t LogData::total_chunks() const
×
32
{
33
    uint32_t partial_chunk = entry.size_bytes % CHUNK_SIZE;
×
34
    uint32_t add_one_chunk = partial_chunk ? 1 : 0;
×
35
    return entry.size_bytes / CHUNK_SIZE + add_one_chunk;
×
36
}
37

38
uint32_t LogData::bins_in_chunk() const
×
39
{
40
    uint32_t size = current_chunk_size();
×
41
    uint32_t add_one_bin = size % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN ? 1 : 0;
×
42
    return size / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN + add_one_bin;
×
43
}
44

45
uint32_t LogData::current_chunk_size() const
×
46
{
47
    uint32_t chunk_size = CHUNK_SIZE;
×
48
    uint32_t chunk_remainder = entry.size_bytes % CHUNK_SIZE;
×
49
    bool is_last_chunk = (current_chunk == total_chunks() - 1);
×
50
    // Last chunk might be less than CHUNK_SIZE
51
    if (is_last_chunk && chunk_remainder) {
×
52
        chunk_size = entry.size_bytes % CHUNK_SIZE;
×
53
    }
54

55
    return chunk_size;
×
56
}
57

58
LogFilesImpl::LogFilesImpl(System& system) : PluginImplBase(system)
×
59
{
60
    _system_impl->register_plugin(this);
×
61
}
×
62

63
LogFilesImpl::LogFilesImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
×
64
{
65
    _system_impl->register_plugin(this);
×
66
}
×
67

68
LogFilesImpl::~LogFilesImpl()
×
69
{
70
    _system_impl->unregister_plugin(this);
×
71
}
×
72

73
void LogFilesImpl::init()
×
74
{
75
    _system_impl->register_mavlink_message_handler(
×
76
        MAVLINK_MSG_ID_LOG_ENTRY,
77
        [this](const mavlink_message_t& message) { process_log_entry(message); },
×
78
        this);
79

80
    _system_impl->register_mavlink_message_handler(
×
81
        MAVLINK_MSG_ID_LOG_DATA,
82
        [this](const mavlink_message_t& message) { process_log_data(message); },
×
83
        this);
84

85
    // Cancel any log file downloads that might still be going on.
86
    request_end();
×
87
}
×
88

89
void LogFilesImpl::deinit()
×
90
{
91
    {
92
        std::lock_guard<std::mutex> lock(_entries_mutex);
×
93
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
94
    }
×
95

96
    {
97
        std::lock_guard<std::mutex> lock(_download_data_mutex);
×
98
        _system_impl->unregister_timeout_handler(_download_data.timeout_cookie);
×
99
    }
×
100
    _system_impl->unregister_all_mavlink_message_handlers(this);
×
101
}
×
102

103
std::pair<LogFiles::Result, std::vector<LogFiles::Entry>> LogFilesImpl::get_entries()
×
104
{
105
    auto prom =
106
        std::make_shared<std::promise<std::pair<LogFiles::Result, std::vector<LogFiles::Entry>>>>();
×
107
    auto future_result = prom->get_future();
×
108

109
    get_entries_async([prom](LogFiles::Result result, std::vector<LogFiles::Entry> entries) {
×
110
        prom->set_value(std::make_pair<>(result, entries));
×
111
    });
×
112

113
    auto result = future_result.get();
×
114

115
    _entries_user_callback = nullptr;
×
116

117
    return result;
×
118
}
×
119

120
void LogFilesImpl::get_entries_async(LogFiles::GetEntriesCallback callback)
×
121
{
122
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
123
    _log_entries.clear();
×
124
    _entries_user_callback = callback;
×
125
    _total_entries = 0;
×
NEW
126
    _entries_retry_count = 0;
×
127

128
    _entries_timeout_cookie = _system_impl->register_timeout_handler(
×
129
        [this]() { entries_timeout(); }, _system_impl->timeout_s() * 10.0);
×
130

131
    request_log_list(0, 0xFFFF);
×
132
}
×
133

134
void LogFilesImpl::request_log_list(uint16_t index_min, uint16_t index_max)
×
135
{
136
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
137
        mavlink_message_t message;
138
        mavlink_msg_log_request_list_pack_chan(
×
139
            mavlink_address.system_id,
×
140
            mavlink_address.component_id,
×
141
            channel,
142
            &message,
143
            _system_impl->get_system_id(),
×
144
            MAV_COMP_ID_AUTOPILOT1,
145
            index_min,
×
146
            index_max);
×
147
        return message;
×
148
    });
149
}
×
150

151
void LogFilesImpl::process_log_entry(const mavlink_message_t& message)
×
152
{
153
    mavlink_log_entry_t msg;
154
    mavlink_msg_log_entry_decode(&message, &msg);
×
155

156
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
157

158
    _system_impl->refresh_timeout_handler(_entries_timeout_cookie);
×
159

160
    // Bad data handling
161
    if (msg.num_logs == 0 || msg.id >= msg.num_logs) {
×
162
        LogWarn() << "No logs available";
×
163

164
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
165

166
        const auto cb = _entries_user_callback;
×
167
        if (cb) {
×
168
            _system_impl->call_user_callback(
×
169
                [cb]() { cb(LogFiles::Result::NoLogfiles, std::vector<LogFiles::Entry>()); });
170
        }
171
        return;
×
172
    }
×
173

174
    // Initialize vector if this is the first entry
NEW
175
    if (_total_entries != msg.num_logs) {
×
NEW
176
        _total_entries = msg.num_logs;
×
NEW
177
        _log_entries.clear();
×
NEW
178
        _log_entries.resize(_total_entries);
×
179
    }
180

181
    LogFiles::Entry new_entry;
×
182
    new_entry.id = msg.id;
×
183

184
    // Convert milliseconds to ISO 8601 date string in UTC.
185
    char buf[sizeof "2018-08-31T20:50:42Z"];
186
    const time_t time_utc = msg.time_utc;
×
187
    strftime(buf, sizeof buf, "%FT%TZ", gmtime(&time_utc));
×
188

189
    new_entry.date = buf;
×
190
    new_entry.size_bytes = msg.size;
×
191

192
    // Store entry at direct index
NEW
193
    _log_entries[msg.id] = new_entry;
×
194

195
    // Check if all entries are received
196
    bool all_received =
NEW
197
        std::all_of(_log_entries.begin(), _log_entries.end(), [](const auto& entry_opt) {
×
NEW
198
            return entry_opt.has_value();
×
199
        });
200

NEW
201
    if (all_received) {
×
UNCOV
202
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
203

204
        // Build result list from vector (safe since all entries are present)
NEW
205
        std::vector<LogFiles::Entry> entry_list;
×
NEW
206
        entry_list.reserve(_log_entries.size());
×
NEW
207
        std::transform(
×
208
            _log_entries.begin(),
209
            _log_entries.end(),
210
            std::back_inserter(entry_list),
NEW
211
            [](const auto& entry_opt) { return entry_opt.value(); });
×
212

213
        const auto cb = _entries_user_callback;
×
214
        if (cb) {
×
215
            _system_impl->call_user_callback(
×
216
                [cb, entry_list]() { cb(LogFiles::Result::Success, entry_list); });
217
        }
NEW
218
    } else {
×
219
        // Check for missing entries when we might have all entries
220
        // This handles: receiving the last expected entry AND receiving retried entries that might
221
        // complete the set
NEW
222
        if (_total_entries > 0) {
×
NEW
223
            const uint32_t expected_last_entry_id = _total_entries - 1;
×
224
            // Check if this could be the last entry we need (either the expected last one, or a
225
            // retried one)
NEW
226
            if (msg.id == expected_last_entry_id ||
×
NEW
227
                _log_entries[expected_last_entry_id].has_value()) {
×
NEW
228
                check_and_request_missing_entries();
×
229
            }
230
        }
231
    }
232
}
×
233

234
void LogFilesImpl::entries_timeout()
×
235
{
236
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
237

NEW
238
    LogDebug() << "Request entries timeout! Retry count: " << _entries_retry_count;
×
239

NEW
240
    constexpr uint32_t MAX_RETRIES = 5;
×
241

NEW
242
    if (_entries_retry_count < MAX_RETRIES) {
×
243
        // Try to request missing entries
NEW
244
        check_and_request_missing_entries();
×
NEW
245
        _entries_retry_count++;
×
246

247
        // Reset timeout for another attempt (use normal timeout, not * 10.0)
NEW
248
        _entries_timeout_cookie = _system_impl->register_timeout_handler(
×
NEW
249
            [this]() { entries_timeout(); }, _system_impl->timeout_s());
×
250

251
        // Don't call user callback yet - give it another chance
NEW
252
        return;
×
253
    }
254

255
    // Max retries exceeded - give up and call user with timeout error
256
    const auto cb = _entries_user_callback;
×
257
    if (cb) {
×
NEW
258
        _system_impl->call_user_callback(
×
259
            [cb]() { cb(LogFiles::Result::Timeout, std::vector<LogFiles::Entry>()); });
260
    }
261
}
×
262

263
std::pair<LogFiles::Result, LogFiles::ProgressData>
264
LogFilesImpl::download_log_file(LogFiles::Entry entry, const std::string& file_path)
×
265
{
266
    auto prom =
267
        std::make_shared<std::promise<std::pair<LogFiles::Result, LogFiles::ProgressData>>>();
×
268
    auto future_result = prom->get_future();
×
269

270
    download_log_file_async(
×
271
        entry, file_path, [prom](LogFiles::Result result, LogFiles::ProgressData progress) {
×
272
            if (result != LogFiles::Result::Next) {
×
273
                prom->set_value(std::make_pair(result, progress));
×
274
            }
275
        });
×
276

277
    return future_result.get();
×
278
}
×
279

280
void LogFilesImpl::download_log_file_async(
×
281
    LogFiles::Entry entry, const std::string& file_path, LogFiles::DownloadLogFileCallback callback)
282
{
283
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
284

NEW
285
    bool error = entry.id >= _log_entries.size() || !_log_entries[entry.id].has_value() ||
×
NEW
286
                 fs::is_directory(fs::path(file_path)) || fs::exists(file_path);
×
287

288
    if (error) {
×
289
        LogErr() << "error: download_log_file_async failed";
×
290

291
        if (callback) {
×
292
            _system_impl->call_user_callback([callback]() {
×
293
                callback(LogFiles::Result::InvalidArgument, LogFiles::ProgressData());
294
            });
295
        }
296
        return;
×
297
    }
298

NEW
299
    const auto& found_entry = _log_entries[entry.id].value();
×
300

301
    // Check for zero-sized file and abort early
NEW
302
    if (found_entry.size_bytes == 0) {
×
NEW
303
        LogErr() << "Cannot download zero-sized log file";
×
304

NEW
305
        if (callback) {
×
NEW
306
            _system_impl->call_user_callback([callback]() {
×
307
                callback(LogFiles::Result::InvalidArgument, LogFiles::ProgressData());
308
            });
309
        }
NEW
310
        return;
×
311
    }
312

NEW
313
    _download_data = LogData(found_entry, file_path, callback);
×
314

315
    if (!_download_data.file_is_open()) {
×
316
        if (callback) {
×
317
            _system_impl->call_user_callback([callback]() {
×
318
                callback(LogFiles::Result::FileOpenFailed, LogFiles::ProgressData());
319
            });
320
        }
321
        return;
×
322
    }
323

324
    _download_data.timeout_cookie = _system_impl->register_timeout_handler(
×
NEW
325
        [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s());
×
326

327
    // Request the first chunk
328
    request_log_data(_download_data.entry.id, 0, _download_data.current_chunk_size());
×
329
}
×
330

331
void LogFilesImpl::process_log_data(const mavlink_message_t& message)
×
332
{
333
    mavlink_log_data_t msg;
334
    mavlink_msg_log_data_decode(&message, &msg);
×
335

336
    std::lock_guard<std::mutex> lock(_download_data_mutex);
×
337

338
    _system_impl->refresh_timeout_handler(_download_data.timeout_cookie);
×
339

340
    if (msg.count > MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
341
        LogErr() << "Ignoring wrong count" << msg.count;
×
342
        return;
×
343
    }
344

345
    if (msg.id != _download_data.entry.id) {
×
346
        LogErr() << "Ignoring wrong ID: actual/expected: " << msg.id << "/"
×
347
                 << _download_data.entry.id;
×
348
        return;
×
349
    }
350

351
    if (msg.ofs > _download_data.entry.size_bytes) {
×
352
        LogErr() << "Offset greater than file size: offset/size: " << msg.ofs << "/"
×
353
                 << _download_data.entry.size_bytes;
×
354
        return;
×
355
    }
356

357
    if (msg.ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
358
        LogErr() << "Ignoring misaligned offset: " << msg.ofs;
×
359
        return;
×
360
    }
361

362
    // Calculate current chunk
363
    const uint32_t chunk = msg.ofs / CHUNK_SIZE;
×
364

365
    if (chunk != _download_data.current_chunk) {
×
366
        // Quietly ignore packets for out of order chunks
367
        // LogErr() << "Ignored packet for out of order chunk actual/expected: " << chunk << "/"
368
        //          << _download_data.current_chunk;
369
        return;
×
370
    }
371

372
    // Calculate current bin within the chunk
373
    const uint16_t bin = (msg.ofs - chunk * CHUNK_SIZE) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
×
374

375
    if (bin >= _download_data.chunk_bin_table.size()) {
×
376
        LogErr() << "Out of range bin received: bin/size: " << bin << "/"
×
377
                 << _download_data.chunk_bin_table.size();
×
378
        return;
×
379
    }
380

381
    if (_download_data.file.tellp() != msg.ofs) {
×
382
        if (!_download_data.file.seekp(msg.ofs)) {
×
383
            LogErr() << "Error while seeking to log file offset";
×
384
            return;
×
385
        }
386
    }
387

388
    _download_data.file.write((char*)msg.data, msg.count);
×
389

390
    // Mark bin as received (quietly ignore duplicates)
NEW
391
    _download_data.chunk_bin_table[bin] = true;
×
392

393
    // Check if all bins in the chunk have been received
NEW
394
    const uint32_t bins_in_chunk = _download_data.bins_in_chunk();
×
NEW
395
    bool chunk_complete = std::all_of(
×
396
        _download_data.chunk_bin_table.begin(),
NEW
397
        _download_data.chunk_bin_table.begin() + bins_in_chunk,
×
NEW
398
        [](bool received) { return received; });
×
399

400
    if (chunk_complete) {
×
NEW
401
        uint32_t chunk_bytes = _download_data.current_chunk_size();
×
402

UNCOV
403
        auto result = LogFiles::Result::Next;
×
404

405
        _download_data.current_chunk++;
×
NEW
406
        _download_data.total_bytes_written += chunk_bytes;
×
407
        _download_data.chunk_bin_table = std::vector<bool>(_download_data.bins_in_chunk(), false);
×
408

409
        bool log_complete = _download_data.total_bytes_written == _download_data.entry.size_bytes;
×
410

411
        if (log_complete) {
×
412
            result = LogFiles::Result::Success;
×
413
            _download_data.file.close();
×
414
            _system_impl->unregister_timeout_handler(_download_data.timeout_cookie);
×
415

416
        } else {
417
            // Request the next chunk
418
            request_log_data(
×
419
                _download_data.entry.id,
420
                _download_data.current_chunk * CHUNK_SIZE,
×
421
                _download_data.current_chunk_size());
422
        }
423

424
        LogFiles::ProgressData progress_data;
×
425
        progress_data.progress =
×
426
            (float)_download_data.total_bytes_written / (float)_download_data.entry.size_bytes;
×
427

428
        // Update progress
429
        const auto cb = _download_data.user_callback;
×
430
        if (cb) {
×
431
            _system_impl->call_user_callback(
×
432
                [cb, progress_data, result]() { cb(result, progress_data); });
433
        }
NEW
434
    } else {
×
435
        // Check for missing bins when we might have all bins for this chunk
436
        // This handles: receiving the last expected bin AND receiving retried bins that might
437
        // complete the chunk
NEW
438
        if (bins_in_chunk > 0) {
×
NEW
439
            const uint32_t expected_last_bin = bins_in_chunk - 1;
×
440
            // Check if this could be the last bin we need (either the expected last one, or a
441
            // retried one)
NEW
442
            if (bin == expected_last_bin || _download_data.chunk_bin_table[expected_last_bin]) {
×
NEW
443
                check_and_request_missing_bins();
×
444
            }
445
        }
446
    }
447
}
×
448

449
void LogFilesImpl::data_timeout()
×
450
{
451
    std::lock_guard<std::mutex> lock(_download_data_mutex);
×
452

453
    LogErr() << "Timeout!";
×
454
    LogErr() << "Requesting missing chunk:\t" << _download_data.current_chunk << "/"
×
455
             << _download_data.total_chunks();
×
456

457
    // Don't reset chunk data - preserve what we've received
458
    // Instead, request missing ranges based on bin table
NEW
459
    check_and_request_missing_bins();
×
460

461
    _download_data.timeout_cookie = _system_impl->register_timeout_handler(
×
NEW
462
        [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s());
×
NEW
463
}
×
464

NEW
465
void LogFilesImpl::check_and_request_missing_bins()
×
466
{
467
    // Note: This function assumes _download_data_mutex is already locked by caller
468

469
    // Find missing ranges and request the first one
NEW
470
    const uint32_t chunk_start = _download_data.current_chunk * CHUNK_SIZE;
×
NEW
471
    const uint32_t bins_in_chunk = _download_data.bins_in_chunk();
×
472

NEW
473
    uint32_t range_start = 0;
×
NEW
474
    bool in_missing_range = false;
×
NEW
475
    bool requested_something = false;
×
476

NEW
477
    for (uint32_t bin = 0; bin <= bins_in_chunk; ++bin) {
×
NEW
478
        bool is_missing = (bin < bins_in_chunk) ? !_download_data.chunk_bin_table[bin] : false;
×
479

NEW
480
        if (is_missing && !in_missing_range) {
×
481
            // Start of a missing range
NEW
482
            range_start = bin;
×
NEW
483
            in_missing_range = true;
×
NEW
484
        } else if (!is_missing && in_missing_range) {
×
485
            // End of a missing range, request it (but only request the first one)
NEW
486
            if (!requested_something) {
×
NEW
487
                const uint32_t missing_start =
×
NEW
488
                    chunk_start + (range_start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
×
NEW
489
                const uint32_t missing_count =
×
NEW
490
                    (bin - range_start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
×
491

NEW
492
                LogDebug() << "Requesting missing range from offset " << missing_start << " count "
×
NEW
493
                           << missing_count;
×
NEW
494
                request_log_data(_download_data.entry.id, missing_start, missing_count);
×
NEW
495
                requested_something = true;
×
496
            }
NEW
497
            in_missing_range = false;
×
498
        }
499
    }
NEW
500
}
×
501

NEW
502
void LogFilesImpl::check_and_request_missing_entries()
×
503
{
504
    // Note: This function assumes _entries_mutex is already locked by caller
505

506
    // Find missing entry ranges and request them
NEW
507
    std::vector<uint16_t> missing_ids;
×
NEW
508
    for (uint16_t i = 0; i < _log_entries.size(); ++i) {
×
NEW
509
        if (!_log_entries[i].has_value()) {
×
NEW
510
            missing_ids.push_back(i);
×
511
        }
512
    }
513

NEW
514
    if (missing_ids.empty()) {
×
NEW
515
        return;
×
516
    }
517

518
    // Group consecutive missing IDs into ranges for efficient requests
519
    // For now, request the first missing range (similar to bins approach)
NEW
520
    uint16_t range_start = missing_ids[0];
×
NEW
521
    uint16_t range_end = range_start;
×
522

523
    // Find end of first consecutive range
NEW
524
    for (size_t i = 1; i < missing_ids.size(); ++i) {
×
NEW
525
        if (missing_ids[i] == missing_ids[i - 1] + 1) {
×
NEW
526
            range_end = missing_ids[i];
×
527
        } else {
NEW
528
            break;
×
529
        }
530
    }
531

NEW
532
    LogDebug() << "Requesting missing log entries from " << range_start << " to " << range_end;
×
NEW
533
    request_log_list(range_start, range_end);
×
UNCOV
534
}
×
535

536
void LogFilesImpl::request_log_data(unsigned id, unsigned start, unsigned count)
×
537
{
538
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
539
        mavlink_message_t message;
540
        mavlink_msg_log_request_data_pack_chan(
×
541
            mavlink_address.system_id,
×
542
            mavlink_address.component_id,
×
543
            channel,
544
            &message,
545
            _system_impl->get_system_id(),
×
546
            MAV_COMP_ID_AUTOPILOT1,
547
            id,
×
548
            start,
×
549
            count);
×
550
        return message;
×
551
    });
552
}
×
553

554
LogFiles::Result LogFilesImpl::erase_all_log_files()
×
555
{
556
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
557
        mavlink_message_t message;
558
        mavlink_msg_log_erase_pack_chan(
×
559
            mavlink_address.system_id,
×
560
            mavlink_address.component_id,
×
561
            channel,
562
            &message,
563
            _system_impl->get_system_id(),
×
564
            MAV_COMP_ID_AUTOPILOT1);
565
        return message;
×
566
    });
567

568
    // TODO: find a good way to know about the success or failure of the operation
569
    return LogFiles::Result::Success;
×
570
}
571

572
void LogFilesImpl::request_end()
×
573
{
574
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
575
        mavlink_message_t message;
576
        mavlink_msg_log_request_end_pack_chan(
×
577
            mavlink_address.system_id,
×
578
            mavlink_address.component_id,
×
579
            channel,
580
            &message,
581
            _system_impl->get_system_id(),
×
582
            MAV_COMP_ID_AUTOPILOT1);
583
        return message;
×
584
    });
585
}
×
586

587
} // 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