2016-05-17 23:26:57 -03:00
|
|
|
#include "Storage.h"
|
2014-11-07 17:10:29 -04:00
|
|
|
|
|
|
|
#include <assert.h>
|
|
|
|
#include <errno.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <fcntl.h>
|
2014-11-07 17:10:29 -04:00
|
|
|
#include <stdio.h>
|
2016-05-17 23:26:57 -03:00
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <sys/types.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-05-03 00:22:03 -03:00
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
2014-11-07 17:10:29 -04:00
|
|
|
|
|
|
|
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
|
2016-06-06 19:16:25 -03:00
|
|
|
#if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO
|
2015-07-10 01:02:32 -03:00
|
|
|
#define STORAGE_DIR "/data/ftp/internal_000/APM"
|
2016-05-03 00:22:03 -03:00
|
|
|
#elif APM_BUILD_TYPE(APM_BUILD_Replay)
|
|
|
|
#define STORAGE_DIR "."
|
2015-07-10 01:02:32 -03:00
|
|
|
#else
|
2014-11-07 17:10:29 -04:00
|
|
|
#define STORAGE_DIR "/var/APM"
|
2015-07-10 01:02:32 -03:00
|
|
|
#endif
|
2014-11-07 17:10:29 -04:00
|
|
|
#define STORAGE_FILE STORAGE_DIR "/" SKETCHNAME ".stg"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Storage::_storage_create(void)
|
2014-11-07 17:10:29 -04:00
|
|
|
{
|
|
|
|
mkdir(STORAGE_DIR, 0777);
|
|
|
|
unlink(STORAGE_FILE);
|
|
|
|
int fd = open(STORAGE_FILE, O_RDWR|O_CREAT, 0666);
|
|
|
|
if (fd == -1) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Failed to create " STORAGE_FILE);
|
2014-11-07 17:10:29 -04:00
|
|
|
}
|
|
|
|
for (uint16_t loc=0; loc<sizeof(_buffer); loc += LINUX_STORAGE_MAX_WRITE) {
|
|
|
|
if (write(fd, &_buffer[loc], LINUX_STORAGE_MAX_WRITE) != LINUX_STORAGE_MAX_WRITE) {
|
2015-07-10 01:02:32 -03:00
|
|
|
perror("write");
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Error filling " STORAGE_FILE);
|
2014-11-07 17:10:29 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
// ensure the directory is updated with the new size
|
|
|
|
fsync(fd);
|
|
|
|
close(fd);
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Storage::_storage_open(void)
|
2014-11-07 17:10:29 -04:00
|
|
|
{
|
|
|
|
if (_initialised) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
_dirty_mask = 0;
|
2015-06-30 03:45:49 -03:00
|
|
|
int fd = open(STORAGE_FILE, O_RDWR);
|
2014-11-07 17:10:29 -04:00
|
|
|
if (fd == -1) {
|
|
|
|
_storage_create();
|
2015-06-30 03:45:49 -03:00
|
|
|
fd = open(STORAGE_FILE, O_RDWR);
|
2014-11-07 17:10:29 -04:00
|
|
|
if (fd == -1) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Failed to open " STORAGE_FILE);
|
2014-11-07 17:10:29 -04:00
|
|
|
}
|
|
|
|
}
|
2015-06-30 03:45:49 -03:00
|
|
|
memset(_buffer, 0, sizeof(_buffer));
|
|
|
|
/*
|
|
|
|
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) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Failed to expand " STORAGE_FILE);
|
2015-06-30 03:45:49 -03:00
|
|
|
}
|
|
|
|
ret = sizeof(_buffer);
|
|
|
|
}
|
|
|
|
if (ret != sizeof(_buffer)) {
|
2014-11-07 17:10:29 -04:00
|
|
|
close(fd);
|
|
|
|
_storage_create();
|
|
|
|
fd = open(STORAGE_FILE, O_RDONLY);
|
|
|
|
if (fd == -1) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Failed to open " STORAGE_FILE);
|
2014-11-07 17:10:29 -04:00
|
|
|
}
|
|
|
|
if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) {
|
2015-11-19 23:10:58 -04:00
|
|
|
AP_HAL::panic("Failed to read " STORAGE_FILE);
|
2014-11-07 17:10:29 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
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.
|
|
|
|
*/
|
2015-10-20 18:13:25 -03:00
|
|
|
void Storage::_mark_dirty(uint16_t loc, uint16_t length)
|
2014-11-07 17:10:29 -04:00
|
|
|
{
|
|
|
|
uint16_t end = loc + length;
|
2014-11-07 20:55:55 -04:00
|
|
|
for (uint8_t line=loc>>LINUX_STORAGE_LINE_SHIFT;
|
|
|
|
line <= end>>LINUX_STORAGE_LINE_SHIFT;
|
|
|
|
line++) {
|
|
|
|
_dirty_mask |= 1U << line;
|
2014-11-07 17:10:29 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2016-05-17 23:26:57 -03:00
|
|
|
void Storage::read_block(void *dst, uint16_t loc, size_t n)
|
2014-11-07 17:10:29 -04:00
|
|
|
{
|
|
|
|
if (loc >= sizeof(_buffer)-(n-1)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
_storage_open();
|
|
|
|
memcpy(dst, &_buffer[loc], n);
|
|
|
|
}
|
|
|
|
|
2016-05-17 23:26:57 -03:00
|
|
|
void Storage::write_block(uint16_t loc, const void *src, size_t n)
|
2014-11-07 17:10:29 -04:00
|
|
|
{
|
|
|
|
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);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void Storage::_timer_tick(void)
|
2014-11-07 17:10:29 -04:00
|
|
|
{
|
|
|
|
if (!_initialised || _dirty_mask == 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (_fd == -1) {
|
|
|
|
_fd = open(STORAGE_FILE, O_WRONLY);
|
|
|
|
if (_fd == -1) {
|
2016-05-17 23:26:57 -03:00
|
|
|
return;
|
2014-11-07 17:10:29 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// 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_NUM_LINES; i++) {
|
|
|
|
if (_dirty_mask & (1<<i)) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
if (i == LINUX_STORAGE_NUM_LINES) {
|
|
|
|
// this shouldn't be possible
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
uint32_t write_mask = (1U<<i);
|
|
|
|
// see how many lines to write
|
2016-05-17 23:26:57 -03:00
|
|
|
for (n=1; (i+n) < LINUX_STORAGE_NUM_LINES &&
|
2014-11-07 17:10:29 -04:00
|
|
|
n < (LINUX_STORAGE_MAX_WRITE>>LINUX_STORAGE_LINE_SHIFT); n++) {
|
|
|
|
if (!(_dirty_mask & (1<<(n+i)))) {
|
|
|
|
break;
|
2016-05-17 23:26:57 -03:00
|
|
|
}
|
2014-11-07 17:10:29 -04:00
|
|
|
// 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<<LINUX_STORAGE_LINE_SHIFT, SEEK_SET) == (i<<LINUX_STORAGE_LINE_SHIFT)) {
|
|
|
|
_dirty_mask &= ~write_mask;
|
|
|
|
if (write(_fd, &_buffer[i<<LINUX_STORAGE_LINE_SHIFT], n<<LINUX_STORAGE_LINE_SHIFT) != n<<LINUX_STORAGE_LINE_SHIFT) {
|
|
|
|
// write error - likely EINTR
|
|
|
|
_dirty_mask |= write_mask;
|
|
|
|
close(_fd);
|
|
|
|
_fd = -1;
|
|
|
|
}
|
|
|
|
if (_dirty_mask == 0) {
|
|
|
|
if (fsync(_fd) != 0) {
|
|
|
|
close(_fd);
|
|
|
|
_fd = -1;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|