APM:Libraries
osd_eeprom.cpp
Go to the documentation of this file.
1 /*
2 (c) 2017 night_ghost@ykoctpa.ru
3 
4  EEPROM emulation for OSD needs. Uses 1 16K page of flash to provide 2K of eeprom so it does wear
5  leveling of 8, excluding the case when we should write 0xff value, but OSD never writes it
6 
7  in time of page erase all data buffered in RAM so will be lost in case of unexpected power off, but there is no in-flight writes
8 
9 */
10 
11 #include "osd_eeprom.h"
12 
13 #include <AP_HAL/AP_HAL.h>
14 
15 extern const AP_HAL::HAL& hal;
16 
17 #include <utility>
18 #include <util.h>
19 #include <string.h>
20 #include <stdarg.h>
21 #include <stdlib.h>
22 
23 uint32_t OSD_EEPROM::ee_ptr=0;
24 static uint8_t data[EEPROM_SIZE] IN_CCM; // buffer for all data to be cached
25 
26 
28 
29  for(uint16_t i=0;i<EEPROM_SIZE; i++){ // read out all to buffer
30  data[i] = _read(i);
31  }
32 }
33 
34 uint8_t OSD_EEPROM::read(uint16_t addr){
35  return data[addr];
36 }
37 
38 void OSD_EEPROM::write(uint16_t addr, uint8_t val){
39  data[addr]=val;
40  _write(addr, val); //
41 }
42 
43 
44 uint8_t OSD_EEPROM::_read(uint16_t addr){
45 
46  for(uint8_t i=PAGE_SIZE/EEPROM_SIZE; i!=0;){
47  // look most recent value from last stage
48  i--;
49  uint32_t ea = EEPROM_PAGE + i*EEPROM_SIZE + addr;
50  uint8_t val = read_8(ea);
51  if(val != 0xFF) {
52  ee_ptr=ea; // remember last read address
53  return val; // first non-FF is a value
54  }
55  }
56  ee_ptr = EEPROM_PAGE + addr;
57  return 0xff; // got to begin and still FF - really FF
58 }
59 
60 
61 void OSD_EEPROM::_write(uint16_t addr, uint8_t val){
62  uint8_t cv = _read(addr);
63  if(cv == val) return; // already is
64 
65 
66  if( /* we can write - there is no '0' where we need '1' */ (~cv & val)==0 ){
68  write_8(ee_ptr, val); // just overwrite last value
69  goto done;
70  }
71 
72  if(val != 0xFF){ // the only way to write FF is to clear all - but OSD don't writes it
73  for(uint8_t i=0; i<PAGE_SIZE/EEPROM_SIZE; i++){
74  // look 0xFF
75  uint32_t ea = EEPROM_PAGE + i*EEPROM_SIZE + addr;
76  cv = read_8(ea);
77  if(cv == 0xFF) { // empty
79  write_8(ea, val);
80  goto done;
81  }
82  }
83  }
84 
85  // no empty slots - so need to erase page
86 
87 
88 // 1st - erase page. power loss here cause data loss! In execution time CPU is frozen!
89  printf("\nEEprom_OSD erase page %d\n ", (uint16_t)((EEPROM_PAGE & 0x00ffffff) / 0x4000) ); // clear high byte of address and count 16K blocks
92 
93 // 2rd write data back to the beginning of Flash page
94  for(uint16_t i=0;i<EEPROM_SIZE; i++){
95  write_8(EEPROM_PAGE+i, data[i]);
96  }
97 
98 done:
100 }
101 
int printf(const char *fmt,...)
Definition: stdio.c:113
#define EEPROM_SIZE
Definition: osd_eeprom.h:17
#define EEPROM_PAGE
Definition: osd_eeprom.h:15
static uint8_t _read(uint16_t addr)
Definition: osd_eeprom.cpp:44
static void _write(uint16_t addr, uint8_t val)
Definition: osd_eeprom.cpp:61
static uint32_t ee_ptr
Definition: osd_eeprom.h:27
static void write(uint16_t addr, uint8_t val)
Definition: osd_eeprom.cpp:38
#define PAGE_SIZE
Definition: osd_eeprom.h:13
static FLASH_Status erasePageByAddress(uint32_t Page_Address)
Definition: osd_eeprom.h:53
static void FLASH_Lock_check()
Definition: osd_eeprom.h:56
static void init()
Definition: osd_eeprom.cpp:27
static uint8_t read_8(uint32_t addr)
Definition: osd_eeprom.h:36
Miscellaneous utility macros and procedures.
static uint8_t data [EEPROM_SIZE] IN_CCM
Definition: osd_eeprom.cpp:24
static FLASH_Status write_8(uint32_t addr, uint8_t data)
Definition: osd_eeprom.h:49
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static uint8_t read(uint16_t addr)
Definition: osd_eeprom.cpp:34
static void FLASH_Unlock_dis()
Definition: osd_eeprom.h:59