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

mavlink / MAVSDK / 21449841169

28 Jan 2026 06:04PM UTC coverage: 49.081% (-0.009%) from 49.09%
21449841169

Pull #2756

github

web-flow
Merge 81baf7a08 into 240136289
Pull Request #2756: log_files: support ArduPilot, fixup example

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

22 existing lines in 6 files now uncovered.

18312 of 37310 relevant lines covered (49.08%)

667.79 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_blocking(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

NEW
113
    return future_result.get();
×
UNCOV
114
}
×
115

116
void LogFilesImpl::get_entries_async(LogFiles::GetEntriesCallback callback)
×
117
{
118
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
119
    _log_entries.clear();
×
120
    _entries_user_callback = callback;
×
121
    _total_entries = 0;
×
122
    _entries_retry_count = 0;
×
NEW
123
    _min_entry_id = 0xFFFF; // Reset to detect indexing scheme
×
124

125
    _entries_timeout_cookie = _system_impl->register_timeout_handler(
×
126
        [this]() { entries_timeout(); }, _system_impl->timeout_s() * 10.0);
×
127

128
    request_log_list(0, 0xFFFF);
×
129
}
×
130

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

148
void LogFilesImpl::process_log_entry(const mavlink_message_t& message)
×
149
{
150
    mavlink_log_entry_t msg;
151
    mavlink_msg_log_entry_decode(&message, &msg);
×
152

153
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
154

155
    _system_impl->refresh_timeout_handler(_entries_timeout_cookie);
×
156

157
    // Bad data handling
158
    // PX4 uses 0-based indexing: valid IDs are 0 to num_logs-1
159
    // ArduPilot uses 1-based indexing: valid IDs are 1 to num_logs
160
    // We detect the scheme by tracking the minimum ID seen
NEW
161
    if (msg.num_logs == 0 || msg.id > msg.num_logs) {
×
UNCOV
162
        LogWarn() << "No logs available";
×
163

164
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
165

166
        // Clear callback before invoking to prevent double-invocation
167
        const auto cb = _entries_user_callback;
×
NEW
168
        _entries_user_callback = nullptr;
×
169
        if (cb) {
×
170
            _system_impl->call_user_callback(
×
171
                [cb]() { cb(LogFiles::Result::NoLogfiles, std::vector<LogFiles::Entry>()); });
172
        }
173
        return;
×
174
    }
×
175

176
    // Track minimum ID to determine indexing scheme (0-based vs 1-based)
NEW
177
    if (msg.id < _min_entry_id) {
×
NEW
178
        _min_entry_id = msg.id;
×
179
    }
180

181
    // Initialize vector if this is the first entry
182
    if (_total_entries != msg.num_logs) {
×
183
        _total_entries = msg.num_logs;
×
184
        _log_entries.clear();
×
185
        _log_entries.resize(_total_entries);
×
186
    }
187

188
    LogFiles::Entry new_entry;
×
189
    new_entry.id = msg.id;
×
190

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

196
    new_entry.date = buf;
×
197
    new_entry.size_bytes = msg.size;
×
198

199
    // Store entry using 0-based index (subtract min_entry_id to handle both schemes)
NEW
200
    const uint16_t storage_index = msg.id - _min_entry_id;
×
NEW
201
    if (storage_index >= _log_entries.size()) {
×
NEW
202
        LogWarn() << "Log entry ID out of range: " << msg.id;
×
NEW
203
        return;
×
204
    }
NEW
205
    _log_entries[storage_index] = new_entry;
×
206

207
    // Check if all entries are received
208
    bool all_received =
209
        std::all_of(_log_entries.begin(), _log_entries.end(), [](const auto& entry_opt) {
×
210
            return entry_opt.has_value();
×
211
        });
212

213
    if (all_received) {
×
214
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
215

216
        // Build result list from vector (safe since all entries are present)
217
        std::vector<LogFiles::Entry> entry_list;
×
218
        entry_list.reserve(_log_entries.size());
×
219
        std::transform(
×
220
            _log_entries.begin(),
221
            _log_entries.end(),
222
            std::back_inserter(entry_list),
223
            [](const auto& entry_opt) { return entry_opt.value(); });
×
224

225
        // Clear callback before invoking to prevent double-invocation if another
226
        // LOG_ENTRY message arrives before the async callback runs
227
        const auto cb = _entries_user_callback;
×
NEW
228
        _entries_user_callback = nullptr;
×
229
        if (cb) {
×
230
            _system_impl->call_user_callback(
×
231
                [cb, entry_list]() { cb(LogFiles::Result::Success, entry_list); });
232
        }
233
    } else {
×
234
        // Check for missing entries when we might have all entries
235
        // This handles: receiving the last expected entry AND receiving retried entries that might
236
        // complete the set
237
        if (_total_entries > 0) {
×
238
            // Expected last ID depends on indexing scheme: min_entry_id + num_logs - 1
NEW
239
            const uint32_t expected_last_entry_id = _min_entry_id + _total_entries - 1;
×
NEW
240
            const uint32_t last_storage_index = _total_entries - 1;
×
241
            // Check if this could be the last entry we need (either the expected last one, or a
242
            // retried one)
NEW
243
            if (msg.id == expected_last_entry_id || _log_entries[last_storage_index].has_value()) {
×
244
                check_and_request_missing_entries();
×
245
            }
246
        }
247
    }
248
}
×
249

