APM:Libraries
AP_FlashStorage.cpp
Go to the documentation of this file.
1 /*
2  Please contribute your ideas! See http://dev.ardupilot.org for details
3 
4  This program is free software: you can redistribute it and/or modify
5  it under the terms of the GNU General Public License as published by
6  the Free Software Foundation, either version 3 of the License, or
7  (at your option) any later version.
8 
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13 
14  You should have received a copy of the GNU General Public License
15  along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <AP_HAL/AP_HAL.h>
20 #include <stdio.h>
21 
22 #define FLASHSTORAGE_DEBUG 0
23 
24 #if FLASHSTORAGE_DEBUG
25 #define debug(fmt, args...) do { printf(fmt, ##args); } while(0)
26 #else
27 #define debug(fmt, args...) do { } while(0)
28 #endif
29 
30 // constructor.
31 AP_FlashStorage::AP_FlashStorage(uint8_t *_mem_buffer,
32  uint32_t _flash_sector_size,
33  FlashWrite _flash_write,
34  FlashRead _flash_read,
35  FlashErase _flash_erase,
36  FlashEraseOK _flash_erase_ok) :
37  mem_buffer(_mem_buffer),
38  flash_sector_size(_flash_sector_size),
39  flash_write(_flash_write),
40  flash_read(_flash_read),
41  flash_erase(_flash_erase),
42  flash_erase_ok(_flash_erase_ok) {}
43 
44 // initialise storage
46 {
47  debug("running init()\n");
48 
49  // start with empty memory buffer
50  memset(mem_buffer, 0, storage_size);
51 
52  // find state of sectors
53  struct sector_header header[2];
54 
55  // read headers and possibly initialise if bad signature
56  for (uint8_t i=0; i<2; i++) {
57  if (!flash_read(i, 0, (uint8_t *)&header[i], sizeof(header[i]))) {
58  return false;
59  }
60  bool bad_header = (header[i].signature != signature);
61  enum SectorState state = (enum SectorState)header[i].state;
62  if (state != SECTOR_STATE_AVAILABLE &&
63  state != SECTOR_STATE_IN_USE &&
64  state != SECTOR_STATE_FULL) {
65  bad_header = true;
66  }
67 
68  // initialise if bad header
69  if (bad_header) {
70  return erase_all();
71  }
72  }
73 
74  // work out the first sector to read from using sector states
75  enum SectorState states[2] {(enum SectorState)header[0].state, (enum SectorState)header[1].state};
76  uint8_t first_sector;
77 
78  if (states[0] == states[1]) {
79  if (states[0] != SECTOR_STATE_AVAILABLE) {
80  return erase_all();
81  }
82  first_sector = 0;
83  } else if (states[0] == SECTOR_STATE_FULL) {
84  first_sector = 0;
85  } else if (states[1] == SECTOR_STATE_FULL) {
86  first_sector = 1;
87  } else if (states[0] == SECTOR_STATE_IN_USE) {
88  first_sector = 0;
89  } else if (states[1] == SECTOR_STATE_IN_USE) {
90  first_sector = 1;
91  } else {
92  // doesn't matter which is first
93  first_sector = 0;
94  }
95 
96  // load data from any current sectors
97  for (uint8_t i=0; i<2; i++) {
98  uint8_t sector = (first_sector + i) & 1;
99  if (states[sector] == SECTOR_STATE_IN_USE ||
100  states[sector] == SECTOR_STATE_FULL) {
101  if (!load_sector(sector)) {
102  return erase_all();
103  }
104  }
105  }
106 
107  // clear any write error
108  write_error = false;
109  reserved_space = 0;
110 
111  // if the first sector is full then write out all data so we can erase it
112  if (states[first_sector] == SECTOR_STATE_FULL) {
113  current_sector = first_sector ^ 1;
114  if (!write_all()) {
115  return erase_all();
116  }
117  }
118 
119  // erase any sectors marked full
120  for (uint8_t i=0; i<2; i++) {
121  if (states[i] == SECTOR_STATE_FULL) {
122  if (!erase_sector(i)) {
123  return false;
124  }
125  }
126  }
127 
128  reserved_space = 0;
129 
130  // ready to use
131  return true;
132 }
133 
134 
135 
136 // switch full sector - should only be called when safe to have CPU
137 // offline for considerable periods as an erase will be needed
139 {
140  debug("running switch_full_sector()\n");
141 
142  // clear any write error
143  write_error = false;
144  reserved_space = 0;
145 
146  if (!write_all()) {
147  return false;
148  }
149 
150  if (!erase_sector(current_sector ^ 1)) {
151  return false;
152  }
153 
154  return switch_sectors();
155 }
156 
157 // write some data to virtual EEPROM
158 bool AP_FlashStorage::write(uint16_t offset, uint16_t length)
159 {
160  if (write_error) {
161  return false;
162  }
163  //debug("write at %u for %u write_offset=%u\n", offset, length, write_offset);
164 
165  while (length > 0) {
166  uint8_t n = max_write;
167  if (length < n) {
168  n = length;
169  }
170 
171  if (write_offset > flash_sector_size - (sizeof(struct block_header) + max_write + reserved_space)) {
172  if (!switch_sectors()) {
173  if (!flash_erase_ok()) {
174  return false;
175  }
176  if (!switch_full_sector()) {
177  return false;
178  }
179  }
180  }
181 
182  struct block_header header;
183  header.state = BLOCK_STATE_WRITING;
184  header.block_num = offset / block_size;
185  header.num_blocks_minus_one = ((n + (block_size - 1)) / block_size)-1;
186  uint16_t block_ofs = header.block_num*block_size;
187  uint16_t block_nbytes = (header.num_blocks_minus_one+1)*block_size;
188 
189  if (!flash_write(current_sector, write_offset, (uint8_t*)&header, sizeof(header))) {
190  return false;
191  }
192  if (!flash_write(current_sector, write_offset+sizeof(header), &mem_buffer[block_ofs], block_nbytes)) {
193  return false;
194  }
195  header.state = BLOCK_STATE_VALID;
196  if (!flash_write(current_sector, write_offset, (uint8_t*)&header, sizeof(header))) {
197  return false;
198  }
199  write_offset += sizeof(header) + block_nbytes;
200 
201  uint8_t n2 = block_nbytes - (offset % block_size);
202  //debug("write_block at %u for %u n2=%u\n", block_ofs, block_nbytes, n2);
203  if (n2 > length) {
204  break;
205  }
206  offset += n2;
207  length -= n2;
208  }
209 
210  // handle wrap to next sector
211  // write data
212  // write header word
213  return true;
214 }
215 
216 /*
217  load all data from a flash sector into mem_buffer
218  */
219 bool AP_FlashStorage::load_sector(uint8_t sector)
220 {
221  uint32_t ofs = sizeof(sector_header);
222  while (ofs < flash_sector_size - sizeof(struct block_header)) {
223  struct block_header header;
224  if (!flash_read(sector, ofs, (uint8_t *)&header, sizeof(header))) {
225  return false;
226  }
227  enum BlockState state = (enum BlockState)header.state;
228 
229  switch (state) {
231  // we've reached the end
232  write_offset = ofs;
233  return true;
234 
235  case BLOCK_STATE_WRITING: {
236  /*
237  we were interrupted while writing a block. We can't
238  re-use the data in this block as it may have some bits
239  that are not set to 1, so by flash rules can't be set to
240  an arbitrary value. So we skip over this block, leaving
241  a gap. The gap size is limited to (7+1)*8=64 bytes. That
242  gap won't be recovered until we next do an erase of this
243  sector
244  */
245  uint16_t block_nbytes = (header.num_blocks_minus_one+1)*block_size;
246  ofs += block_nbytes + sizeof(header);
247  break;
248  }
249 
250  case BLOCK_STATE_VALID: {
251  uint16_t block_nbytes = (header.num_blocks_minus_one+1)*block_size;
252  uint16_t block_ofs = header.block_num*block_size;
253  if (block_ofs + block_nbytes > storage_size) {
254  // the data is invalid (out of range)
255  return false;
256  }
257  if (!flash_read(sector, ofs+sizeof(header), &mem_buffer[block_ofs], block_nbytes)) {
258  return false;
259  }
260  //debug("read at %u for %u\n", block_ofs, block_nbytes);
261  ofs += block_nbytes + sizeof(header);
262  break;
263  }
264  default:
265  // invalid state
266  return false;
267  }
268  }
269  write_offset = ofs;
270  return true;
271 }
272 
273 /*
274  erase one sector
275  */
276 bool AP_FlashStorage::erase_sector(uint8_t sector)
277 {
278  if (!flash_erase(sector)) {
279  return false;
280  }
281 
282  struct sector_header header;
283  header.signature = signature;
284  header.state = SECTOR_STATE_AVAILABLE;
285  return flash_write(sector, 0, (const uint8_t *)&header, sizeof(header));
286 }
287 
288 /*
289  erase both sectors
290  */
292 {
293  write_error = false;
294 
295  current_sector = 0;
296  write_offset = sizeof(struct sector_header);
297 
298  if (!erase_sector(0) || !erase_sector(1)) {
299  return false;
300  }
301 
302  // mark current sector as in-use
303  struct sector_header header;
304  header.signature = signature;
305  header.state = SECTOR_STATE_IN_USE;
306  return flash_write(current_sector, 0, (const uint8_t *)&header, sizeof(header));
307 }
308 
309 /*
310  write all of mem_buffer to current sector
311  */
313 {
314  debug("write_all to sector %u at %u with reserved_space=%u\n",
316  for (uint16_t ofs=0; ofs<storage_size; ofs += max_write) {
317  if (!all_zero(ofs, max_write)) {
318  if (!write(ofs, max_write)) {
319  return false;
320  }
321  }
322  }
323  return true;
324 }
325 
326 // return true if all bytes are zero
327 bool AP_FlashStorage::all_zero(uint16_t ofs, uint16_t size)
328 {
329  while (size--) {
330  if (mem_buffer[ofs++] != 0) {
331  return false;
332  }
333  }
334  return true;
335 }
336 
337 // switch to next sector for writing
339 {
340  if (reserved_space != 0) {
341  // other sector is already full
342  debug("both sectors are full\n");
343  return false;
344  }
345 
346  struct sector_header header;
347  header.signature = signature;
348 
349  uint8_t new_sector = current_sector ^ 1;
350  debug("switching to sector %u\n", new_sector);
351 
352  // check sector is available
353  if (!flash_read(new_sector, 0, (uint8_t *)&header, sizeof(header))) {
354  return false;
355  }
356  if (header.signature != signature) {
357  write_error = true;
358  return false;
359  }
360  if (SECTOR_STATE_AVAILABLE != (enum SectorState)header.state) {
361  write_error = true;
362  debug("both sectors full\n");
363  return false;
364  }
365 
366  // mark current sector as full. This needs to be done before we
367  // mark the new sector as in-use so that a power failure between
368  // the two steps doesn't leave us with an erase on the
369  // reboot. Thanks to night-ghost for spotting this.
370  header.state = SECTOR_STATE_FULL;
371  if (!flash_write(current_sector, 0, (const uint8_t *)&header, sizeof(header))) {
372  return false;
373  }
374 
375  // mark new sector as in-use
376  header.state = SECTOR_STATE_IN_USE;
377  if (!flash_write(new_sector, 0, (const uint8_t *)&header, sizeof(header))) {
378  return false;
379  }
380 
381  // switch sectors
382  current_sector = new_sector;
383 
384  // we need to reserve some space in next sector to ensure we can successfully do a
385  // full write out on init()
387 
388  write_offset = sizeof(header);
389  return true;
390 }
391 
392 /*
393  re-initialise, using current mem_buffer
394  */
396 {
397  if (!flash_erase_ok()) {
398  return false;
399  }
400  if (!erase_all()) {
401  return false;
402  }
403  return write_all();
404 }
bool switch_sectors(void)
FlashWrite flash_write
FlashErase flash_erase
uint8_t current_sector
static const uint32_t reserve_size
uint32_t reserved_space
FlashRead flash_read
bool switch_full_sector(void)
bool erase_sector(uint8_t sector)
static const uint16_t storage_size
bool all_zero(uint16_t ofs, uint16_t size)
static const uint8_t block_size
static int state
Definition: Util.cpp:20
bool write(uint16_t offset, uint16_t length)
#define debug(fmt, args...)
FlashEraseOK flash_erase_ok
const uint32_t flash_sector_size
uint8_t * mem_buffer
uint32_t write_offset
bool re_initialise(void)
static const uint8_t max_write
bool load_sector(uint8_t sector)
AP_FlashStorage(uint8_t *mem_buffer, uint32_t flash_sector_size, FlashWrite flash_write, FlashRead flash_read, FlashErase flash_erase, FlashEraseOK flash_erase_ok)
static const uint32_t signature