From 73445fdae95b35a57bacc046187be55c8ad2bfa1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 30 May 2015 22:16:22 +1000 Subject: [PATCH] DataFlash: added error checking and fixed a warning --- libraries/DataFlash/DataFlash.h | 2 +- libraries/DataFlash/DataFlash_Block.cpp | 19 ++++++++++++++----- libraries/DataFlash/DataFlash_Block.h | 2 +- libraries/DataFlash/DataFlash_File.cpp | 9 ++++++--- libraries/DataFlash/DataFlash_File.h | 2 +- libraries/DataFlash/LogFile.cpp | 8 ++++++-- 6 files changed, 29 insertions(+), 13 deletions(-) diff --git a/libraries/DataFlash/DataFlash.h b/libraries/DataFlash/DataFlash.h index 0fa9504c71..1732c59bce 100644 --- a/libraries/DataFlash/DataFlash.h +++ b/libraries/DataFlash/DataFlash.h @@ -135,7 +135,7 @@ protected: /* read a block */ - virtual void ReadBlock(void *pkt, uint16_t size) = 0; + virtual bool ReadBlock(void *pkt, uint16_t size) = 0; }; diff --git a/libraries/DataFlash/DataFlash_Block.cpp b/libraries/DataFlash/DataFlash_Block.cpp index b3d167bbea..6f0b0eeacc 100644 --- a/libraries/DataFlash/DataFlash_Block.cpp +++ b/libraries/DataFlash/DataFlash_Block.cpp @@ -104,7 +104,7 @@ void DataFlash_Block::StartRead(uint16_t PageAdr) df_Read_BufferIdx = sizeof(ph); } -void DataFlash_Block::ReadBlock(void *pBuffer, uint16_t size) +bool DataFlash_Block::ReadBlock(void *pBuffer, uint16_t size) { while (size > 0) { uint16_t n = df_PageSize - df_Read_BufferIdx; @@ -114,7 +114,9 @@ void DataFlash_Block::ReadBlock(void *pBuffer, uint16_t size) WaitReady(); - BlockRead(df_Read_BufferNum, df_Read_BufferIdx, pBuffer, n); + if (!BlockRead(df_Read_BufferNum, df_Read_BufferIdx, pBuffer, n)) { + return false; + } size -= n; pBuffer = (void *)(n + (uintptr_t)pBuffer); @@ -129,13 +131,16 @@ void DataFlash_Block::ReadBlock(void *pBuffer, uint16_t size) // We are starting a new page - read FileNumber and FilePage struct PageHeader ph; - BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph)); + if (!BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph))) { + return false; + } df_FileNumber = ph.FileNumber; df_FilePage = ph.FilePage; df_Read_BufferIdx = sizeof(ph); } } + return true; } void DataFlash_Block::SetFileNumber(uint16_t FileNumber) @@ -182,7 +187,9 @@ bool DataFlash_Block::NeedErase(void) { uint32_t version = 0; StartRead(df_NumPages+1); - ReadBlock(&version, sizeof(version)); + if (!ReadBlock(&version, sizeof(version))) { + return true; + } StartRead(1); return version != DF_LOGGING_FORMAT; } @@ -207,7 +214,9 @@ int16_t DataFlash_Block::get_log_data_raw(uint16_t log_num, uint16_t page, uint3 } df_Read_BufferIdx = offset + sizeof(struct PageHeader); - ReadBlock(data, len); + if (!ReadBlock(data, len)) { + return -1; + } return (int16_t)len; } diff --git a/libraries/DataFlash/DataFlash_Block.h b/libraries/DataFlash/DataFlash_Block.h index 85563bc18f..2ab1ee1d4d 100644 --- a/libraries/DataFlash/DataFlash_Block.h +++ b/libraries/DataFlash/DataFlash_Block.h @@ -93,7 +93,7 @@ private: void FinishWrite(void); // Read methods - void ReadBlock(void *pBuffer, uint16_t size); + bool ReadBlock(void *pBuffer, uint16_t size); // file numbers void SetFileNumber(uint16_t FileNumber); diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index 5d2109bbbb..5e8759b9bd 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -229,15 +229,18 @@ void DataFlash_File::WriteBlock(const void *pBuffer, uint16_t size) /* read a packet. The header bytes have already been read. */ -void DataFlash_File::ReadBlock(void *pkt, uint16_t size) +bool DataFlash_File::ReadBlock(void *pkt, uint16_t size) { if (_read_fd == -1 || !_initialised || _open_error) { - return; + return false; } memset(pkt, 0, size); - ::read(_read_fd, pkt, size); + if (::read(_read_fd, pkt, size) != size) { + return false; + } _read_offset += size; + return true; } diff --git a/libraries/DataFlash/DataFlash_File.h b/libraries/DataFlash/DataFlash_File.h index 373ad4164c..53b4ab6f94 100644 --- a/libraries/DataFlash/DataFlash_File.h +++ b/libraries/DataFlash/DataFlash_File.h @@ -64,7 +64,7 @@ private: /* read a block */ - void ReadBlock(void *pkt, uint16_t size); + bool ReadBlock(void *pkt, uint16_t size); // write buffer uint8_t *_writebuf; diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index aa2425d05a..7f519b200d 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -292,7 +292,9 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type, } uint8_t msg_len = PGM_UINT8(&_structures[i].msg_len) - 3; uint8_t pkt[msg_len]; - ReadBlock(pkt, msg_len); + if (!ReadBlock(pkt, msg_len)) { + return; + } port->printf_P(PSTR("%S, "), _structures[i].name); for (uint8_t ofs=0, fmt_ofs=0; ofs