250
void LogFilesImpl::entries_timeout()
×
251
{
252
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
253

254
    LogDebug() << "Request entries timeout! Retry count: " << _entries_retry_count;
×
255

256
    constexpr uint32_t MAX_RETRIES = 5;
×
257

258
    if (_entries_retry_count < MAX_RETRIES) {
×
259
        // Try to request missing entries
260
        check_and_request_missing_entries();
×
261
        _entries_retry_count++;
×
262

263
        // Reset timeout for another attempt (use normal timeout, not * 10.0)
264
        _entries_timeout_cookie = _system_impl->register_timeout_handler(
×
265
            [this]() { entries_timeout(); }, _system_impl->timeout_s());
×
266

267
        // Don't call user callback yet - give it another chance
268
        return;
×
269
    }
270

271
    // Max retries exceeded - give up and call user with timeout error
272
    // Clear callback before invoking to prevent double-invocation
273
    const auto cb = _entries_user_callback;
×
NEW
274
    _entries_user_callback = nullptr;
×
275
    if (cb) {
×
276
        _system_impl->call_user_callback(
×
277
            [cb]() { cb(LogFiles::Result::Timeout, std::vector<LogFiles::Entry>()); });
278
    }
279
}
×
280

281
std::pair<LogFiles::Result, LogFiles::ProgressData>
282
LogFilesImpl::download_log_file(LogFiles::Entry entry, const std::string& file_path)
×
283
{
284
    auto prom =
285
        std::make_shared<std::promise<std::pair<LogFiles::Result, LogFiles::ProgressData>>>();
×
286
    auto future_result = prom->get_future();
×
287

288
    download_log_file_async(
×
289
        entry, file_path, [prom](LogFiles::Result result, LogFiles::ProgressData progress) {
×
290
            if (result != LogFiles::Result::Next) {
×
291
                prom->set_value(std::make_pair(result, progress));
×
292
            }
293
        });
×
294

295
    return future_result.get();
×
296
}
×
297

298
void LogFilesImpl::download_log_file_async(
×
299
    LogFiles::Entry entry, const std::string& file_path, LogFiles::DownloadLogFileCallback callback)
