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

mavlink / MAVSDK / 6739182515

02 Nov 2023 11:04PM UTC coverage: 36.952% (+5.7%) from 31.229%
6739182515

push

github

web-flow
Merge pull request #2060 from mavlink/pr-split-ftp

Split Ftp plugin into Ftp and FtpServer

2002 of 2573 new or added lines in 26 files covered. (77.81%)

3 existing lines in 3 files now uncovered.

9920 of 26846 relevant lines covered (36.95%)

112.43 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
#include "unused.h"
5

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

12
namespace mavsdk {
13

14
namespace fs = std::filesystem;
15

UNCOV
16
LogFilesImpl::LogFilesImpl(System& system) : PluginImplBase(system)
×
17
{
18
    _system_impl->register_plugin(this);
×
19
}
×
20

21
LogFilesImpl::LogFilesImpl(std::shared_ptr<System> system) : PluginImplBase(std::move(system))
×
22
{
23
    _system_impl->register_plugin(this);
×
24
}
×
25

26
LogFilesImpl::~LogFilesImpl()
×
27
{
28
    _system_impl->unregister_plugin(this);
×
29
}
×
30

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

38
    _system_impl->register_mavlink_message_handler(
×
39
        MAVLINK_MSG_ID_LOG_DATA,
40
        [this](const mavlink_message_t& message) { process_log_data(message); },
×
41
        this);
42

43
    // Cancel any log file downloads that might still be going on.
44
    request_end();
×
45
}
×
46

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

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

61
void LogFilesImpl::enable() {}
×
62

63
void LogFilesImpl::disable() {}
×
64

65
void LogFilesImpl::request_end()
×
66
{
67
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
68
        mavlink_message_t message;
69
        mavlink_msg_log_request_end_pack_chan(
×
70
            mavlink_address.system_id,
×
71
            mavlink_address.component_id,
×
72
            channel,
73
            &message,
74
            _system_impl->get_system_id(),
×
75
            MAV_COMP_ID_AUTOPILOT1);
76
        return message;
×
77
    });
78
}
×
79

80
std::pair<LogFiles::Result, std::vector<LogFiles::Entry>> LogFilesImpl::get_entries()
×
81
{
82
    auto prom =
×
83
        std::make_shared<std::promise<std::pair<LogFiles::Result, std::vector<LogFiles::Entry>>>>();
×
84
    auto future_result = prom->get_future();
×
85

86
    get_entries_async([prom](LogFiles::Result result, std::vector<LogFiles::Entry> entries) {
×
87
        prom->set_value(std::make_pair<>(result, entries));
×
88
    });
×
89
    return future_result.get();
×
90
}
91

92
void LogFilesImpl::get_entries_async(LogFiles::GetEntriesCallback callback)
×
93
{
94
    {
95
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
96
        _entries.entry_map.clear();
×
97
        _entries.callback = callback;
×
98
        _entries.max_list_id = 0;
×
99
        _entries.retries = 0;
×
100
    }
101

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

106
    request_list_entry(-1);
×
107
}
×
108

109
void LogFilesImpl::request_list_entry(int entry_id)
×
110
{
111
    // all
112
    uint16_t index_min = 0;
×
113
    uint16_t index_max = 0xFFFF;
×
114

115
    if (entry_id >= 0) {
×
116
        index_min = entry_id;
×
117
        index_max = entry_id;
×
118
    }
119

120
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
121
        mavlink_message_t message;
122
        mavlink_msg_log_request_list_pack_chan(
×
123
            mavlink_address.system_id,
×
124
            mavlink_address.component_id,
×
125
            channel,
126
            &message,
127
            _system_impl->get_system_id(),
×
128
            MAV_COMP_ID_AUTOPILOT1,
129
            index_min,
×
130
            index_max);
×
131
        return message;
×
132
    });
133
}
×
134

