APM:Libraries
Storage.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
3 
4 #include <assert.h>
5 #include <sys/types.h>
6 #include <sys/stat.h>
7 #include <fcntl.h>
8 #include <unistd.h>
9 
10 #include "Storage.h"
11 using namespace HALSITL;
12 
14 {
15  if (_eeprom_fd == -1) {
16  _eeprom_fd = open("eeprom.bin", O_RDWR|O_CREAT|O_CLOEXEC, 0777);
17  assert(ftruncate(_eeprom_fd, HAL_STORAGE_SIZE) == 0);
18  }
19 }
20 
21 void EEPROMStorage::read_block(void *dst, uint16_t src, size_t n)
22 {
23  assert(src < HAL_STORAGE_SIZE && src + n <= HAL_STORAGE_SIZE);
24  _eeprom_open();
25  assert(pread(_eeprom_fd, dst, n, src) == (ssize_t)n);
26 }
27 
28 void EEPROMStorage::write_block(uint16_t dst, const void *src, size_t n)
29 {
30  assert(dst < HAL_STORAGE_SIZE);
31  _eeprom_open();
32  assert(pwrite(_eeprom_fd, src, n, dst) == (ssize_t)n);
33 }
34 
35 #endif
#define HAL_STORAGE_SIZE
Definition: empty.h:5
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
void _eeprom_open(void)
Definition: Storage.cpp:13
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:21
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:28
int ftruncate(int fd, off_t length)
POSIX truncate open file to length.
Definition: posix.c:817