From 81c5edbdb5dd1bf429addcf0177000f6678f6bd7 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 14 Feb 2014 13:14:07 +1100 Subject: [PATCH] GCS_MAVLink: fixed a log download bug for repeated downloads we were not resetting the offset to 0 correctly --- libraries/GCS_MAVLink/GCS_Logs.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS_Logs.cpp b/libraries/GCS_MAVLink/GCS_Logs.cpp index 72ad38f633..11687e2806 100644 --- a/libraries/GCS_MAVLink/GCS_Logs.cpp +++ b/libraries/GCS_MAVLink/GCS_Logs.cpp @@ -110,6 +110,7 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas dataflash.get_log_boundaries(packet.id, _log_data_page, end); } + _log_data_offset = packet.ofs; if (_log_data_offset >= _log_data_size) { _log_data_remaining = 0; } else { @@ -118,7 +119,6 @@ void GCS_MAVLINK::handle_log_request_data(mavlink_message_t *msg, DataFlash_Clas if (_log_data_remaining > packet.count) { _log_data_remaining = packet.count; } - _log_data_offset = packet.ofs; _log_sending = true; handle_log_send(dataflash);