#include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #include #include #include #include #include #include #include #include #include #include #include "Storage.h" using namespace PX4; /* This stores eeprom data in the PX4 MTD interface with a 4k size, and a in-memory buffer. This keeps the latency and devices IOs down. */ // name the storage file after the sketch so you can use the same sd // card for ArduCopter and ArduPlane #define STORAGE_DIR "/fs/microsd/APM" #define SAVE_STORAGE_FILE STORAGE_DIR "/" SKETCHNAME ".bak" #define MTD_PARAMS_FILE "/fs/mtd" extern const AP_HAL::HAL& hal; extern "C" int mtd_main(int, char **); PX4Storage::PX4Storage(void) : _perf_storage(perf_alloc(PC_ELAPSED, "APM_storage")), _perf_errors(perf_alloc(PC_COUNT, "APM_storage_errors")) { } void PX4Storage::_storage_open(void) { if (_initialised) { return; } _dirty_mask.clearall(); // load from storage backend #if USE_FLASH_STORAGE _flash_load(); #else _mtd_load(); #endif #ifdef SAVE_STORAGE_FILE int fd = open(SAVE_STORAGE_FILE, O_WRONLY|O_CREAT|O_TRUNC, 0644); if (fd != -1) { write(fd, _buffer, sizeof(_buffer)); close(fd); } #endif _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 PX4Storage::_mark_dirty(uint16_t loc, uint16_t length) { uint16_t end = loc + length; for (uint16_t line=loc>>PX4_STORAGE_LINE_SHIFT; line <= end>>PX4_STORAGE_LINE_SHIFT; line++) { _dirty_mask.set(line); } } void PX4Storage::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 PX4Storage::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 PX4Storage::_timer_tick(void) { if (!_initialised || _dirty_mask.empty()) { return; } perf_begin(_perf_storage); #if !USE_FLASH_STORAGE if (_fd == -1) { _fd = open(MTD_PARAMS_FILE, O_WRONLY); if (_fd == -1) { perf_end(_perf_storage); perf_count(_perf_errors); return; } } #endif // write out the first dirty line. We don't write more // than one to keep the latency of this call to a minimum uint16_t i; for (i=0; i 5000) { _last_re_init_ms = now; bool ok = _flash.re_initialise(); printf("Storage: failed at %u:%u for %u - re-init %u\n", sector, offset, length, (unsigned)ok); } } return ret; } /* callback to read data from flash */ bool PX4Storage::_flash_read_data(uint8_t sector, uint32_t offset, uint8_t *data, uint16_t length) { size_t base_address = up_progmem_getaddress(_flash_page+sector); const uint8_t *b = ((const uint8_t *)base_address)+offset; memcpy(data, b, length); return true; } /* callback to erase flash sector */ bool PX4Storage::_flash_erase_sector(uint8_t sector) { return up_progmem_erasepage(_flash_page+sector) > 0; } /* callback to check if erase is allowed */ bool PX4Storage::_flash_erase_ok(void) { // only allow erase while disarmed return !hal.util->get_soft_armed(); } #endif // USE_FLASH_STORAGE #endif // CONFIG_HAL_BOARD