Storage.h 2.1 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970
  1. #pragma once
  2. #include <AP_HAL/AP_HAL.h>
  3. #include <AP_Common/Bitmask.h>
  4. #include "AP_HAL_SITL_Namespace.h"
  5. #include <AP_FlashStorage/AP_FlashStorage.h>
  6. #ifndef HAL_STORAGE_FILE
  7. #define HAL_STORAGE_FILE "eeprom.bin"
  8. #endif
  9. // define which storage system to use. This allows us to test flash storage with --sitl-flash-storage
  10. // configure option
  11. #ifndef STORAGE_USE_FLASH
  12. #define STORAGE_USE_FLASH 0
  13. #endif
  14. #define STORAGE_USE_POSIX 1
  15. #define STORAGE_LINE_SHIFT 3
  16. #define STORAGE_LINE_SIZE (1<<STORAGE_LINE_SHIFT)
  17. #define STORAGE_NUM_LINES (HAL_STORAGE_SIZE/STORAGE_LINE_SIZE)
  18. class HALSITL::Storage : public AP_HAL::Storage {
  19. public:
  20. void init() override {}
  21. void read_block(void *dst, uint16_t src, size_t n) override;
  22. void write_block(uint16_t dst, const void* src, size_t n) override;
  23. void _timer_tick(void) override;
  24. bool healthy(void) override;
  25. private:
  26. volatile bool _initialised;
  27. void _storage_create(void);
  28. void _storage_open(void);
  29. void _save_backup(void);
  30. void _mark_dirty(uint16_t loc, uint16_t length);
  31. uint8_t _buffer[HAL_STORAGE_SIZE] __attribute__((aligned(4)));
  32. Bitmask<STORAGE_NUM_LINES> _dirty_mask;
  33. #if STORAGE_USE_FLASH
  34. bool _flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length);
  35. bool _flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length);
  36. bool _flash_erase_sector(uint8_t sector);
  37. bool _flash_erase_ok(void);
  38. #endif
  39. bool _flash_failed;
  40. uint32_t _last_re_init_ms;
  41. uint32_t _last_empty_ms;
  42. #if STORAGE_USE_FLASH
  43. AP_FlashStorage _flash{_buffer,
  44. HAL_STORAGE_SIZE,
  45. FUNCTOR_BIND_MEMBER(&Storage::_flash_write_data, bool, uint8_t, uint32_t, const uint8_t *, uint16_t),
  46. FUNCTOR_BIND_MEMBER(&Storage::_flash_read_data, bool, uint8_t, uint32_t, uint8_t *, uint16_t),
  47. FUNCTOR_BIND_MEMBER(&Storage::_flash_erase_sector, bool, uint8_t),
  48. FUNCTOR_BIND_MEMBER(&Storage::_flash_erase_ok, bool)};
  49. #endif
  50. void _flash_load(void);
  51. void _flash_write(uint16_t line);
  52. #if STORAGE_USE_POSIX
  53. bool using_filesystem;
  54. int log_fd;
  55. #endif
  56. };