#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 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO #define STORAGE_DIR "/data/ftp/internal_000/APM" #elif APM_BUILD_TYPE(APM_BUILD_Replay) #define STORAGE_DIR "." #else #define STORAGE_DIR "/var/APM" #endif #define STORAGE_FILE STORAGE_DIR "/" SKETCHNAME ".stg" extern const AP_HAL::HAL& hal; void Storage::_storage_create(void) { mkdir(STORAGE_DIR, 0777); unlink(STORAGE_FILE); int fd = open(STORAGE_FILE, O_RDWR|O_CREAT, 0666); if (fd == -1) { AP_HAL::panic("Failed to create " STORAGE_FILE); } for (uint16_t loc=0; 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); 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<