2016-09-27 11:46:23 -03:00
|
|
|
#pragma once
|
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
/*
|
|
|
|
we can optionally use flash for storage instead of FRAM. That allows
|
|
|
|
ArduPilot to run on a wider range of boards and reduces board cost
|
|
|
|
*/
|
|
|
|
#ifndef USE_FLASH_STORAGE
|
|
|
|
#define USE_FLASH_STORAGE 0
|
|
|
|
#endif
|
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#include "AP_HAL_VRBRAIN_Namespace.h"
|
|
|
|
#include <systemlib/perf_counter.h>
|
2018-02-03 09:46:18 -04:00
|
|
|
#include <AP_Common/Bitmask.h>
|
|
|
|
#include <AP_FlashStorage/AP_FlashStorage.h>
|
2016-09-27 11:46:23 -03:00
|
|
|
|
|
|
|
#define VRBRAIN_STORAGE_SIZE HAL_STORAGE_SIZE
|
2018-02-03 09:46:18 -04:00
|
|
|
|
|
|
|
#if USE_FLASH_STORAGE
|
|
|
|
// when using flash storage we use a small line size to make storage
|
|
|
|
// compact and minimise the number of erase cycles needed
|
|
|
|
#define VRBRAIN_STORAGE_LINE_SHIFT 3
|
|
|
|
#else
|
2016-09-27 11:46:23 -03:00
|
|
|
#define VRBRAIN_STORAGE_LINE_SHIFT 9
|
2018-02-03 09:46:18 -04:00
|
|
|
#endif
|
|
|
|
|
2016-09-27 11:46:23 -03:00
|
|
|
#define VRBRAIN_STORAGE_LINE_SIZE (1<<VRBRAIN_STORAGE_LINE_SHIFT)
|
|
|
|
#define VRBRAIN_STORAGE_NUM_LINES (VRBRAIN_STORAGE_SIZE/VRBRAIN_STORAGE_LINE_SIZE)
|
|
|
|
|
|
|
|
class VRBRAIN::VRBRAINStorage : public AP_HAL::Storage {
|
|
|
|
public:
|
2018-02-03 09:46:18 -04:00
|
|
|
VRBRAINStorage();
|
2016-09-27 11:46:23 -03:00
|
|
|
|
|
|
|
void init() {}
|
|
|
|
void read_block(void *dst, uint16_t src, size_t n);
|
|
|
|
void write_block(uint16_t dst, const void* src, size_t n);
|
|
|
|
|
2018-01-26 22:32:19 -04:00
|
|
|
void _timer_tick(void) override;
|
2016-09-27 11:46:23 -03:00
|
|
|
|
|
|
|
private:
|
|
|
|
volatile bool _initialised;
|
|
|
|
void _storage_create(void);
|
|
|
|
void _storage_open(void);
|
|
|
|
void _mark_dirty(uint16_t loc, uint16_t length);
|
|
|
|
uint8_t _buffer[VRBRAIN_STORAGE_SIZE] __attribute__((aligned(4)));
|
2018-02-03 09:46:18 -04:00
|
|
|
Bitmask _dirty_mask{VRBRAIN_STORAGE_NUM_LINES};
|
2016-09-27 11:46:23 -03:00
|
|
|
perf_counter_t _perf_storage;
|
|
|
|
perf_counter_t _perf_errors;
|
2018-02-03 09:46:18 -04:00
|
|
|
uint32_t _last_re_init_ms;
|
2016-09-27 11:46:23 -03:00
|
|
|
|
2018-02-03 09:46:18 -04:00
|
|
|
#if !USE_FLASH_STORAGE
|
|
|
|
int _fd = -1;
|
2016-09-27 11:46:23 -03:00
|
|
|
void bus_lock(bool lock);
|
2018-02-03 09:46:18 -04:00
|
|
|
void _mtd_load(void);
|
|
|
|
void _mtd_write(uint16_t line);
|
|
|
|
#if defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
|
|
|
|
irqstate_t irq_state;
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#else // USE_FLASH_STORAGE
|
|
|
|
bool _flash_write_data(uint8_t sector, uint32_t offset, const uint8_t *data, uint16_t length);
|
|
|
|
bool _flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length);
|
|
|
|
bool _flash_erase_sector(uint8_t sector);
|
|
|
|
bool _flash_erase_ok(void);
|
|
|
|
uint8_t _flash_page;
|
|
|
|
bool _flash_failed;
|
|
|
|
|
|
|
|
AP_FlashStorage _flash{_buffer,
|
|
|
|
128*1024U,
|
|
|
|
FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_write_data, bool, uint8_t, uint32_t, const uint8_t *, uint16_t),
|
|
|
|
FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_read_data, bool, uint8_t, uint32_t, uint8_t *, uint16_t),
|
|
|
|
FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_erase_sector, bool, uint8_t),
|
|
|
|
FUNCTOR_BIND_MEMBER(&VRBRAINStorage::_flash_erase_ok, bool)};
|
|
|
|
|
|
|
|
void _flash_load(void);
|
|
|
|
void _flash_write(uint16_t line);
|
|
|
|
#endif
|
2016-09-27 11:46:23 -03:00
|
|
|
};
|