From 146b0c69d607a1d349680b5d26c784cb74f29f8b Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 19 Apr 2019 07:43:24 +1000 Subject: [PATCH] AP_Logger: check return values from get_log_data --- libraries/AP_Logger/AP_Logger_Block.cpp | 10 ++++++++-- libraries/AP_Logger/AP_Logger_Block.h | 4 ++-- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Logger/AP_Logger_Block.cpp b/libraries/AP_Logger/AP_Logger_Block.cpp index 10d354cee6..fc0c81cf3d 100644 --- a/libraries/AP_Logger/AP_Logger_Block.cpp +++ b/libraries/AP_Logger/AP_Logger_Block.cpp @@ -279,7 +279,9 @@ int16_t AP_Logger_Block::get_log_data(uint16_t log_num, uint16_t page, uint32_t WITH_SEMAPHORE(sem); if (offset == 0) { uint8_t header[3]; - get_log_data_raw(log_num, page, 0, 3, header); + if (get_log_data_raw(log_num, page, 0, 3, header) == -1) { + return -1; + } adding_fmt_headers = (header[0] != HEAD_BYTE1 || header[1] != HEAD_BYTE2 || header[2] != LOG_FORMAT_MSG); } uint16_t ret = 0; @@ -307,7 +309,11 @@ int16_t AP_Logger_Block::get_log_data(uint16_t log_num, uint16_t page, uint32_t } if (len > 0) { - ret += get_log_data_raw(log_num, page, offset, len, data); + const int16_t bytes = get_log_data_raw(log_num, page, offset, len, data); + if (bytes == -1) { + return ret == 0 ? -1 : ret; + } + ret += bytes; } return ret; diff --git a/libraries/AP_Logger/AP_Logger_Block.h b/libraries/AP_Logger/AP_Logger_Block.h index e29c4dfc9f..5028e21d2b 100644 --- a/libraries/AP_Logger/AP_Logger_Block.h +++ b/libraries/AP_Logger/AP_Logger_Block.h @@ -23,7 +23,7 @@ public: uint16_t find_last_log() override; void get_log_boundaries(uint16_t log_num, uint32_t & start_page, uint32_t & end_page) override; void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override; - int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override; + int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override WARN_IF_UNUSED; uint16_t get_num_logs() override; uint16_t start_new_log(void) override; uint32_t bufferspace_available() override; @@ -76,7 +76,7 @@ private: bool NeedErase(void); // internal high level functions - int16_t get_log_data_raw(uint16_t log_num, uint32_t page, uint32_t offset, uint16_t len, uint8_t *data); + int16_t get_log_data_raw(uint16_t log_num, uint32_t page, uint32_t offset, uint16_t len, uint8_t *data) WARN_IF_UNUSED; void StartRead(uint32_t PageAdr); uint32_t find_last_page(void); uint32_t find_last_page_of_log(uint16_t log_number);