AP_FlashStorage.h 5.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176
  1. /*
  2. Please contribute your ideas! See http://dev.ardupilot.org for details
  3. This program is free software: you can redistribute it and/or modify
  4. it under the terms of the GNU General Public License as published by
  5. the Free Software Foundation, either version 3 of the License, or
  6. (at your option) any later version.
  7. This program is distributed in the hope that it will be useful,
  8. but WITHOUT ANY WARRANTY; without even the implied warranty of
  9. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  10. GNU General Public License for more details.
  11. You should have received a copy of the GNU General Public License
  12. along with this program. If not, see <http://www.gnu.org/licenses/>.
  13. */
  14. /*
  15. a class to allow for FLASH to be used as a memory backed storage
  16. backend for any HAL. The basic methodology is to use a log based
  17. storage system over two flash sectors. Key design elements:
  18. - erase of sectors only called on init, as erase will lock the flash
  19. and prevent code execution
  20. - write using log based system
  21. - read requires scan of all log elements. This is expected to be called rarely
  22. - assumes flash that erases to 0xFF and where writing can only clear
  23. bits, not set them
  24. - assumes flash sectors are much bigger than storage size. If they
  25. aren't then caller can aggregate multiple sectors. Designed for
  26. 128k flash sectors with 16k storage size.
  27. - assumes two flash sectors are available
  28. */
  29. #pragma once
  30. #include <AP_HAL/AP_HAL.h>
  31. #if defined(STM32F1)
  32. /*
  33. the STM32F1 can't change individual bits from 1 to 0 unless all bits in
  34. the 16 bit word are 1
  35. */
  36. #define AP_FLASHSTORAGE_MULTI_WRITE 0
  37. #else
  38. #define AP_FLASHSTORAGE_MULTI_WRITE 1
  39. #endif
  40. /*
  41. The StorageManager holds the layout of non-volatile storeage
  42. */
  43. class AP_FlashStorage {
  44. private:
  45. static const uint8_t block_size = 8;
  46. static const uint16_t num_blocks = HAL_STORAGE_SIZE / block_size;
  47. static const uint8_t max_write = 64;
  48. public:
  49. // caller provided function to write to a flash sector
  50. FUNCTOR_TYPEDEF(FlashWrite, bool, uint8_t , uint32_t , const uint8_t *, uint16_t );
  51. // caller provided function to read from a flash sector. Only called on init()
  52. FUNCTOR_TYPEDEF(FlashRead, bool, uint8_t , uint32_t , uint8_t *, uint16_t );
  53. // caller provided function to erase a flash sector. Only called from init()
  54. FUNCTOR_TYPEDEF(FlashErase, bool, uint8_t );
  55. // caller provided function to indicate if erasing is allowed
  56. FUNCTOR_TYPEDEF(FlashEraseOK, bool);
  57. // constructor.
  58. AP_FlashStorage(uint8_t *mem_buffer, // buffer of storage_size bytes
  59. uint32_t flash_sector_size, // size of each flash sector in bytes
  60. FlashWrite flash_write, // function to write to flash
  61. FlashRead flash_read, // function to read from flash
  62. FlashErase flash_erase, // function to erase flash
  63. FlashEraseOK flash_erase_ok); // function to check if erasing allowed
  64. // initialise storage, filling mem_buffer with current contents
  65. bool init(void);
  66. // re-initialise storage, using current mem_buffer
  67. bool re_initialise(void);
  68. // switch full sector - should only be called when safe to have CPU
  69. // offline for considerable periods as an erase will be needed
  70. bool switch_full_sector(void);
  71. // write some data to storage from mem_buffer
  72. bool write(uint16_t offset, uint16_t length);
  73. // fixed storage size
  74. static const uint16_t storage_size = block_size * num_blocks;
  75. private:
  76. uint8_t *mem_buffer;
  77. const uint32_t flash_sector_size;
  78. FlashWrite flash_write;
  79. FlashRead flash_read;
  80. FlashErase flash_erase;
  81. FlashEraseOK flash_erase_ok;
  82. uint8_t current_sector;
  83. uint32_t write_offset;
  84. uint32_t reserved_space;
  85. bool write_error;
  86. // 24 bit signature
  87. #if AP_FLASHSTORAGE_MULTI_WRITE
  88. static const uint32_t signature = 0x51685B;
  89. #else
  90. static const uint32_t signature = 0x51;
  91. #endif
  92. // 8 bit sector states
  93. enum SectorState {
  94. #if AP_FLASHSTORAGE_MULTI_WRITE
  95. SECTOR_STATE_AVAILABLE = 0xFF,
  96. SECTOR_STATE_IN_USE = 0xFE,
  97. SECTOR_STATE_FULL = 0xFC
  98. #else
  99. SECTOR_STATE_AVAILABLE = 0xFFFFFFFF,
  100. SECTOR_STATE_IN_USE = 0xFFFFFFF1,
  101. SECTOR_STATE_FULL = 0xFFF2FFF1,
  102. #endif
  103. };
  104. // header in first word of each sector
  105. struct sector_header {
  106. #if AP_FLASHSTORAGE_MULTI_WRITE
  107. uint32_t state:8;
  108. uint32_t signature:24;
  109. #else
  110. uint32_t state:32;
  111. uint32_t signature:16;
  112. #endif
  113. };
  114. enum BlockState {
  115. BLOCK_STATE_AVAILABLE = 0x3,
  116. BLOCK_STATE_WRITING = 0x1,
  117. BLOCK_STATE_VALID = 0x0
  118. };
  119. // header of each block of data
  120. struct block_header {
  121. uint16_t state:2;
  122. uint16_t block_num:11;
  123. uint16_t num_blocks_minus_one:3;
  124. };
  125. // amount of space needed to write full storage
  126. static const uint32_t reserve_size = (storage_size / max_write) * (sizeof(block_header) + max_write) + max_write;
  127. // load data from a sector
  128. bool load_sector(uint8_t sector);
  129. // erase a sector and write header
  130. bool erase_sector(uint8_t sector);
  131. // erase all sectors and reset
  132. bool erase_all();
  133. // write all of mem_buffer to current sector
  134. bool write_all();
  135. // return true if all bytes are zero
  136. bool all_zero(uint16_t ofs, uint16_t size);
  137. // switch to next sector for writing
  138. bool switch_sectors(void);
  139. };