2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2013-09-22 03:01:24 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2014-08-25 13:18:48 -03:00
|
|
|
|
2015-03-19 09:52:55 -03:00
|
|
|
#define LINUX_STORAGE_SIZE HAL_STORAGE_SIZE
|
2014-08-25 13:18:48 -03:00
|
|
|
#define LINUX_STORAGE_MAX_WRITE 512
|
|
|
|
#define LINUX_STORAGE_LINE_SHIFT 9
|
|
|
|
#define LINUX_STORAGE_LINE_SIZE (1<<LINUX_STORAGE_LINE_SHIFT)
|
|
|
|
#define LINUX_STORAGE_NUM_LINES (LINUX_STORAGE_SIZE/LINUX_STORAGE_LINE_SIZE)
|
|
|
|
|
2016-07-29 16:14:02 -03:00
|
|
|
namespace Linux {
|
|
|
|
|
|
|
|
class Storage : public AP_HAL::Storage
|
2014-08-25 13:18:48 -03:00
|
|
|
{
|
|
|
|
public:
|
2015-10-20 18:13:25 -03:00
|
|
|
Storage() : _fd(-1),_dirty_mask(0) { }
|
2015-09-13 15:28:02 -03:00
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
static Storage *from(AP_HAL::Storage *storage) {
|
|
|
|
return static_cast<Storage*>(storage);
|
2015-09-13 15:28:02 -03:00
|
|
|
}
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void init() {}
|
2014-08-25 13:18:48 -03:00
|
|
|
uint8_t read_byte(uint16_t loc);
|
|
|
|
uint16_t read_word(uint16_t loc);
|
|
|
|
uint32_t read_dword(uint16_t loc);
|
|
|
|
void read_block(void *dst, uint16_t src, size_t n);
|
|
|
|
|
|
|
|
void write_byte(uint16_t loc, uint8_t value);
|
|
|
|
void write_word(uint16_t loc, uint16_t value);
|
|
|
|
void write_dword(uint16_t loc, uint32_t value);
|
|
|
|
void write_block(uint16_t dst, const void* src, size_t n);
|
|
|
|
|
|
|
|
virtual void _timer_tick(void);
|
|
|
|
protected:
|
|
|
|
void _mark_dirty(uint16_t loc, uint16_t length);
|
|
|
|
virtual void _storage_create(void);
|
|
|
|
virtual void _storage_open(void);
|
|
|
|
int _fd;
|
|
|
|
volatile bool _initialised;
|
|
|
|
uint8_t _buffer[LINUX_STORAGE_SIZE];
|
|
|
|
volatile uint32_t _dirty_mask;
|
|
|
|
};
|
2016-07-29 16:14:02 -03:00
|
|
|
|
|
|
|
}
|