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

mavlink / MAVSDK / 8114402865

01 Mar 2024 04:44PM UTC coverage: 36.362% (+0.05%) from 36.316%
8114402865

push

github

web-flow
Merge pull request #2234 from dakejahl/dev/log_files_redesign

[log_files] Major fixes for log download

0 of 163 new or added lines in 2 files covered. (0.0%)

15 existing lines in 3 files now uncovered.

10078 of 27716 relevant lines covered (36.36%)

129.39 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

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

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

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

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

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

NEW
55
    return chunk_size;
×
56
}
57

UNCOV
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
    {
NEW
92
        std::lock_guard<std::mutex> lock(_entries_mutex);
×
NEW
93
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
94
    }
95

96
    {
NEW
97
        std::lock_guard<std::mutex> lock(_download_data_mutex);
×
NEW
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

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

116
void LogFilesImpl::get_entries_async(LogFiles::GetEntriesCallback callback)
×
117
{
NEW
118
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
NEW
119
    _log_entries.clear();
×
NEW
120
    _entries_user_callback = callback;
×
NEW
121
    _total_entries = 0;
×
122

UNCOV
123
    _system_impl->register_timeout_handler(
×
NEW
124
        [this]() { entries_timeout(); },
×
NEW
125
        _system_impl->timeout_s() * 10.0,
×
126
        &_entries_timeout_cookie);
127

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

NEW
131
void LogFilesImpl::request_log_list(uint16_t index_min, uint16_t index_max)
×
132
{
UNCOV
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
{
NEW
150
    mavlink_log_entry_t msg;
×
NEW
151
    mavlink_msg_log_entry_decode(&message, &msg);
×
152

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

NEW
155
    _system_impl->refresh_timeout_handler(_entries_timeout_cookie);
×
156

157
    // Bad data handling
NEW
158
    if (msg.num_logs == 0 || msg.id >= msg.num_logs) {
×
NEW
159
        LogWarn() << "No logs available";
×
160

NEW
161
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
162

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

171
    LogFiles::Entry new_entry;
×
NEW
172
    new_entry.id = msg.id;
×
173

174
    // Convert milliseconds to ISO 8601 date string in UTC.
175
    char buf[sizeof "2018-08-31T20:50:42Z"];
×
NEW
176
    const time_t time_utc = msg.time_utc;
×
177
    strftime(buf, sizeof buf, "%FT%TZ", gmtime(&time_utc));
×
178

179
    new_entry.date = buf;
×
NEW
180
    new_entry.size_bytes = msg.size;
×
181

NEW
182
    _log_entries[new_entry.id] = new_entry;
×
NEW
183
    _total_entries = msg.num_logs;
×
184

185
    // Check if all entries are received
NEW
186
    if (_log_entries.size() == _total_entries) {
×
NEW
187
        _system_impl->unregister_timeout_handler(_entries_timeout_cookie);
×
188

189
        // Copy map entries into list to return
190
        std::vector<LogFiles::Entry> entry_list{};
×
NEW
191
        for (unsigned i = 0; i < _log_entries.size(); i++) {
×
NEW
192
            entry_list.push_back(_log_entries[i]);
×
193
        }
194

NEW
195
        const auto cb = _entries_user_callback;
×
NEW
196
        if (cb) {
×
NEW
197
            _system_impl->call_user_callback(
×
198
                [cb, entry_list]() { cb(LogFiles::Result::Success, entry_list); });
199
        }
200
    }
201
}
202

NEW
203
void LogFilesImpl::entries_timeout()
×
204
{
NEW
205
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
206

NEW
207
    const auto cb = _entries_user_callback;
×
NEW
208
    if (cb) {
×
NEW
209
        _system_impl->call_user_callback([cb]() {
×
210
            LogDebug() << "Request entries timeout!";
211
            cb(LogFiles::Result::Timeout, std::vector<LogFiles::Entry>());
212
        });
213
    }
NEW
214
}
×
215

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

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

UNCOV
230
    return future_result.get();
×
231
}
232

233
void LogFilesImpl::download_log_file_async(
×
234
    LogFiles::Entry entry, const std::string& file_path, LogFiles::DownloadLogFileCallback callback)
235
{
NEW
236
    std::lock_guard<std::mutex> lock(_entries_mutex);
×
237

NEW
238
    auto entry_it = _log_entries.find(entry.id);
×
NEW
239
    bool error = entry_it == _log_entries.end() || fs::is_directory(fs::path(file_path)) ||
×
NEW
240
                 fs::exists(file_path);
×
241

NEW
242
    if (error) {
×
NEW
243
        LogErr() << "error: download_log_file_async failed";
×
244

NEW
245
        if (callback) {
×
NEW
246
            _system_impl->call_user_callback([callback]() {
×
247
                callback(LogFiles::Result::InvalidArgument, LogFiles::ProgressData());
248
            });
249
        }
NEW
250
        return;
×
251
    }
252

NEW
253
    _download_data = LogData(entry_it->second, file_path, callback);
×
254

NEW
255
    if (!_download_data.file_is_open()) {
×
NEW
256
        if (callback) {
×
NEW
257
            _system_impl->call_user_callback([callback]() {
×
258
                callback(LogFiles::Result::FileOpenFailed, LogFiles::ProgressData());
259
            });
260
        }
NEW
261
        return;
×
262
    }
263

NEW
264
    _system_impl->register_timeout_handler(
×
NEW
265
        [this]() { LogFilesImpl::data_timeout(); },
×
NEW
266
        _system_impl->timeout_s() * 1.0,
×
267
        &_download_data.timeout_cookie);
268

269
    // Request the first chunk
NEW
270
    request_log_data(_download_data.entry.id, 0, _download_data.current_chunk_size());
×
271
}
272

NEW
273
void LogFilesImpl::process_log_data(const mavlink_message_t& message)
×
274
{
NEW
275
    mavlink_log_data_t msg;
×
NEW
276
    mavlink_msg_log_data_decode(&message, &msg);
×
277

NEW
278
    std::lock_guard<std::mutex> lock(_download_data_mutex);
×
279

NEW
280
    _system_impl->refresh_timeout_handler(_download_data.timeout_cookie);
×
281

NEW
282
    if (msg.count > MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
NEW
283
        LogErr() << "Ignoring wrong count" << msg.count;
×
UNCOV
284
        return;
×
285
    }
286

NEW
287
    if (msg.id != _download_data.entry.id) {
×
NEW
288
        LogErr() << "Ignoring wrong ID: actual/expected: " << msg.id << "/"
×
NEW
289
                 << _download_data.entry.id;
×
NEW
290
        return;
×
291
    }
292

NEW
293
    if (msg.ofs > _download_data.entry.size_bytes) {
×
NEW
294
        LogErr() << "Offset greater than file size: offset/size: " << msg.ofs << "/"
×
NEW
295
                 << _download_data.entry.size_bytes;
×
UNCOV
296
        return;
×
297
    }
298

NEW
299
    if (msg.ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) {
×
NEW
300
        LogErr() << "Ignoring misaligned offset: " << msg.ofs;
×
UNCOV
301
        return;
×
302
    }
303

304
    // Calculate current chunk
NEW
305
    const uint32_t chunk = msg.ofs / CHUNK_SIZE;
×
306

NEW
307
    if (chunk != _download_data.current_chunk) {
×
308
        // Quietly ignore packets for out of order chunks
309
        // LogErr() << "Ignored packet for out of order chunk actual/expected: " << chunk << "/"
310
        //          << _download_data.current_chunk;
NEW
311
        return;
×
312
    }
313

314
    // Calculate current bin within the chunk
NEW
315
    const uint16_t bin = (msg.ofs - chunk * CHUNK_SIZE) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
×
316

NEW
317
    if (bin >= _download_data.chunk_bin_table.size()) {
×
NEW
318
        LogErr() << "Out of range bin received: bin/size: " << bin << "/"
×
NEW
319
                 << _download_data.chunk_bin_table.size();
×
NEW
320
        return;
×
321
    }
322

NEW
323
    if (_download_data.file.tellp() != msg.ofs) {
×
NEW
324
        if (!_download_data.file.seekp(msg.ofs)) {
×
NEW
325
            LogErr() << "Error while seeking to log file offset";
×
NEW
326
            return;
×
327
        }
328
    }
329

NEW
330
    _download_data.file.write((char*)msg.data, msg.count);
×
331

332
    // Quietly ignore duplicate packets -- we don't want to record the bytes_written twice
NEW
333
    if (!_download_data.chunk_bin_table[bin]) {
×
NEW
334
        _download_data.chunk_bytes_written += msg.count;
×
NEW
335
        _download_data.chunk_bin_table[bin] = true;
×
336
    }
337

NEW
338
    bool chunk_complete = _download_data.chunk_bytes_written == _download_data.current_chunk_size();
×
339

NEW
340
    if (chunk_complete) {
×
NEW
341
        auto result = LogFiles::Result::Next;
×
342

NEW
343
        _download_data.current_chunk++;
×
NEW
344
        _download_data.total_bytes_written += _download_data.chunk_bytes_written;
×
NEW
345
        _download_data.chunk_bytes_written = 0;
×
NEW
346
        _download_data.chunk_bin_table = std::vector<bool>(_download_data.bins_in_chunk(), false);
×
347

NEW
348
        bool log_complete = _download_data.total_bytes_written == _download_data.entry.size_bytes;
×
349

NEW
350
        if (log_complete) {
×
NEW
351
            result = LogFiles::Result::Success;
×
NEW
352
            _download_data.file.close();
×
NEW
353
            _system_impl->unregister_timeout_handler(_download_data.timeout_cookie);
×
354

355
        } else {
356
            // Request the next chunk
NEW
357
            request_log_data(
×
358
                _download_data.entry.id,
NEW
359
                _download_data.current_chunk * CHUNK_SIZE,
×
360
                _download_data.current_chunk_size());
361
        }
362

NEW
363
        LogFiles::ProgressData progress_data;
×
NEW
364
        progress_data.progress =
×
NEW
365
            (float)_download_data.total_bytes_written / (float)_download_data.entry.size_bytes;
×
366

367
        // Update progress
NEW
368
        const auto cb = _download_data.user_callback;
×
NEW
369
        if (cb) {
×
NEW
370
            _system_impl->call_user_callback(
×
371
                [cb, progress_data, result]() { cb(result, progress_data); });
372
        }
373
    }
374
}
375

NEW
376
void LogFilesImpl::data_timeout()
×
377
{
NEW
378
    std::lock_guard<std::mutex> lock(_download_data_mutex);
×
379

NEW
380
    LogErr() << "Timeout!";
×
NEW
381
    LogErr() << "Requesting missing chunk:\t" << _download_data.current_chunk << "/"
×
NEW
382
             << _download_data.total_chunks();
×
383

384
    // Reset chunk data
NEW
385
    _download_data.chunk_bytes_written = 0;
×
NEW
386
    _download_data.chunk_bin_table = std::vector<bool>(_download_data.bins_in_chunk(), false);
×
387

NEW
388
    request_log_data(
×
389
        _download_data.entry.id,
NEW
390
        _download_data.current_chunk * CHUNK_SIZE,
×
391
        _download_data.current_chunk_size());
392

NEW
393
    _system_impl->register_timeout_handler(
×
NEW
394
        [this]() { LogFilesImpl::data_timeout(); },
×
NEW
395
        _system_impl->timeout_s() * 1.0,
×
396
        &_download_data.timeout_cookie);
UNCOV
397
}
×
398

399
void LogFilesImpl::request_log_data(unsigned id, unsigned start, unsigned count)
×
400
{
UNCOV
401
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
402
        mavlink_message_t message;
403
        mavlink_msg_log_request_data_pack_chan(
×
404
            mavlink_address.system_id,
×
405
            mavlink_address.component_id,
×
406
            channel,
407
            &message,
408
            _system_impl->get_system_id(),
×
409
            MAV_COMP_ID_AUTOPILOT1,
410
            id,
×
411
            start,
×
412
            count);
×
413
        return message;
×
414
    });
415
}
×
416

NEW
417
LogFiles::Result LogFilesImpl::erase_all_log_files()
×
418
{
NEW
419
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
420
        mavlink_message_t message;
NEW
421
        mavlink_msg_log_erase_pack_chan(
×
NEW
422
            mavlink_address.system_id,
×
NEW
423
            mavlink_address.component_id,
×
424
            channel,
425
            &message,
NEW
426
            _system_impl->get_system_id(),
×
427
            MAV_COMP_ID_AUTOPILOT1);
NEW
428
        return message;
×
429
    });
430

431
    // TODO: find a good way to know about the success or failure of the operation
NEW
432
    return LogFiles::Result::Success;
×
433
}
434

NEW
435
void LogFilesImpl::request_end()
×
436
{
NEW
437
    _system_impl->queue_message([&](MavlinkAddress mavlink_address, uint8_t channel) {
×
438
        mavlink_message_t message;
NEW
439
        mavlink_msg_log_request_end_pack_chan(
×
NEW
440
            mavlink_address.system_id,
×
NEW
441
            mavlink_address.component_id,
×
442
            channel,
443
            &message,
NEW
444
            _system_impl->get_system_id(),
×
445
            MAV_COMP_ID_AUTOPILOT1);
NEW
446
        return message;
×
447
    });
UNCOV
448
}
×
449

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