Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_FlashStorage/AP_FlashStorage.cpp
Views: 1798
/*1Please contribute your ideas! See https://ardupilot.org/dev for details23This program is free software: you can redistribute it and/or modify4it under the terms of the GNU General Public License as published by5the Free Software Foundation, either version 3 of the License, or6(at your option) any later version.78This program is distributed in the hope that it will be useful,9but WITHOUT ANY WARRANTY; without even the implied warranty of10MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the11GNU General Public License for more details.1213You should have received a copy of the GNU General Public License14along with this program. If not, see <http://www.gnu.org/licenses/>.15*/1617#include <AP_HAL/AP_HAL.h>18#include <AP_FlashStorage/AP_FlashStorage.h>19#include <AP_Math/AP_Math.h>20#include <AP_InternalError/AP_InternalError.h>21#include <stdio.h>2223#define FLASHSTORAGE_DEBUG 02425#if FLASHSTORAGE_DEBUG26#define debug(fmt, args...) do { printf(fmt, ##args); } while(0)27#else28#define debug(fmt, args...) do { } while(0)29#endif3031// constructor.32AP_FlashStorage::AP_FlashStorage(uint8_t *_mem_buffer,33uint32_t _flash_sector_size,34FlashWrite _flash_write,35FlashRead _flash_read,36FlashErase _flash_erase,37FlashEraseOK _flash_erase_ok) :38mem_buffer(_mem_buffer),39flash_sector_size(_flash_sector_size),40flash_write(_flash_write),41flash_read(_flash_read),42flash_erase(_flash_erase),43flash_erase_ok(_flash_erase_ok) {}4445// initialise storage46bool AP_FlashStorage::init(void)47{48debug("running init()\n");4950// start with empty memory buffer51memset(mem_buffer, 0, storage_size);5253// find state of sectors54struct sector_header header[2];5556// read headers and possibly initialise if bad signature57for (uint8_t i=0; i<2; i++) {58if (!flash_read(i, 0, (uint8_t *)&header[i], sizeof(header[i]))) {59return false;60}61bool bad_header = !header[i].signature_ok();62enum SectorState state = header[i].get_state();63if (state != SECTOR_STATE_AVAILABLE &&64state != SECTOR_STATE_IN_USE &&65state != SECTOR_STATE_FULL) {66bad_header = true;67}6869// initialise if bad header70if (bad_header) {71return erase_all();72}73}7475// work out the first sector to read from using sector states76enum SectorState states[2] {header[0].get_state(), header[1].get_state()};77uint8_t first_sector;7879if (states[0] == states[1]) {80if (states[0] != SECTOR_STATE_AVAILABLE) {81return erase_all();82}83first_sector = 0;84} else if (states[0] == SECTOR_STATE_FULL) {85first_sector = 0;86} else if (states[1] == SECTOR_STATE_FULL) {87first_sector = 1;88} else if (states[0] == SECTOR_STATE_IN_USE) {89first_sector = 0;90} else if (states[1] == SECTOR_STATE_IN_USE) {91first_sector = 1;92} else {93// doesn't matter which is first94first_sector = 0;95}9697// load data from any current sectors98for (uint8_t i=0; i<2; i++) {99uint8_t sector = (first_sector + i) & 1;100if (states[sector] == SECTOR_STATE_IN_USE ||101states[sector] == SECTOR_STATE_FULL) {102if (!load_sector(sector)) {103return erase_all();104}105}106}107108// clear any write error109write_error = false;110reserved_space = 0;111112// if the first sector is full then write out all data so we can erase it113if (states[first_sector] == SECTOR_STATE_FULL) {114current_sector = first_sector ^ 1;115if (!write_all()) {116return erase_all();117}118}119120// erase any sectors marked full121for (uint8_t i=0; i<2; i++) {122if (states[i] == SECTOR_STATE_FULL) {123if (!erase_sector(i, true)) {124return false;125}126}127}128129reserved_space = 0;130131// ready to use132return true;133}134135136137// switch full sector - should only be called when safe to have CPU138// offline for considerable periods as an erase will be needed139bool AP_FlashStorage::switch_full_sector(void)140{141debug("running switch_full_sector()\n");142143if (in_switch_full_sector) {144INTERNAL_ERROR(AP_InternalError::error_t::switch_full_sector_recursion);145return false;146}147in_switch_full_sector = true;148bool ret = protected_switch_full_sector();149in_switch_full_sector = false;150return ret;151}152153// protected_switch_full_sector is protected by switch_full_sector to154// avoid an infinite recursion problem; switch_full_sector calls155// write() which can call switch_full_sector. This has been seen in156// practice, and while it might be caused by corruption... corruption157// happens.158bool AP_FlashStorage::protected_switch_full_sector(void)159{160// clear any write error161write_error = false;162reserved_space = 0;163164if (!write_all()) {165return false;166}167168if (!erase_sector(current_sector ^ 1, true)) {169return false;170}171172return switch_sectors();173}174175// write some data to virtual EEPROM176bool AP_FlashStorage::write(uint16_t offset, uint16_t length)177{178if (write_error) {179return false;180}181//debug("write at %u for %u write_offset=%u\n", offset, length, write_offset);182183while (length > 0) {184uint8_t n = max_write;185#if AP_FLASHSTORAGE_TYPE != AP_FLASHSTORAGE_TYPE_H7 && AP_FLASHSTORAGE_TYPE != AP_FLASHSTORAGE_TYPE_G4186if (length < n) {187n = length;188}189#endif190191const uint32_t space_available = flash_sector_size - write_offset;192const uint32_t space_required = sizeof(struct block_header) + max_write + reserved_space;193if (space_available < space_required) {194if (!switch_sectors()) {195if (!flash_erase_ok()) {196return false;197}198if (!switch_full_sector()) {199return false;200}201}202}203204struct PACKED {205struct block_header header;206uint8_t data[max_write];207} blk;208209blk.header.state = BLOCK_STATE_WRITING;210blk.header.block_num = offset / block_size;211blk.header.num_blocks_minus_one = ((n + (block_size - 1)) / block_size)-1;212213uint16_t block_ofs = blk.header.block_num*block_size;214uint16_t block_nbytes = (blk.header.num_blocks_minus_one+1)*block_size;215216memcpy(blk.data, &mem_buffer[block_ofs], block_nbytes);217218#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F4219if (!flash_write(current_sector, write_offset, (uint8_t*)&blk.header, sizeof(blk.header))) {220return false;221}222if (!flash_write(current_sector, write_offset+sizeof(blk.header), blk.data, block_nbytes)) {223return false;224}225blk.header.state = BLOCK_STATE_VALID;226if (!flash_write(current_sector, write_offset, (uint8_t*)&blk.header, sizeof(blk.header))) {227return false;228}229#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F1230blk.header.state = BLOCK_STATE_VALID;231if (!flash_write(current_sector, write_offset, (uint8_t*)&blk, sizeof(blk.header) + block_nbytes)) {232return false;233}234#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7 || AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4235blk.header.state = BLOCK_STATE_VALID;236if (!flash_write(current_sector, write_offset, (uint8_t*)&blk, sizeof(blk.header) + max_write)) {237return false;238}239#endif240241write_offset += sizeof(blk.header) + block_nbytes;242243uint8_t n2 = block_nbytes - (offset % block_size);244//debug("write_block at %u for %u n2=%u\n", block_ofs, block_nbytes, n2);245if (n2 > length) {246break;247}248offset += n2;249length -= n2;250}251252//debug("write_offset %u\n", write_offset);253254// handle wrap to next sector255// write data256// write header word257return true;258}259260/*261load all data from a flash sector into mem_buffer262*/263bool AP_FlashStorage::load_sector(uint8_t sector)264{265uint32_t ofs = sizeof(sector_header);266while (ofs < flash_sector_size - sizeof(struct block_header)) {267struct block_header header;268if (!flash_read(sector, ofs, (uint8_t *)&header, sizeof(header))) {269return false;270}271enum BlockState state = (enum BlockState)header.state;272273switch (state) {274case BLOCK_STATE_AVAILABLE:275// we've reached the end276write_offset = ofs;277return true;278279case BLOCK_STATE_WRITING: {280/*281we were interrupted while writing a block. We can't282re-use the data in this block as it may have some bits283that are not set to 1, so by flash rules can't be set to284an arbitrary value. So we skip over this block, leaving285a gap. The gap size is limited to (7+1)*8=64 bytes. That286gap won't be recovered until we next do an erase of this287sector288*/289uint16_t block_nbytes = (header.num_blocks_minus_one+1)*block_size;290ofs += block_nbytes + sizeof(header);291break;292}293294case BLOCK_STATE_VALID: {295uint16_t block_nbytes = (header.num_blocks_minus_one+1)*block_size;296uint16_t block_ofs = header.block_num*block_size;297if (block_ofs + block_nbytes > storage_size) {298// the data is invalid (out of range)299return false;300}301if (!flash_read(sector, ofs+sizeof(header), &mem_buffer[block_ofs], block_nbytes)) {302return false;303}304//debug("read at %u for %u\n", block_ofs, block_nbytes);305ofs += block_nbytes + sizeof(header);306break;307}308default:309// invalid state310return false;311}312#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7313// offsets must be advanced to a multiple of 32 on H7314ofs = (ofs + 31U) & ~31U;315#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4316// offsets must be advanced to a multiple of 8 on G4317ofs = (ofs + 7U) & ~7U;318#endif319}320write_offset = ofs;321return true;322}323324/*325erase one sector326*/327bool AP_FlashStorage::erase_sector(uint8_t sector, bool mark_available)328{329if (!flash_erase(sector)) {330return false;331}332if (!mark_available) {333return true;334}335struct sector_header header;336header.set_state(SECTOR_STATE_AVAILABLE);337return flash_write(sector, 0, (const uint8_t *)&header, sizeof(header));338}339340/*341erase both sectors342*/343bool AP_FlashStorage::erase_all(void)344{345write_error = false;346347current_sector = 0;348write_offset = sizeof(struct sector_header);349350if (!erase_sector(0, current_sector!=0)) {351return false;352}353if (!erase_sector(1, current_sector!=1)) {354return false;355}356357// mark current sector as in-use358struct sector_header header;359header.set_state(SECTOR_STATE_IN_USE);360return flash_write(current_sector, 0, (const uint8_t *)&header, sizeof(header));361}362363/*364write all of mem_buffer to current sector365*/366bool AP_FlashStorage::write_all()367{368debug("write_all to sector %u at %u with reserved_space=%u\n",369current_sector, write_offset, reserved_space);370for (uint16_t ofs=0; ofs<storage_size; ofs += max_write) {371// local variable needed to overcome problem with MIN() macro and -O0372const uint8_t max_write_local = max_write;373uint8_t n = MIN(max_write_local, storage_size-ofs);374if (!all_zero(ofs, n)) {375if (!write(ofs, n)) {376return false;377}378}379}380return true;381}382383// return true if all bytes are zero384bool AP_FlashStorage::all_zero(uint16_t ofs, uint16_t size)385{386while (size--) {387if (mem_buffer[ofs++] != 0) {388return false;389}390}391return true;392}393394// switch to next sector for writing395bool AP_FlashStorage::switch_sectors(void)396{397if (reserved_space != 0) {398// other sector is already full399debug("both sectors are full\n");400return false;401}402403struct sector_header header;404405uint8_t new_sector = current_sector ^ 1;406debug("switching to sector %u\n", new_sector);407408// check sector is available409if (!flash_read(new_sector, 0, (uint8_t *)&header, sizeof(header))) {410return false;411}412if (!header.signature_ok()) {413write_error = true;414return false;415}416if (SECTOR_STATE_AVAILABLE != header.get_state()) {417write_error = true;418debug("new sector unavailable; state=0x%02x\n", (unsigned)header.get_state());419return false;420}421422// mark current sector as full. This needs to be done before we423// mark the new sector as in-use so that a power failure between424// the two steps doesn't leave us with an erase on the425// reboot. Thanks to night-ghost for spotting this.426header.set_state(SECTOR_STATE_FULL);427if (!flash_write(current_sector, 0, (const uint8_t *)&header, sizeof(header))) {428return false;429}430431// mark new sector as in-use432header.set_state(SECTOR_STATE_IN_USE);433if (!flash_write(new_sector, 0, (const uint8_t *)&header, sizeof(header))) {434return false;435}436437// switch sectors438current_sector = new_sector;439440// we need to reserve some space in next sector to ensure we can successfully do a441// full write out on init()442reserved_space = reserve_size;443444write_offset = sizeof(header);445return true;446}447448/*449re-initialise, using current mem_buffer450*/451bool AP_FlashStorage::re_initialise(void)452{453if (!flash_erase_ok()) {454return false;455}456if (!erase_all()) {457return false;458}459return write_all();460}461462#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7463/*464H7 specific sector header functions465*/466bool AP_FlashStorage::sector_header::signature_ok(void) const467{468for (uint8_t i=0; i<ARRAY_SIZE(pad1); i++) {469if (pad1[i] != 0xFFFFFFFFU || pad2[i] != 0xFFFFFFFFU || pad3[i] != 0xFFFFFFFFU) {470return false;471}472}473return signature1 == signature;474}475476AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const477{478if (state1 == 0xFFFFFFF1 &&479state2 == 0xFFFFFFFF &&480state3 == 0xFFFFFFFF &&481signature1 == signature &&482signature2 == 0xFFFFFFFF &&483signature3 == 0xFFFFFFFF) {484return SECTOR_STATE_AVAILABLE;485}486if (state1 == 0xFFFFFFF1 &&487state2 == 0xFFFFFFF2 &&488state3 == 0xFFFFFFFF &&489signature1 == signature &&490signature2 == signature &&491signature3 == 0xFFFFFFFF) {492return SECTOR_STATE_IN_USE;493}494if (state1 == 0xFFFFFFF1 &&495state2 == 0xFFFFFFF2 &&496state3 == 0xFFFFFFF3 &&497signature1 == signature &&498signature2 == signature &&499signature3 == signature) {500return SECTOR_STATE_FULL;501}502return SECTOR_STATE_INVALID;503}504505void AP_FlashStorage::sector_header::set_state(SectorState state)506{507memset(pad1, 0xff, sizeof(pad1));508memset(pad2, 0xff, sizeof(pad2));509memset(pad3, 0xff, sizeof(pad3));510switch (state) {511case SECTOR_STATE_AVAILABLE:512signature1 = signature;513signature2 = 0xFFFFFFFF;514signature3 = 0xFFFFFFFF;515state1 = 0xFFFFFFF1;516state2 = 0xFFFFFFFF;517state3 = 0xFFFFFFFF;518break;519case SECTOR_STATE_IN_USE:520signature1 = signature;521signature2 = signature;522signature3 = 0xFFFFFFFF;523state1 = 0xFFFFFFF1;524state2 = 0xFFFFFFF2;525state3 = 0xFFFFFFFF;526break;527case SECTOR_STATE_FULL:528signature1 = signature;529signature2 = signature;530signature3 = signature;531state1 = 0xFFFFFFF1;532state2 = 0xFFFFFFF2;533state3 = 0xFFFFFFF3;534break;535default:536break;537}538}539540#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4541/*542G4 specific sector header functions543*/544bool AP_FlashStorage::sector_header::signature_ok(void) const545{546return signature1 == signature;547}548549AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const550{551if (state1 == 0xFFFFFFF1 &&552state2 == 0xFFFFFFFF &&553state3 == 0xFFFFFFFF &&554signature1 == signature &&555signature2 == 0xFFFFFFFF &&556signature3 == 0xFFFFFFFF) {557return SECTOR_STATE_AVAILABLE;558}559if (state1 == 0xFFFFFFF1 &&560state2 == 0xFFFFFFF2 &&561state3 == 0xFFFFFFFF &&562signature1 == signature &&563signature2 == signature &&564signature3 == 0xFFFFFFFF) {565return SECTOR_STATE_IN_USE;566}567if (state1 == 0xFFFFFFF1 &&568state2 == 0xFFFFFFF2 &&569state3 == 0xFFFFFFF3 &&570signature1 == signature &&571signature2 == signature &&572signature3 == signature) {573return SECTOR_STATE_FULL;574}575return SECTOR_STATE_INVALID;576}577578void AP_FlashStorage::sector_header::set_state(SectorState state)579{580switch (state) {581case SECTOR_STATE_AVAILABLE:582signature1 = signature;583signature2 = 0xFFFFFFFF;584signature3 = 0xFFFFFFFF;585state1 = 0xFFFFFFF1;586state2 = 0xFFFFFFFF;587state3 = 0xFFFFFFFF;588break;589case SECTOR_STATE_IN_USE:590signature1 = signature;591signature2 = signature;592signature3 = 0xFFFFFFFF;593state1 = 0xFFFFFFF1;594state2 = 0xFFFFFFF2;595state3 = 0xFFFFFFFF;596break;597case SECTOR_STATE_FULL:598signature1 = signature;599signature2 = signature;600signature3 = signature;601state1 = 0xFFFFFFF1;602state2 = 0xFFFFFFF2;603state3 = 0xFFFFFFF3;604break;605default:606break;607}608}609610#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F1611/*612F1/F3 specific sector header functions613*/614bool AP_FlashStorage::sector_header::signature_ok(void) const615{616return signature1 == signature;617}618619AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const620{621if (state1 == 0xFFFFFFFF) {622return SECTOR_STATE_AVAILABLE;623}624if (state1 == 0xFFFFFFF1) {625return SECTOR_STATE_IN_USE;626}627if (state1 == 0xFFF2FFF1) {628return SECTOR_STATE_FULL;629}630return SECTOR_STATE_INVALID;631}632633void AP_FlashStorage::sector_header::set_state(SectorState state)634{635signature1 = signature;636switch (state) {637case SECTOR_STATE_AVAILABLE:638state1 = 0xFFFFFFFF;639break;640case SECTOR_STATE_IN_USE:641state1 = 0xFFFFFFF1;642break;643case SECTOR_STATE_FULL:644state1 = 0xFFF2FFF1;645break;646default:647break;648}649}650#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F4651/*652F4 specific sector header functions653*/654bool AP_FlashStorage::sector_header::signature_ok(void) const655{656return signature1 == signature;657}658659AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const660{661if (state1 == 0xFF) {662return SECTOR_STATE_AVAILABLE;663}664if (state1 == 0xFE) {665return SECTOR_STATE_IN_USE;666}667if (state1 == 0xFC) {668return SECTOR_STATE_FULL;669}670return SECTOR_STATE_INVALID;671}672673void AP_FlashStorage::sector_header::set_state(SectorState state)674{675signature1 = signature;676switch (state) {677case SECTOR_STATE_AVAILABLE:678state1 = 0xFF;679break;680case SECTOR_STATE_IN_USE:681state1 = 0xFE;682break;683case SECTOR_STATE_FULL:684state1 = 0xFC;685break;686default:687break;688}689}690#endif691692693