APM:Libraries
Storage.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 #define LINUX_STORAGE_SIZE HAL_STORAGE_SIZE
6 #define LINUX_STORAGE_MAX_WRITE 512
7 #define LINUX_STORAGE_LINE_SHIFT 9
8 #define LINUX_STORAGE_LINE_SIZE (1<<LINUX_STORAGE_LINE_SHIFT)
9 #define LINUX_STORAGE_NUM_LINES (LINUX_STORAGE_SIZE/LINUX_STORAGE_LINE_SIZE)
10 
11 namespace Linux {
12 
13 class Storage : public AP_HAL::Storage
14 {
15 public:
16  Storage() : _fd(-1),_dirty_mask(0) { }
17 
18  static Storage *from(AP_HAL::Storage *storage) {
19  return static_cast<Storage*>(storage);
20  }
21 
22 
23  void init() override;
24 
25  uint8_t read_byte(uint16_t loc);
26  uint16_t read_word(uint16_t loc);
27  uint32_t read_dword(uint16_t loc);
28  void read_block(void *dst, uint16_t src, size_t n);
29 
30  void write_byte(uint16_t loc, uint8_t value);
31  void write_word(uint16_t loc, uint16_t value);
32  void write_dword(uint16_t loc, uint32_t value);
33  void write_block(uint16_t dst, const void* src, size_t n);
34 
35  virtual void _timer_tick(void) override;
36 
37 protected:
38  void _mark_dirty(uint16_t loc, uint16_t length);
39  int _storage_create(const char *dpath);
40 
41  int _fd;
42  volatile bool _initialised;
43  volatile uint32_t _dirty_mask;
45 };
46 
47 }
void write_dword(uint16_t loc, uint32_t value)
static Storage * from(AP_HAL::Storage *storage)
Definition: Storage.h:18
uint32_t read_dword(uint16_t loc)
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:203
void write_byte(uint16_t loc, uint8_t value)
#define LINUX_STORAGE_SIZE
Definition: Storage.h:5
int _storage_create(const char *dpath)
Definition: Storage.cpp:94
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:194
uint8_t read_byte(uint16_t loc)
virtual void _timer_tick(void) override
Definition: Storage.cpp:215
void write_word(uint16_t loc, uint16_t value)
volatile bool _initialised
Definition: Storage.h:42
void _mark_dirty(uint16_t loc, uint16_t length)
Definition: Storage.cpp:184
uint16_t read_word(uint16_t loc)
void init() override
Definition: Storage.cpp:136
float value
volatile uint32_t _dirty_mask
Definition: Storage.h:43
uint8_t _buffer[LINUX_STORAGE_SIZE]
Definition: Storage.h:44