CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_FlashStorage/AP_FlashStorage.cpp
Views: 1798
1
/*
2
Please contribute your ideas! See https://ardupilot.org/dev 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>
19
#include <AP_FlashStorage/AP_FlashStorage.h>
20
#include <AP_Math/AP_Math.h>
21
#include <AP_InternalError/AP_InternalError.h>
22
#include <stdio.h>
23
24
#define FLASHSTORAGE_DEBUG 0
25
26
#if FLASHSTORAGE_DEBUG
27
#define debug(fmt, args...) do { printf(fmt, ##args); } while(0)
28
#else
29
#define debug(fmt, args...) do { } while(0)
30
#endif
31
32
// constructor.
33
AP_FlashStorage::AP_FlashStorage(uint8_t *_mem_buffer,
34
uint32_t _flash_sector_size,
35
FlashWrite _flash_write,
36
FlashRead _flash_read,
37
FlashErase _flash_erase,
38
FlashEraseOK _flash_erase_ok) :
39
mem_buffer(_mem_buffer),
40
flash_sector_size(_flash_sector_size),
41
flash_write(_flash_write),
42
flash_read(_flash_read),
43
flash_erase(_flash_erase),
44
flash_erase_ok(_flash_erase_ok) {}
45
46
// initialise storage
47
bool AP_FlashStorage::init(void)
48
{
49
debug("running init()\n");
50
51
// start with empty memory buffer
52
memset(mem_buffer, 0, storage_size);
53
54
// find state of sectors
55
struct sector_header header[2];
56
57
// read headers and possibly initialise if bad signature
58
for (uint8_t i=0; i<2; i++) {
59
if (!flash_read(i, 0, (uint8_t *)&header[i], sizeof(header[i]))) {
60
return false;
61
}
62
bool bad_header = !header[i].signature_ok();
63
enum SectorState state = header[i].get_state();
64
if (state != SECTOR_STATE_AVAILABLE &&
65
state != SECTOR_STATE_IN_USE &&
66
state != SECTOR_STATE_FULL) {
67
bad_header = true;
68
}
69
70
// initialise if bad header
71
if (bad_header) {
72
return erase_all();
73
}
74
}
75
76
// work out the first sector to read from using sector states
77
enum SectorState states[2] {header[0].get_state(), header[1].get_state()};
78
uint8_t first_sector;
79
80
if (states[0] == states[1]) {
81
if (states[0] != SECTOR_STATE_AVAILABLE) {
82
return erase_all();
83
}
84
first_sector = 0;
85
} else if (states[0] == SECTOR_STATE_FULL) {
86
first_sector = 0;
87
} else if (states[1] == SECTOR_STATE_FULL) {
88
first_sector = 1;
89
} else if (states[0] == SECTOR_STATE_IN_USE) {
90
first_sector = 0;
91
} else if (states[1] == SECTOR_STATE_IN_USE) {
92
first_sector = 1;
93
} else {
94
// doesn't matter which is first
95
first_sector = 0;
96
}
97
98
// load data from any current sectors
99
for (uint8_t i=0; i<2; i++) {
100
uint8_t sector = (first_sector + i) & 1;
101
if (states[sector] == SECTOR_STATE_IN_USE ||
102
states[sector] == SECTOR_STATE_FULL) {
103
if (!load_sector(sector)) {
104
return erase_all();
105
}
106
}
107
}
108
109
// clear any write error
110
write_error = false;
111
reserved_space = 0;
112
113
// if the first sector is full then write out all data so we can erase it
114
if (states[first_sector] == SECTOR_STATE_FULL) {
115
current_sector = first_sector ^ 1;
116
if (!write_all()) {
117
return erase_all();
118
}
119
}
120
121
// erase any sectors marked full
122
for (uint8_t i=0; i<2; i++) {
123
if (states[i] == SECTOR_STATE_FULL) {
124
if (!erase_sector(i, true)) {
125
return false;
126
}
127
}
128
}
129
130
reserved_space = 0;
131
132
// ready to use
133
return true;
134
}
135
136
137
138
// switch full sector - should only be called when safe to have CPU
139
// offline for considerable periods as an erase will be needed
140
bool AP_FlashStorage::switch_full_sector(void)
141
{
142
debug("running switch_full_sector()\n");
143
144
if (in_switch_full_sector) {
145
INTERNAL_ERROR(AP_InternalError::error_t::switch_full_sector_recursion);
146
return false;
147
}
148
in_switch_full_sector = true;
149
bool ret = protected_switch_full_sector();
150
in_switch_full_sector = false;
151
return ret;
152
}
153
154
// protected_switch_full_sector is protected by switch_full_sector to
155
// avoid an infinite recursion problem; switch_full_sector calls
156
// write() which can call switch_full_sector. This has been seen in
157
// practice, and while it might be caused by corruption... corruption
158
// happens.
159
bool AP_FlashStorage::protected_switch_full_sector(void)
160
{
161
// clear any write error
162
write_error = false;
163
reserved_space = 0;
164
165
if (!write_all()) {
166
return false;
167
}
168
169
if (!erase_sector(current_sector ^ 1, true)) {
170
return false;
171
}
172
173
return switch_sectors();
174
}
175
176
// write some data to virtual EEPROM
177
bool AP_FlashStorage::write(uint16_t offset, uint16_t length)
178
{
179
if (write_error) {
180
return false;
181
}
182
//debug("write at %u for %u write_offset=%u\n", offset, length, write_offset);
183
184
while (length > 0) {
185
uint8_t n = max_write;
186
#if AP_FLASHSTORAGE_TYPE != AP_FLASHSTORAGE_TYPE_H7 && AP_FLASHSTORAGE_TYPE != AP_FLASHSTORAGE_TYPE_G4
187
if (length < n) {
188
n = length;
189
}
190
#endif
191
192
const uint32_t space_available = flash_sector_size - write_offset;
193
const uint32_t space_required = sizeof(struct block_header) + max_write + reserved_space;
194
if (space_available < space_required) {
195
if (!switch_sectors()) {
196
if (!flash_erase_ok()) {
197
return false;
198
}
199
if (!switch_full_sector()) {
200
return false;
201
}
202
}
203
}
204
205
struct PACKED {
206
struct block_header header;
207
uint8_t data[max_write];
208
} blk;
209
210
blk.header.state = BLOCK_STATE_WRITING;
211
blk.header.block_num = offset / block_size;
212
blk.header.num_blocks_minus_one = ((n + (block_size - 1)) / block_size)-1;
213
214
uint16_t block_ofs = blk.header.block_num*block_size;
215
uint16_t block_nbytes = (blk.header.num_blocks_minus_one+1)*block_size;
216
217
memcpy(blk.data, &mem_buffer[block_ofs], block_nbytes);
218
219
#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F4
220
if (!flash_write(current_sector, write_offset, (uint8_t*)&blk.header, sizeof(blk.header))) {
221
return false;
222
}
223
if (!flash_write(current_sector, write_offset+sizeof(blk.header), blk.data, block_nbytes)) {
224
return false;
225
}
226
blk.header.state = BLOCK_STATE_VALID;
227
if (!flash_write(current_sector, write_offset, (uint8_t*)&blk.header, sizeof(blk.header))) {
228
return false;
229
}
230
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F1
231
blk.header.state = BLOCK_STATE_VALID;
232
if (!flash_write(current_sector, write_offset, (uint8_t*)&blk, sizeof(blk.header) + block_nbytes)) {
233
return false;
234
}
235
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7 || AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4
236
blk.header.state = BLOCK_STATE_VALID;
237
if (!flash_write(current_sector, write_offset, (uint8_t*)&blk, sizeof(blk.header) + max_write)) {
238
return false;
239
}
240
#endif
241
242
write_offset += sizeof(blk.header) + block_nbytes;
243
244
uint8_t n2 = block_nbytes - (offset % block_size);
245
//debug("write_block at %u for %u n2=%u\n", block_ofs, block_nbytes, n2);
246
if (n2 > length) {
247
break;
248
}
249
offset += n2;
250
length -= n2;
251
}
252
253
//debug("write_offset %u\n", write_offset);
254
255
// handle wrap to next sector
256
// write data
257
// write header word
258
return true;
259
}
260
261
/*
262
load all data from a flash sector into mem_buffer
263
*/
264
bool AP_FlashStorage::load_sector(uint8_t sector)
265
{
266
uint32_t ofs = sizeof(sector_header);
267
while (ofs < flash_sector_size - sizeof(struct block_header)) {
268
struct block_header header;
269
if (!flash_read(sector, ofs, (uint8_t *)&header, sizeof(header))) {
270
return false;
271
}
272
enum BlockState state = (enum BlockState)header.state;
273
274
switch (state) {
275
case BLOCK_STATE_AVAILABLE:
276
// we've reached the end
277
write_offset = ofs;
278
return true;
279
280
case BLOCK_STATE_WRITING: {
281
/*
282
we were interrupted while writing a block. We can't
283
re-use the data in this block as it may have some bits
284
that are not set to 1, so by flash rules can't be set to
285
an arbitrary value. So we skip over this block, leaving
286
a gap. The gap size is limited to (7+1)*8=64 bytes. That
287
gap won't be recovered until we next do an erase of this
288
sector
289
*/
290
uint16_t block_nbytes = (header.num_blocks_minus_one+1)*block_size;
291
ofs += block_nbytes + sizeof(header);
292
break;
293
}
294
295
case BLOCK_STATE_VALID: {
296
uint16_t block_nbytes = (header.num_blocks_minus_one+1)*block_size;
297
uint16_t block_ofs = header.block_num*block_size;
298
if (block_ofs + block_nbytes > storage_size) {
299
// the data is invalid (out of range)
300
return false;
301
}
302
if (!flash_read(sector, ofs+sizeof(header), &mem_buffer[block_ofs], block_nbytes)) {
303
return false;
304
}
305
//debug("read at %u for %u\n", block_ofs, block_nbytes);
306
ofs += block_nbytes + sizeof(header);
307
break;
308
}
309
default:
310
// invalid state
311
return false;
312
}
313
#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7
314
// offsets must be advanced to a multiple of 32 on H7
315
ofs = (ofs + 31U) & ~31U;
316
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4
317
// offsets must be advanced to a multiple of 8 on G4
318
ofs = (ofs + 7U) & ~7U;
319
#endif
320
}
321
write_offset = ofs;
322
return true;
323
}
324
325
/*
326
erase one sector
327
*/
328
bool AP_FlashStorage::erase_sector(uint8_t sector, bool mark_available)
329
{
330
if (!flash_erase(sector)) {
331
return false;
332
}
333
if (!mark_available) {
334
return true;
335
}
336
struct sector_header header;
337
header.set_state(SECTOR_STATE_AVAILABLE);
338
return flash_write(sector, 0, (const uint8_t *)&header, sizeof(header));
339
}
340
341
/*
342
erase both sectors
343
*/
344
bool AP_FlashStorage::erase_all(void)
345
{
346
write_error = false;
347
348
current_sector = 0;
349
write_offset = sizeof(struct sector_header);
350
351
if (!erase_sector(0, current_sector!=0)) {
352
return false;
353
}
354
if (!erase_sector(1, current_sector!=1)) {
355
return false;
356
}
357
358
// mark current sector as in-use
359
struct sector_header header;
360
header.set_state(SECTOR_STATE_IN_USE);
361
return flash_write(current_sector, 0, (const uint8_t *)&header, sizeof(header));
362
}
363
364
/*
365
write all of mem_buffer to current sector
366
*/
367
bool AP_FlashStorage::write_all()
368
{
369
debug("write_all to sector %u at %u with reserved_space=%u\n",
370
current_sector, write_offset, reserved_space);
371
for (uint16_t ofs=0; ofs<storage_size; ofs += max_write) {
372
// local variable needed to overcome problem with MIN() macro and -O0
373
const uint8_t max_write_local = max_write;
374
uint8_t n = MIN(max_write_local, storage_size-ofs);
375
if (!all_zero(ofs, n)) {
376
if (!write(ofs, n)) {
377
return false;
378
}
379
}
380
}
381
return true;
382
}
383
384
// return true if all bytes are zero
385
bool AP_FlashStorage::all_zero(uint16_t ofs, uint16_t size)
386
{
387
while (size--) {
388
if (mem_buffer[ofs++] != 0) {
389
return false;
390
}
391
}
392
return true;
393
}
394
395
// switch to next sector for writing
396
bool AP_FlashStorage::switch_sectors(void)
397
{
398
if (reserved_space != 0) {
399
// other sector is already full
400
debug("both sectors are full\n");
401
return false;
402
}
403
404
struct sector_header header;
405
406
uint8_t new_sector = current_sector ^ 1;
407
debug("switching to sector %u\n", new_sector);
408
409
// check sector is available
410
if (!flash_read(new_sector, 0, (uint8_t *)&header, sizeof(header))) {
411
return false;
412
}
413
if (!header.signature_ok()) {
414
write_error = true;
415
return false;
416
}
417
if (SECTOR_STATE_AVAILABLE != header.get_state()) {
418
write_error = true;
419
debug("new sector unavailable; state=0x%02x\n", (unsigned)header.get_state());
420
return false;
421
}
422
423
// mark current sector as full. This needs to be done before we
424
// mark the new sector as in-use so that a power failure between
425
// the two steps doesn't leave us with an erase on the
426
// reboot. Thanks to night-ghost for spotting this.
427
header.set_state(SECTOR_STATE_FULL);
428
if (!flash_write(current_sector, 0, (const uint8_t *)&header, sizeof(header))) {
429
return false;
430
}
431
432
// mark new sector as in-use
433
header.set_state(SECTOR_STATE_IN_USE);
434
if (!flash_write(new_sector, 0, (const uint8_t *)&header, sizeof(header))) {
435
return false;
436
}
437
438
// switch sectors
439
current_sector = new_sector;
440
441
// we need to reserve some space in next sector to ensure we can successfully do a
442
// full write out on init()
443
reserved_space = reserve_size;
444
445
write_offset = sizeof(header);
446
return true;
447
}
448
449
/*
450
re-initialise, using current mem_buffer
451
*/
452
bool AP_FlashStorage::re_initialise(void)
453
{
454
if (!flash_erase_ok()) {
455
return false;
456
}
457
if (!erase_all()) {
458
return false;
459
}
460
return write_all();
461
}
462
463
#if AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_H7
464
/*
465
H7 specific sector header functions
466
*/
467
bool AP_FlashStorage::sector_header::signature_ok(void) const
468
{
469
for (uint8_t i=0; i<ARRAY_SIZE(pad1); i++) {
470
if (pad1[i] != 0xFFFFFFFFU || pad2[i] != 0xFFFFFFFFU || pad3[i] != 0xFFFFFFFFU) {
471
return false;
472
}
473
}
474
return signature1 == signature;
475
}
476
477
AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const
478
{
479
if (state1 == 0xFFFFFFF1 &&
480
state2 == 0xFFFFFFFF &&
481
state3 == 0xFFFFFFFF &&
482
signature1 == signature &&
483
signature2 == 0xFFFFFFFF &&
484
signature3 == 0xFFFFFFFF) {
485
return SECTOR_STATE_AVAILABLE;
486
}
487
if (state1 == 0xFFFFFFF1 &&
488
state2 == 0xFFFFFFF2 &&
489
state3 == 0xFFFFFFFF &&
490
signature1 == signature &&
491
signature2 == signature &&
492
signature3 == 0xFFFFFFFF) {
493
return SECTOR_STATE_IN_USE;
494
}
495
if (state1 == 0xFFFFFFF1 &&
496
state2 == 0xFFFFFFF2 &&
497
state3 == 0xFFFFFFF3 &&
498
signature1 == signature &&
499
signature2 == signature &&
500
signature3 == signature) {
501
return SECTOR_STATE_FULL;
502
}
503
return SECTOR_STATE_INVALID;
504
}
505
506
void AP_FlashStorage::sector_header::set_state(SectorState state)
507
{
508
memset(pad1, 0xff, sizeof(pad1));
509
memset(pad2, 0xff, sizeof(pad2));
510
memset(pad3, 0xff, sizeof(pad3));
511
switch (state) {
512
case SECTOR_STATE_AVAILABLE:
513
signature1 = signature;
514
signature2 = 0xFFFFFFFF;
515
signature3 = 0xFFFFFFFF;
516
state1 = 0xFFFFFFF1;
517
state2 = 0xFFFFFFFF;
518
state3 = 0xFFFFFFFF;
519
break;
520
case SECTOR_STATE_IN_USE:
521
signature1 = signature;
522
signature2 = signature;
523
signature3 = 0xFFFFFFFF;
524
state1 = 0xFFFFFFF1;
525
state2 = 0xFFFFFFF2;
526
state3 = 0xFFFFFFFF;
527
break;
528
case SECTOR_STATE_FULL:
529
signature1 = signature;
530
signature2 = signature;
531
signature3 = signature;
532
state1 = 0xFFFFFFF1;
533
state2 = 0xFFFFFFF2;
534
state3 = 0xFFFFFFF3;
535
break;
536
default:
537
break;
538
}
539
}
540
541
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_G4
542
/*
543
G4 specific sector header functions
544
*/
545
bool AP_FlashStorage::sector_header::signature_ok(void) const
546
{
547
return signature1 == signature;
548
}
549
550
AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const
551
{
552
if (state1 == 0xFFFFFFF1 &&
553
state2 == 0xFFFFFFFF &&
554
state3 == 0xFFFFFFFF &&
555
signature1 == signature &&
556
signature2 == 0xFFFFFFFF &&
557
signature3 == 0xFFFFFFFF) {
558
return SECTOR_STATE_AVAILABLE;
559
}
560
if (state1 == 0xFFFFFFF1 &&
561
state2 == 0xFFFFFFF2 &&
562
state3 == 0xFFFFFFFF &&
563
signature1 == signature &&
564
signature2 == signature &&
565
signature3 == 0xFFFFFFFF) {
566
return SECTOR_STATE_IN_USE;
567
}
568
if (state1 == 0xFFFFFFF1 &&
569
state2 == 0xFFFFFFF2 &&
570
state3 == 0xFFFFFFF3 &&
571
signature1 == signature &&
572
signature2 == signature &&
573
signature3 == signature) {
574
return SECTOR_STATE_FULL;
575
}
576
return SECTOR_STATE_INVALID;
577
}
578
579
void AP_FlashStorage::sector_header::set_state(SectorState state)
580
{
581
switch (state) {
582
case SECTOR_STATE_AVAILABLE:
583
signature1 = signature;
584
signature2 = 0xFFFFFFFF;
585
signature3 = 0xFFFFFFFF;
586
state1 = 0xFFFFFFF1;
587
state2 = 0xFFFFFFFF;
588
state3 = 0xFFFFFFFF;
589
break;
590
case SECTOR_STATE_IN_USE:
591
signature1 = signature;
592
signature2 = signature;
593
signature3 = 0xFFFFFFFF;
594
state1 = 0xFFFFFFF1;
595
state2 = 0xFFFFFFF2;
596
state3 = 0xFFFFFFFF;
597
break;
598
case SECTOR_STATE_FULL:
599
signature1 = signature;
600
signature2 = signature;
601
signature3 = signature;
602
state1 = 0xFFFFFFF1;
603
state2 = 0xFFFFFFF2;
604
state3 = 0xFFFFFFF3;
605
break;
606
default:
607
break;
608
}
609
}
610
611
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F1
612
/*
613
F1/F3 specific sector header functions
614
*/
615
bool AP_FlashStorage::sector_header::signature_ok(void) const
616
{
617
return signature1 == signature;
618
}
619
620
AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const
621
{
622
if (state1 == 0xFFFFFFFF) {
623
return SECTOR_STATE_AVAILABLE;
624
}
625
if (state1 == 0xFFFFFFF1) {
626
return SECTOR_STATE_IN_USE;
627
}
628
if (state1 == 0xFFF2FFF1) {
629
return SECTOR_STATE_FULL;
630
}
631
return SECTOR_STATE_INVALID;
632
}
633
634
void AP_FlashStorage::sector_header::set_state(SectorState state)
635
{
636
signature1 = signature;
637
switch (state) {
638
case SECTOR_STATE_AVAILABLE:
639
state1 = 0xFFFFFFFF;
640
break;
641
case SECTOR_STATE_IN_USE:
642
state1 = 0xFFFFFFF1;
643
break;
644
case SECTOR_STATE_FULL:
645
state1 = 0xFFF2FFF1;
646
break;
647
default:
648
break;
649
}
650
}
651
#elif AP_FLASHSTORAGE_TYPE == AP_FLASHSTORAGE_TYPE_F4
652
/*
653
F4 specific sector header functions
654
*/
655
bool AP_FlashStorage::sector_header::signature_ok(void) const
656
{
657
return signature1 == signature;
658
}
659
660
AP_FlashStorage::SectorState AP_FlashStorage::sector_header::get_state(void) const
661
{
662
if (state1 == 0xFF) {
663
return SECTOR_STATE_AVAILABLE;
664
}
665
if (state1 == 0xFE) {
666
return SECTOR_STATE_IN_USE;
667
}
668
if (state1 == 0xFC) {
669
return SECTOR_STATE_FULL;
670
}
671
return SECTOR_STATE_INVALID;
672
}
673
674
void AP_FlashStorage::sector_header::set_state(SectorState state)
675
{
676
signature1 = signature;
677
switch (state) {
678
case SECTOR_STATE_AVAILABLE:
679
state1 = 0xFF;
680
break;
681
case SECTOR_STATE_IN_USE:
682
state1 = 0xFE;
683
break;
684
case SECTOR_STATE_FULL:
685
state1 = 0xFC;
686
break;
687
default:
688
break;
689
}
690
}
691
#endif
692
693