Storage.h 1.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #define LINUX_STORAGE_SIZE HAL_STORAGE_SIZE
  4. #define LINUX_STORAGE_MAX_WRITE 512
  5. #define LINUX_STORAGE_LINE_SHIFT 9
  6. #define LINUX_STORAGE_LINE_SIZE (1<<LINUX_STORAGE_LINE_SHIFT)
  7. #define LINUX_STORAGE_NUM_LINES (LINUX_STORAGE_SIZE/LINUX_STORAGE_LINE_SIZE)
  8. namespace Linux {
  9. class Storage : public AP_HAL::Storage
  10. {
  11. public:
  12. Storage() : _fd(-1),_dirty_mask(0) { }
  13. static Storage *from(AP_HAL::Storage *storage) {
  14. return static_cast<Storage*>(storage);
  15. }
  16. void init() override;
  17. uint8_t read_byte(uint16_t loc);
  18. uint16_t read_word(uint16_t loc);
  19. uint32_t read_dword(uint16_t loc);
  20. void read_block(void *dst, uint16_t src, size_t n) override;
  21. void write_byte(uint16_t loc, uint8_t value);
  22. void write_word(uint16_t loc, uint16_t value);
  23. void write_dword(uint16_t loc, uint32_t value);
  24. void write_block(uint16_t dst, const void* src, size_t n) override;
  25. virtual void _timer_tick(void) override;
  26. protected:
  27. void _mark_dirty(uint16_t loc, uint16_t length);
  28. int _storage_create(const char *dpath);
  29. int _fd;
  30. volatile bool _initialised;
  31. volatile uint32_t _dirty_mask;
  32. uint8_t _buffer[LINUX_STORAGE_SIZE];
  33. };
  34. }