diff --git a/libraries/GCS_MAVLink/GCS_Logs.cpp b/libraries/GCS_MAVLink/GCS_Logs.cpp index c7e5e7b23b..6894eb8c1e 100644 --- a/libraries/GCS_MAVLink/GCS_Logs.cpp +++ b/libraries/GCS_MAVLink/GCS_Logs.cpp @@ -62,18 +62,20 @@ void GCS_MAVLINK::handle_log_request_list(mavlink_message_t *msg, DataFlash_Clas _log_num_logs = dataflash.get_num_logs(); if (_log_num_logs == 0) { - return; - } - int16_t last_log_num = dataflash.find_last_log(); + _log_next_list_entry = 0; + _log_last_list_entry = 0; + } else { + int16_t last_log_num = dataflash.find_last_log(); - _log_next_list_entry = packet.start; - _log_last_list_entry = packet.end; + _log_next_list_entry = packet.start; + _log_last_list_entry = packet.end; - if (_log_last_list_entry > last_log_num) { - _log_last_list_entry = last_log_num; - } - if (_log_next_list_entry < last_log_num + 1 - _log_num_logs) { - _log_next_list_entry = last_log_num + 1 - _log_num_logs; + if (_log_last_list_entry > last_log_num) { + _log_last_list_entry = last_log_num; + } + 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; @@ -176,7 +178,12 @@ void GCS_MAVLINK::handle_log_send_listing(DataFlash_Class &dataflash) } uint32_t size, time_utc; - dataflash.get_log_info(_log_next_list_entry, size, time_utc); + if (_log_next_list_entry == 0) { + size = 0; + time_utc = 0; + } else { + dataflash.get_log_info(_log_next_list_entry, size, time_utc); + } mavlink_msg_log_entry_send(chan, _log_next_list_entry, _log_num_logs, _log_last_list_entry, time_utc, size); if (_log_next_list_entry == _log_last_list_entry) { _log_listing = false;