APM:Libraries
Storage.cpp
Go to the documentation of this file.
1 #include "Storage.h"
2 
3 #include <assert.h>
4 #include <errno.h>
5 #include <fcntl.h>
6 #include <stdio.h>
7 #include <sys/stat.h>
8 #include <sys/types.h>
9 #include <unistd.h>
10 
11 #include <AP_HAL/AP_HAL.h>
13 
14 using namespace Linux;
15 
16 /*
17  This stores 'eeprom' data on the SD card, with a 4k size, and a
18  in-memory buffer. This keeps the latency down.
19  */
20 
21 // name the storage file after the sketch so you can use the same board
22 // card for ArduCopter and ArduPlane
23 #define STORAGE_FILE SKETCHNAME ".stg"
24 
25 extern const AP_HAL::HAL& hal;
26 
27 static inline int is_dir(const char *path)
28 {
29  struct stat st;
30 
31  if (stat(path, &st) < 0) {
32  return -errno;
33  }
34 
35  return S_ISDIR(st.st_mode);
36 }
37 
38 static int mkdir_p(const char *path, int len, mode_t mode)
39 {
40  char *start, *end;
41 
42  start = strndupa(path, len);
43  end = start + len;
44 
45  /*
46  * scan backwards, replacing '/' with '\0' while the component doesn't
47  * exist
48  */
49  for (;;) {
50  int r = is_dir(start);
51  if (r > 0) {
52  end += strlen(end);
53 
54  if (end == start + len) {
55  return 0;
56  }
57 
58  /* end != start, since it would be caught on the first
59  * iteration */
60  *end = '/';
61  break;
62  } else if (r == 0) {
63  return -ENOTDIR;
64  }
65 
66  if (end == start) {
67  break;
68  }
69 
70  *end = '\0';
71 
72  /* Find the next component, backwards, discarding extra '/'*/
73  while (end > start && *end != '/') {
74  end--;
75  }
76 
77  while (end > start && *(end - 1) == '/') {
78  end--;
79  }
80  }
81 
82  while (end < start + len) {
83  if (mkdir(start, mode) < 0 && errno != EEXIST) {
84  return -errno;
85  }
86 
87  end += strlen(end);
88  *end = '/';
89  }
90 
91  return 0;
92 }
93 
94 int Storage::_storage_create(const char *dpath)
95 {
96  int dfd = -1;
97 
98  mkdir_p(dpath, strlen(dpath), 0777);
99  dfd = open(dpath, O_RDONLY|O_CLOEXEC);
100  if (dfd == -1) {
101  fprintf(stderr, "Failed to open storage directory: %s (%m)\n", dpath);
102  return -1;
103  }
104 
105  unlinkat(dfd, dpath, 0);
106  int fd = openat(dfd, STORAGE_FILE, O_RDWR|O_CREAT|O_CLOEXEC, 0666);
107 
108  close(dfd);
109 
110  if (fd == -1) {
111  fprintf(stderr, "Failed to create storage file %s/%s\n", dpath,
112  STORAGE_FILE);
113  goto fail;
114  }
115 
116  // take up all needed space
117  if (ftruncate(fd, sizeof(_buffer)) == -1) {
118  fprintf(stderr, "Failed to set file size to %u kB (%m)\n",
119  sizeof(_buffer) / 1024);
120  goto fail;
121  }
122 
123  // ensure the directory is updated with the new size
124  fsync(fd);
125  fsync(dfd);
126 
127  close(dfd);
128 
129  return fd;
130 
131 fail:
132  close(dfd);
133  return -1;
134 }
135 
137 {
138  const char *dpath;
139 
140  if (_initialised) {
141  return;
142  }
143 
144  _dirty_mask = 0;
145 
146  dpath = hal.util->get_custom_storage_directory();
147  if (!dpath) {
149  }
150 
151  int fd = open(dpath, O_RDWR|O_CLOEXEC);
152  if (fd == -1) {
153  fd = _storage_create(dpath);
154  if (fd == -1) {
155  AP_HAL::panic("Cannot create storage %s (%m)", dpath);
156  }
157  }
158 
159  ssize_t ret = read(fd, _buffer, sizeof(_buffer));
160 
161  if (ret != sizeof(_buffer)) {
162  close(fd);
163  _storage_create(dpath);
164  fd = open(dpath, O_RDONLY|O_CLOEXEC);
165  if (fd == -1) {
166  AP_HAL::panic("Failed to open %s (%m)", dpath);
167  }
168  if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
169  AP_HAL::panic("Failed to read %s (%m)", dpath);
170  }
171  }
172 
173  _fd = fd;
174  _initialised = true;
175 }
176 
177 /*
178  mark some lines as dirty. Note that there is no attempt to avoid
179  the race condition between this code and the _timer_tick() code
180  below, which both update _dirty_mask. If we lose the race then the
181  result is that a line is written more than once, but it won't result
182  in a line not being written.
183  */
184 void Storage::_mark_dirty(uint16_t loc, uint16_t length)
185 {
186  uint16_t end = loc + length;
187  for (uint8_t line=loc>>LINUX_STORAGE_LINE_SHIFT;
188  line <= end>>LINUX_STORAGE_LINE_SHIFT;
189  line++) {
190  _dirty_mask |= 1U << line;
191  }
192 }
193 
194 void Storage::read_block(void *dst, uint16_t loc, size_t n)
195 {
196  if (loc >= sizeof(_buffer)-(n-1)) {
197  return;
198  }
199  init();
200  memcpy(dst, &_buffer[loc], n);
201 }
202 
203 void Storage::write_block(uint16_t loc, const void *src, size_t n)
204 {
205  if (loc >= sizeof(_buffer)-(n-1)) {
206  return;
207  }
208  if (memcmp(src, &_buffer[loc], n) != 0) {
209  init();
210  memcpy(&_buffer[loc], src, n);
211  _mark_dirty(loc, n);
212  }
213 }
214 
216 {
217  if (!_initialised || _dirty_mask == 0 || _fd == -1) {
218  return;
219  }
220 
221  // write out the first dirty set of lines. We don't write more
222  // than one to keep the latency of this call to a minimum
223  uint8_t i, n;
224  for (i=0; i<LINUX_STORAGE_NUM_LINES; i++) {
225  if (_dirty_mask & (1<<i)) {
226  break;
227  }
228  }
229  if (i == LINUX_STORAGE_NUM_LINES) {
230  // this shouldn't be possible
231  return;
232  }
233  uint32_t write_mask = (1U<<i);
234  // see how many lines to write
235  for (n=1; (i+n) < LINUX_STORAGE_NUM_LINES &&
237  if (!(_dirty_mask & (1<<(n+i)))) {
238  break;
239  }
240  // mark that line clean
241  write_mask |= (1<<(n+i));
242  }
243 
244  /*
245  write the lines. This also updates _dirty_mask. Note that
246  because this is a SCHED_FIFO thread it will not be preempted
247  by the main task except during blocking calls. This means we
248  don't need a semaphore around the _dirty_mask updates.
249  */
250  if (lseek(_fd, i<<LINUX_STORAGE_LINE_SHIFT, SEEK_SET) == (i<<LINUX_STORAGE_LINE_SHIFT)) {
251  _dirty_mask &= ~write_mask;
253  // write error - likely EINTR
254  _dirty_mask |= write_mask;
255  close(_fd);
256  _fd = -1;
257  }
258  if (_dirty_mask == 0) {
259  if (fsync(_fd) != 0) {
260  close(_fd);
261  _fd = -1;
262  }
263  }
264  }
265 }
#define LINUX_STORAGE_MAX_WRITE
Definition: Storage.h:6
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
ssize_t write(int fd, const void *buf, size_t count)
POSIX Write count bytes from *buf to fileno fd.
Definition: posix.c:1169
AP_HAL::Util * util
Definition: HAL.h:115
void write_block(uint16_t dst, const void *src, size_t n)
Definition: Storage.cpp:203
#define HAL_BOARD_STORAGE_DIRECTORY
Definition: linux.h:13
void fail(const char *why)
Definition: eedump.c:28
#define LINUX_STORAGE_LINE_SHIFT
Definition: Storage.h:7
int _storage_create(const char *dpath)
Definition: Storage.cpp:94
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
#define LINUX_STORAGE_NUM_LINES
Definition: Storage.h:9
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
static int mkdir_p(const char *path, int len, mode_t mode)
Definition: Storage.cpp:38
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
void read_block(void *dst, uint16_t src, size_t n)
Definition: Storage.cpp:194
virtual void _timer_tick(void) override
Definition: Storage.cpp:215
off_t lseek(int fileno, off_t position, int whence)
POSIX seek to file position.
Definition: posix.c:612
int mkdir(const char *pathname, mode_t mode)
POSIX make a directory.
Definition: posix.c:1620
int ftruncate(int fd, off_t length)
POSIX truncate open file to length.
Definition: posix.c:817
volatile bool _initialised
Definition: Storage.h:42
virtual const char * get_custom_storage_directory() const
Definition: Util.h:23
static int is_dir(const char *path)
Definition: Storage.cpp:27
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
Definition: posix.c:1319
void _mark_dirty(uint16_t loc, uint16_t length)
Definition: Storage.cpp:184
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
int fsync(int fileno)
Definition: posix.c:2562
void init() override
Definition: Storage.cpp:136
volatile uint32_t _dirty_mask
Definition: Storage.h:43
uint8_t _buffer[LINUX_STORAGE_SIZE]
Definition: Storage.h:44
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define STORAGE_FILE
Definition: Storage.cpp:23