APM:Libraries
osd_eeprom.h
Go to the documentation of this file.
1 #pragma once
2 /*
3  EEPROM emulation for OSD needs.
4 
5  uses 16k Flash sector at 0x08004000 (Page1) to emulate (almost) read-only storage
6  for OSD configuration
7 
8 */
9 
10 #include "AP_HAL_F4Light/EEPROM.h"
11 
12 // This is the size of each FLASH ROM page
13 #define PAGE_SIZE 0x4000l // real page size
14 
15 #define EEPROM_PAGE 0x08004000l // Page1
16 
17 #define EEPROM_SIZE 2048 // 2 k for wear leveling
18 
19 class OSD_EEPROM /*: public EEPROMClass*/ { // mostly to not redefine some functions
20 
21 public:
22  static uint8_t read(uint16_t addr);
23  static void write(uint16_t addr, uint8_t val);
24  static void init();
25 
26 private:
27  static uint32_t ee_ptr; // address of current bank
28 
29  static uint8_t _read(uint16_t addr);
30  static void _write(uint16_t addr, uint8_t val);
31 
32  static inline uint32_t read_16(uint32_t addr){
33  return *(__IO uint16_t*)addr;
34  }
35 
36  static inline uint8_t read_8(uint32_t addr){
37  return *(__IO uint8_t*)addr;
38  }
39 
40  static inline uint32_t read_32(uint32_t addr){
41  return *(__IO uint32_t*)addr;
42  }
43 
44  static inline FLASH_Status write_16(uint32_t addr, uint16_t data){
45  return EEPROMClass::write_16(addr, data);
46  }
47 
48 
49  static inline FLASH_Status write_8(uint32_t addr, uint8_t data){ // need to unlock first
50  return EEPROMClass::write_8(addr, data);
51  }
52 
53  static inline FLASH_Status erasePageByAddress(uint32_t Page_Address) {
54  return EEPROMClass::_ErasePageByAddress(Page_Address);
55  }
56  static inline void FLASH_Lock_check() {
58  }
59  static inline void FLASH_Unlock_dis() {
61  }
62 };
static uint8_t _read(uint16_t addr)
Definition: osd_eeprom.cpp:44
static uint32_t read_32(uint32_t addr)
Definition: osd_eeprom.h:40
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
static FLASH_Status erasePageByAddress(uint32_t Page_Address)
Definition: osd_eeprom.h:53
static FLASH_Status write_16(uint32_t addr, uint16_t data)
Definition: osd_eeprom.h:44
static void FLASH_Lock_check()
Definition: osd_eeprom.h:56
static FLASH_Status write_8(uint32_t addr, uint8_t data)
Definition: EEPROM.cpp:77
static void init()
Definition: osd_eeprom.cpp:27
static uint8_t read_8(uint32_t addr)
Definition: osd_eeprom.h:36
static FLASH_Status write_8(uint32_t addr, uint8_t data)
Definition: osd_eeprom.h:49
static uint8_t read(uint16_t addr)
Definition: osd_eeprom.cpp:34
static void FLASH_Unlock_dis()
Definition: EEPROM.cpp:98
static FLASH_Status write_16(uint32_t addr, uint16_t data)
Definition: EEPROM.cpp:64
static FLASH_Status _ErasePageByAddress(uint32_t Page_Address)
Erases a specified FLASH page by address.
Definition: EEPROM.cpp:130
static uint32_t read_16(uint32_t addr)
Definition: osd_eeprom.h:32
static void FLASH_Lock_check()
Definition: EEPROM.cpp:92
static void FLASH_Unlock_dis()
Definition: osd_eeprom.h:59