#include "Storage.h" #include #include #include #include #include #include #include #include #include using namespace Linux; /* This stores 'eeprom' data on the SD card, with a 4k size, and a in-memory buffer. This keeps the latency down. */ // name the storage file after the sketch so you can use the same board // card for ArduCopter and ArduPlane #define STORAGE_FILE SKETCHNAME ".stg" extern const AP_HAL::HAL& hal; static inline int is_dir(const char *path) { struct stat st; if (stat(path, &st) < 0) { return -errno; } return S_ISDIR(st.st_mode); } static int mkdir_p(const char *path, int len, mode_t mode) { char *start, *end; start = strndupa(path, len); end = start + len; /* * scan backwards, replacing '/' with '\0' while the component doesn't * exist */ for (;;) { int r = is_dir(start); if (r > 0) { end += strlen(end); if (end == start + len) { return 0; } /* end != start, since it would be caught on the first * iteration */ *end = '/'; break; } else if (r == 0) { return -ENOTDIR; } if (end == start) { break; } *end = '\0'; /* Find the next component, backwards, discarding extra '/'*/ while (end > start && *end != '/') { end--; } while (end > start && *(end - 1) == '/') { end--; } } while (end < start + len) { if (mkdir(start, mode) < 0 && errno != EEXIST) { return -errno; } end += strlen(end); *end = '/'; } return 0; } void Storage::_storage_create(void) { const char *dpath = HAL_BOARD_STORAGE_DIRECTORY, *p; int dfd = -1; p = hal.util->get_custom_storage_directory(); if (p) { dpath = p; } mkdir_p(dpath, strlen(dpath), 0777); dfd = open(dpath, O_RDWR|O_CLOEXEC); if (dfd < 0) { AP_HAL::panic("Error opening storage directory: %s\n", dpath); } unlinkat(dfd, STORAGE_FILE, 0); int fd = openat(dfd, STORAGE_FILE, O_RDWR|O_CREAT|O_CLOEXEC, 0666); close(dfd); if (fd == -1) { AP_HAL::panic("Failed to create %s/%s", HAL_BOARD_STORAGE_DIRECTORY, STORAGE_FILE); } // ensure the directory is updated with the new size fsync(fd); close(fd); } void Storage::_storage_open(void) { if (_initialised) { return; } _dirty_mask = 0; memset(_buffer, 0, sizeof(_buffer)); int fd = open(STORAGE_FILE, O_RDWR|O_CLOEXEC); if (fd == -1) { _storage_create(); fd = open(STORAGE_FILE, O_RDWR|O_CLOEXEC); if (fd == -1) { AP_HAL::panic("Failed to open " STORAGE_FILE); } } /* we allow a read of size 4096 to cope with the old storage size without forcing users to reset all parameters */ ssize_t ret = read(fd, _buffer, sizeof(_buffer)); if (ret == 4096 && ret != sizeof(_buffer)) { if (ftruncate(fd, sizeof(_buffer)) != 0) { AP_HAL::panic("Failed to expand " STORAGE_FILE); } ret = sizeof(_buffer); } if (ret != sizeof(_buffer)) { close(fd); _storage_create(); fd = open(STORAGE_FILE, O_RDONLY|O_CLOEXEC); if (fd == -1) { AP_HAL::panic("Failed to open " STORAGE_FILE); } if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) { AP_HAL::panic("Failed to read " STORAGE_FILE); } } close(fd); _initialised = true; } /* mark some lines as dirty. Note that there is no attempt to avoid the race condition between this code and the _timer_tick() code below, which both update _dirty_mask. If we lose the race then the result is that a line is written more than once, but it won't result in a line not being written. */ void Storage::_mark_dirty(uint16_t loc, uint16_t length) { uint16_t end = loc + length; for (uint8_t line=loc>>LINUX_STORAGE_LINE_SHIFT; line <= end>>LINUX_STORAGE_LINE_SHIFT; line++) { _dirty_mask |= 1U << line; } } void Storage::read_block(void *dst, uint16_t loc, size_t n) { if (loc >= sizeof(_buffer)-(n-1)) { return; } _storage_open(); memcpy(dst, &_buffer[loc], n); } void Storage::write_block(uint16_t loc, const void *src, size_t n) { if (loc >= sizeof(_buffer)-(n-1)) { return; } if (memcmp(src, &_buffer[loc], n) != 0) { _storage_open(); memcpy(&_buffer[loc], src, n); _mark_dirty(loc, n); } } void Storage::_timer_tick(void) { if (!_initialised || _dirty_mask == 0) { return; } if (_fd == -1) { _fd = open(STORAGE_FILE, O_WRONLY|O_CLOEXEC); if (_fd == -1) { return; } } // write out the first dirty set of lines. We don't write more // than one to keep the latency of this call to a minimum uint8_t i, n; for (i=0; i>LINUX_STORAGE_LINE_SHIFT); n++) { if (!(_dirty_mask & (1<<(n+i)))) { break; } // mark that line clean write_mask |= (1<<(n+i)); } /* write the lines. This also updates _dirty_mask. Note that because this is a SCHED_FIFO thread it will not be preempted by the main task except during blocking calls. This means we don't need a semaphore around the _dirty_mask updates. */ if (lseek(_fd, i<