300
{
301
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
302

303
    // Convert entry.id to storage index using detected min_entry_id
304
    // Handles both 0-based (PX4) and 1-based (ArduPilot) indexing
305
    const bool id_in_range =
NEW
306
        entry.id >= _min_entry_id && (entry.id - _min_entry_id) < _log_entries.size();
×
NEW
307
    const uint16_t storage_index = entry.id - _min_entry_id;
×
308

NEW
309
    bool error = !id_in_range || !_log_entries[storage_index].has_value() ||
×
UNCOV
310
                 fs::is_directory(fs::path(file_path)) || fs::exists(file_path);
×
311

312
    if (error) {
×
313
        LogErr() << "error: download_log_file_async failed";
×
314

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

NEW
323
    const auto& found_entry = _log_entries[storage_index].value();
×
324

325
    // Check for zero-sized file and abort early
326
    if (found_entry.size_bytes == 0) {
×
327
        LogErr() << "Cannot download zero-sized log file";
×
328

329
        if (callback) {
×
330
            _system_impl->call_user_callback([callback]() {
×
331
                callback(LogFiles::Result::InvalidArgument, LogFiles::ProgressData());
332
            });
333
        }
334
        return;
×
335
    }
336

337
    _download_data = LogData(found_entry, file_path, callback);
×
338

339
    if (!_download_data.file_is_open()) {
×
340
        if (callback) {
×
341
            _system_impl->call_user_callback([callback]() {
×
342
                callback(LogFiles::Result::FileOpenFailed, LogFiles::ProgressData());
343
            });
344
        }
345
        return;
×
346
    }
347

348
    _download_data.timeout_cookie = _system_impl->register_timeout_handler(
×
349
        [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s());
×
350

351
    // Request the first chunk
352
    request_log_data(_download_data.entry.id, 0, _download_data.current_chunk_size());
×
353
}
×
354

355
void LogFilesImpl::process_log_data(const mavlink_message_t& message)
×
356
{
357
    mavlink_log_data_t msg;
358
    mavlink_msg_log_data_decode(&message, &msg);
×
359

360
    std::lock_guard<std::mutex> lock(_download_data_mutex);
×
361

362
    _system_impl->refresh_timeout_handler(_download_data.timeout_cookie);
×
363

364
    if (msg.count > MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
365
        LogErr() << "Ignoring wrong count" << msg.count;
×
366
        return;
×
367
    }
368

369
    if (msg.id != _download_data.entry.id) {
×
370
        LogErr() << "Ignoring wrong ID: actual/expected: " << msg.id << "/"
×
371
                 << _download_data.entry.id;
×
372
        return;
×
373
    }
374

375
    if (msg.ofs > _download_data.entry.size_bytes) {
×
376
        LogErr() << "Offset greater than file size: offset/size: " << msg.ofs << "/"
×
377
                 << _download_data.entry.size_bytes;
×
378
        return;
×
379
    }
380

381
    if (msg.ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
382
        LogErr() << "Ignoring misaligned offset: " << msg.ofs;
×
383
        return;
×
384
    }
385

386
    // Calculate current chunk
387
    const uint32_t chunk = msg.ofs / CHUNK_SIZE;
×
388

389
    if (chunk != _download_data.current_chunk) {
×
390
        // Quietly ignore packets for out of order chunks
391
        // LogErr() << "Ignored packet for out of order chunk actual/expected: " << chunk << "/"
392
        //          << _download_data.current_chunk;
393
        return;
×
394
    }
395

396
    // Calculate current bin within the chunk
397
    const uint16_t bin = (msg.ofs - chunk * CHUNK_SIZE) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
×
398

399
    if (bin >= _download_data.chunk_bin_table.size()) {
×
400
        LogErr() << "Out of range bin received: bin/size: " << bin << "/"
×
401
                 << _download_data.chunk_bin_table.size();
×
402
        return;
×
403
    }
404

405
    if (_download_data.file.tellp() != msg.ofs) {
×
406
        if (!_download_data.file.seekp(msg.ofs)) {
×
407
            LogErr() << "Error while seeking to log file offset";
×
408
            return;
×
409
        }
410
    }
411

412
    _download_data.file.write((char*)msg.data, msg.count);
×
413

414
    // Mark bin as received (quietly ignore duplicates)
415
    _download_data.chunk_bin_table[bin] = true;
×
416

417
    // Check if all bins in the chunk have been received
418
    const uint32_t bins_in_chunk = _download_data.bins_in_chunk();
×
419
    bool chunk_complete = std::all_of(
×
420
        _download_data.chunk_bin_table.begin(),
421
        _download_data.chunk_bin_table.begin() + bins_in_chunk,
×
422
        [](bool received) { return received; });
×
423

424
    if (chunk_complete) {
×
425
        uint32_t chunk_bytes = _download_data.current_chunk_size();
×
426

427
        auto result = LogFiles::Result::Next;
×
428

429
        _download_data.current_chunk++;
×
430
        _download_data.total_bytes_written += chunk_bytes;
×
431
        _download_data.chunk_bin_table = std::vector<bool>(_download_data.bins_in_chunk(), false);
×
432

433
        bool log_complete = _download_data.total_bytes_written == _download_data.entry.size_bytes;
×
434

435
        if (log_complete) {
×
436
            result = LogFiles::Result::Success;
×
437
            _download_data.file.close();
×
438
            _system_impl->unregister_timeout_handler(_download_data.timeout_cookie);
×
439

440
        } else {
441
            // Request the next chunk
442
            request_log_data(
×
443
                _download_data.entry.id,
444
                _download_data.current_chunk * CHUNK_SIZE,
×
445
                _download_data.current_chunk_size());
446
        }
447

448
        LogFiles::ProgressData progress_data;
×
449
        progress_data.progress =
×
450
            (float)_download_data.total_bytes_written / (float)_download_data.entry.size_bytes;
×
451

452
        // Update progress
453
        const auto cb = _download_data.user_callback;
×
454
        if (cb) {
×
455
            _system_impl->call_user_callback(
×
456
                [cb, progress_data, result]() { cb(result, progress_data); });
457
        }
458
    } else {
×
459
        // Check for missing bins when we might have all bins for this chunk
460
        // This handles: receiving the last expected bin AND receiving retried bins that might
461
        // complete the chunk
462
        if (bins_in_chunk > 0) {
×
463
            const uint32_t expected_last_bin = bins_in_chunk - 1;
×
464
            // Check if this could be the last bin we need (either the expected last one, or a
465
            // retried one)
466
            if (bin == expected_last_bin || _download_data.chunk_bin_table[expected_last_bin]) {
×
467
                check_and_request_missing_bins();
×
468
            }
469
        }
470
    }
471
}
×
472

473
void LogFilesImpl::data_timeout()
×
474
{
475
    std::lock_guard<std::mutex> lock(_download_data_mutex);
×
476

477
    LogErr() << "Timeout!";
×
478
    LogErr() << "Requesting missing chunk:\t" << _download_data.current_chunk << "/"
×
479
             << _download_data.total_chunks();
×
480

481
    // Don't reset chunk data - preserve what we've received
482
    // Instead, request missing ranges based on bin table
483
    check_and_request_missing_bins();
×
484

485
    _download_data.timeout_cookie = _system_impl->register_timeout_handler(
×
486
        [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s());
×
487
}
×
488

489
void LogFilesImpl::check_and_request_missing_bins()
×
490
{
491
    // Note: This function assumes _download_data_mutex is already locked by caller
492

493
    // Find missing ranges and request the first one
494
    const uint32_t chunk_start = _download_data.current_chunk * CHUNK_SIZE;
×
495
    const uint32_t bins_in_chunk = _download_data.bins_in_chunk();
×
496

497
    uint32_t range_start = 0;
×
498
    bool in_missing_range = false;
×
499
    bool requested_something = false;
×
500

501
    for (uint32_t bin = 0; bin <= bins_in_chunk; ++bin) {
×
502
        bool is_missing = (bin < bins_in_chunk) ? !_download_data.chunk_bin_table[bin] : false;
×
503

504
        if (is_missing && !in_missing_range) {
×
505
            // Start of a missing range
506
            range_start = bin;
×
507
            in_missing_range = true;
×
508
        } else if (!is_missing && in_missing_range) {
×
509
            // End of a missing range, request it (but only request the first one)
510
            if (!requested_something) {
×
511
                const uint32_t missing_start =
×
512
                    chunk_start + (range_start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
×
513
                const uint32_t missing_count =
×
514
                    (bin - range_start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
×
515

516
                LogDebug() << "Requesting missing range from offset " << missing_start << " count "
×
517
                           << missing_count;
×
518
                request_log_data(_download_data.entry.id, missing_start, missing_count);
×
519
                requested_something = true;
×
520
            }
521
            in_missing_range = false;
×
522
        }
523
    }
524
}
×
525

526
void LogFilesImpl::check_and_request_missing_entries()
×
527
{
528
    // Note: This function assumes _entries_mutex is already locked by caller
529

530
    // Find missing entry ranges and request them
531
    std::vector<uint16_t> missing_ids;
×
532
    for (uint16_t i = 0; i < _log_entries.size(); ++i) {
×
533
        if (!_log_entries[i].has_value()) {
×
534
            // Convert storage index back to MAVLink ID using min_entry_id
535
            // Works for both 0-based (PX4) and 1-based (ArduPilot) indexing
NEW
536
            missing_ids.push_back(i + _min_entry_id);
×
537
        }
538
    }
539

540
    if (missing_ids.empty()) {
×
541
        return;
×
542
    }
543

544
    // Group consecutive missing IDs into ranges for efficient requests
545
    // For now, request the first missing range (similar to bins approach)
546
    uint16_t range_start = missing_ids[0];
×
547
    uint16_t range_end = range_start;
×
548

549
    // Find end of first consecutive range
550
    for (size_t i = 1; i < missing_ids.size(); ++i) {
×
551
        if (missing_ids[i] == missing_ids[i - 1] + 1) {
×
552
            range_end = missing_ids[i];
×
553
        } else {
554
            break;
×
555
        }
556
    }
557

558
    LogDebug() << "Requesting missing log entries from " << range_start << " to " << range_end;
×
559
    request_log_list(range_start, range_end);
×
560
}
×
561

562
void LogFilesImpl::request_log_data(unsigned id, unsigned start, unsigned count)
×
563
{
564
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
565
        mavlink_message_t message;
566
        mavlink_msg_log_request_data_pack_chan(
×
567
            mavlink_address.system_id,
×
568
            mavlink_address.component_id,
×
569
            channel,
570
            &message,
571
            _system_impl->get_system_id(),
×
572
            MAV_COMP_ID_AUTOPILOT1,
573
            id,
×
574
            start,
×
575
            count);
×
576
        return message;
×
577
    });
578
}
×
579

580
LogFiles::Result LogFilesImpl::erase_all_log_files()
×
581
{
582
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
583
        mavlink_message_t message;
584
        mavlink_msg_log_erase_pack_chan(
×
585
            mavlink_address.system_id,
×
586
            mavlink_address.component_id,
×
587
            channel,
588
            &message,
589
            _system_impl->get_system_id(),
×
590
            MAV_COMP_ID_AUTOPILOT1);
591
        return message;
×
592
    });
593

594
    // TODO: find a good way to know about the success or failure of the operation
595
    return LogFiles::Result::Success;
×
596
}
597

598
void LogFilesImpl::request_end()
×
599
{
600
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
601
        mavlink_message_t message;
602
        mavlink_msg_log_request_end_pack_chan(
×
603
            mavlink_address.system_id,
×
604
            mavlink_address.component_id,
×
605
            channel,
606
            &message,
607
            _system_impl->get_system_id(),
×
608
            MAV_COMP_ID_AUTOPILOT1);
609
        return message;
×
610
    });
611
}
×
612

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