AP_HAL: removed old storage type read/write functions

not needed any more
This commit is contained in:
Andrew Tridgell 2014-08-13 14:59:28 +10:00
parent 65614da10b
commit d40d0f6aec
15 changed files with 26 additions and 390 deletions

View File

@ -8,14 +8,7 @@
class AP_HAL::Storage { class AP_HAL::Storage {
public: public:
virtual void init(void *) = 0; virtual void init(void *) = 0;
virtual uint8_t read_byte(uint16_t loc) = 0; virtual void read_block(void *dst, uint16_t src, size_t n) = 0;
virtual uint16_t read_word(uint16_t loc) = 0;
virtual uint32_t read_dword(uint16_t loc) = 0;
virtual void read_block(void *dst, uint16_t src, size_t n) = 0;
virtual void write_byte(uint16_t loc, uint8_t value) = 0;
virtual void write_word(uint16_t loc, uint16_t value) = 0;
virtual void write_dword(uint16_t loc, uint32_t value) = 0;
virtual void write_block(uint16_t dst, const void* src, size_t n) = 0; virtual void write_block(uint16_t dst, const void* src, size_t n) = 0;
}; };

View File

@ -6,41 +6,25 @@
#include "Storage.h" #include "Storage.h"
using namespace AP_HAL_AVR; using namespace AP_HAL_AVR;
uint8_t AVREEPROMStorage::read_byte(uint16_t loc) { void AVREEPROMStorage::read_block(void *dst, uint16_t src, size_t n)
return eeprom_read_byte((uint8_t*)loc); {
}
uint16_t AVREEPROMStorage::read_word(uint16_t loc) {
return eeprom_read_word((uint16_t*)loc);
}
uint32_t AVREEPROMStorage::read_dword(uint16_t loc) {
return eeprom_read_dword((uint32_t*)loc);
}
void AVREEPROMStorage::read_block(void *dst, uint16_t src, size_t n) {
eeprom_read_block(dst,(const void*)src,n); eeprom_read_block(dst,(const void*)src,n);
} }
void AVREEPROMStorage::write_byte(uint16_t loc, uint8_t value) { void AVREEPROMStorage::write_block(uint16_t dst, const void *src, size_t n)
uint8_t b = eeprom_read_byte((uint8_t*)loc); {
if (b != value) {
eeprom_write_byte((uint8_t*)loc, value);
}
}
void AVREEPROMStorage::write_word(uint16_t loc, uint16_t value) {
write_block(loc, &value, sizeof(value));
}
void AVREEPROMStorage::write_dword(uint16_t loc, uint32_t value) {
write_block(loc, &value, sizeof(value));
}
void AVREEPROMStorage::write_block(uint16_t dst, const void *src, size_t n) {
uint8_t *p = (uint8_t *)src; uint8_t *p = (uint8_t *)src;
while (n--) { while (n--) {
write_byte(dst++, *p++); /*
it is much faster to read than write, so it is worth
checking if the value is already correct
*/
uint8_t b = eeprom_read_byte((uint8_t*)dst);
if (b != *p) {
eeprom_write_byte((uint8_t*)dst, *p);
}
dst++;
*p++;
} }
} }

View File

@ -10,14 +10,7 @@ class AP_HAL_AVR::AVREEPROMStorage : public AP_HAL::Storage {
public: public:
AVREEPROMStorage() {} AVREEPROMStorage() {}
void init(void* machtnichts) {} void init(void* machtnichts) {}
uint8_t read_byte(uint16_t loc); void read_block(void *dst, uint16_t src, size_t n);
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); void write_block(uint16_t dst, const void* src, size_t n);
}; };

View File

