Skip to content

Commit

Permalink
Revert "GCS_MAVLink: use simple log entry number to reference df logs"
Browse files Browse the repository at this point in the history
This reverts commit 55575c0.
  • Loading branch information
jschall committed Nov 16, 2015
1 parent 9be9c63 commit e699ca1
Showing 1 changed file with 9 additions and 6 deletions.
15 changes: 9 additions & 6 deletions libraries/GCS_MAVLink/GCS_Logs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,16 +63,18 @@ void GCS_MAVLINK::handle_log_request_list(mavlink_message_t *msg, DataFlash_Clas
_log_next_list_entry = 0;
_log_last_list_entry = 0;
} else {
uint16_t last_log_num = dataflash.find_last_log();

_log_next_list_entry = packet.start;
_log_last_list_entry = packet.end;

if (_log_last_list_entry > _log_num_logs) {
_log_last_list_entry = _log_num_logs;
if (_log_last_list_entry > last_log_num) {
_log_last_list_entry = last_log_num;
}
if (_log_next_list_entry < 1) {
_log_next_list_entry = 1;
if (_log_next_list_entry < last_log_num + 1 - _log_num_logs) {
_log_next_list_entry = last_log_num + 1 - _log_num_logs;
}
}
}

_log_listing = true;
handle_log_send_listing(dataflash);
Expand All @@ -92,7 +94,8 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas
_log_sending = false;

uint16_t num_logs = dataflash.get_num_logs();
if (packet.id > num_logs || packet.id < 1) {
uint16_t last_log_num = dataflash.find_last_log();
if (packet.id > last_log_num || packet.id < last_log_num + 1 - num_logs) {
return;
}

Expand Down

0 comments on commit e699ca1

Please sign in to comment.