2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2013-01-03 04:35:05 -04:00
|
|
|
|
2016-11-27 17:52:19 -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-11-17 05:22:00 -04:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2013-01-03 04:35:05 -04:00
|
|
|
#include "AP_HAL_PX4_Namespace.h"
|
2013-01-24 00:02:10 -04:00
|
|
|
#include <systemlib/perf_counter.h>
|
2016-11-17 03:19:25 -04:00
|
|
|
#include <AP_Common/Bitmask.h>
|
2016-11-17 05:22:00 -04:00
|
|
|
#include <AP_FlashStorage/AP_FlashStorage.h>
|
2013-01-03 04:35:05 -04:00
|
|
|
|
2014-08-13 05:41:47 -03:00
|
|
|
#define PX4_STORAGE_SIZE HAL_STORAGE_SIZE
|
2016-11-17 05:22:00 -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 PX4_STORAGE_LINE_SHIFT 3
|
|
|
|
#else
|
2013-01-23 18:21:01 -04:00
|
|
|
#define PX4_STORAGE_LINE_SHIFT 9
|
2016-11-17 05:22:00 -04:00
|
|
|
#endif
|
|
|
|
|
2013-01-23 01:37:11 -04:00
|
|
|
#define PX4_STORAGE_LINE_SIZE (1<<PX4_STORAGE_LINE_SHIFT)
|
|
|
|
#define PX4_STORAGE_NUM_LINES (PX4_STORAGE_SIZE/PX4_STORAGE_LINE_SIZE)
|
|
|
|
|
|
|
|
class PX4::PX4Storage : public AP_HAL::Storage {
|
2013-01-03 04:35:05 -04:00
|
|
|
public:
|
2014-01-13 00:04:22 -04:00
|
|
|
PX4Storage();
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void init() {}
|
2014-08-13 01:59:28 -03:00
|
|
|
void read_block(void *dst, uint16_t src, size_t n);
|
2013-06-04 01:02:13 -03:00
|
|
|
void write_block(uint16_t dst, const void* src, size_t n);
|
2013-01-03 04:35:05 -04:00
|
|
|
|
2013-01-23 01:37:11 -04:00
|
|
|
void _timer_tick(void);
|
|
|
|
|
2013-01-03 04:35:05 -04:00
|
|
|
private:
|
2013-01-26 22:38:47 -04:00
|
|
|
volatile bool _initialised;
|
2013-01-23 01:37:11 -04:00
|
|
|
void _storage_create(void);
|
|
|
|
void _storage_open(void);
|
|
|
|
void _mark_dirty(uint16_t loc, uint16_t length);
|
2013-08-12 23:21:29 -03:00
|
|
|
uint8_t _buffer[PX4_STORAGE_SIZE] __attribute__((aligned(4)));
|
2016-11-17 03:19:25 -04:00
|
|
|
Bitmask _dirty_mask{PX4_STORAGE_NUM_LINES};
|
2013-01-24 00:02:10 -04:00
|
|
|
perf_counter_t _perf_storage;
|
|
|
|
perf_counter_t _perf_errors;
|
2016-02-23 01:32:19 -04:00
|
|
|
|
2016-11-27 17:52:19 -04:00
|
|
|
#if !USE_FLASH_STORAGE
|
2016-11-17 03:36:37 -04:00
|
|
|
int _fd = -1;
|
2016-11-27 17:52:19 -04:00
|
|
|
void bus_lock(bool lock);
|
2016-11-17 03:36:37 -04:00
|
|
|
void _mtd_load(void);
|
|
|
|
void _mtd_write(uint16_t line);
|
2016-02-23 01:32:19 -04:00
|
|
|
#if defined (CONFIG_ARCH_BOARD_PX4FMU_V4)
|
|
|
|
irqstate_t irq_state;
|
|
|
|
#endif
|
2016-11-17 05:22:00 -04:00
|
|
|
|
2016-11-27 17:52:19 -04:00
|
|
|
#else // USE_FLASH_STORAGE
|
2016-11-17 05:22:00 -04:00
|
|
|
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);
|
2016-11-18 20:29:43 -04:00
|
|
|
bool _flash_erase_ok(void);
|
2016-11-17 05:22:00 -04:00
|
|
|
uint8_t _flash_page;
|
2016-11-18 20:29:43 -04:00
|
|
|
bool _flash_failed;
|
2016-11-17 05:22:00 -04:00
|
|
|
|
|
|
|
AP_FlashStorage _flash{_buffer,
|
|
|
|
128*1024U,
|
|
|
|
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_write_data, bool, uint8_t, uint32_t, const uint8_t *, uint16_t),
|
|
|
|
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_read_data, bool, uint8_t, uint32_t, uint8_t *, uint16_t),
|
2016-11-18 20:29:43 -04:00
|
|
|
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_erase_sector, bool, uint8_t),
|
|
|
|
FUNCTOR_BIND_MEMBER(&PX4Storage::_flash_erase_ok, bool)};
|
2016-11-17 05:22:00 -04:00
|
|
|
|
|
|
|
void _flash_load(void);
|
|
|
|
void _flash_write(uint16_t line);
|
2016-11-27 17:52:19 -04:00
|
|
|
#endif
|
2013-01-03 04:35:05 -04:00
|
|
|
};
|