@ -18,33 +18,6 @@ void SITLEEPROMStorage::_eeprom_open(void)
} }
} }
uint8_t SITLEEPROMStorage::read_byte(uint16_t loc)
{
uint8_t value;
assert(loc < HAL_STORAGE_SIZE);
_eeprom_open();
assert(pread(_eeprom_fd, &value, 1, loc) == 1);
return value;
}
uint16_t SITLEEPROMStorage::read_word(uint16_t loc)
{
uint16_t value;
assert(loc < HAL_STORAGE_SIZE);
_eeprom_open();
assert(pread(_eeprom_fd, &value, 2, loc) == 2);
return value;
}
uint32_t SITLEEPROMStorage::read_dword(uint16_t loc)
{
uint32_t value;
assert(loc < HAL_STORAGE_SIZE);
_eeprom_open();
assert(pread(_eeprom_fd, &value, 4, loc) == 4);
return value;
}
void SITLEEPROMStorage::read_block(void *dst, uint16_t src, size_t n) void SITLEEPROMStorage::read_block(void *dst, uint16_t src, size_t n)
{ {
assert(src < HAL_STORAGE_SIZE && src + n < HAL_STORAGE_SIZE); assert(src < HAL_STORAGE_SIZE && src + n < HAL_STORAGE_SIZE);
@ -52,27 +25,6 @@ void SITLEEPROMStorage::read_block(void *dst, uint16_t src, size_t n)
assert(pread(_eeprom_fd, dst, n, src) == (ssize_t)n); assert(pread(_eeprom_fd, dst, n, src) == (ssize_t)n);
} }
void SITLEEPROMStorage::write_byte(uint16_t loc, uint8_t value)
{
assert(loc < HAL_STORAGE_SIZE);
_eeprom_open();
assert(pwrite(_eeprom_fd, &value, 1, loc) == 1);
}
void SITLEEPROMStorage::write_word(uint16_t loc, uint16_t value)
{
assert(loc < HAL_STORAGE_SIZE);
_eeprom_open();
assert(pwrite(_eeprom_fd, &value, 2, loc) == 2);
}
void SITLEEPROMStorage::write_dword(uint16_t loc, uint32_t value)
{
assert(loc < HAL_STORAGE_SIZE);
_eeprom_open();
assert(pwrite(_eeprom_fd, &value, 4, loc) == 4);
}
void SITLEEPROMStorage::write_block(uint16_t dst, const void *src, size_t n) void SITLEEPROMStorage::write_block(uint16_t dst, const void *src, size_t n)
{ {
assert(dst < HAL_STORAGE_SIZE); assert(dst < HAL_STORAGE_SIZE);

View File

@ -12,14 +12,7 @@ public:
_eeprom_fd = -1; _eeprom_fd = -1;
} }
void init(void* machtnichts) {} void init(void* machtnichts) {}
uint8_t read_byte(uint16_t loc); void read_block(void *dst, uint16_t src, size_t n);
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); void write_block(uint16_t dst, const void* src, size_t n);
private: private:

View File

@ -10,31 +10,10 @@ EmptyStorage::EmptyStorage()
void EmptyStorage::init(void*) void EmptyStorage::init(void*)
{} {}
uint8_t EmptyStorage::read_byte(uint16_t loc){
return 0;
}
uint16_t EmptyStorage::read_word(uint16_t loc){
return 0;
}
uint32_t EmptyStorage::read_dword(uint16_t loc){
return 0;
}
void EmptyStorage::read_block(void* dst, uint16_t src, size_t n) { void EmptyStorage::read_block(void* dst, uint16_t src, size_t n) {
memset(dst, 0, n); memset(dst, 0, n);
} }
void EmptyStorage::write_byte(uint16_t loc, uint8_t value)
{}
void EmptyStorage::write_word(uint16_t loc, uint16_t value)
{}
void EmptyStorage::write_dword(uint16_t loc, uint32_t value)
{}
void EmptyStorage::write_block(uint16_t loc, const void* src, size_t n) void EmptyStorage::write_block(uint16_t loc, const void* src, size_t n)
{} {}

View File

