APM:Libraries
Storage.h
Go to the documentation of this file.
1 #pragma once
2 
3 /*
4  we can optionally use flash for storage instead of FRAM. That allows
5  ArduPilot to run on a wider range of boards and reduces board cost
6  */
7 #ifndef USE_FLASH_STORAGE
8 #define USE_FLASH_STORAGE 0
9 #endif
10 
11 #include <AP_HAL/AP_HAL.h>
13 #include <systemlib/perf_counter.h>
14 #include <AP_Common/Bitmask.h>
16 
17 #define VRBRAIN_STORAGE_SIZE HAL_STORAGE_SIZE
18 
19 #if USE_FLASH_STORAGE
20 // when using flash storage we use a small line size to make storage
21 // compact and minimise the number of erase cycles needed
22 #define VRBRAIN_STORAGE_LINE_SHIFT 3
23 #else
24 #define VRBRAIN_STORAGE_LINE_SHIFT 9
25 #endif
26 
27 #define VRBRAIN_STORAGE_LINE_SIZE (1<<VRBRAIN_STORAGE_LINE_SHIFT)
28 #define VRBRAIN_STORAGE_NUM_LINES (VRBRAIN_STORAGE_SIZE/VRBRAIN_STORAGE_LINE_SIZE)
29 
31 public:
33 
34  void init() {}
35  void read_block(void *dst, uint16_t src, size_t n);
36  void write_block(uint16_t dst, const void* src, size_t n);
37 
38  void _timer_tick(void) override;
39 
40 private:
41  volatile bool _initialised;
42  void _storage_create(void);
43  void _storage_open(void);
44  void _mark_dirty(uint16_t loc, uint16_t length);
45  uint8_t _buffer[VRBRAIN_STORAGE_SIZE] __attribute__((aligned(4)));
47  perf_counter_t _perf_storage;
48  perf_counter_t _perf_errors;
49  uint32_t _last_re_init_ms;
50 
51 #if !USE_FLASH_STORAGE
52  int _fd = -1;
53  void bus_lock(bool lock);
54  void _mtd_load(void);
55  void _mtd_write(uint16_t line);
56 #if defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
57  irqstate_t irq_state;
58 #endif
59 
60 #else // USE_FLASH_STORAGE
61  bool _flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length);
62  bool _flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length);
63  bool _flash_erase_sector(uint8_t sector);
64  bool _flash_erase_ok(void);
65  uint8_t _flash_page;
66  bool _flash_failed;
67 
68  AP_FlashStorage _flash{_buffer,
69  128*1024U,
70  FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_write_data, bool, uint8_t, uint32_t, const uint8_t *, uint16_t),
71  FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_read_data, bool, uint8_t, uint32_t, uint8_t *, uint16_t),
72  FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_erase_sector, bool, uint8_t),
73  FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_erase_ok, bool)};
74 
75  void _flash_load(void);
76  void _flash_write(uint16_t line);
77 #endif
78 };
void bus_lock(bool lock)
Definition: Storage.cpp:148
void _storage_open(void)
Definition: Storage.cpp:40
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:83
uint8_t _buffer [VRBRAIN_STORAGE_SIZE] __attribute__((aligned(4)))
void _timer_tick(void) override
Definition: Storage.cpp:104
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:92
perf_counter_t _perf_storage
Definition: Storage.h:47
void _mtd_write(uint16_t line)
Definition: Storage.cpp:172
uint32_t _last_re_init_ms
Definition: Storage.h:49
#define VRBRAIN_STORAGE_NUM_LINES
Definition: Storage.h:28
#define VRBRAIN_STORAGE_SIZE
Definition: Storage.h:17
volatile bool _initialised
Definition: Storage.h:41
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
perf_counter_t _perf_errors
Definition: Storage.h:48
void _mark_dirty(uint16_t loc, uint16_t length)
Definition: Storage.cpp:73