mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Flashstorage: fixed init bug on F1
we can't mark available just before we mark in use on F1
This commit is contained in:
parent
5efaea2d92
commit
40431100a9
@ -120,7 +120,7 @@ bool AP_FlashStorage::init(void)
|
|||||||
// erase any sectors marked full
|
// erase any sectors marked full
|
||||||
for (uint8_t i=0; i<2; i++) {
|
for (uint8_t i=0; i<2; i++) {
|
||||||
if (states[i] == SECTOR_STATE_FULL) {
|
if (states[i] == SECTOR_STATE_FULL) {
|
||||||
if (!erase_sector(i)) {
|
if (!erase_sector(i, true)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -148,7 +148,7 @@ bool AP_FlashStorage::switch_full_sector(void)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!erase_sector(current_sector ^ 1)) {
|
if (!erase_sector(current_sector ^ 1, true)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -276,12 +276,14 @@ bool AP_FlashStorage::load_sector(uint8_t sector)
|
|||||||
/*
|
/*
|
||||||
erase one sector
|
erase one sector
|
||||||
*/
|
*/
|
||||||
bool AP_FlashStorage::erase_sector(uint8_t sector)
|
bool AP_FlashStorage::erase_sector(uint8_t sector, bool mark_available)
|
||||||
{
|
{
|
||||||
if (!flash_erase(sector)) {
|
if (!flash_erase(sector)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
if (!mark_available) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
struct sector_header header;
|
struct sector_header header;
|
||||||
header.signature = signature;
|
header.signature = signature;
|
||||||
header.state = SECTOR_STATE_AVAILABLE;
|
header.state = SECTOR_STATE_AVAILABLE;
|
||||||
@ -298,7 +300,10 @@ bool AP_FlashStorage::erase_all(void)
|
|||||||
current_sector = 0;
|
current_sector = 0;
|
||||||
write_offset = sizeof(struct sector_header);
|
write_offset = sizeof(struct sector_header);
|
||||||
|
|
||||||
if (!erase_sector(0) || !erase_sector(1)) {
|
if (!erase_sector(0, current_sector!=0)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (!erase_sector(1, current_sector!=1)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -160,7 +160,7 @@ private:
|
|||||||
bool load_sector(uint8_t sector);
|
bool load_sector(uint8_t sector);
|
||||||
|
|
||||||
// erase a sector and write header
|
// erase a sector and write header
|
||||||
bool erase_sector(uint8_t sector);
|
bool erase_sector(uint8_t sector, bool mark_available);
|
||||||
|
|
||||||
// erase all sectors and reset
|
// erase all sectors and reset
|
||||||
bool erase_all();
|
bool erase_all();
|
||||||
|
Loading…
Reference in New Issue
Block a user