Skip to content

Commit 554e283

Browse files
authored
Merge pull request #2654 from mavlink/pr-logfiles-fixup
LogFiles fixup
2 parents 70f93a6 + a41be31 commit 554e283

File tree

5 files changed

+184
-40
lines changed

5 files changed

+184
-40
lines changed

examples/fly_qgc_mission/fly_qgc_mission.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ using std::this_thread::sleep_for;
3333

3434
void usage(const std::string& bin_name)
3535
{
36-
std::cerr << "Usage : " << bin_name << " <connection_url>\n"
36+
std::cerr << "Usage : " << bin_name << " <connection_url> <mission_plan_file>\n"
3737
<< "Connection URL format should be :\n"
3838
<< " For TCP server: tcpin://<our_ip>:<port>\n"
3939
<< " For TCP client: tcpout://<remote_ip>:<port>\n"

examples/logfile_download/logfile_download.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ void usage(const std::string& bin_name)
3535

3636
int main(int argc, char** argv)
3737
{
38-
if (argc > 3) {
38+
if (argc < 3) {
3939
usage(argv[0]);
4040
return 1;
4141
}

examples/set_actuator/set_actuator.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@ using namespace mavsdk;
1313

1414
void usage(const std::string& bin_name)
1515
{
16-
std::cerr << "Usage : " << bin_name << " <connection_url>\n"
16+
std::cerr << "Usage : " << bin_name << " <connection_url> <index> <value>\n"
1717
<< "Connection URL format should be :\n"
1818
<< " For TCP server: tcpin://<our_ip>:<port>\n"
1919
<< " For TCP client: tcpout://<remote_ip>:<port>\n"

src/mavsdk/plugins/log_files/log_files_impl.cpp

Lines changed: 173 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -123,6 +123,7 @@ void LogFilesImpl::get_entries_async(LogFiles::GetEntriesCallback callback)
123123
_log_entries.clear();
124124
_entries_user_callback = callback;
125125
_total_entries = 0;
126+
_entries_retry_count = 0;
126127

127128
_entries_timeout_cookie = _system_impl->register_timeout_handler(
128129
[this]() { entries_timeout(); }, _system_impl->timeout_s() * 10.0);
@@ -170,6 +171,13 @@ void LogFilesImpl::process_log_entry(const mavlink_message_t& message)
170171
return;
171172
}
172173

174+
// Initialize vector if this is the first entry
175+
if (_total_entries != msg.num_logs) {
176+
_total_entries = msg.num_logs;
177+
_log_entries.clear();
178+
_log_entries.resize(_total_entries);
179+
}
180+
173181
LogFiles::Entry new_entry;
174182
new_entry.id = msg.id;
175183

@@ -181,37 +189,74 @@ void LogFilesImpl::process_log_entry(const mavlink_message_t& message)
181189
new_entry.date = buf;
182190
new_entry.size_bytes = msg.size;
183191

184-
_log_entries[new_entry.id] = new_entry;
185-
_total_entries = msg.num_logs;
192+
// Store entry at direct index
193+
_log_entries[msg.id] = new_entry;
186194

187195
// Check if all entries are received
188-
if (_log_entries.size() == _total_entries) {
196+
bool all_received =
197+
std::all_of(_log_entries.begin(), _log_entries.end(), [](const auto& entry_opt) {
198+
return entry_opt.has_value();
199+
});
200+
201+
if (all_received) {
189202
_system_impl->unregister_timeout_handler(_entries_timeout_cookie);
190203

191-
// Copy map entries into list to return
192-
std::vector<LogFiles::Entry> entry_list{};
193-
for (unsigned i = 0; i < _log_entries.size(); i++) {
194-
entry_list.push_back(_log_entries[i]);
195-
}
204+
// Build result list from vector (safe since all entries are present)
205+
std::vector<LogFiles::Entry> entry_list;
206+
entry_list.reserve(_log_entries.size());
207+
std::transform(
208+
_log_entries.begin(),
209+
_log_entries.end(),
210+
std::back_inserter(entry_list),
211+
[](const auto& entry_opt) { return entry_opt.value(); });
196212

197213
const auto cb = _entries_user_callback;
198214
if (cb) {
199215
_system_impl->call_user_callback(
200216
[cb, entry_list]() { cb(LogFiles::Result::Success, entry_list); });
201217
}
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
222+
if (_total_entries > 0) {
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)
226+
if (msg.id == expected_last_entry_id ||
227+
_log_entries[expected_last_entry_id].has_value()) {
228+
check_and_request_missing_entries();
229+
}
230+
}
202231
}
203232
}
204233

205234
void LogFilesImpl::entries_timeout()
206235
{
207236
std::lock_guard<std::mutex> lock(_entries_mutex);
208237

238+
LogDebug() << "Request entries timeout! Retry count: " << _entries_retry_count;
239+
240+
constexpr uint32_t MAX_RETRIES = 5;
241+
242+
if (_entries_retry_count < MAX_RETRIES) {
243+
// Try to request missing entries
244+
check_and_request_missing_entries();
245+
_entries_retry_count++;
246+
247+
// Reset timeout for another attempt (use normal timeout, not * 10.0)
248+
_entries_timeout_cookie = _system_impl->register_timeout_handler(
249+
[this]() { entries_timeout(); }, _system_impl->timeout_s());
250+
251+
// Don't call user callback yet - give it another chance
252+
return;
253+
}
254+
255+
// Max retries exceeded - give up and call user with timeout error
209256
const auto cb = _entries_user_callback;
210257
if (cb) {
211-
_system_impl->call_user_callback([cb]() {
212-
LogDebug() << "Request entries timeout!";
213-
cb(LogFiles::Result::Timeout, std::vector<LogFiles::Entry>());
214-
});
258+
_system_impl->call_user_callback(
259+
[cb]() { cb(LogFiles::Result::Timeout, std::vector<LogFiles::Entry>()); });
215260
}
216261
}
217262

@@ -237,9 +282,8 @@ void LogFilesImpl::download_log_file_async(
237282
{
238283
std::lock_guard<std::mutex> lock(_entries_mutex);
239284

240-
auto entry_it = _log_entries.find(entry.id);
241-
bool error = entry_it == _log_entries.end() || fs::is_directory(fs::path(file_path)) ||
242-
fs::exists(file_path);
285+
bool error = entry.id >= _log_entries.size() || !_log_entries[entry.id].has_value() ||
286+
fs::is_directory(fs::path(file_path)) || fs::exists(file_path);
243287

244288
if (error) {
245289
LogErr() << "error: download_log_file_async failed";
@@ -252,7 +296,21 @@ void LogFilesImpl::download_log_file_async(
252296
return;
253297
}
254298

255-
_download_data = LogData(entry_it->second, file_path, callback);
299+
const auto& found_entry = _log_entries[entry.id].value();
300+
301+
// Check for zero-sized file and abort early
302+
if (found_entry.size_bytes == 0) {
303+
LogErr() << "Cannot download zero-sized log file";
304+
305+
if (callback) {
306+
_system_impl->call_user_callback([callback]() {
307+
callback(LogFiles::Result::InvalidArgument, LogFiles::ProgressData());
308+
});
309+
}
310+
return;
311+
}
312+
313+
_download_data = LogData(found_entry, file_path, callback);
256314

257315
if (!_download_data.file_is_open()) {
258316
if (callback) {
@@ -264,7 +322,7 @@ void LogFilesImpl::download_log_file_async(
264322
}
265323

266324
_download_data.timeout_cookie = _system_impl->register_timeout_handler(
267-
[this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s() * 1.0);
325+
[this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s());
268326

269327
// Request the first chunk
270328
request_log_data(_download_data.entry.id, 0, _download_data.current_chunk_size());
@@ -329,20 +387,23 @@ void LogFilesImpl::process_log_data(const mavlink_message_t& message)
329387

330388
_download_data.file.write((char*)msg.data, msg.count);
331389

332-
// Quietly ignore duplicate packets -- we don't want to record the bytes_written twice
333-
if (!_download_data.chunk_bin_table[bin]) {
334-
_download_data.chunk_bytes_written += msg.count;
335-
_download_data.chunk_bin_table[bin] = true;
336-
}
390+
// Mark bin as received (quietly ignore duplicates)
391+
_download_data.chunk_bin_table[bin] = true;
337392

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

340400
if (chunk_complete) {
401+
uint32_t chunk_bytes = _download_data.current_chunk_size();
402+
341403
auto result = LogFiles::Result::Next;
342404

343405
_download_data.current_chunk++;
344-
_download_data.total_bytes_written += _download_data.chunk_bytes_written;
345-
_download_data.chunk_bytes_written = 0;
406+
_download_data.total_bytes_written += chunk_bytes;
346407
_download_data.chunk_bin_table = std::vector<bool>(_download_data.bins_in_chunk(), false);
347408

348409
bool log_complete = _download_data.total_bytes_written == _download_data.entry.size_bytes;
@@ -370,6 +431,18 @@ void LogFilesImpl::process_log_data(const mavlink_message_t& message)
370431
_system_impl->call_user_callback(
371432
[cb, progress_data, result]() { cb(result, progress_data); });
372433
}
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
438+
if (bins_in_chunk > 0) {
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)
442+
if (bin == expected_last_bin || _download_data.chunk_bin_table[expected_last_bin]) {
443+
check_and_request_missing_bins();
444+
}
445+
}
373446
}
374447
}
375448

@@ -381,17 +454,83 @@ void LogFilesImpl::data_timeout()
381454
LogErr() << "Requesting missing chunk:\t" << _download_data.current_chunk << "/"
382455
<< _download_data.total_chunks();
383456

384-
// Reset chunk data
385-
_download_data.chunk_bytes_written = 0;
386-
_download_data.chunk_bin_table = std::vector<bool>(_download_data.bins_in_chunk(), false);
387-
388-
request_log_data(
389-
_download_data.entry.id,
390-
_download_data.current_chunk * CHUNK_SIZE,
391-
_download_data.current_chunk_size());
457+
// Don't reset chunk data - preserve what we've received
458+
// Instead, request missing ranges based on bin table
459+
check_and_request_missing_bins();
392460

393461
_download_data.timeout_cookie = _system_impl->register_timeout_handler(
394-
[this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s() * 1.0);
462+
[this]() { LogFilesImpl::data_timeout(); }, _system_impl->timeout_s());
463+
}
464+
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
470+
const uint32_t chunk_start = _download_data.current_chunk * CHUNK_SIZE;
471+
const uint32_t bins_in_chunk = _download_data.bins_in_chunk();
472+
473+
uint32_t range_start = 0;
474+
bool in_missing_range = false;
475+
bool requested_something = false;
476+
477+
for (uint32_t bin = 0; bin <= bins_in_chunk; ++bin) {
478+
bool is_missing = (bin < bins_in_chunk) ? !_download_data.chunk_bin_table[bin] : false;
479+
480+
if (is_missing && !in_missing_range) {
481+
// Start of a missing range
482+
range_start = bin;
483+
in_missing_range = true;
484+
} else if (!is_missing && in_missing_range) {
485+
// End of a missing range, request it (but only request the first one)
486+
if (!requested_something) {
487+
const uint32_t missing_start =
488+
chunk_start + (range_start * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
489+
const uint32_t missing_count =
490+
(bin - range_start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
491+
492+
LogDebug() << "Requesting missing range from offset " << missing_start << " count "
493+
<< missing_count;
494+
request_log_data(_download_data.entry.id, missing_start, missing_count);
495+
requested_something = true;
496+
}
497+
in_missing_range = false;
498+
}
499+
}
500+
}
501+
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
507+
std::vector<uint16_t> missing_ids;
508+
for (uint16_t i = 0; i < _log_entries.size(); ++i) {
509+
if (!_log_entries[i].has_value()) {
510+
missing_ids.push_back(i);
511+
}
512+
}
513+
514+
if (missing_ids.empty()) {
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)
520+
uint16_t range_start = missing_ids[0];
521+
uint16_t range_end = range_start;
522+
523+
// Find end of first consecutive range
524+
for (size_t i = 1; i < missing_ids.size(); ++i) {
525+
if (missing_ids[i] == missing_ids[i - 1] + 1) {
526+
range_end = missing_ids[i];
527+
} else {
528+
break;
529+
}
530+
}
531+
532+
LogDebug() << "Requesting missing log entries from " << range_start << " to " << range_end;
533+
request_log_list(range_start, range_end);
395534
}
396535

397536
void LogFilesImpl::request_log_data(unsigned id, unsigned start, unsigned count)

src/mavsdk/plugins/log_files/log_files_impl.h

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -5,10 +5,13 @@
55
#include "plugin_impl_base.h"
66
#include "system.h"
77
#include <fstream>
8+
#include <optional>
89

910
namespace mavsdk {
1011

11-
static constexpr uint32_t TABLE_BINS = 512;
12+
// We need to keep this smaller, otherwise we end up running over the UDP buffer in Linux when PX4
13+
// sends too much all at once.
14+
static constexpr uint32_t TABLE_BINS = 128;
1215
static constexpr uint32_t CHUNK_SIZE = (TABLE_BINS * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
1316

1417
struct LogData {
@@ -31,7 +34,6 @@ struct LogData {
3134
uint32_t current_chunk{};
3235
std::vector<bool> chunk_bin_table{};
3336

34-
uint32_t chunk_bytes_written{};
3537
uint32_t total_bytes_written{};
3638

3739
TimeoutHandler::Cookie timeout_cookie{};
@@ -70,15 +72,18 @@ class LogFilesImpl : public PluginImplBase {
7072

7173
void process_log_data(const mavlink_message_t& message);
7274
void data_timeout();
75+
void check_and_request_missing_bins();
76+
void check_and_request_missing_entries();
7377

7478
void request_log_list(uint16_t index_min, uint16_t index_max);
7579
void request_log_data(unsigned id, unsigned start, unsigned count);
7680

7781
void request_end();
7882

7983
std::mutex _entries_mutex;
80-
std::unordered_map<uint16_t, LogFiles::Entry> _log_entries;
84+
std::vector<std::optional<LogFiles::Entry>> _log_entries;
8185
uint32_t _total_entries{0};
86+
uint32_t _entries_retry_count{0};
8287
TimeoutHandler::Cookie _entries_timeout_cookie{};
8388
LogFiles::GetEntriesCallback _entries_user_callback{};
8489

0 commit comments

Comments
 (0)