mirror of https://github.com/ArduPilot/ardupilot
AP_FlashStorage: added re_initialise() API
This commit is contained in:
parent
d1fd843539
commit
0bfbc4bf72
|
@ -277,9 +277,7 @@ bool AP_FlashStorage::erase_sector(uint8_t sector)
|
||||||
bool AP_FlashStorage::erase_all(void)
|
bool AP_FlashStorage::erase_all(void)
|
||||||
{
|
{
|
||||||
write_error = false;
|
write_error = false;
|
||||||
|
|
||||||
// start with empty memory buffer
|
|
||||||
memset(mem_buffer, 0, storage_size);
|
|
||||||
current_sector = 0;
|
current_sector = 0;
|
||||||
write_offset = sizeof(struct sector_header);
|
write_offset = sizeof(struct sector_header);
|
||||||
|
|
||||||
|
@ -374,3 +372,17 @@ bool AP_FlashStorage::switch_sectors(void)
|
||||||
write_offset = sizeof(header);
|
write_offset = sizeof(header);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
re-initialise, using current mem_buffer
|
||||||
|
*/
|
||||||
|
bool AP_FlashStorage::re_initialise(void)
|
||||||
|
{
|
||||||
|
if (!flash_erase_ok()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (!erase_all()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
return write_all();
|
||||||
|
}
|
||||||
|
|
|
@ -72,6 +72,9 @@ public:
|
||||||
// initialise storage, filling mem_buffer with current contents
|
// initialise storage, filling mem_buffer with current contents
|
||||||
bool init(void);
|
bool init(void);
|
||||||
|
|
||||||
|
// re-initialise storage, using current mem_buffer
|
||||||
|
bool re_initialise(void);
|
||||||
|
|
||||||
// switch full sector - should only be called when safe to have CPU
|
// switch full sector - should only be called when safe to have CPU
|
||||||
// offline for considerable periods as an erase will be needed
|
// offline for considerable periods as an erase will be needed
|
||||||
bool switch_full_sector(void);
|
bool switch_full_sector(void);
|
||||||
|
@ -135,7 +138,7 @@ private:
|
||||||
bool erase_sector(uint8_t sector);
|
bool erase_sector(uint8_t sector);
|
||||||
|
|
||||||
// erase all sectors and reset
|
// erase all sectors and reset
|
||||||
bool erase_all(void);
|
bool erase_all();
|
||||||
|
|
||||||
// write all of mem_buffer to current sector
|
// write all of mem_buffer to current sector
|
||||||
bool write_all(void);
|
bool write_all(void);
|
||||||
|
|
Loading…
Reference in New Issue