@ -8,14 +8,7 @@ class Empty::EmptyStorage : public AP_HAL::Storage {
public: public:
EmptyStorage(); EmptyStorage();
void init(void *); void init(void *);
uint8_t read_byte(uint16_t loc); void read_block(void *dst, uint16_t src, size_t n);
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); void write_block(uint16_t dst, const void* src, size_t n);
}; };

View File

@ -89,20 +89,6 @@ uint8_t FLYMAPLEStorage::read_byte(uint16_t loc){
return data & 0xff; // Even lower byte return data & 0xff; // Even lower byte
} }
uint16_t FLYMAPLEStorage::read_word(uint16_t loc){
//hal.console->printf("read_word %d\n", loc);
uint16_t value;
read_block(&value, loc, sizeof(value));
return value;
}
uint32_t FLYMAPLEStorage::read_dword(uint16_t loc){
//hal.console->printf("read_dword %d\n", loc);
uint32_t value;
read_block(&value, loc, sizeof(value));
return value;
}
void FLYMAPLEStorage::read_block(void* dst, uint16_t src, size_t n) { void FLYMAPLEStorage::read_block(void* dst, uint16_t src, size_t n) {
// hal.console->printf("read_block %d %d\n", src, n); // hal.console->printf("read_block %d %d\n", src, n);
// Treat as a block of bytes // Treat as a block of bytes
@ -132,18 +118,6 @@ void FLYMAPLEStorage::write_byte(uint16_t loc, uint8_t value)
eeprom[eeprom_index].write(eeprom_offset >> 1, data); eeprom[eeprom_index].write(eeprom_offset >> 1, data);
} }
void FLYMAPLEStorage::write_word(uint16_t loc, uint16_t value)
{
// hal.console->printf("write_word %d, %d\n", loc, value);
write_block(loc, &value, sizeof(value));
}
void FLYMAPLEStorage::write_dword(uint16_t loc, uint32_t value)
{
// hal.console->printf("write_dword %d, %d\n", loc, value);
write_block(loc, &value, sizeof(value));
}
void FLYMAPLEStorage::write_block(uint16_t loc, const void* src, size_t n) void FLYMAPLEStorage::write_block(uint16_t loc, const void* src, size_t n)
{ {
// hal.console->printf("write_block %d, %d\n", loc, n); // hal.console->printf("write_block %d, %d\n", loc, n);

View File

@ -25,15 +25,12 @@ class AP_HAL_FLYMAPLE_NS::FLYMAPLEStorage : public AP_HAL::Storage {
public: public:
FLYMAPLEStorage(); FLYMAPLEStorage();
void init(void *); void init(void *);
uint8_t read_byte(uint16_t loc); void read_block(void *dst, uint16_t src, size_t n);
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); void write_block(uint16_t dst, const void* src, size_t n);
private:
uint8_t read_byte(uint16_t loc);
void write_byte(uint16_t loc, uint8_t value);
}; };
#endif // __AP_HAL_FLYMAPLE_STORAGE_H__ #endif // __AP_HAL_FLYMAPLE_STORAGE_H__

View File