135
void LogFilesImpl::process_log_entry(const mavlink_message_t& message)
×
136
{
137
    mavlink_log_entry_t log_entry;
×
138
    mavlink_msg_log_entry_decode(&message, &log_entry);
×
139

140
    // Catch case where there are no log files to be found.
141
    if (log_entry.num_logs == 0 && log_entry.id == 0) {
×
142
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
143
        _system_impl->unregister_timeout_handler(_entries.cookie);
×
144
        if (_entries.callback) {
×
145
            const auto tmp_callback = _entries.callback;
×
146
            std::vector<LogFiles::Entry> empty_list{};
×
147
            _system_impl->call_user_callback([tmp_callback, empty_list]() {
×
148
                tmp_callback(LogFiles::Result::NoLogfiles, empty_list);
149
            });
150
        }
151
        return;
×
152
    }
153

154
    LogFiles::Entry new_entry;
×
155
    new_entry.id = log_entry.id;
×
156

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

162
    new_entry.date = buf;
×
163
    new_entry.size_bytes = log_entry.size;
×
164
    {
165
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
166
        _entries.entry_map[new_entry.id] = new_entry;
×
167
        _entries.max_list_id = log_entry.num_logs;
×
168
        _system_impl->refresh_timeout_handler(_entries.cookie);
×
169
    }
170
}
171

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

215
std::pair<LogFiles::Result, LogFiles::ProgressData>
216
LogFilesImpl::download_log_file(LogFiles::Entry entry, const std::string& file_path)
×
217
{
218
    auto prom =
×
219
        std::make_shared<std::promise<std::pair<LogFiles::Result, LogFiles::ProgressData>>>();
×
220
    auto future_result = prom->get_future();
×
221

222
    download_log_file_async(
×
223
        entry, file_path, [prom](LogFiles::Result result, LogFiles::ProgressData progress) {
×
224
            UNUSED(progress);
×
225
            if (result != LogFiles::Result::Next) {
×
226
                prom->set_value(std::make_pair(result, progress));
×
227
            }
228
        });
×
229
    return future_result.get();
×
230
}
231

232
void LogFilesImpl::download_log_file_async(
×
233
    LogFiles::Entry entry, const std::string& file_path, LogFiles::DownloadLogFileCallback callback)
234
{
235
    unsigned bytes_to_get;
236
    {
237
        std::lock_guard<std::mutex> lock(_entries.mutex);
×
238

239
        auto it = _entries.entry_map.find(entry.id);
×
240
        if (it == _entries.entry_map.end()) {
×
241
            LogErr() << "Log entry id " << entry.id << " not found";
×
242
            if (callback) {
×
243
                const auto tmp_callback = callback;
×
244
                _system_impl->call_user_callback([tmp_callback]() {
×
245
                    LogFiles::ProgressData progress;
246
                    progress.progress = 0.0f;
247
                    tmp_callback(LogFiles::Result::InvalidArgument, progress);
248
                });
249
            }
250
            return;
×
251
        }
252

253
        bytes_to_get = _entries.entry_map[entry.id].size_bytes;
×
254
    }
255

256
    {
257
        std::lock_guard<std::mutex> lock(_data.mutex);
×
258

259
        if (is_directory(file_path)) {
×
260
            if (callback) {
×
261
                const auto tmp_callback = callback;
×
262
                _system_impl->call_user_callback([tmp_callback]() {
×
263
                    LogFiles::ProgressData progress;
264
                    progress.progress = NAN;
265
                    LogErr()
266
                        << "Invalid path! The path must point to an unexisting file, and it points to a directory!";
267
                    tmp_callback(LogFiles::Result::InvalidArgument, progress);
268
                });
269
            }
270
            return;
×
271
        }
272

273
        if (file_exists(file_path)) {
×
274
            if (callback) {
×
275
                const auto tmp_callback = callback;
×
276
                _system_impl->call_user_callback([tmp_callback]() {
×
277
                    LogFiles::ProgressData progress;
278
                    progress.progress = NAN;
279
                    LogErr() << "Target log file already exists!";
280
                    tmp_callback(LogFiles::Result::InvalidArgument, progress);
281
                });
282
            }
283
            return;
×
284
        }
285

286
        if (!start_logfile(file_path)) {
×
287
            if (callback) {
×
288
                const auto tmp_callback = callback;
×
289
                _system_impl->call_user_callback([tmp_callback]() {
×
290
                    LogFiles::ProgressData progress;
291
                    progress.progress = NAN;
292
                    tmp_callback(LogFiles::Result::FileOpenFailed, progress);
293
                });
294
            }
295
            return;
×
296
        }
297

298
        _data.id = entry.id;
×
299
        _data.callback = callback;
×
300
        _data.time_started = _time.steady_time();
×
301
        _data.bytes_to_get = bytes_to_get;
×
302
        _data.part_start = 0;
×
303
        const auto part_size = determine_part_end() - _data.part_start;
×
304
        _data.bytes.resize(part_size);
×
305
        _data.chunks_received.resize(
×
306
            part_size / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN +
×
307
            ((part_size % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0));
×
308

309
        _system_impl->register_timeout_handler(
×
310
            [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s(), &_data.cookie);
×
311

312
        request_log_data(_data.id, _data.part_start, _data.bytes.size());
×
313

314
        if (_data.callback) {
×
315
            const auto tmp_callback = _data.callback;
×
316
            _system_impl->call_user_callback([tmp_callback]() {
×
317
                LogFiles::ProgressData progress;
318
                progress.progress = 0.0f;
319
                tmp_callback(LogFiles::Result::Next, progress);
320
            });
321
        }
322
    }
323
}
324

325
LogFiles::Result LogFilesImpl::erase_all_log_files()
×
326
{
327
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
328
        mavlink_message_t message;
329
        mavlink_msg_log_erase_pack_chan(
×
330
            mavlink_address.system_id,
×
331
            mavlink_address.component_id,
×
332
            channel,
333
            &message,
334
            _system_impl->get_system_id(),
×
335
            MAV_COMP_ID_AUTOPILOT1);
336
        return message;
×
337
    });
338

339
    // TODO: find a good way to know about the success or failure of the operation
340
    return LogFiles::Result::Success;
×
341
}
342

