mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
DataFlash: prevent the dataflash erase problem
only allow writes to dataflash block devices once StartNewLog() has been called
This commit is contained in:
parent
e843bf3dfd
commit
411e940342
@ -37,7 +37,7 @@ void DataFlash_Block::FinishWrite(void)
|
||||
|
||||
void DataFlash_Block::WriteBlock(const void *pBuffer, uint16_t size)
|
||||
{
|
||||
if (!CardInserted()) {
|
||||
if (!CardInserted() || !log_write_started) {
|
||||
return;
|
||||
}
|
||||
while (size > 0) {
|
||||
@ -163,7 +163,9 @@ void DataFlash_Block::EraseAll()
|
||||
hal.scheduler->delay(100);
|
||||
StartWrite(df_NumPages+1);
|
||||
uint32_t version = DF_LOGGING_FORMAT;
|
||||
log_write_started = true;
|
||||
WriteBlock(&version, sizeof(version));
|
||||
log_write_started = false;
|
||||
FinishWrite();
|
||||
hal.scheduler->delay(100);
|
||||
}
|
||||
@ -173,8 +175,9 @@ void DataFlash_Block::EraseAll()
|
||||
*/
|
||||
bool DataFlash_Block::NeedErase(void)
|
||||
{
|
||||
uint32_t version;
|
||||
uint32_t version = 0;
|
||||
StartRead(df_NumPages+1);
|
||||
ReadBlock(&version, sizeof(version));
|
||||
StartRead(1);
|
||||
return version != DF_LOGGING_FORMAT;
|
||||
}
|
||||
|
@ -53,6 +53,7 @@ private:
|
||||
uint16_t df_Read_PageAdr;
|
||||
uint16_t df_FileNumber;
|
||||
uint16_t df_FilePage;
|
||||
bool log_write_started;
|
||||
|
||||
/*
|
||||
functions implemented by the board specific backends
|
||||
|
@ -58,6 +58,7 @@ uint16_t DataFlash_Block::start_new_log(void)
|
||||
SetFileNumber(1);
|
||||
StartWrite(1);
|
||||
//Serial.println("start log from 0");
|
||||
log_write_started = true;
|
||||
return 1;
|
||||
}
|
||||
|
||||
@ -78,6 +79,7 @@ uint16_t DataFlash_Block::start_new_log(void)
|
||||
SetFileNumber(new_log_num);
|
||||
StartWrite(last_page + 1);
|
||||
}
|
||||
log_write_started = true;
|
||||
return new_log_num;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user