@ -89,37 +89,6 @@ void LinuxStorage::_mark_dirty(uint16_t loc, uint16_t length)
} }
} }
uint8_t LinuxStorage::read_byte(uint16_t loc)
{
if (loc >= sizeof(_buffer)) {
return 0;
}
_storage_open();
return _buffer[loc];
}
uint16_t LinuxStorage::read_word(uint16_t loc)
{
uint16_t value;
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return 0;
}
_storage_open();
memcpy(&value, &_buffer[loc], sizeof(value));
return value;
}
uint32_t LinuxStorage::read_dword(uint16_t loc)
{
uint32_t value;
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return 0;
}
_storage_open();
memcpy(&value, &_buffer[loc], sizeof(value));
return value;
}
void LinuxStorage::read_block(void *dst, uint16_t loc, size_t n) void LinuxStorage::read_block(void *dst, uint16_t loc, size_t n)
{ {
if (loc >= sizeof(_buffer)-(n-1)) { if (loc >= sizeof(_buffer)-(n-1)) {
@ -129,42 +98,6 @@ void LinuxStorage::read_block(void *dst, uint16_t loc, size_t n)
memcpy(dst, &_buffer[loc], n); memcpy(dst, &_buffer[loc], n);
} }
void LinuxStorage::write_byte(uint16_t loc, uint8_t value)
{
if (loc >= sizeof(_buffer)) {
return;
}
if (_buffer[loc] != value) {
_storage_open();
_buffer[loc] = value;
_mark_dirty(loc, sizeof(value));
}
}
void LinuxStorage::write_word(uint16_t loc, uint16_t value)
{
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return;
}
if (memcmp(&value, &_buffer[loc], sizeof(value)) != 0) {
_storage_open();
memcpy(&_buffer[loc], &value, sizeof(value));
_mark_dirty(loc, sizeof(value));
}
}
void LinuxStorage::write_dword(uint16_t loc, uint32_t value)
{
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return;
}
if (memcmp(&value, &_buffer[loc], sizeof(value)) != 0) {
_storage_open();
memcpy(&_buffer[loc], &value, sizeof(value));
_mark_dirty(loc, sizeof(value));
}
}
void LinuxStorage::write_block(uint16_t loc, const void *src, size_t n) void LinuxStorage::write_block(uint16_t loc, const void *src, size_t n)
{ {
if (loc >= sizeof(_buffer)-(n-1)) { if (loc >= sizeof(_buffer)-(n-1)) {

View File

@ -20,14 +20,7 @@ public:
_dirty_mask(0) _dirty_mask(0)
{} {}
void init(void* machtnichts) {} void init(void* machtnichts) {}
uint8_t read_byte(uint16_t loc); void read_block(void *dst, uint16_t src, size_t n);
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); void write_block(uint16_t dst, const void* src, size_t n);
void _timer_tick(void); void _timer_tick(void);

View File

@ -184,37 +184,6 @@ void PX4Storage::_mark_dirty(uint16_t loc, uint16_t length)
} }
} }
uint8_t PX4Storage::read_byte(uint16_t loc)
{
if (loc >= sizeof(_buffer)) {
return 0;
}
_storage_open();
return _buffer[loc];
}
uint16_t PX4Storage::read_word(uint16_t loc)
{
uint16_t value;
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return 0;
}
_storage_open();
memcpy(&value, &_buffer[loc], sizeof(value));
return value;
}
uint32_t PX4Storage::read_dword(uint16_t loc)
{
uint32_t value;
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return 0;
}
_storage_open();
memcpy(&value, &_buffer[loc], sizeof(value));
return value;
}
void PX4Storage::read_block(void *dst, uint16_t loc, size_t n) void PX4Storage::read_block(void *dst, uint16_t loc, size_t n)
{ {
if (loc >= sizeof(_buffer)-(n-1)) { if (loc >= sizeof(_buffer)-(n-1)) {
@ -224,42 +193,6 @@ void PX4Storage::read_block(void *dst, uint16_t loc, size_t n)
memcpy(dst, &_buffer[loc], n); memcpy(dst, &_buffer[loc], n);
} }
void PX4Storage::write_byte(uint16_t loc, uint8_t value)
{
if (loc >= sizeof(_buffer)) {
return;
}
if (_buffer[loc] != value) {
_storage_open();
_buffer[loc] = value;
_mark_dirty(loc, sizeof(value));
}
}
void PX4Storage::write_word(uint16_t loc, uint16_t value)
{
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return;
}
if (memcmp(&value, &_buffer[loc], sizeof(value)) != 0) {
_storage_open();
memcpy(&_buffer[loc], &value, sizeof(value));
_mark_dirty(loc, sizeof(value));
}
}
void PX4Storage::write_dword(uint16_t loc, uint32_t value)
{
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return;
}
if (memcmp(&value, &_buffer[loc], sizeof(value)) != 0) {
_storage_open();
memcpy(&_buffer[loc], &value, sizeof(value));
_mark_dirty(loc, sizeof(value));
}
}
void PX4Storage::write_block(uint16_t loc, const void *src, size_t n) void PX4Storage::write_block(uint16_t loc, const void *src, size_t n)
{ {
if (loc >= sizeof(_buffer)-(n-1)) { if (loc >= sizeof(_buffer)-(n-1)) {

View File

@ -18,14 +18,7 @@ public:
PX4Storage(); PX4Storage();
void init(void* machtnichts) {} void init(void* machtnichts) {}
uint8_t read_byte(uint16_t loc); void read_block(void *dst, uint16_t src, size_t n);
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); void write_block(uint16_t dst, const void* src, size_t n);
void _timer_tick(void); void _timer_tick(void);

View File

@ -184,37 +184,6 @@ void VRBRAINStorage::_mark_dirty(uint16_t loc, uint16_t length)
} }
} }
uint8_t VRBRAINStorage::read_byte(uint16_t loc)
{
if (loc >= sizeof(_buffer)) {
return 0;
}
_storage_open();
return _buffer[loc];
}
uint16_t VRBRAINStorage::read_word(uint16_t loc)
{
uint16_t value;
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return 0;
}
_storage_open();
memcpy(&value, &_buffer[loc], sizeof(value));
return value;
}
uint32_t VRBRAINStorage::read_dword(uint16_t loc)
{
uint32_t value;
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return 0;
}
_storage_open();
memcpy(&value, &_buffer[loc], sizeof(value));
return value;
}
void VRBRAINStorage::read_block(void *dst, uint16_t loc, size_t n) void VRBRAINStorage::read_block(void *dst, uint16_t loc, size_t n)
{ {
if (loc >= sizeof(_buffer)-(n-1)) { if (loc >= sizeof(_buffer)-(n-1)) {
@ -224,42 +193,6 @@ void VRBRAINStorage::read_block(void *dst, uint16_t loc, size_t n)
memcpy(dst, &_buffer[loc], n); memcpy(dst, &_buffer[loc], n);
} }
void VRBRAINStorage::write_byte(uint16_t loc, uint8_t value)
{
if (loc >= sizeof(_buffer)) {
return;
}
if (_buffer[loc] != value) {
_storage_open();
_buffer[loc] = value;
_mark_dirty(loc, sizeof(value));
}
}
void VRBRAINStorage::write_word(uint16_t loc, uint16_t value)
{
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return;
}
if (memcmp(&value, &_buffer[loc], sizeof(value)) != 0) {
_storage_open();
memcpy(&_buffer[loc], &value, sizeof(value));
_mark_dirty(loc, sizeof(value));
}
}
void VRBRAINStorage::write_dword(uint16_t loc, uint32_t value)
{
if (loc >= sizeof(_buffer)-(sizeof(value)-1)) {
return;
}
if (memcmp(&value, &_buffer[loc], sizeof(value)) != 0) {
_storage_open();
memcpy(&_buffer[loc], &value, sizeof(value));
_mark_dirty(loc, sizeof(value));
}
}
void VRBRAINStorage::write_block(uint16_t loc, const void *src, size_t n) void VRBRAINStorage::write_block(uint16_t loc, const void *src, size_t n)
{ {
if (loc >= sizeof(_buffer)-(n-1)) { if (loc >= sizeof(_buffer)-(n-1)) {

View File

@ -18,14 +18,7 @@ public:
VRBRAINStorage(); VRBRAINStorage();
void init(void* machtnichts) {} void init(void* machtnichts) {}
uint8_t read_byte(uint16_t loc); void read_block(void *dst, uint16_t src, size_t n);
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); void write_block(uint16_t dst, const void* src, size_t n);
void _timer_tick(void); void _timer_tick(void);