343
std::size_t LogFilesImpl::determine_part_end()
×
344
{
345
    // Assumes to have the lock for _data.mutex.
346

347
    return std::min(
348
        _data.part_start + PART_SIZE * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN,
×
349
        std::size_t(_data.bytes_to_get));
×
350
}
351

352
void LogFilesImpl::process_log_data(const mavlink_message_t& message)
×
353
{
354
    mavlink_log_data_t log_data;
×
355
    mavlink_msg_log_data_decode(&message, &log_data);
×
356

357
#if 0
358
    // To test retransmission
359
    static unsigned counter = 0;
360
    if (counter < 10 && (log_data.ofs == 1800 || log_data.ofs == 3600)) {
361
        ++counter;
362
        return;
363
    }
364
#endif
365

366
    std::lock_guard<std::mutex> lock(_data.mutex);
×
367

368
    _system_impl->refresh_timeout_handler(_data.cookie);
×
369

370
    if (log_data.count > MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
371
        LogErr() << "Ignoring wrong count";
×
372
        return;
×
373
    }
374

375
    if (log_data.ofs < _data.part_start ||
×
376
        log_data.ofs + log_data.count > _data.part_start + _data.bytes.size()) {
×
377
        LogErr() << "Ignoring wrong offset";
×
378
        return;
×
379
    }
380

381
    std::memcpy(&_data.bytes[log_data.ofs - _data.part_start], log_data.data, log_data.count);
×
382
    _data.chunks_received[(log_data.ofs - _data.part_start) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN] =
×
383
        true;
×
384

385
    if (log_data.ofs + log_data.count - _data.part_start == _data.bytes.size() ||
×
386
        _data.rerequesting) {
×
387
        // We received last message of this part.
388
        _data.rerequesting = true;
×
389
        check_part();
×
390
    }
391
}
392

393
void LogFilesImpl::report_progress(unsigned transferred, unsigned total)
×
394
{
395
    float progress = float(transferred) / float(total);
×
396

397
    if (_data.callback) {
×
398
        const auto tmp_callback = _data.callback;
×
399
        _system_impl->call_user_callback([tmp_callback, progress]() {
×
400
            LogFiles::ProgressData progress_data;
401
            progress_data.progress = progress;
402

403
            tmp_callback(LogFiles::Result::Next, progress_data);
404
        });
405
    }
406
}
×
407

