APM:Libraries
EEPROM.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4 
5 */
6 #pragma GCC optimize ("O2")
7 
8 #include <AP_HAL/AP_HAL.h>
9 
10 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
11 
12 
13 #include <string.h>
14 #include "stm32f4xx.h"
15 #include "EEPROM.h"
16 #include <hal.h>
17 
18 #include <GCS_MAVLink/GCS.h>
19 
20 /*
21  address not uses 2 high bits so we will use them as flags of right written slot - if address has high bit then it written wrong
22 */
23 
25 : PageSize(0)
26 , _status(EEPROM_NOT_INIT)
27 {
28 }
29 
30 static void reset_flash_errors(){
31  if(FLASH->SR & 0xE0) FLASH->SR = 0xE0; // reset Programming Sequence, Parallelism and Alignment errors
32  if(FLASH->SR & FLASH_FLAG_WRPERR) { // write protection detected
33  FLASH_OB_Unlock();
34 
35  FLASH_OB_WRPConfig(OB_WRP_Sector_All, DISABLE); // remove protection
36  FLASH->SR |= FLASH_FLAG_WRPERR; // reset flag
37  }
38 }
39 
40 // библиотечная версия содержит ошибку и не разблокирует память
41 void EEPROMClass::FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
42 {
43 
44  /* Check the parameters */
45  assert_param(IS_OB_WRP(OB_WRP));
46  assert_param(IS_FUNCTIONAL_STATE(NewState));
47 
48  FLASH_WaitForLastOperation();
49 
50 // if(status == FLASH_COMPLETE) { тут может быть любая ошибка - оттого мы и вызываем разблокировку!
51  if(NewState != DISABLE)
52  {
53  *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS &= (~OB_WRP);
54  }
55  else
56  {
57  *(__IO uint16_t*)OPTCR_BYTE2_ADDRESS |= (uint16_t)OB_WRP;
58  }
59 // }
60 }
61 
62 
63 
64 FLASH_Status EEPROMClass::write_16(uint32_t addr, uint16_t data){
65  uint16_t n_try=16;
66 again:
67  FLASH_Status sts = FLASH_ProgramHalfWord(addr, data);
68 
69  if(sts != FLASH_COMPLETE ) {
71  if(n_try-- > 0) goto again;
72  }
73 
74  return sts;
75 }
76 
77 FLASH_Status EEPROMClass::write_8(uint32_t addr, uint8_t data){
78  uint16_t n_try=16;
79 again:
80 
81  FLASH_Status sts = FLASH_ProgramByte(addr, data);
82 
83  if(sts != FLASH_COMPLETE ) {
85 
86  if(n_try-- > 0) goto again;
87  }
88 
89  return sts;
90 }
91 
93  FLASH_Lock();
94  FLASH->CR |= FLASH_CR_ERRIE;
95  FLASH->ACR |= FLASH_ACR_DCEN; // enable data cache again
96 }
97 
99  FLASH->ACR &= ~FLASH_ACR_DCEN; // disable data cache
100  FLASH_Unlock();
101 }
102 
110 uint16_t EEPROMClass::_CheckPage(uint32_t pageBase, uint16_t status)
111 {
112  uint32_t pageEnd = pageBase + PageSize;
113 
114  // Page Status not EEPROM_ERASED and not a "state"
115  if (read_16(pageBase) != EEPROM_ERASED && read_16(pageBase) != status)
116  return EEPROM_BAD_FLASH;
117 
118  for(pageBase += 4; pageBase < pageEnd; pageBase += 4)
119  if (read_32(pageBase) != 0xFFFFFFFF) // Verify if slot is empty
120  return EEPROM_BAD_FLASH;
121  return EEPROM_OK;
122 }
123 
130 FLASH_Status EEPROMClass::_ErasePageByAddress(uint32_t Page_Address)
131 {
132 
133  int Page_Offset = Page_Address - 0x08000000; // calculates sector by address
134  uint32_t FLASH_Sector;
135 
136  if(Page_Offset < 0x10000) {
137  FLASH_Sector = Page_Offset / 0x4000; // 4 * 16K pages
138  } else if(Page_Offset < 0x20000) {
139  FLASH_Sector = 4; // 1 * 64K page
140  } else {
141  FLASH_Sector = 4 + Page_Offset / 0x20000; // all another pages of 128K
142  }
143 
144  uint8_t n_try = 16;
145 again:
146  FLASH_Status ret = FLASH_EraseSector(8 * FLASH_Sector, VoltageRange_3);
147 
148  if(ret != FLASH_COMPLETE ) {
150  if(n_try-- > 0) goto again;
151  }
152 
153  return ret;
154 }
155 
163 FLASH_Status EEPROMClass::_ErasePage(uint32_t pageBase)
164 {
165 
166  FLASH_Status status;
167  uint16_t data = read_16(pageBase);
168  if ((data == EEPROM_ERASED) || (data == EEPROM_VALID_PAGE) || (data == EEPROM_RECEIVE_DATA))
169  data = read_16(pageBase + 2) + 1; // erase count +1
170  else
171  data = 0;
172 #ifdef DEBUG_BUILD
173  printf("\nEEprom erase page %d\n ", (uint16_t)((pageBase & 0x00ffffff) / 0x4000) ); // clear high byte of address and count 16K blocks
174 #endif
175  gcs().send_text(MAV_SEVERITY_INFO, "EEprom erase page %d", (uint16_t)((pageBase & 0x00ffffff) / 0x4000) );
176 
177  status = _ErasePageByAddress(pageBase);
178 
179  if (status == FLASH_COMPLETE)
180  status = write_16(pageBase + 2, data); // write count back
181 
182  return status;
183 }
184 
193 uint16_t EEPROMClass::_CheckErasePage(uint32_t pageBase, uint16_t req)
194 {
195  uint16_t status;
196  if (_CheckPage(pageBase, req) != EEPROM_OK) {
197  status = _ErasePage(pageBase);
198  if (status != FLASH_COMPLETE)
199  return status;
200  return _CheckPage(pageBase, req);
201  }
202  return EEPROM_OK;
203 }
204 
212 {
213 
214  if (_status == EEPROM_NOT_INIT) {
215  if (_init() != EEPROM_OK) return 0;
216  }
217 again:
218  uint16_t status0 = read_16(PageBase0); // Get Page0 actual status
219  uint16_t status1 = read_16(PageBase1); // Get Page1 actual status
220 
221  if (status0 == EEPROM_VALID_PAGE && status1 == EEPROM_ERASED)
222  return PageBase0;
223  if (status1 == EEPROM_VALID_PAGE && status0 == EEPROM_ERASED)
224  return PageBase1;
225 // something went wrong, try to recover
226  if(_init() == EEPROM_OK) goto again;
227 
228 // all bad - -_init() fails. TODO: Panic()?
229  return 0;
230 }
231 
239 uint16_t EEPROMClass::_GetVariablesCount(uint32_t pageBase, uint16_t skipAddress)
240 {
241  uint16_t varAddress, nextAddress;
242  uint32_t idx;
243  uint32_t pageEnd = pageBase + PageSize;
244  uint16_t mycount = 0;
245 
246  for (pageBase += 6; pageBase < pageEnd; pageBase += 4) {
247  varAddress = read_16(pageBase);
248  if (varAddress == 0xFFFF || (varAddress & ADDRESS_MASK)== skipAddress || /* partially written */ (varAddress & FLAGS_MASK)!=0 )
249  continue;
250 
251  mycount++;
252 
253  for(idx = pageBase + 4; idx < pageEnd; idx += 4) {
254  nextAddress = read_16(idx);
255  if ((nextAddress & ADDRESS_MASK) == (varAddress & ADDRESS_MASK)) {
256  mycount--;
257  break;
258  }
259  }
260  }
261  return mycount;
262 }
263 
274 uint16_t EEPROMClass::_PageTransfer(uint32_t newPage, uint32_t oldPage, uint16_t SkipAddress)
275 {
276  uint32_t oldEnd, newEnd;
277  uint32_t oldIdx, newIdx, idx;
278  uint16_t address, data, found;
279  FLASH_Status status;
280 
281  // Transfer process: transfer variables from old to the new active page
282  newEnd = newPage + PageSize;
283 
284  // Find first free element in new page
285  for (newIdx = newPage + 4; newIdx < newEnd; newIdx += 4)
286  if (read_32(newIdx) == 0xFFFFFFFF) // Verify if element contents are 0xFFFFFFFF
287  break;
288  if (newIdx >= newEnd)
289  return EEPROM_OUT_SIZE;
290 
291  oldEnd = oldPage + 4;
292  oldIdx = oldPage + (PageSize - 2);
293 
294  for (; oldIdx > oldEnd; oldIdx -= 4) {
295  address = read_16(oldIdx);
296  if ( address == SkipAddress || (address & FLAGS_MASK)!=0)
297  continue; // it's means that power off after write data
298 
299  found = 0;
300 
301  for (idx = newPage + 6; idx < newIdx; idx += 4){
302  if (read_16(idx) == address) {
303  found = 1;
304  break;
305  }
306  }
307  if (found)
308  continue; // There is more recent data with this address
309 
310  if (newIdx < newEnd) {
311  data = read_16(oldIdx - 2);
312 
313  status = write_16(newIdx, data);
314  if (status != FLASH_COMPLETE)
315  return status;
316 
317  status = write_16(newIdx + 2, address & ADDRESS_MASK);
318  if (status != FLASH_COMPLETE)
319  return status;
320 
321  newIdx += 4;
322  }
323  else
324  return EEPROM_OUT_SIZE;
325  }
326 
327  // Erase the old Page: Set old Page status to EEPROM_EEPROM_ERASED status
328  data = _CheckErasePage(oldPage, EEPROM_ERASED);
329  if (data != EEPROM_OK)
330  return data;
331 
332  // Set new Page status
333  status = write_16(newPage, EEPROM_VALID_PAGE);
334  if (status != FLASH_COMPLETE)
335  return status;
336 
337  return EEPROM_OK;
338 }
339 
351 uint16_t EEPROMClass::_VerifyPageFullWriteVariable(uint16_t Address, uint16_t Data)
352 {
353  FLASH_Status status;
354  uint32_t idx, pageBase, pageEnd, newPage;
355  uint16_t mycount;
356  uint16_t old_data;
357 
358  // Get valid Page for write operation
359  pageBase = _FindValidPage();
360  if (pageBase == 0)
361  return EEPROM_NO_VALID_PAGE;
362 
363  // Get the valid Page end Address
364  pageEnd = pageBase + PageSize; // Set end of page
365 
366 // read from end to begin
367  for (idx = pageEnd - 2; idx > pageBase; idx -= 4) {
368  if (read_16(idx) == Address){ // Find last value for address, will stop loop if found
369  old_data = read_16(idx - 2); // Read last data
370  if (old_data == Data){
371  return EEPROM_OK; // data already OK
372  }
373  if (old_data == 0xFFFF || /* we can write - there is no '0' where we need '1' */ (~old_data & Data)==0 ) {
374  status = write_16(idx - 2, Data); // Set variable data
375  if (status == FLASH_COMPLETE && read_16(idx - 2) == Data) // check if writen
376  return EEPROM_OK;
377  }
378  break;
379  }
380  }
381 
382  // Check each active page address starting from begining
383  for (idx = pageBase + 4; idx < pageEnd; idx += 4){
384  if (read_32(idx) == 0xFFFFFFFF){ // Verify if element contents are 0xFFFFFFFF
385  status = write_16(idx, Data); // Set variable data
386  if (status != FLASH_COMPLETE)
387  return status;
388  status = write_16(idx + 2, Address & ADDRESS_MASK); // Set variable virtual address
389  if (status != FLASH_COMPLETE)
390  return 0x90 + status;
391  return EEPROM_OK;
392  }
393  }
394 
395  // Empty slot not found, need page transfer
396  // Calculate unique variables in page
397  mycount = _GetVariablesCount(pageBase, Address) + 1;
398  if (mycount >= maxcount())
399  return EEPROM_OUT_SIZE;
400 
401  if (pageBase == PageBase1)
402  newPage = PageBase0; // New page address where variable will be moved to
403  else
404  newPage = PageBase1;
405 
406  // Set the new Page status to RECEIVE_DATA status
407  status = write_16(newPage, EEPROM_RECEIVE_DATA);
408  if (status != FLASH_COMPLETE)
409  return status;
410 
411  // Write the variable passed as parameter in the new active page
412  status = write_16(newPage + 4, Data);
413  if (status != FLASH_COMPLETE)
414  return status;
415 
416  status = write_16(newPage + 6, Address);
417  if (status != FLASH_COMPLETE)
418  return status;
419 
420  return _PageTransfer(newPage, pageBase, Address);
421 }
422 
423 
424 uint16_t EEPROMClass::init(uint32_t pageBase0, uint32_t pageBase1, uint32_t pageSize)
425 {
428  PageSize = pageSize;
429 
430  return _init();
431 }
432 
433 uint16_t EEPROMClass::_init(void) //
434 {
435 
436  uint16_t status0, status1, erased0;
437  FLASH_Status status;
438 
440 
441  if(PageSize == 0) return _status; // no real Init call
442 
443  FLASH_Unlock();
444 
445  erased0 = read_16(PageBase0 + 2);
446  if (erased0 == 0xffff) erased0 = 0;
447  // Print number of EEprom write cycles - but it cleared each reflash
448 #ifdef DEBUG_BUILD
449  printf("\nEEprom write cycles %d\n ", erased0);
450 #endif
451 
452  status0 = read_16(PageBase0);
453  status1 = read_16(PageBase1);
454 
455  // Check if EEprom is formatted
456  if ( status0 != EEPROM_VALID_PAGE && status0 != EEPROM_RECEIVE_DATA && status0 != EEPROM_ERASED){
457  // _status = _format(); как-то жестко форматировать ВСЕ по одиночной ошибке. Если ВТОРАЯ страница валидная то достаточно стереть пострадавшую
459  else _status = _format();
460  status0 = read_16(PageBase0);
461  status1 = read_16(PageBase1);
462  }else if (status1 != EEPROM_VALID_PAGE && status1 != EEPROM_RECEIVE_DATA && status1 != EEPROM_ERASED){
463  // _status = _format(); тут мы первую страницу уже проверили - валидная, отставить вредительство!
465  status0 = read_16(PageBase0);
466  status1 = read_16(PageBase1);
467  }
468 
469 
470  switch (status0) {
471 /*
472  Page0 Page1
473  ----- -----
474  EEPROM_ERASED EEPROM_VALID_PAGE Page1 valid, Page0 erased
475  EEPROM_RECEIVE_DATA Page1 need set to valid, Page0 erased
476  EEPROM_ERASED make _Format
477  any Error: EEPROM_NO_VALID_PAGE
478 */
479  case EEPROM_ERASED:
480  if (status1 == EEPROM_VALID_PAGE) // Page0 erased, Page1 valid
482  else if (status1 == EEPROM_RECEIVE_DATA) { // Page0 erased, Page1 receive
483  // Page Transfer failed! we can't be sure if it finished OK so should restart transfer - but page is erased. This can be if write "valid" mark fails
484  status = write_16(PageBase1, EEPROM_VALID_PAGE); // so just mark it as valid
485  if (status != FLASH_COMPLETE)
486  _status = status;
487  else
489 
490  }
491  else /* if (status1 == EEPROM_ERASED)*/ // Both in erased OR 2nd in unknown state so format EEPROM
492  _status = _format();
493  break;
494 /*
495  Page0 Page1
496  ----- -----
497  EEPROM_RECEIVE_DATA EEPROM_VALID_PAGE Transfer Page1 to Page0
498  EEPROM_ERASED Page0 need set to valid, Page1 erased
499  any EEPROM_NO_VALID_PAGE
500 */
501  case EEPROM_RECEIVE_DATA:
502  if (status1 == EEPROM_VALID_PAGE) // Page0 receive, Page1 valid
503  // transfer failed and we have good data - restart transfer
505  else if (status1 == EEPROM_ERASED){ // Page0 receive, Page1 erased
506  // setting "valid" mark failed
508  if (_status == EEPROM_OK){
509  status = write_16(PageBase0, EEPROM_VALID_PAGE); // mark as valid again
510  if (status != FLASH_COMPLETE)
511  _status = status;
512  else
513  _status = EEPROM_OK;
514  }
515  }
516  else _status = _format(); // all bad
517  break;
518 /*
519  Page0 Page1
520  ----- -----
521  EEPROM_VALID_PAGE EEPROM_VALID_PAGE Error: EEPROM_NO_VALID_PAGE
522  EEPROM_RECEIVE_DATA Transfer Page0 to Page1
523  any Page0 valid, Page1 erased
524 */
525  case EEPROM_VALID_PAGE:
526  if (status1 == EEPROM_VALID_PAGE){ // Both pages valid
527 // just check amount and correctness of data
528  uint16_t cnt0 = _GetVariablesCount(PageBase0, 0xFFFF);
529  uint16_t cnt1 = _GetVariablesCount(PageBase1, 0xFFFF);
530  if(cnt0>cnt1){
532  }else if(cnt0<cnt1){
534  } else { // ну такого совсем не может быть ибо марку "валид" мы делаем только после стирания.
535  // _status = EEPROM_NO_VALID_PAGE;
536  _status = _CheckErasePage(PageBase1, EEPROM_ERASED); // сотрем вторую - я монетку бросил
537  }
538  }else if (status1 == EEPROM_RECEIVE_DATA) {
539  _status = _PageTransfer(PageBase1, PageBase0, 0xFFFF); // restart transfer
540  } else {
542  }
543  break;
544 /*
545  Page0 Page1
546  ----- -----
547  any EEPROM_VALID_PAGE Page1 valid, Page0 erased
548  EEPROM_RECEIVE_DATA Page1 valid, Page0 erased
549  any EEPROM_NO_VALID_PAGE
550 */
551  default:
552  if (status1 == EEPROM_VALID_PAGE)
553  _status = _CheckErasePage(PageBase0, EEPROM_ERASED); // Check/Erase Page0
554  else if (status1 == EEPROM_RECEIVE_DATA) {
556  if (status != FLASH_COMPLETE)
557  _status = status;
558  else
560  }
561  else _status = _format(); // all bad
562  break;
563  }
564 
565  FLASH_Lock_check(); // lock after all writes
566  return _status;
567 }
568 
574 uint16_t EEPROMClass::_format(void)
575 {
576  uint16_t status;
577  uint16_t n_try=16;
578 
579 again:
580 
581  // Erase Page0
583  if (status != EEPROM_OK) goto error;
584 
585  if (read_16(PageBase0) == EEPROM_ERASED) {
586  // Set Page0 as valid page: Write VALID_PAGE at Page0 base address
587  FLASH_Status fs = write_16(PageBase0, EEPROM_VALID_PAGE);
588  if (fs != FLASH_COMPLETE) goto error;
589  }
590  // Erase Page1
592  if (status == EEPROM_OK) return status;
593 error:
594  // something went wrong
596 
597  if(n_try-- > 0) goto again;
598 
599  return status;
600 }
601 
602 uint16_t EEPROMClass::format(void){
603  uint16_t status;
604  FLASH_Unlock();
605  status = _format();
607  return status;
608 }
609 
610 
618 uint16_t EEPROMClass::erases(uint16_t *Erases)
619 {
620  uint32_t pageBase;
621 
622  // Get active Page for read operation
623  pageBase = _FindValidPage();
624  if (pageBase == 0)
625  return EEPROM_NO_VALID_PAGE;
626 
627  *Erases = read_16(pageBase+2);
628  return EEPROM_OK;
629 }
630 
631 
642 uint16_t EEPROMClass::read(uint16_t Address, uint16_t *Data)
643 {
644  uint32_t pageBase, pageEnd;
645 
646  *Data = EEPROM_DEFAULT_DATA; // Set default data (empty EEPROM)
647 
648  // Get active Page for read operation
649  pageBase = _FindValidPage();
650  if (pageBase == 0) return EEPROM_NO_VALID_PAGE;
651 
652  // Get the valid Page end Address
653  pageEnd = pageBase + (PageSize - 2);
654 
655  Address &= ADDRESS_MASK;
656 
657  uint32_t ptr = pageEnd;
658 
659  // Check each active page address starting from end - the last value written
660  for (pageBase += 6; ptr >= pageBase; ptr -= 4){
661  if (read_16(ptr) == Address){// Compare the read address with the virtual address
662  *Data = read_16(ptr - 2); // Get content of Address-2 which is variable value
663  return EEPROM_OK;
664  }
665  }
666 
667  return EEPROM_BAD_ADDRESS;
668 }
669 
682 uint16_t EEPROMClass::write(uint16_t Address, uint16_t Data)
683 {
684  if (_status == EEPROM_NOT_INIT)
685  if (_init() != EEPROM_OK)
686  return _status;
687 
688  if (Address == 0xFFFF)
689  return EEPROM_BAD_ADDRESS;
690 
691  FLASH_Unlock();
692 
693  // Write the variable virtual address and value in the EEPROM
694  uint16_t status = _VerifyPageFullWriteVariable(Address & ADDRESS_MASK, Data);
696 
698  return status;
699 }
700 
705 uint16_t EEPROMClass::count(uint16_t *cnt)
706 {
707  // Get valid Page for write operation
708  uint32_t pageBase = _FindValidPage();
709  if (pageBase == 0)
710  return EEPROM_NO_VALID_PAGE; // No valid page, return max. numbers
711 
712  *cnt = _GetVariablesCount(pageBase, 0xFFFF);
713  return EEPROM_OK;
714 }
715 
716 
718 #endif
#define EEPROM_RECEIVE_DATA
Definition: EEPROM.h:8
int printf(const char *fmt,...)
Definition: stdio.c:113
FLASH_Status _ErasePage(uint32_t)
Erase page with increment erase counter (page + 2)
Definition: EEPROM.cpp:163
uint16_t _status
Definition: EEPROM.h:117
uint16_t read(uint16_t address, uint16_t *data)
Returns the last stored variable data, if found, which correspond to the passed virtual address...
Definition: EEPROM.cpp:642
#define ADDRESS_MASK
Definition: EEPROM.h:11
uint16_t _format(void)
Erases PAGE0 and PAGE1 and writes EEPROM_VALID_PAGE / 0 header to PAGE0.
Definition: EEPROM.cpp:574
uint16_t _VerifyPageFullWriteVariable(uint16_t, uint16_t)
Verify if active page is full and Writes variable in EEPROM.
Definition: EEPROM.cpp:351
Interface definition for the various Ground Control System.
#define assert_param(expr)
EEPROMClass(void)
Definition: EEPROM.cpp:24
uint16_t _CheckErasePage(uint32_t, uint16_t)
Check page for blank and erase it.
Definition: EEPROM.cpp:193
uint16_t _CheckPage(uint32_t, uint16_t)
Check page for blank.
Definition: EEPROM.cpp:110
GCS & gcs()
uint32_t PageBase0
Definition: EEPROM.h:114
static uint32_t read_32(uint32_t addr)
Definition: EEPROM.h:104
uint16_t _PageTransfer(uint32_t, uint32_t, uint16_t)
Transfers last updated variables data from the full Page to an empty one.
Definition: EEPROM.cpp:274
static FLASH_Status write_8(uint32_t addr, uint8_t data)
Definition: EEPROM.cpp:77
static void reset_flash_errors()
Definition: EEPROM.cpp:30
static void FLASH_OB_WRPConfig(uint32_t OB_WRP, FunctionalState NewState)
Definition: EEPROM.cpp:41
uint16_t init(uint32_t, uint32_t, uint32_t)
Definition: EEPROM.cpp:424
uint32_t PageSize
Definition: EEPROM.h:116
const uint32_t pageBase0
Definition: Storage.cpp:68
EEPROMClass EEPROM
Definition: EEPROM.cpp:717
uint16_t _GetVariablesCount(uint32_t, uint16_t)
Calculate unique variables in EEPROM.
Definition: EEPROM.cpp:239
void send_text(MAV_SEVERITY severity, const char *fmt,...)
Definition: GCS.cpp:8
uint16_t write(uint16_t address, uint16_t data)
Writes/upadtes variable data in EEPROM.
Definition: EEPROM.cpp:682
const uint32_t pageBase1
Definition: Storage.cpp:69
#define EEPROM_ERASED
Definition: EEPROM.h:7
#define EEPROM_VALID_PAGE
Definition: EEPROM.h:9
static void FLASH_Unlock_dis()
Definition: EEPROM.cpp:98
static FLASH_Status write_16(uint32_t addr, uint16_t data)
Definition: EEPROM.cpp:64
uint16_t _init(void)
Definition: EEPROM.cpp:433
uint16_t format(void)
Erases PAGE0 and PAGE1 and writes EEPROM_VALID_PAGE / 0 header to PAGE0.
Definition: EEPROM.cpp:602
#define error(fmt, args ...)
static FLASH_Status _ErasePageByAddress(uint32_t Page_Address)
Erases a specified FLASH page by address.
Definition: EEPROM.cpp:130
static void FLASH_Lock_check()
Definition: EEPROM.cpp:92
uint32_t _FindValidPage(void)
Find valid Page for write or read operation.
Definition: EEPROM.cpp:211
#define EEPROM_DEFAULT_DATA
Definition: EEPROM.h:25
uint32_t PageBase1
Definition: EEPROM.h:115
#define FLAGS_MASK
Definition: EEPROM.h:12
#define FLASH_CR_ERRIE
Definition: EEPROM.h:27
const uint32_t pageSize
Definition: Storage.cpp:63
uint16_t maxcount(void)
Definition: EEPROM.h:93
uint16_t count(uint16_t *data)
Return number of variable.
Definition: EEPROM.cpp:705
uint16_t erases(uint16_t *)
Returns the erase counter for current page.
Definition: EEPROM.cpp:618
static uint32_t read_16(uint32_t addr)
Definition: EEPROM.h:100