Path: blob/master/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp
4232 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/14/*15ArduPilot filesystem interface for systems using the LittleFS filesystem in16flash memory1718Original littlefs integration by Tamas Nepusz <[email protected]>19Further development by Andy Piper <[email protected]>20*/21#include "AP_Filesystem_config.h"2223#if AP_FILESYSTEM_LITTLEFS_ENABLED2425#include "AP_Filesystem.h"26#include "AP_Filesystem_FlashMemory_LittleFS.h"27#include <GCS_MAVLink/GCS.h>28#include <AP_RTC/AP_RTC.h>2930#if CONFIG_HAL_BOARD == HAL_BOARD_SITL31#include "bd/lfs_filebd.h"32#include <cstdio>33#endif3435//#define AP_LFS_DEBUG36#ifdef AP_LFS_DEBUG37#define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)38#else39#define debug(fmt, args ...)40#endif4142#define ENSURE_MOUNTED() do { if (!mounted && !mount_filesystem()) { errno = EIO; return -1; }} while (0)43#define ENSURE_MOUNTED_NULL() do { if (!mounted && !mount_filesystem()) { errno = EIO; return nullptr; }} while (0)44#define LFS_CHECK(func) do { int __retval = func; if (__retval < 0) { errno = errno_from_lfs_error(__retval); return -1; }} while (0)45#define LFS_CHECK_NULL(func) do { int __retval = func; if (__retval < 0) { errno = errno_from_lfs_error(__retval); return nullptr; }} while (0)46#define LFS_ATTR_MTIME 'M'4748#if CONFIG_HAL_BOARD != HAL_BOARD_SITL49static int flashmem_read(50const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,51void* buffer, lfs_size_t size52);53static int flashmem_prog(54const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,55const void* buffer, lfs_size_t size56);57static int flashmem_erase(const struct lfs_config *cfg, lfs_block_t block);58static int flashmem_sync(const struct lfs_config *cfg);59#endif60static int errno_from_lfs_error(int lfs_error);61static int lfs_flags_from_flags(int flags);6263const extern AP_HAL::HAL& hal;6465int AP_Filesystem_FlashMemory_LittleFS::open(const char *pathname, int flags, bool allow_absolute_path)66{67FS_CHECK_ALLOWED(-1);68WITH_SEMAPHORE(fs_sem);6970ENSURE_MOUNTED();7172int fd = allocate_fd();73if (fd < 0) {74return -1;75}7677FileDescriptor* fp = lfs_file_from_fd(fd);78if (fp == nullptr) {79return -1;80}8182// file is closed, see if we already have a modification time83if (lfs_getattr(&fs, pathname, LFS_ATTR_MTIME, &fp->mtime, sizeof(fp->mtime)) != sizeof(fp->mtime)) {84// no attribute, populate from RTC85uint64_t utc_usec = 0;86AP::rtc().get_utc_usec(utc_usec);87fp->mtime = utc_usec/(1000U*1000U);88}8990// populate the file config with the mtime attribute, will get written out on first sync or close91fp->cfg.attrs = fp->attrs;92fp->cfg.attr_count = 1;93fp->attrs[0] = {94.type = LFS_ATTR_MTIME,95.buffer = &fp->mtime,96.size = sizeof(fp->mtime)97};98fp->filename = strdup(pathname);99if (fp->filename == nullptr) {100errno = ENOMEM;101free_fd(fd);102return -1;103}104105int retval = lfs_file_opencfg(&fs, &fp->file, pathname, lfs_flags_from_flags(flags), &fp->cfg);106107if (retval < 0) {108errno = errno_from_lfs_error(retval);109free_fd(fd);110return -1;111}112113114return fd;115}116117int AP_Filesystem_FlashMemory_LittleFS::close(int fileno)118{119FS_CHECK_ALLOWED(-1);120WITH_SEMAPHORE(fs_sem);121122FileDescriptor* fp = lfs_file_from_fd(fileno);123if (fp == nullptr) {124return -1;125}126127int retval = lfs_file_close(&fs, &(fp->file));128if (retval < 0) {129free_fd(fileno); // ignore error code, we have something else to report130errno = errno_from_lfs_error(retval);131return -1;132}133134if (free_fd(fileno) < 0) {135return -1;136}137138return 0;139}140141int32_t AP_Filesystem_FlashMemory_LittleFS::read(int fd, void *buf, uint32_t count)142{143FS_CHECK_ALLOWED(-1);144WITH_SEMAPHORE(fs_sem);145ENSURE_MOUNTED();146147FileDescriptor* fp = lfs_file_from_fd(fd);148if (fp == nullptr) {149return -1;150}151152lfs_ssize_t read = lfs_file_read(&fs, &(fp->file), buf, count);153if (read < 0) {154errno = errno_from_lfs_error(read);155return -1;156}157158return read;159}160161int32_t AP_Filesystem_FlashMemory_LittleFS::write(int fd, const void *buf, uint32_t count)162{163FS_CHECK_ALLOWED(-1);164WITH_SEMAPHORE(fs_sem);165ENSURE_MOUNTED();166167FileDescriptor* fp = lfs_file_from_fd(fd);168if (fp == nullptr) {169return -1;170}171172lfs_ssize_t written = lfs_file_write(&fs, &(fp->file), buf, count);173if (written < 0) {174errno = errno_from_lfs_error(written);175return -1;176}177178return written;179}180181int AP_Filesystem_FlashMemory_LittleFS::fsync(int fd)182{183FS_CHECK_ALLOWED(-1);184WITH_SEMAPHORE(fs_sem);185ENSURE_MOUNTED();186187FileDescriptor* fp = lfs_file_from_fd(fd);188if (fp == nullptr) {189return -1;190}191192if (fp->file.off != fs_cfg.block_size) {193debug("misaligned fsync: %lu\n", fp->file.off);194}195196LFS_CHECK(lfs_file_sync(&fs, &(fp->file)));197return 0;198}199200int32_t AP_Filesystem_FlashMemory_LittleFS::lseek(int fd, int32_t position, int whence)201{202FS_CHECK_ALLOWED(-1);203WITH_SEMAPHORE(fs_sem);204ENSURE_MOUNTED();205206FileDescriptor* fp = lfs_file_from_fd(fd);207if (fp == nullptr) {208return -1;209}210211int lfs_whence;212switch (whence) {213case SEEK_END:214lfs_whence = LFS_SEEK_SET;215break;216case SEEK_CUR:217lfs_whence = LFS_SEEK_CUR;218break;219case SEEK_SET:220default:221lfs_whence = LFS_SEEK_SET;222break;223}224225lfs_soff_t pos = lfs_file_seek(&fs, &(fp->file), position, lfs_whence);226if (pos < 0) {227errno = errno_from_lfs_error(pos);228return -1;229}230231return pos;232}233234int AP_Filesystem_FlashMemory_LittleFS::stat(const char *name, struct stat *buf)235{236FS_CHECK_ALLOWED(-1);237WITH_SEMAPHORE(fs_sem);238ENSURE_MOUNTED();239240lfs_info info;241LFS_CHECK(lfs_stat(&fs, name, &info));242243memset(buf, 0, sizeof(*buf));244uint32_t mtime;245if (lfs_getattr(&fs, name, LFS_ATTR_MTIME, &mtime, sizeof(mtime)) == sizeof(mtime)) {246buf->st_mtime = mtime;247buf->st_atime = mtime;248buf->st_ctime = mtime;249}250buf->st_mode = (info.type == LFS_TYPE_DIR ? S_IFDIR : S_IFREG) | 0666;251buf->st_nlink = 1;252buf->st_size = info.size;253buf->st_blksize = fs_cfg.read_size;254buf->st_uid=1000;255buf->st_gid=1000;256buf->st_blocks = (info.size >> 9) + ((info.size & 0x1FF) > 0 ? 1 : 0);257258return 0;259}260261// set modification time on a file262bool AP_Filesystem_FlashMemory_LittleFS::set_mtime(const char *filename, const uint32_t mtime_sec)263{264// unfortunately lfs_setattr will not work while the file is open, instead265// we need to update the file config, but that means finding the file config266for (int fd = 0; fd < MAX_OPEN_FILES; fd++) {267if (open_files[fd] != nullptr && strcmp(open_files[fd]->filename, filename) == 0) {268open_files[fd]->mtime = mtime_sec;269return true;270}271}272return false;273}274275int AP_Filesystem_FlashMemory_LittleFS::unlink(const char *pathname)276{277FS_CHECK_ALLOWED(-1);278WITH_SEMAPHORE(fs_sem);279ENSURE_MOUNTED();280LFS_CHECK(lfs_remove(&fs, pathname));281return 0;282}283284int AP_Filesystem_FlashMemory_LittleFS::mkdir(const char *pathname)285{286FS_CHECK_ALLOWED(-1);287WITH_SEMAPHORE(fs_sem);288ENSURE_MOUNTED();289LFS_CHECK(lfs_mkdir(&fs, pathname));290return 0;291}292293294struct DirEntry {295lfs_dir_t dir;296struct dirent entry;297};298299void *AP_Filesystem_FlashMemory_LittleFS::opendir(const char *pathdir)300{301FS_CHECK_ALLOWED(nullptr);302WITH_SEMAPHORE(fs_sem);303ENSURE_MOUNTED_NULL();304305DirEntry *result = NEW_NOTHROW DirEntry;306if (!result) {307errno = ENOMEM;308return nullptr;309}310311int retval = lfs_dir_open(&fs, &result->dir, pathdir);312if (retval < 0) {313delete result;314errno = errno_from_lfs_error(retval);315return nullptr;316}317318memset(&result->entry, 0, sizeof(result->entry));319320#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL321result->entry.d_reclen = sizeof(result->entry);322#endif323324// LittleFS has issues with opendir where filesystem operations that trigger325// writes while a directory is open can break the iteration and cause326// LittleFS to report filesystem corruption. We hope readdir loops don't do327// writes (none do in ArduPilot at the time of writing), but also take the328// lock again so other threads can't write until the corresponding release329// in closedir. This is safe here since the lock is recursive; recursion330// also lets the thread with the directory open do reads. Hopefully this331// will be fixed upstream so we can remove this quirk.332fs_sem.take_blocking();333334return result;335}336337#pragma GCC diagnostic push338#pragma GCC diagnostic ignored "-Wstringop-truncation"339struct dirent *AP_Filesystem_FlashMemory_LittleFS::readdir(void *ptr)340{341FS_CHECK_ALLOWED(nullptr);342WITH_SEMAPHORE(fs_sem);343344DirEntry *pair = static_cast<DirEntry*>(ptr);345if (!pair) {346errno = EINVAL;347return nullptr;348}349350lfs_info info;351int retval = lfs_dir_read(&fs, &pair->dir, &info);352if (retval == 0) {353/* no more entries */354return nullptr;355}356if (retval < 0) {357// failure358errno = errno_from_lfs_error(retval);359return nullptr;360}361362memset(&pair->entry, 0, sizeof(pair->entry));363364#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX365pair->entry.d_ino = 0;366pair->entry.d_seekoff++;367#endif368369strncpy(pair->entry.d_name, info.name, MIN(strlen(info.name)+1, sizeof(pair->entry.d_name)));370#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX371pair->entry.d_namlen = strlen(info.name);372#endif373374pair->entry.d_type = info.type == LFS_TYPE_DIR ? DT_DIR : DT_REG;375376return &pair->entry;377}378#pragma GCC diagnostic pop379380int AP_Filesystem_FlashMemory_LittleFS::closedir(void *ptr)381{382FS_CHECK_ALLOWED(-1);383WITH_SEMAPHORE(fs_sem);384385DirEntry *pair = static_cast<DirEntry*>(ptr);386if (!pair) {387errno = EINVAL;388return 0;389}390391// Before the close, undo the lock we did in opendir so it's released even392// if the close fails. We don't undo it above, as the input being nullptr393// means we didn't successfully open the directory and lock.394fs_sem.give();395396int retval = lfs_dir_close(&fs, &pair->dir);397delete pair;398399if (retval < 0) {400errno = errno_from_lfs_error(retval);401return -1;402}403404return 0;405}406407// return number of bytes that should be written before fsync for optimal408// streaming performance/robustness. if zero, any number can be written.409// LittleFS needs to copy the block contents to a new one if fsync is called410// in the middle of a block. LittleFS also is guaranteed to not remember any411// file contents until fsync is called!412uint32_t AP_Filesystem_FlashMemory_LittleFS::bytes_until_fsync(int fd)413{414FS_CHECK_ALLOWED(0);415WITH_SEMAPHORE(fs_sem);416417FileDescriptor* fp = lfs_file_from_fd(fd);418if (!mounted || fp == nullptr) {419return 0;420}421422uint32_t file_pos = fp->file.pos;423uint32_t block_size = fs_cfg.block_size;424425// first block exclusively stores data:426// https://github.com/littlefs-project/littlefs/issues/564#issuecomment-2555733922427if (file_pos < block_size) {428return block_size - file_pos; // so block_offset is exactly file_pos429}430431// see https://github.com/littlefs-project/littlefs/issues/564#issuecomment-2363032827432// n = (N − w/8 ( popcount( N/(B − 2w/8) − 1) + 2))/(B − 2w/8))433// off = N − ( B − 2w/8 ) n − w/8popcount( n )434#define BLOCK_INDEX(N, B) \435(N - sizeof(uint32_t) * (__builtin_popcount(N/(B - 2 * sizeof(uint32_t)) -1) + 2))/(B - 2 * sizeof(uint32_t))436437#define BLOCK_OFFSET(N, B, n) \438(N - (B - 2*sizeof(uint32_t)) * n - sizeof(uint32_t) * __builtin_popcount(n))439440uint32_t block_index = BLOCK_INDEX(file_pos, block_size);441// offset will be 4 (or bigger) through (block_size-1) as subsequent blocks442// start with one or more pointers; offset will never equal block_size443uint32_t block_offset = BLOCK_OFFSET(file_pos, block_size, block_index);444445#undef BLOCK_INDEX446#undef BLOCK_OFFSET447448return block_size - block_offset;449}450451452int64_t AP_Filesystem_FlashMemory_LittleFS::disk_free(const char *path)453{454FS_CHECK_ALLOWED(-1);455WITH_SEMAPHORE(fs_sem);456ENSURE_MOUNTED();457458lfs_ssize_t alloc_size = lfs_fs_size(&fs);459if (alloc_size < 0) {460errno = errno_from_lfs_error(alloc_size);461return -1;462}463464return disk_space(path) - alloc_size;465}466467int64_t AP_Filesystem_FlashMemory_LittleFS::disk_space(const char *path)468{469return fs_cfg.block_count * fs_cfg.block_size;470}471472bool AP_Filesystem_FlashMemory_LittleFS::retry_mount(void)473{474FS_CHECK_ALLOWED(false);475WITH_SEMAPHORE(fs_sem);476477if (!dead) {478if (!mounted && !mount_filesystem()) {479errno = EIO;480return false;481}482483return true;484} else {485return false;486}487}488489void AP_Filesystem_FlashMemory_LittleFS::unmount(void)490{491WITH_SEMAPHORE(fs_sem);492493if (mounted && !dead) {494free_all_fds();495lfs_unmount(&fs);496mounted = false;497}498}499500/* ************************************************************************* */501/* Private functions */502/* ************************************************************************* */503504int AP_Filesystem_FlashMemory_LittleFS::allocate_fd()505{506for (int fd = 0; fd < MAX_OPEN_FILES; fd++) {507if (open_files[fd] == nullptr) {508open_files[fd] = static_cast<FileDescriptor*>(calloc(1, sizeof(FileDescriptor)));509if (open_files[fd] == nullptr) {510errno = ENOMEM;511return -1;512}513514return fd;515}516}517518errno = ENFILE;519return -1;520}521522int AP_Filesystem_FlashMemory_LittleFS::free_fd(int fd)523{524FileDescriptor* fp = lfs_file_from_fd(fd);525if (!fp) {526return -1;527}528529free(fp->filename);530free(fp);531open_files[fd] = nullptr;532533return 0;534}535536void AP_Filesystem_FlashMemory_LittleFS::free_all_fds()537{538for (int fd = 0; fd < MAX_OPEN_FILES; fd++) {539if (open_files[fd] != nullptr) {540free_fd(fd);541}542}543}544545AP_Filesystem_FlashMemory_LittleFS::FileDescriptor* AP_Filesystem_FlashMemory_LittleFS::lfs_file_from_fd(int fd) const546{547if (fd < 0 || fd >= MAX_OPEN_FILES || open_files[fd] == nullptr) {548errno = EBADF;549return nullptr;550}551552return open_files[fd];553}554555void AP_Filesystem_FlashMemory_LittleFS::mark_dead()556{557if (!dead) {558printf("FlashMemory_LittleFS: dead\n");559free_all_fds();560dead = true;561}562}563564/* ************************************************************************* */565/* Low-level flash memory access */566/* ************************************************************************* */567568#define JEDEC_WRITE_ENABLE 0x06569#define JEDEC_READ_STATUS 0x05570#define JEDEC_WRITE_STATUS 0x01571#define JEDEC_READ_DATA 0x03572#define JEDEC_PAGE_DATA_READ 0x13573#define JEDEC_DEVICE_ID 0x9F574#define JEDEC_PAGE_WRITE 0x02575#define JEDEC_PROGRAM_EXECUTE 0x10576577#define JEDEC_DEVICE_RESET 0xFF578579#define JEDEC_BULK_ERASE 0xC7580#define JEDEC_SECTOR4_ERASE 0x20 // 4k erase581#define JEDEC_BLOCK_ERASE 0xD8582583#define JEDEC_STATUS_BUSY 0x01584#define JEDEC_STATUS_WRITEPROTECT 0x02585#define JEDEC_STATUS_BP0 0x04586#define JEDEC_STATUS_BP1 0x08587#define JEDEC_STATUS_BP2 0x10588#define JEDEC_STATUS_TP 0x20589#define JEDEC_STATUS_SEC 0x40590#define JEDEC_STATUS_SRP0 0x80591592#define W25NXX_STATUS_EFAIL 0x04593#define W25NXX_STATUS_PFAIL 0x08594595596/*597flash device IDs taken from betaflight flash_m25p16.c598599Format is manufacturer, memory type, then capacity600*/601#define JEDEC_ID_UNKNOWN 0x000000602#define JEDEC_ID_MACRONIX_MX25L3206E 0xC22016603#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017604#define JEDEC_ID_MACRONIX_MX25L25635E 0xC22019605#define JEDEC_ID_MICRON_M25P16 0x202015606#define JEDEC_ID_MICRON_N25Q064 0x20BA17607#define JEDEC_ID_MICRON_N25Q128 0x20BA18608#define JEDEC_ID_WINBOND_W25Q16 0xEF4015609#define JEDEC_ID_WINBOND_W25Q32 0xEF4016610#define JEDEC_ID_WINBOND_W25X32 0xEF3016611#define JEDEC_ID_WINBOND_W25Q64 0xEF4017612#define JEDEC_ID_WINBOND_W25Q128 0xEF4018613#define JEDEC_ID_WINBOND_W25Q256 0xEF4019614#define JEDEC_ID_WINBOND_W25Q128_2 0xEF7018615#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21616#define JEDEC_ID_WINBOND_W25N02KV 0xEFAA22617#define JEDEC_ID_CYPRESS_S25FL128L 0x016018618#define JEDEC_ID_GIGA_GD25Q16E 0xC84015619620/* Hardware-specific constants */621622#define W25NXX_PROT_REG 0xA0623#define W25NXX_CONF_REG 0xB0624#define W25NXX_STATUS_REG 0xC0625#define W25NXX_STATUS_EFAIL 0x04626#define W25NXX_STATUS_PFAIL 0x08627628#define W25N01G_NUM_BLOCKS 1024629#define W25N02K_NUM_BLOCKS 2048630631#define W25NXX_CONFIG_ECC_ENABLE (1 << 4)632#define W25NXX_CONFIG_BUFFER_READ_MODE (1 << 3)633634#define W25NXX_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled)635#define W25NXX_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us636#define W25NXX_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms637#define W25NXX_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms638639bool AP_Filesystem_FlashMemory_LittleFS::is_busy()640{641WITH_SEMAPHORE(dev_sem);642uint8_t status;643#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX644uint8_t cmd[2] { JEDEC_READ_STATUS, W25NXX_STATUS_REG };645dev->transfer(cmd, 2, &status, 1);646return (status & (JEDEC_STATUS_BUSY | W25NXX_STATUS_PFAIL | W25NXX_STATUS_EFAIL)) != 0;647#else648uint8_t cmd = JEDEC_READ_STATUS;649dev->transfer(&cmd, 1, &status, 1);650return (status & (JEDEC_STATUS_BUSY | JEDEC_STATUS_SRP0)) != 0;651#endif652}653654void AP_Filesystem_FlashMemory_LittleFS::send_command_addr(uint8_t command, uint32_t addr)655{656uint8_t cmd[5];657cmd[0] = command;658659if (use_32bit_address) {660cmd[1] = (addr >> 24) & 0xff;661cmd[2] = (addr >> 16) & 0xff;662cmd[3] = (addr >> 8) & 0xff;663cmd[4] = (addr >> 0) & 0xff;664} else {665cmd[1] = (addr >> 16) & 0xff;666cmd[2] = (addr >> 8) & 0xff;667cmd[3] = (addr >> 0) & 0xff;668cmd[4] = 0;669}670671dev->transfer(cmd, use_32bit_address ? 5 : 4, nullptr, 0);672}673674void AP_Filesystem_FlashMemory_LittleFS::send_command_page(uint8_t command, uint32_t page)675{676uint8_t cmd[3];677cmd[0] = command;678cmd[1] = (page >> 8) & 0xff;679cmd[2] = (page >> 0) & 0xff;680dev->transfer(cmd, 3, nullptr, 0);681}682683bool AP_Filesystem_FlashMemory_LittleFS::wait_until_device_is_ready()684{685if (dead) {686return false;687}688689uint32_t t = AP_HAL::millis();690while (is_busy()) {691hal.scheduler->delay_microseconds(100);692if (AP_HAL::millis() - t > 5000) {693mark_dead();694return false;695}696}697698return true;699}700701void AP_Filesystem_FlashMemory_LittleFS::write_status_register(uint8_t reg, uint8_t bits)702{703WITH_SEMAPHORE(dev_sem);704uint8_t cmd[3] = { JEDEC_WRITE_STATUS, reg, bits };705dev->transfer(cmd, 3, nullptr, 0);706}707708#if CONFIG_HAL_BOARD == HAL_BOARD_SITL709const static struct lfs_filebd_config fbd_config {710.read_size = 2048,711.prog_size = 2048,712.erase_size = 131072,713.erase_count = 256714};715#endif716717uint32_t AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() {718#if CONFIG_HAL_BOARD != HAL_BOARD_SITL719if (!wait_until_device_is_ready()) {720return false;721}722723WITH_SEMAPHORE(dev_sem);724725// Read manufacturer ID726uint8_t cmd = JEDEC_DEVICE_ID;727uint8_t buf[4];728dev->transfer(&cmd, 1, buf, 4);729730#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX731uint32_t id = buf[1] << 16 | buf[2] << 8 | buf[3];732#else733uint32_t id = buf[0] << 16 | buf[1] << 8 | buf[2];734#endif735736// Let's specify the terminology here.737//738// 1 block = smallest unit that we _erase_ in a single operation739// 1 page = smallest unit that we read or program in a single operation740//741// regardless of what the flash chip documentation refers to as a "block"742743#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX744// these NAND chips have 2048 byte pages and 128K erase blocks745lfs_size_t page_size = 2048;746lfs_size_t block_size = 131072;747#else748// typical JEDEC-ish NOR flash chips have 256 byte pages and 64K blocks.749// many also support smaller erase sizes like 4K "sectors", but the largest750// block size is fastest to erase in bytes per second by 3-5X so we use751// that. be aware that worst case erase time can be seconds!752lfs_size_t page_size = 256;753lfs_size_t block_size = 65536;754#endif755756lfs_size_t block_count;757switch (id) {758#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX759case JEDEC_ID_WINBOND_W25N01GV:760block_count = 1024; /* 128MiB */761break;762case JEDEC_ID_WINBOND_W25N02KV:763block_count = 2048; /* 256MiB */764break;765#else766case JEDEC_ID_WINBOND_W25Q16:767case JEDEC_ID_MICRON_M25P16:768case JEDEC_ID_GIGA_GD25Q16E:769block_count = 32; /* 2MiB */770break;771772case JEDEC_ID_WINBOND_W25Q32:773case JEDEC_ID_WINBOND_W25X32:774case JEDEC_ID_MACRONIX_MX25L3206E:775block_count = 64; /* 4MiB */776break;777778case JEDEC_ID_MICRON_N25Q064:779case JEDEC_ID_WINBOND_W25Q64:780case JEDEC_ID_MACRONIX_MX25L6406E:781block_count = 128; /* 8MiB */782break;783784case JEDEC_ID_MICRON_N25Q128:785case JEDEC_ID_WINBOND_W25Q128:786case JEDEC_ID_WINBOND_W25Q128_2:787case JEDEC_ID_CYPRESS_S25FL128L:788block_count = 256; /* 16MiB */789break;790791case JEDEC_ID_WINBOND_W25Q256:792case JEDEC_ID_MACRONIX_MX25L25635E:793block_count = 512; /* 32MiB */794use_32bit_address = true;795break;796#endif797default:798block_count = 0;799hal.scheduler->delay(2000);800printf("Unknown SPI Flash 0x%08x\n", id);801return 0;802}803804fs_cfg.read_size = page_size;805fs_cfg.prog_size = page_size; // we assume this is equal to read_size!806fs_cfg.block_size = block_size;807fs_cfg.block_count = block_count;808809// larger metadata blocks mean less frequent compaction operations, but each810// takes longer. however, the total time spent compacting for a given file811// size still goes down with larger metadata blocks. 4096 was chosen to812// minimize both frequency and log buffer utilization.813fs_cfg.metadata_max = 4096;814fs_cfg.compact_thresh = 4096*0.88f;815#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX816fs_cfg.metadata_max = page_size * 2;817fs_cfg.compact_thresh = fs_cfg.metadata_max * 0.88f;818#endif819#else820// SITL config821fs_cfg.read_size = 2048;822fs_cfg.prog_size = 2048;823fs_cfg.block_size = 131072;824fs_cfg.block_count = 256;825fs_cfg.metadata_max = 2048;826827char lfsname[L_tmpnam];828uint32_t id = 0;829if (std::tmpnam(lfsname)) {830lfs_filebd_create(&fs_cfg, lfsname, &fbd_config);831id = 0xFAFF;832}833#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL834fs_cfg.block_cycles = 75000;835// cache entire flash state in RAM (8 blocks = 1 byte of storage) to836// avoid scanning while logging837fs_cfg.lookahead_size = fs_cfg.block_count/8;838// non-inlined files require their own block, but must be copie. Generally we have requirements for tiny files839// (scripting) and very large files (e.g. logging), but not much in-between. Setting the cache size will also840// limit the inline size.841fs_cfg.cache_size = fs_cfg.prog_size;842843return id;844}845846bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() {847if (dead) {848return false;849}850851if (mounted) {852return true;853}854855EXPECT_DELAY_MS(3000);856857fs_cfg.context = this;858#if CONFIG_HAL_BOARD != HAL_BOARD_SITL859fs_cfg.read = flashmem_read;860fs_cfg.prog = flashmem_prog;861fs_cfg.erase = flashmem_erase;862fs_cfg.sync = flashmem_sync;863864dev = hal.spi->get_device("dataflash");865866if (!dev) {867mark_dead();868return false;869}870871dev_sem = dev->get_semaphore();872#else873fs_cfg.read = lfs_filebd_read;874fs_cfg.prog = lfs_filebd_prog;875fs_cfg.erase = lfs_filebd_erase;876fs_cfg.sync = lfs_filebd_sync;877#endif878879uint32_t id = find_block_size_and_count();880881if (!id) {882mark_dead();883return false;884}885#if CONFIG_HAL_BOARD != HAL_BOARD_SITL886if (!init_flash()) {887mark_dead();888return false;889}890#endif891if (lfs_mount(&fs, &fs_cfg) < 0) {892/* maybe not formatted? try formatting it */893GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash");894895if (lfs_format(&fs, &fs_cfg) < 0) {896mark_dead();897return false;898}899900/* try mounting again */901if (lfs_mount(&fs, &fs_cfg) < 0) {902/* cannot mount after formatting */903mark_dead();904return false;905}906}907908// try to create the root storage folder. Ignore the error code in case909// the filesystem is corrupted or it already exists.910if (strlen(HAL_BOARD_STORAGE_DIRECTORY) > 0) {911lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY);912}913914// Force garbage collection to avoid expensive operations after boot915lfs_fs_gc(&fs);916GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Mounted flash 0x%x as littlefs", unsigned(id));917mounted = true;918return true;919}920921/*922format sdcard923*/924bool AP_Filesystem_FlashMemory_LittleFS::format(void)925{926WITH_SEMAPHORE(fs_sem);927hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FlashMemory_LittleFS::format_handler, void));928// the format is handled asynchronously, we inform user of success929// via a text message. format_status can be polled for progress930format_status = FormatStatus::PENDING;931return true;932}933934/*935format sdcard936*/937void AP_Filesystem_FlashMemory_LittleFS::format_handler(void)938{939if (format_status != FormatStatus::PENDING) {940return;941}942WITH_SEMAPHORE(fs_sem);943format_status = FormatStatus::IN_PROGRESS;944GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash using littlefs");945946int ret = lfs_format(&fs, &fs_cfg);947948/* try mounting */949if (ret == LFS_ERR_OK) {950ret = lfs_mount(&fs, &fs_cfg);951}952953// try to create the root storage folder. Ignore the error code in case954// the filesystem is corrupted or it already exists.955if (ret == LFS_ERR_OK && strlen(HAL_BOARD_STORAGE_DIRECTORY) > 0) {956ret = lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY);957}958959if (ret == LFS_ERR_OK) {960format_status = FormatStatus::SUCCESS;961GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: OK");962} else {963format_status = FormatStatus::FAILURE;964mark_dead();965GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: Failed (%d)", int(ret));966}967}968969// returns true if we are currently formatting the SD card:970AP_Filesystem_Backend::FormatStatus AP_Filesystem_FlashMemory_LittleFS::get_format_status(void) const971{972// note that format_handler holds sem, so we can't take it here.973return format_status;974}975976bool AP_Filesystem_FlashMemory_LittleFS::write_enable()977{978uint8_t b = JEDEC_WRITE_ENABLE;979980if (!wait_until_device_is_ready()) {981return false;982}983984WITH_SEMAPHORE(dev_sem);985return dev->transfer(&b, 1, nullptr, 0);986}987988bool AP_Filesystem_FlashMemory_LittleFS::init_flash()989{990if (!wait_until_device_is_ready()) {991return false;992}993994#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX995// reset the device996{997WITH_SEMAPHORE(dev_sem);998uint8_t b = JEDEC_DEVICE_RESET;999dev->transfer(&b, 1, nullptr, 0);1000}1001hal.scheduler->delay(W25NXX_TIMEOUT_RESET_MS);10021003// disable write protection1004write_status_register(W25NXX_PROT_REG, 0);10051006// enable ECC and buffer mode1007write_status_register(W25NXX_CONF_REG, W25NXX_CONFIG_ECC_ENABLE | W25NXX_CONFIG_BUFFER_READ_MODE);1008#else1009if (use_32bit_address) {1010WITH_SEMAPHORE(dev_sem);1011// enter 4-byte address mode1012const uint8_t cmd = 0xB7;1013dev->transfer(&cmd, 1, nullptr, 0);1014}1015#endif10161017return true;1018}10191020#ifdef AP_LFS_DEBUG1021static uint32_t page_writes;1022static uint32_t last_write_msg_ms;1023static uint32_t page_reads;1024static uint32_t block_erases;1025#endif1026int AP_Filesystem_FlashMemory_LittleFS::_flashmem_read(1027lfs_block_t block, lfs_off_t off, void* buffer, lfs_size_t size1028) {1029EXPECT_DELAY_MS((25*size)/(fs_cfg.read_size*1000));10301031// LittleFS always calls us with off aligned to read_size and size a1032// multiple of read_size1033const uint32_t page_size = fs_cfg.read_size;1034uint32_t num_pages = size / page_size;1035uint32_t address = (block * fs_cfg.block_size) + off;1036uint8_t* p = static_cast<uint8_t*>(buffer);10371038while (num_pages--) {1039#ifdef AP_LFS_DEBUG1040page_reads++;1041#endif1042#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX1043/* We need to read an entire page into an internal buffer and then read1044* that buffer with JEDEC_READ_DATA later */1045if (!wait_until_device_is_ready()) {1046return LFS_ERR_IO;1047}1048{1049WITH_SEMAPHORE(dev_sem);1050send_command_addr(JEDEC_PAGE_DATA_READ, address / page_size);1051}1052#endif1053if (!wait_until_device_is_ready()) {1054return LFS_ERR_IO;1055}10561057WITH_SEMAPHORE(dev_sem);10581059dev->set_chip_select(true);1060#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX1061send_command_addr(JEDEC_READ_DATA, 0); // read one page internal buffer1062#else1063send_command_addr(JEDEC_READ_DATA, address);1064#endif1065dev->transfer(nullptr, 0, p, page_size);1066dev->set_chip_select(false);10671068address += page_size;1069p += page_size;1070}1071return LFS_ERR_OK;1072}107310741075int AP_Filesystem_FlashMemory_LittleFS::_flashmem_prog(1076lfs_block_t block, lfs_off_t off, const void* buffer, lfs_size_t size1077) {1078EXPECT_DELAY_MS((250*size)/(fs_cfg.read_size*1000));10791080// LittleFS always calls us with off aligned to prog_size and size a1081// multiple of prog_size (which we set equal to read_size)1082const uint32_t page_size = fs_cfg.read_size;1083uint32_t num_pages = size / page_size;1084uint32_t address = (block * fs_cfg.block_size) + off;1085const uint8_t* p = static_cast<const uint8_t*>(buffer);10861087while (num_pages--) {1088if (!write_enable()) {1089return LFS_ERR_IO;1090}10911092#ifdef AP_LFS_DEBUG1093page_writes++;1094if (AP_HAL::millis() - last_write_msg_ms > 5000) {1095debug("LFS: writes %lukB/s, pages %lu/s (reads %lu/s, block erases %lu/s)",1096(page_writes*page_size)/(5*1024), page_writes/5, page_reads/5, block_erases/5);1097page_writes = 0;1098page_reads = 0;1099block_erases = 0;1100last_write_msg_ms = AP_HAL::millis();1101}1102#endif11031104WITH_SEMAPHORE(dev_sem);1105#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX1106/* First we need to write into the data buffer at column address zero,1107* then we need to issue PROGRAM_EXECUTE to commit the internal buffer */1108dev->set_chip_select(true);1109send_command_page(JEDEC_PAGE_WRITE, 0);1110dev->transfer(p, page_size, nullptr, 0);1111dev->set_chip_select(false);1112send_command_addr(JEDEC_PROGRAM_EXECUTE, address / page_size);1113#else1114dev->set_chip_select(true);1115send_command_addr(JEDEC_PAGE_WRITE, address);1116dev->transfer(p, page_size, nullptr, 0);1117dev->set_chip_select(false);1118#endif1119// writing simply means the data is in the internal cache, it will take1120// some period to propagate to the flash itself11211122address += page_size;1123p += page_size;1124}1125return LFS_ERR_OK;1126}11271128int AP_Filesystem_FlashMemory_LittleFS::_flashmem_erase(lfs_block_t block) {1129if (!write_enable()) {1130return LFS_ERR_IO;1131}11321133#ifdef AP_LFS_DEBUG1134block_erases++;1135#endif11361137WITH_SEMAPHORE(dev_sem);11381139#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX1140const uint32_t pages_per_block = fs_cfg.block_size / fs_cfg.read_size;1141send_command_addr(JEDEC_BLOCK_ERASE, block * pages_per_block);1142#else1143send_command_addr(JEDEC_BLOCK_ERASE, block * fs_cfg.block_size);1144#endif11451146// sleep so that other processes get the CPU cycles that the 4ms erase cycle needs.1147hal.scheduler->delay(4);11481149return LFS_ERR_OK;1150}11511152int AP_Filesystem_FlashMemory_LittleFS::_flashmem_sync() {1153if (wait_until_device_is_ready()) {1154return LFS_ERR_OK;1155} else {1156return LFS_ERR_IO;1157}1158}11591160#if CONFIG_HAL_BOARD != HAL_BOARD_SITL1161static int flashmem_read(1162const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,1163void* buffer, lfs_size_t size1164) {1165AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);1166return self->_flashmem_read(block, off, buffer, size);1167}11681169static int flashmem_prog(1170const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,1171const void* buffer, lfs_size_t size1172) {1173AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);1174return self->_flashmem_prog(block, off, buffer, size);1175}11761177static int flashmem_erase(const struct lfs_config *cfg, lfs_block_t block) {1178AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);1179return self->_flashmem_erase(block);1180}11811182static int flashmem_sync(const struct lfs_config *cfg) {1183AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);1184return self->_flashmem_sync();1185}1186#endif11871188/* ************************************************************************* */1189/* LittleFS to POSIX API conversion functions */1190/* ************************************************************************* */11911192static int errno_from_lfs_error(int lfs_error)1193{1194switch (lfs_error) {1195case LFS_ERR_OK: return 0;1196case LFS_ERR_IO: return EIO;1197case LFS_ERR_CORRUPT: return EIO;1198case LFS_ERR_NOENT: return ENOENT;1199case LFS_ERR_EXIST: return EEXIST;1200case LFS_ERR_NOTDIR: return ENOTDIR;1201case LFS_ERR_ISDIR: return EISDIR;1202case LFS_ERR_NOTEMPTY: return ENOTEMPTY;1203case LFS_ERR_BADF: return EBADF;1204case LFS_ERR_FBIG: return EFBIG;1205case LFS_ERR_INVAL: return EINVAL;1206case LFS_ERR_NOSPC: return ENOSPC;1207case LFS_ERR_NOMEM: return ENOMEM;1208#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX1209case LFS_ERR_NOATTR: return ENOATTR;1210#endif1211case LFS_ERR_NAMETOOLONG: return ENAMETOOLONG;1212default: return EIO;1213}1214}12151216static int lfs_flags_from_flags(int flags)1217{1218int outflags = 0;12191220if (flags & O_WRONLY) {1221outflags |= LFS_O_WRONLY | LFS_F_WRUNCHECKED;1222} else if (flags & O_RDWR) {1223outflags |= LFS_O_RDWR;1224} else {1225outflags |= LFS_O_RDONLY;1226}12271228if (flags & O_CREAT) {1229outflags |= LFS_O_CREAT;1230}12311232if (flags & O_EXCL) {1233outflags |= LFS_O_EXCL;1234}12351236if (flags & O_TRUNC) {1237outflags |= LFS_O_TRUNC;1238}12391240if (flags & O_APPEND) {1241outflags |= LFS_O_APPEND;1242}12431244return outflags;1245}12461247#endif // AP_FILESYSTEM_LITTLEFS_ENABLED124812491250