408
void LogFilesImpl::check_part()
×
409
{
410
    // Assumes to have the lock for _data.mutex.
411

412
    auto first_missing =
×
413
        std::find(_data.chunks_received.begin(), _data.chunks_received.end(), false);
×
414
    if (first_missing != _data.chunks_received.end()) {
×
415
        auto first_missing_index = std::distance(_data.chunks_received.begin(), first_missing);
×
416

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

419
        auto first_not_missing_index =
420
            std::distance(_data.chunks_received.begin(), first_not_missing);
×
421

422
        request_log_data(
×
423
            _data.id,
424
            _data.part_start + first_missing_index * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN,
×
425
            (first_not_missing_index - first_missing_index) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
×
426
    } else {
427
        _data.rerequesting = false;
×
428

429
        write_part_to_disk();
×
430

431
        report_progress(_data.part_start + _data.bytes.size(), _data.bytes_to_get);
×
432

433
        const float kib_s = float(_data.part_start + _data.bytes.size()) /
×
434
                            float(_time.elapsed_since_s(_data.time_started)) / 1024.0f;
×
435

436
        LogDebug() << _data.part_start + _data.bytes.size() << " B of " << _data.bytes_to_get
×
437
                   << " B (" << kib_s << " kiB/s)";
×
438

439
        if (_data.part_start + _data.bytes.size() == _data.bytes_to_get) {
×
440
            _system_impl->unregister_timeout_handler(_data.cookie);
×
441

442
            finish_logfile();
×
443

444
            if (_data.callback) {
×
445
                const auto tmp_callback = _data.callback;
×
446
                _system_impl->call_user_callback([tmp_callback]() {
×
447
                    LogFiles::ProgressData progress_data;
448
                    progress_data.progress = 1.0f;
449
                    tmp_callback(LogFiles::Result::Success, progress_data);
450
                });
451
            }
452

453
            reset_data();
×
454
        } else {
455
            _data.part_start = _data.part_start + _data.bytes.size();
×
456

457
            const auto part_size = determine_part_end() - _data.part_start;
×
458
            _data.bytes.resize(part_size);
×
459
            _data.chunks_received.resize(
×
460
                part_size / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN +
×
461
                ((part_size % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0));
×
462
            std::fill(_data.chunks_received.begin(), _data.chunks_received.end(), false);
×
463

464
            request_log_data(_data.id, _data.part_start, _data.bytes.size());
×
465
        }
466
    }
467
}
×
468

469
void LogFilesImpl::request_log_data(unsigned id, unsigned start, unsigned count)
×
470
{
471
    // LogDebug() << "requesting: " << start << ".." << start+count << " (" << id << ")";
472
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
473
        mavlink_message_t message;
474
        mavlink_msg_log_request_data_pack_chan(
×
475
            mavlink_address.system_id,
×
476
            mavlink_address.component_id,
×
477
            channel,
478
            &message,
479
            _system_impl->get_system_id(),
×
480
            MAV_COMP_ID_AUTOPILOT1,
481
            id,
×
482
            start,
×
483
            count);
×
484
        return message;
×
485
    });
486
}
×
487

488
void LogFilesImpl::data_timeout()
×
489
{
490
    {
491
        std::lock_guard<std::mutex> lock(_data.mutex);
×
492
        _system_impl->register_timeout_handler(
×
493
            [this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s(), &_data.cookie);
×
494
        _data.rerequesting = true;
×
495
        check_part();
×
496
    }
497
}
×
498

499
bool LogFilesImpl::is_directory(const std::string& path) const
×
500
{
501
    fs::path file_path(path);
×
502
    std::error_code ignored;
×
503
    return fs::is_directory(file_path, ignored);
×
504
}
505

506
bool LogFilesImpl::file_exists(const std::string& path) const
×
507
{
508
    fs::path file_path(path);
×
509
    std::error_code ignored;
×
510
    return fs::exists(file_path, ignored);
×
511
}
512

513
bool LogFilesImpl::start_logfile(const std::string& path)
×
514
{
515
    // Assumes to have the lock for _data.mutex.
516
    // Assumes that the path is valid and points to a file (not a directory)
517

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

520
    return ((_data.file.rdstate() & std::ofstream::failbit) == 0);
×
521
}
522

523
void LogFilesImpl::write_part_to_disk()
×
524
{
525
    // Assumes to have the lock for _data.mutex.
526

527
    _data.file.write(reinterpret_cast<char*>(_data.bytes.data()), _data.bytes.size());
×
528
}
×
529

530
void LogFilesImpl::finish_logfile()
×
531
{
532
    // Assumes to have the lock for _data.mutex.
533

534
    _data.file.close();
×
535
}
×
536

537
void LogFilesImpl::reset_data()
×
538
{
539
    // Assumes to have the lock for _data.mutex.
540
    _data.id = 0;
×
541
    _data.bytes_to_get = 0;
×
542
    _data.bytes.clear();
×
543
    _data.chunks_received.clear();
×
544
    _data.part_start = 0;
×
545
    _data.retries = 0;
×
546
    _data.rerequesting = false;
×
547
    _data.last_ofs_rerequested = -1;
×
548
    _data.callback = nullptr;
×
549
}
×
550

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