7 #ifndef USE_FLASH_STORAGE 8 #define USE_FLASH_STORAGE 0 13 #include <systemlib/perf_counter.h> 17 #define PX4_STORAGE_SIZE HAL_STORAGE_SIZE 22 #define PX4_STORAGE_LINE_SHIFT 3 24 #define PX4_STORAGE_LINE_SHIFT 9 27 #define PX4_STORAGE_LINE_SIZE (1<<PX4_STORAGE_LINE_SHIFT) 28 #define PX4_STORAGE_NUM_LINES (PX4_STORAGE_SIZE/PX4_STORAGE_LINE_SIZE) 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);
51 #if !USE_FLASH_STORAGE 56 #if defined (CONFIG_ARCH_BOARD_PX4FMU_V4) 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);
70 FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_write_data,
bool, uint8_t, uint32_t,
const uint8_t *, uint16_t),
71 FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_read_data,
bool, uint8_t, uint32_t, uint8_t *, uint16_t),
75 void _flash_load(
void);
76 void _flash_write(uint16_t line);
perf_counter_t _perf_storage
volatile bool _initialised
void write_block(uint16_t dst, const void *src, size_t n)
void read_block(void *dst, uint16_t src, size_t n)
void _storage_create(void)
void _timer_tick(void) override
uint32_t _last_re_init_ms
perf_counter_t _perf_errors
void _mark_dirty(uint16_t loc, uint16_t length)
uint8_t _buffer [PX4_STORAGE_SIZE] __attribute__((aligned(4)))
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
void _mtd_write(uint16_t line)
#define PX4_STORAGE_NUM_LINES