DataFlash: added error checking and fixed a warning

This commit is contained in:
Andrew Tridgell 2015-05-30 22:16:22 +10:00
parent b87cc80486
commit 73445fdae9
6 changed files with 29 additions and 13 deletions

View File

@ -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;
};

View File

@ -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;
}

View File

@ -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);

View File

@ -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;
}

View File

@ -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;

View File

@ -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<msg_len; fmt_ofs++) {
char fmt = PGM_UINT8(&_structures[i].format[fmt_ofs]);
@ -469,7 +471,9 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
while (true) {
uint8_t data;
ReadBlock(&data, 1);
if (!ReadBlock(&data, 1)) {
break;
}
// This is a state machine to read the packets
switch(log_step) {