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

mavlink / MAVSDK / 5383331079

pending completion
5383331079

push

github

web-flow
Merge pull request #2092 from mavlink/pr-fix-logfile-timeouts

log_files: remove hard-coded timeout values

4 of 4 new or added lines in 1 file covered. (100.0%)

7691 of 24911 relevant lines covered (30.87%)

21.19 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 "mavsdk_impl.h"
3
#include "filesystem_include.h"
4
#include "unused.h"
5

6
#include <algorithm>
7
#include <cmath>
8
#include <ctime>
9
#include <cstring>
10

11
namespace mavsdk {
12

13
LogFilesImpl::LogFilesImpl(System& system) : PluginImplBase(system)
×
14
{
15
    _system_impl->register_plugin(this);
×
16
}
×
17

18
LogFilesImpl::LogFilesImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
×
19
{
20
    _system_impl->register_plugin(this);
×
21
}
×
22

23
LogFilesImpl::~LogFilesImpl()
×
24
{
25
    _system_impl->unregister_plugin(this);
×
26
}
×
27

28
void LogFilesImpl::init()
×
29
{
30
    _system_impl->register_mavlink_message_handler(
×
31
        MAVLINK_MSG_ID_LOG_ENTRY,
32
        [this](const mavlink_message_t& message) { process_log_entry(message); },
×
33
        this);
34

35
    _system_impl->register_mavlink_message_handler(
×
36
        MAVLINK_MSG_ID_LOG_DATA,
37
        [this](const mavlink_message_t& message) { process_log_data(message); },
×
38
        this);
39

40
    // Cancel any log file downloads that might still be going on.
41
    request_end();
×
42
}
×
43

44
void LogFilesImpl::deinit()
×
45
{
46
    {
47
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
48
        _system_impl->unregister_timeout_handler(_entries.cookie);
×
49
    }
50

51
    {
52
        std::lock_guard<std::mutex> lock(_data.mutex);
×
53
        _system_impl->unregister_timeout_handler(_data.cookie);
×
54
    }
55
    _system_impl->unregister_all_mavlink_message_handlers(this);
×
56
}
×
57

58
void LogFilesImpl::enable() {}
×
59

60
void LogFilesImpl::disable() {}
×
61

62
void LogFilesImpl::request_end()
×
63
{
64
    mavlink_message_t msg;
×
65
    mavlink_msg_log_request_end_pack(
×
66
        _system_impl->get_own_system_id(),
×
67
        _system_impl->get_own_component_id(),
×
68
        &msg,
69
        _system_impl->get_system_id(),
×
70
        MAV_COMP_ID_AUTOPILOT1);
71
    _system_impl->send_message(msg);
×
72
}
×
73

74
std::pair<LogFiles::Result, std::vector<LogFiles::Entry>> LogFilesImpl::get_entries()
×
75
{
76
    auto prom =
×
77
        std::make_shared<std::promise<std::pair<LogFiles::Result, std::vector<LogFiles::Entry>>>>();
×
78
    auto future_result = prom->get_future();
×
79

80
    get_entries_async([prom](LogFiles::Result result, std::vector<LogFiles::Entry> entries) {
×
81
        prom->set_value(std::make_pair<>(result, entries));
×
82
    });
×
83
    return future_result.get();
×
84
}
85

86
void LogFilesImpl::get_entries_async(LogFiles::GetEntriesCallback callback)
×
87
{
88
    {
89
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
90
        _entries.entry_map.clear();
×
91
        _entries.callback = callback;
×
92
        _entries.max_list_id = 0;
×
93
        _entries.retries = 0;
×
94
    }
95

96
    // This first step can take a moment, on PX4 with 100+ logs I see about 2-3s.
97
    _system_impl->register_timeout_handler(
×
98
        [this]() { list_timeout(); }, _system_impl->timeout_s() * 10.0, &_entries.cookie);
×
99

100
    request_list_entry(-1);
×
101
}
×
102

103
void LogFilesImpl::request_list_entry(int entry_id)
×
104
{
105
    // all
106
    uint16_t index_min = 0;
×
107
    uint16_t index_max = 0xFFFF;
×
108

109
    if (entry_id >= 0) {
×
110
        index_min = entry_id;
×
111
        index_max = entry_id;
×
112
    }
113

114
    mavlink_message_t msg;
×
115
    mavlink_msg_log_request_list_pack(
×
116
        _system_impl->get_own_system_id(),
×
117
        _system_impl->get_own_component_id(),
×
118
        &msg,
119
        _system_impl->get_system_id(),
×
120
        MAV_COMP_ID_AUTOPILOT1,
121
        index_min,
122
        index_max);
123

124
    _system_impl->send_message(msg);
×
125
}
×
126

127
void LogFilesImpl::process_log_entry(const mavlink_message_t& message)
×
128
{
129
    mavlink_log_entry_t log_entry;
×
130
    mavlink_msg_log_entry_decode(&message, &log_entry);
×
131

132
    // Catch case where there are no log files to be found.
133
    if (log_entry.num_logs == 0 && log_entry.id == 0) {
×
134
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
135
        _system_impl->unregister_timeout_handler(_entries.cookie);
×
136
        if (_entries.callback) {
×
137
            const auto tmp_callback = _entries.callback;
×
138
            std::vector<LogFiles::Entry> empty_list{};
×
139
            _system_impl->call_user_callback([tmp_callback, empty_list]() {
×
140
                tmp_callback(LogFiles::Result::NoLogfiles, empty_list);
141
            });
142
        }
143
        return;
×
144
    }
145

146
    LogFiles::Entry new_entry;
×
147
    new_entry.id = log_entry.id;
×
148

149
    // Convert milliseconds to ISO 8601 date string in UTC.
150
    char buf[sizeof "2018-08-31T20:50:42Z"];
×
151
    const time_t time_utc = log_entry.time_utc;
×
152
    strftime(buf, sizeof buf, "%FT%TZ", gmtime(&time_utc));
×
153

154
    new_entry.date = buf;
×
155
    new_entry.size_bytes = log_entry.size;
×
156
    {
157
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
158
        _entries.entry_map[new_entry.id] = new_entry;
×
159
        _entries.max_list_id = log_entry.num_logs;
×
160
        _system_impl->refresh_timeout_handler(_entries.cookie);
×
161
    }
162
}
163

164
void LogFilesImpl::list_timeout()
×
165
{
166
    std::lock_guard<std::mutex> lock(_entries.mutex);
×
167
    if (_entries.entry_map.size() == 0) {
×
168
        LogWarn() << "No entries received";
×
169
    } else if (_entries.entry_map.size() == _entries.max_list_id) {
×
170
        LogDebug() << "Received all entries";
×
171
        // Copy map entries into list to return;
172
        std::vector<LogFiles::Entry> entry_list{};
×
173
        for (unsigned i = 0; i < _entries.max_list_id; ++i) {
×
174
            entry_list.push_back(_entries.entry_map[i]);
×
175
        }
176
        if (_entries.callback) {
×
177
            const auto tmp_callback = _entries.callback;
×
178
            _system_impl->call_user_callback([tmp_callback, entry_list]() {
×
179
                tmp_callback(LogFiles::Result::Success, entry_list);
180
            });
181
        }
182
    } else {
183
        if (_entries.retries > 3) {
×
184
            LogWarn() << "Too many log entry retries, giving up.";
×
185
            if (_entries.callback) {
×
186
                const auto tmp_callback = _entries.callback;
×
187
                _system_impl->call_user_callback([tmp_callback]() {
×
188
                    std::vector<LogFiles::Entry> empty_vector{};
189
                    tmp_callback(LogFiles::Result::Timeout, empty_vector);
190
                });
191
            }
192
        } else {
193
            for (unsigned i = 0; i < _entries.max_list_id; ++i) {
×
194
                auto it = _entries.entry_map.find(i);
×
195
                if (it == _entries.entry_map.end()) {
×
196
                    LogDebug() << "Requesting log entry " << i << " again";
×
197
                    request_list_entry(int(i));
×
198
                }
199
            }
200
            _system_impl->register_timeout_handler(
×
201
                [this]() { list_timeout(); }, _system_impl->timeout_s() * 10.0, &_entries.cookie);
×
202
            _entries.retries++;
×
203
        }
204
    }
205
}
×
206

207
std::pair<LogFiles::Result, LogFiles::ProgressData>
208
LogFilesImpl::download_log_file(LogFiles::Entry entry, const std::string& file_path)
×
209
{
210
    auto prom =
×
211
        std::make_shared<std::promise<std::pair<LogFiles::Result, LogFiles::ProgressData>>>();
×
212
    auto future_result = prom->get_future();
×
213

214
    download_log_file_async(
×
215
        entry, file_path, [prom](LogFiles::Result result, LogFiles::ProgressData progress) {
×
216
            UNUSED(progress);
×
217
            if (result != LogFiles::Result::Next) {
×
218
                prom->set_value(std::make_pair(result, progress));
×
219
            }
220
        });
×
221
    return future_result.get();
×
222
}
223

224
void LogFilesImpl::download_log_file_async(
×
225
    LogFiles::Entry entry, const std::string& file_path, LogFiles::DownloadLogFileCallback callback)
226
{
227
    unsigned bytes_to_get;
228
    {
229
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
230

231
        auto it = _entries.entry_map.find(entry.id);
×
232
        if (it == _entries.entry_map.end()) {
×
233
            LogErr() << "Log entry id " << entry.id << " not found";
×
234
            if (callback) {
×
235
                const auto tmp_callback = callback;
×
236
                _system_impl->call_user_callback([tmp_callback]() {
×
237
                    LogFiles::ProgressData progress;
238
                    progress.progress = 0.0f;
239
                    tmp_callback(LogFiles::Result::InvalidArgument, progress);
240
                });
241
            }
242
            return;
×
243
        }
244

245
        bytes_to_get = _entries.entry_map[entry.id].size_bytes;
×
246
    }
247

248
    {
249
        std::lock_guard<std::mutex> lock(_data.mutex);
×
250

251
        if (is_directory(file_path)) {
×
252
            if (callback) {
×
253
                const auto tmp_callback = callback;
×
254
                _system_impl->call_user_callback([tmp_callback]() {
×
255
                    LogFiles::ProgressData progress;
256
                    progress.progress = NAN;
257
                    LogErr()
258
                        << "Invalid path! The path must point to an unexisting file, and it points to a directory!";
259
                    tmp_callback(LogFiles::Result::InvalidArgument, progress);
260
                });
261
            }
262
            return;
×
263
        }
264

265
        if (file_exists(file_path)) {
×
266
            if (callback) {
×
267
                const auto tmp_callback = callback;
×
268
                _system_impl->call_user_callback([tmp_callback]() {
×
269
                    LogFiles::ProgressData progress;
270
                    progress.progress = NAN;
271
                    LogErr() << "Target log file already exists!";
272
                    tmp_callback(LogFiles::Result::InvalidArgument, progress);
273
                });
274
            }
275
            return;
×
276
        }
277

278
        if (!start_logfile(file_path)) {
×
279
            if (callback) {
×
280
                const auto tmp_callback = callback;
×
281
                _system_impl->call_user_callback([tmp_callback]() {
×
282
                    LogFiles::ProgressData progress;
283
                    progress.progress = NAN;
284
                    tmp_callback(LogFiles::Result::FileOpenFailed, progress);
285
                });
286
            }
287
            return;
×
288
        }
289

290
        _data.id = entry.id;
×
291
        _data.callback = callback;
×
292
        _data.time_started = _time.steady_time();
×
293
        _data.bytes_to_get = bytes_to_get;
×
294
        _data.part_start = 0;
×
295
        const auto part_size = determine_part_end() - _data.part_start;
×
296
        _data.bytes.resize(part_size);
×
297
        _data.chunks_received.resize(
×
298
            part_size / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN +
×
299
            ((part_size % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0));
×
300

301
        _system_impl->register_timeout_handler(
×
302
            [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s(), &_data.cookie);
×
303

304
        request_log_data(_data.id, _data.part_start, _data.bytes.size());
×
305

306
        if (_data.callback) {
×
307
            const auto tmp_callback = _data.callback;
×
308
            _system_impl->call_user_callback([tmp_callback]() {
×
309
                LogFiles::ProgressData progress;
310
                progress.progress = 0.0f;
311
                tmp_callback(LogFiles::Result::Next, progress);
312
            });
313
        }
314
    }
315
}
316

317
LogFiles::Result LogFilesImpl::erase_all_log_files()
×
318
{
319
    mavlink_message_t msg;
×
320
    mavlink_msg_log_erase_pack(
×
321
        _system_impl->get_own_system_id(),
×
322
        _system_impl->get_own_component_id(),
×
323
        &msg,
324
        _system_impl->get_system_id(),
×
325
        MAV_COMP_ID_AUTOPILOT1);
326
    _system_impl->send_message(msg);
×
327

328
    // TODO: find a good way to know about the success or failure of the operation
329
    return LogFiles::Result::Success;
×
330
}
331

332
std::size_t LogFilesImpl::determine_part_end()
×
333
{
334
    // Assumes to have the lock for _data.mutex.
335

336
    return std::min(
337
        _data.part_start + PART_SIZE * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN,
×
338
        std::size_t(_data.bytes_to_get));
×
339
}
340

341
void LogFilesImpl::process_log_data(const mavlink_message_t& message)
×
342
{
343
    mavlink_log_data_t log_data;
×
344
    mavlink_msg_log_data_decode(&message, &log_data);
×
345

346
#if 0
347
    // To test retransmission
348
    static unsigned counter = 0;
349
    if (counter < 10 && (log_data.ofs == 1800 || log_data.ofs == 3600)) {
350
        ++counter;
351
        return;
352
    }
353
#endif
354

355
    std::lock_guard<std::mutex> lock(_data.mutex);
×
356

357
    _system_impl->refresh_timeout_handler(_data.cookie);
×
358

359
    if (log_data.count > MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
360
        LogErr() << "Ignoring wrong count";
×
361
        return;
×
362
    }
363

364
    if (log_data.ofs < _data.part_start ||
×
365
        log_data.ofs + log_data.count > _data.part_start + _data.bytes.size()) {
×
366
        LogErr() << "Ignoring wrong offset";
×
367
        return;
×
368
    }
369

370
    std::memcpy(&_data.bytes[log_data.ofs - _data.part_start], log_data.data, log_data.count);
×
371
    _data.chunks_received[(log_data.ofs - _data.part_start) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN] =
×
372
        true;
×
373

374
    if (log_data.ofs + log_data.count - _data.part_start == _data.bytes.size() ||
×
375
        _data.rerequesting) {
×
376
        // We received last message of this part.
377
        _data.rerequesting = true;
×
378
        check_part();
×
379
    }
380
}
381

382
void LogFilesImpl::report_progress(unsigned transferred, unsigned total)
×
383
{
384
    float progress = float(transferred) / float(total);
×
385

386
    if (_data.callback) {
×
387
        const auto tmp_callback = _data.callback;
×
388
        _system_impl->call_user_callback([tmp_callback, progress]() {
×
389
            LogFiles::ProgressData progress_data;
390
            progress_data.progress = progress;
391

392
            tmp_callback(LogFiles::Result::Next, progress_data);
393
        });
394
    }
395
}
×
396

397
void LogFilesImpl::check_part()
×
398
{
399
    // Assumes to have the lock for _data.mutex.
400

401
    auto first_missing =
×
402
        std::find(_data.chunks_received.begin(), _data.chunks_received.end(), false);
×
403
    if (first_missing != _data.chunks_received.end()) {
×
404
        auto first_missing_index = std::distance(_data.chunks_received.begin(), first_missing);
×
405

406
        auto first_not_missing = std::find(first_missing, _data.chunks_received.end(), true);
×
407

408
        auto first_not_missing_index =
409
            std::distance(_data.chunks_received.begin(), first_not_missing);
×
410

411
        request_log_data(
×
412
            _data.id,
413
            _data.part_start + first_missing_index * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN,
×
414
            (first_not_missing_index - first_missing_index) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
×
415
    } else {
416
        _data.rerequesting = false;
×
417

418
        write_part_to_disk();
×
419

420
        report_progress(_data.part_start + _data.bytes.size(), _data.bytes_to_get);
×
421

422
        const float kib_s = float(_data.part_start + _data.bytes.size()) /
×
423
                            float(_time.elapsed_since_s(_data.time_started)) / 1024.0f;
×
424

425
        LogDebug() << _data.part_start + _data.bytes.size() << " B of " << _data.bytes_to_get
×
426
                   << " B (" << kib_s << " kiB/s)";
×
427

428
        if (_data.part_start + _data.bytes.size() == _data.bytes_to_get) {
×
429
            _system_impl->unregister_timeout_handler(_data.cookie);
×
430

431
            finish_logfile();
×
432

433
            if (_data.callback) {
×
434
                const auto tmp_callback = _data.callback;
×
435
                _system_impl->call_user_callback([tmp_callback]() {
×
436
                    LogFiles::ProgressData progress_data;
437
                    progress_data.progress = 1.0f;
438
                    tmp_callback(LogFiles::Result::Success, progress_data);
439
                });
440
            }
441

442
            reset_data();
×
443
        } else {
444
            _data.part_start = _data.part_start + _data.bytes.size();
×
445

446
            const auto part_size = determine_part_end() - _data.part_start;
×
447
            _data.bytes.resize(part_size);
×
448
            _data.chunks_received.resize(
×
449
                part_size / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN +
×
450
                ((part_size % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0));
×
451
            std::fill(_data.chunks_received.begin(), _data.chunks_received.end(), false);
×
452

453
            request_log_data(_data.id, _data.part_start, _data.bytes.size());
×
454
        }
455
    }
456
}
×
457

458
void LogFilesImpl::request_log_data(unsigned id, unsigned start, unsigned count)
×
459
{
460
    // LogDebug() << "requesting: " << start << ".." << start+count << " (" << id << ")";
461
    mavlink_message_t msg;
×
462
    mavlink_msg_log_request_data_pack(
×
463
        _system_impl->get_own_system_id(),
×
464
        _system_impl->get_own_component_id(),
×
465
        &msg,
466
        _system_impl->get_system_id(),
×
467
        MAV_COMP_ID_AUTOPILOT1,
468
        id,
469
        start,
470
        count);
471
    _system_impl->send_message(msg);
×
472
}
×
473

474
void LogFilesImpl::data_timeout()
×
475
{
476
    {
477
        std::lock_guard<std::mutex> lock(_data.mutex);
×
478
        _system_impl->register_timeout_handler(
×
479
            [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s(), &_data.cookie);
×
480
        _data.rerequesting = true;
×
481
        check_part();
×
482
    }
483
}
×
484

485
bool LogFilesImpl::is_directory(const std::string& path) const
×
486
{
487
    fs::path file_path(path);
×
488
    std::error_code ignored;
×
489
    return fs::is_directory(file_path, ignored);
×
490
}
491

492
bool LogFilesImpl::file_exists(const std::string& path) const
×
493
{
494
    fs::path file_path(path);
×
495
    std::error_code ignored;
×
496
    return fs::exists(file_path, ignored);
×
497
}
498

499
bool LogFilesImpl::start_logfile(const std::string& path)
×
500
{
501
    // Assumes to have the lock for _data.mutex.
502
    // Assumes that the path is valid and points to a file (not a directory)
503

504
    _data.file.open(path, std::ios::out | std::ios::binary);
×
505

506
    return ((_data.file.rdstate() & std::ofstream::failbit) == 0);
×
507
}
508

509
void LogFilesImpl::write_part_to_disk()
×
510
{
511
    // Assumes to have the lock for _data.mutex.
512

513
    _data.file.write(reinterpret_cast<char*>(_data.bytes.data()), _data.bytes.size());
×
514
}
×
515

516
void LogFilesImpl::finish_logfile()
×
517
{
518
    // Assumes to have the lock for _data.mutex.
519

520
    _data.file.close();
×
521
}
×
522

523
void LogFilesImpl::reset_data()
×
524
{
525
    // Assumes to have the lock for _data.mutex.
526
    _data.id = 0;
×
527
    _data.bytes_to_get = 0;
×
528
    _data.bytes.clear();
×
529
    _data.chunks_received.clear();
×
530
    _data.part_start = 0;
×
531
    _data.retries = 0;
×
532
    _data.rerequesting = false;
×
533
    _data.last_ofs_rerequested = -1;
×
534
    _data.callback = nullptr;
×
535
}
×
536

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