mirror of https://github.com/ArduPilot/ardupilot
SITL: allow for different storage sizes
This commit is contained in:
parent
1a007dfcc0
commit
3640ae9cdf
|
@ -14,14 +14,14 @@ void SITLEEPROMStorage::_eeprom_open(void)
|
||||||
{
|
{
|
||||||
if (_eeprom_fd == -1) {
|
if (_eeprom_fd == -1) {
|
||||||
_eeprom_fd = open("eeprom.bin", O_RDWR|O_CREAT, 0777);
|
_eeprom_fd = open("eeprom.bin", O_RDWR|O_CREAT, 0777);
|
||||||
assert(ftruncate(_eeprom_fd, 4096) == 0);
|
assert(ftruncate(_eeprom_fd, HAL_STORAGE_SIZE) == 0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t SITLEEPROMStorage::read_byte(uint16_t loc)
|
uint8_t SITLEEPROMStorage::read_byte(uint16_t loc)
|
||||||
{
|
{
|
||||||
uint8_t value;
|
uint8_t value;
|
||||||
assert(loc < 4096);
|
assert(loc < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
assert(pread(_eeprom_fd, &value, 1, loc) == 1);
|
assert(pread(_eeprom_fd, &value, 1, loc) == 1);
|
||||||
return value;
|
return value;
|
||||||
|
@ -30,7 +30,7 @@ uint8_t SITLEEPROMStorage::read_byte(uint16_t loc)
|
||||||
uint16_t SITLEEPROMStorage::read_word(uint16_t loc)
|
uint16_t SITLEEPROMStorage::read_word(uint16_t loc)
|
||||||
{
|
{
|
||||||
uint16_t value;
|
uint16_t value;
|
||||||
assert(loc < 4096);
|
assert(loc < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
assert(pread(_eeprom_fd, &value, 2, loc) == 2);
|
assert(pread(_eeprom_fd, &value, 2, loc) == 2);
|
||||||
return value;
|
return value;
|
||||||
|
@ -39,7 +39,7 @@ uint16_t SITLEEPROMStorage::read_word(uint16_t loc)
|
||||||
uint32_t SITLEEPROMStorage::read_dword(uint16_t loc)
|
uint32_t SITLEEPROMStorage::read_dword(uint16_t loc)
|
||||||
{
|
{
|
||||||
uint32_t value;
|
uint32_t value;
|
||||||
assert(loc < 4096);
|
assert(loc < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
assert(pread(_eeprom_fd, &value, 4, loc) == 4);
|
assert(pread(_eeprom_fd, &value, 4, loc) == 4);
|
||||||
return value;
|
return value;
|
||||||
|
@ -47,35 +47,35 @@ uint32_t SITLEEPROMStorage::read_dword(uint16_t loc)
|
||||||
|
|
||||||
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 < 4096 && src + n < 4096);
|
assert(src < HAL_STORAGE_SIZE && src + n < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
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)
|
void SITLEEPROMStorage::write_byte(uint16_t loc, uint8_t value)
|
||||||
{
|
{
|
||||||
assert(loc < 4096);
|
assert(loc < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
assert(pwrite(_eeprom_fd, &value, 1, loc) == 1);
|
assert(pwrite(_eeprom_fd, &value, 1, loc) == 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SITLEEPROMStorage::write_word(uint16_t loc, uint16_t value)
|
void SITLEEPROMStorage::write_word(uint16_t loc, uint16_t value)
|
||||||
{
|
{
|
||||||
assert(loc < 4096);
|
assert(loc < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
assert(pwrite(_eeprom_fd, &value, 2, loc) == 2);
|
assert(pwrite(_eeprom_fd, &value, 2, loc) == 2);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SITLEEPROMStorage::write_dword(uint16_t loc, uint32_t value)
|
void SITLEEPROMStorage::write_dword(uint16_t loc, uint32_t value)
|
||||||
{
|
{
|
||||||
assert(loc < 4096);
|
assert(loc < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
assert(pwrite(_eeprom_fd, &value, 4, loc) == 4);
|
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 < 4096);
|
assert(dst < HAL_STORAGE_SIZE);
|
||||||
_eeprom_open();
|
_eeprom_open();
|
||||||
assert(pwrite(_eeprom_fd, src, n, dst) == (ssize_t)n);
|
assert(pwrite(_eeprom_fd, src, n, dst) == (ssize_t)n);
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue