diff --git a/.gitmodules b/.gitmodules index 6a900f5fbaad6..3c1434efc720f 100644 --- a/.gitmodules +++ b/.gitmodules @@ -42,3 +42,6 @@ [submodule "modules/lwip"] path = modules/lwip url = https://github.com/ArduPilot/lwip.git +[submodule "modules/littlefs"] + path = modules/littlefs + url = https://github.com/ArduPilot/littlefs.git diff --git a/Tools/AP_Bootloader/wscript b/Tools/AP_Bootloader/wscript index 172db17626123..9e951d638f8c1 100644 --- a/Tools/AP_Bootloader/wscript +++ b/Tools/AP_Bootloader/wscript @@ -12,7 +12,7 @@ def build(bld): bld.ap_stlib( name= 'AP_Bootloader_libs', - use='dronecan', + use=['dronecan'], dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', ap_vehicle='AP_Bootloader', ap_libraries= flashiface_lib + [ @@ -27,7 +27,7 @@ def build(bld): # build external libcanard library bld.stlib(source='../../modules/DroneCAN/libcanard/canard.c', name='libcanard', - use='dronecan', + use=['dronecan'], target='libcanard') bld.ap_program( diff --git a/Tools/AP_Periph/wscript b/Tools/AP_Periph/wscript index a65b269c32f32..0d275bdf80a8d 100644 --- a/Tools/AP_Periph/wscript +++ b/Tools/AP_Periph/wscript @@ -91,7 +91,7 @@ def build(bld): dynamic_source='modules/DroneCAN/libcanard/dsdlc_generated/src/**.c', ap_vehicle='AP_Periph', ap_libraries= libraries, - use='dronecan', + use=['dronecan'], exclude_src=[ 'libraries/AP_HAL_ChibiOS/Storage.cpp' ] @@ -100,7 +100,7 @@ def build(bld): # build external libcanard library bld.stlib(source='../../modules/DroneCAN/libcanard/canard.c', name='libcanard', - use='dronecan', + use=['dronecan'], target='libcanard') bld.ap_program( diff --git a/Tools/Replay/wscript b/Tools/Replay/wscript index 0e3b9c28ba508..bdf08a411a5c6 100644 --- a/Tools/Replay/wscript +++ b/Tools/Replay/wscript @@ -7,7 +7,7 @@ def configure(cfg): cfg.env.HAL_GCS_ENABLED = 0 def build(bld): - if isinstance(bld.get_board(), boards.chibios) and bld.env['WITH_FATFS'] != '1': + if isinstance(bld.get_board(), boards.chibios) and bld.env['WITH_FATFS'] != '1' and bld.env['WITH_LITTLEFS'] != 1: # we need a filesystem for replay return diff --git a/Tools/ardupilotwaf/ardupilotwaf.py b/Tools/ardupilotwaf/ardupilotwaf.py index 880d1978dff09..4c2f837e24de4 100644 --- a/Tools/ardupilotwaf/ardupilotwaf.py +++ b/Tools/ardupilotwaf/ardupilotwaf.py @@ -426,6 +426,10 @@ def ap_stlib(bld, **kw): kw['target'] = kw['name'] kw['source'] = [] + if 'use' not in kw: + kw['use'] = [] + kw['use'].append('littlefs') + bld.stlib(**kw) _created_program_dirs = set() diff --git a/Tools/ardupilotwaf/littlefs.py b/Tools/ardupilotwaf/littlefs.py new file mode 100644 index 0000000000000..864983e20ffab --- /dev/null +++ b/Tools/ardupilotwaf/littlefs.py @@ -0,0 +1,25 @@ +# encoding: utf-8 + +""" +Adds support for building littlefs as part of a Waf build +""" + +from waflib.Configure import conf + +def configure(cfg): + cfg.env.append_value('GIT_SUBMODULES', 'littlefs') + cfg.env.prepend_value('INCLUDES', [ + cfg.srcnode.abspath() + '/modules/littlefs/', + ]) + + +@conf +def littlefs(bld, **kw): + kw.update( + name='littlefs', + source=['modules/littlefs/lfs.c', 'modules/littlefs/lfs_util.c'], + target='littlefs', + defines=['LFS_NO_DEBUG'], + cflags=['-Wno-format', '-Wno-format-extra-args', '-Wno-shadow', '-Wno-unused-function', '-Wno-missing-declarations'] + ) + return bld.stlib(**kw) diff --git a/libraries/AP_Filesystem/AP_Filesystem.cpp b/libraries/AP_Filesystem/AP_Filesystem.cpp index 240e95e41de9c..a20a5e2c05d13 100644 --- a/libraries/AP_Filesystem/AP_Filesystem.cpp +++ b/libraries/AP_Filesystem/AP_Filesystem.cpp @@ -35,6 +35,9 @@ static AP_Filesystem_ESP32 fs_local; #elif AP_FILESYSTEM_POSIX_ENABLED #include "AP_Filesystem_posix.h" static AP_Filesystem_Posix fs_local; +#elif AP_FILESYSTEM_LITTLEFS_ENABLED +#include "AP_Filesystem_FlashMemory_LittleFS.h" +static AP_Filesystem_FlashMemory_LittleFS fs_local; #else static AP_Filesystem_Backend fs_local; int errno; diff --git a/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp b/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp new file mode 100644 index 0000000000000..6870b4d253968 --- /dev/null +++ b/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp @@ -0,0 +1,1046 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + ArduPilot filesystem interface for systems using the LittleFS filesystem in + flash memory + + littlefs integration by Tamas Nepusz +*/ +#include "AP_Filesystem_config.h" + +#if AP_FILESYSTEM_LITTLEFS_ENABLED + +#include "AP_Filesystem.h" +#include "AP_Filesystem_FlashMemory_LittleFS.h" +#include + +#include "lfs.h" + +#if 0 +#define debug(fmt, args ...) do {printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0) +#else +#define debug(fmt, args ...) +#endif + +#define ENSURE_MOUNTED() do { if (!mounted && !mount_filesystem()) { errno = EIO; return -1; }} while (0) +#define ENSURE_MOUNTED_NULL() do { if (!mounted && !mount_filesystem()) { errno = EIO; return nullptr; }} while (0) +#define LFS_CHECK(func) do { int __retval = func; if (__retval < 0) { errno = errno_from_lfs_error(__retval); return -1; }} while (0) +#define LFS_CHECK_NULL(func) do { int __retval = func; if (__retval < 0) { errno = errno_from_lfs_error(__retval); return nullptr; }} while (0) + +static int flashmem_read( + const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off, + void* buffer, lfs_size_t size +); +static int flashmem_prog( + const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off, + const void* buffer, lfs_size_t size +); +static int flashmem_erase(const struct lfs_config *cfg, lfs_block_t block); +static int flashmem_sync(const struct lfs_config *cfg); + +static int errno_from_lfs_error(int lfs_error); +static int lfs_flags_from_flags(int flags); + +const extern AP_HAL::HAL& hal; + +int AP_Filesystem_FlashMemory_LittleFS::open(const char *pathname, int flags, bool allow_absolute_path) +{ + int fd, retval; + lfs_file_t* fp; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + + ENSURE_MOUNTED(); + + fd = allocate_fd(); + if (fd < 0) { + return -1; + } + + fp = lfs_file_from_fd(fd); + if (fp == nullptr) { + return -1; + } + + retval = lfs_file_open(&fs, fp, pathname, lfs_flags_from_flags(flags)); + if (retval < 0) { + errno = errno_from_lfs_error(retval); + free_fd(fd); + return -1; + } + + return fd; +} + +int AP_Filesystem_FlashMemory_LittleFS::close(int fileno) +{ + lfs_file_t* fp; + int retval; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + + fp = lfs_file_from_fd(fileno); + if (fp == nullptr) { + return -1; + } + + retval = lfs_file_close(&fs, fp); + if (retval < 0) { + free_fd(fileno); // ignore error code, we have something else to report + errno = errno_from_lfs_error(retval); + return -1; + } + + if (free_fd(fileno) < 0) { + return -1; + } + + return 0; +} + +int32_t AP_Filesystem_FlashMemory_LittleFS::read(int fd, void *buf, uint32_t count) +{ + lfs_file_t* fp; + lfs_ssize_t read; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + + fp = lfs_file_from_fd(fd); + if (fp == nullptr) { + return -1; + } + + read = lfs_file_read(&fs, fp, buf, count); + if (read < 0) { + errno = errno_from_lfs_error(read); + return -1; + } + + return read; +} + +int32_t AP_Filesystem_FlashMemory_LittleFS::write(int fd, const void *buf, uint32_t count) +{ + lfs_file_t* fp; + lfs_ssize_t written; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + + fp = lfs_file_from_fd(fd); + if (fp == nullptr) { + return -1; + } + + written = lfs_file_write(&fs, fp, buf, count); + if (written < 0) { + errno = errno_from_lfs_error(written); + return -1; + } + + return written; +} + +int AP_Filesystem_FlashMemory_LittleFS::fsync(int fd) +{ + lfs_file_t* fp; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + + fp = lfs_file_from_fd(fd); + if (fp == nullptr) { + return -1; + } + + LFS_CHECK(lfs_file_sync(&fs, fp)); + return 0; +} + +int32_t AP_Filesystem_FlashMemory_LittleFS::lseek(int fd, int32_t position, int whence) +{ + lfs_file_t* fp; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + + fp = lfs_file_from_fd(fd); + if (fp == nullptr) { + return -1; + } + + LFS_CHECK(lfs_file_seek(&fs, fp, position, whence)); + return 0; +} + +int AP_Filesystem_FlashMemory_LittleFS::stat(const char *name, struct stat *buf) +{ + lfs_info info; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + + LFS_CHECK(lfs_stat(&fs, name, &info)); + + memset(buf, 0, sizeof(*buf)); + buf->st_mode = (info.type == LFS_TYPE_DIR ? S_IFREG : S_IFDIR) | 0666; + buf->st_nlink = 1; + buf->st_size = info.size; + buf->st_blksize = fs_cfg.read_size; + buf->st_blocks = (info.size >> 9) + ((info.size & 0x1FF) > 0 ? 1 : 0); + + return 0; +} + +int AP_Filesystem_FlashMemory_LittleFS::unlink(const char *pathname) +{ + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + LFS_CHECK(lfs_remove(&fs, pathname)); + return 0; +} + +int AP_Filesystem_FlashMemory_LittleFS::mkdir(const char *pathname) +{ + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + LFS_CHECK(lfs_mkdir(&fs, pathname)); + return 0; +} + +typedef struct { + lfs_dir_t dir; + struct dirent entry; +} lfs_dir_entry_pair; + +void *AP_Filesystem_FlashMemory_LittleFS::opendir(const char *pathdir) +{ + int retval; + + FS_CHECK_ALLOWED(nullptr); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED_NULL(); + + lfs_dir_entry_pair *result = new lfs_dir_entry_pair; + if (!result) { + errno = ENOMEM; + return nullptr; + } + + retval = lfs_dir_open(&fs, &result->dir, pathdir); + if (retval < 0) { + delete result; + errno = errno_from_lfs_error(retval); + return nullptr; + } + + memset(&result->entry, 0, sizeof(result->entry)); + +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL + result->entry.d_reclen = sizeof(result->entry); +#endif + + return result; +} + +struct dirent *AP_Filesystem_FlashMemory_LittleFS::readdir(void *ptr) +{ + FS_CHECK_ALLOWED(nullptr); + WITH_SEMAPHORE(fs_sem); + + lfs_info info; + lfs_dir_entry_pair *pair = static_cast(ptr); + if (!pair) { + errno = EINVAL; + return nullptr; + } + + if (!lfs_dir_read(&fs, &pair->dir, &info)) { + /* no more entries */ + return nullptr; + } + + memset(&pair->entry, 0, sizeof(pair->entry)); + +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL + pair->entry.d_ino = 0; + pair->entry.d_seekoff++; +#endif + + strncpy(pair->entry.d_name, info.name, MIN(strlen(info.name)+1, sizeof(pair->entry.d_name))); +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL + pair->entry.d_namlen = strlen(info.name); +#endif + + pair->entry.d_type = info.type == LFS_TYPE_DIR ? DT_DIR : DT_REG; + + return &pair->entry; +} + +int AP_Filesystem_FlashMemory_LittleFS::closedir(void *ptr) +{ + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + + lfs_dir_entry_pair *pair = static_cast(ptr); + if (!pair) { + errno = EINVAL; + return 0; + } + + LFS_CHECK(lfs_dir_close(&fs, &pair->dir)); + + delete pair; + + return 0; +} + +int64_t AP_Filesystem_FlashMemory_LittleFS::disk_free(const char *path) +{ + lfs_ssize_t alloc_size; + + FS_CHECK_ALLOWED(-1); + WITH_SEMAPHORE(fs_sem); + ENSURE_MOUNTED(); + + alloc_size = lfs_fs_size(&fs); + if (alloc_size < 0) { + errno = errno_from_lfs_error(alloc_size); + return -1; + } + + return disk_space(path) - alloc_size; +} + +int64_t AP_Filesystem_FlashMemory_LittleFS::disk_space(const char *path) +{ + return fs_cfg.block_count * fs_cfg.block_size; +} + +bool AP_Filesystem_FlashMemory_LittleFS::retry_mount(void) +{ + FS_CHECK_ALLOWED(false); + WITH_SEMAPHORE(fs_sem); + + if (!dead) { + if (!mounted && !mount_filesystem()) { + errno = EIO; + return false; + } + + return true; + } else { + return false; + } +} + +void AP_Filesystem_FlashMemory_LittleFS::unmount(void) +{ + WITH_SEMAPHORE(fs_sem); + + if (mounted && !dead) { + if (lfs_unmount(&fs) >= 0) { + mounted = false; + } + } +} + +/* ************************************************************************* */ +/* Private functions */ +/* ************************************************************************* */ + +int AP_Filesystem_FlashMemory_LittleFS::allocate_fd() +{ + int fd; + + for (fd = 0; fd < MAX_OPEN_FILES; fd++) { + if (open_files[fd] == nullptr) { + open_files[fd] = static_cast(calloc(1, sizeof(lfs_file_t))); + if (open_files[fd] == nullptr) { + errno = ENOMEM; + return -1; + } + + return fd; + } + } + + errno = ENFILE; + return -1; +} + +int AP_Filesystem_FlashMemory_LittleFS::free_fd(int fd) +{ + lfs_file_t* fp = lfs_file_from_fd(fd); + if (!fp) { + return -1; + } + + free(fp); + open_files[fd] = fp = nullptr; + + return 0; +} + +void AP_Filesystem_FlashMemory_LittleFS::free_all_fds() +{ + int fd; + + for (fd = 0; fd < MAX_OPEN_FILES; fd++) { + if (open_files[fd] == nullptr) { + free_fd(fd); + } + } +} + +lfs_file_t* AP_Filesystem_FlashMemory_LittleFS::lfs_file_from_fd(int fd) const +{ + if (fd < 0 || fd >= MAX_OPEN_FILES || open_files[fd] == nullptr) { + errno = EBADF; + return nullptr; + } + + return open_files[fd]; +} + +void AP_Filesystem_FlashMemory_LittleFS::mark_dead() +{ + if (!dead) { + printf("FlashMemory_LittleFS: dead\n"); + free_all_fds(); + dead = true; + } +} + +/* ************************************************************************* */ +/* Low-level flash memory access */ +/* ************************************************************************* */ + +#define JEDEC_WRITE_ENABLE 0x06 +#define JEDEC_READ_STATUS 0x05 +#define JEDEC_WRITE_STATUS 0x01 +#define JEDEC_READ_DATA 0x03 +#define JEDEC_PAGE_DATA_READ 0x13 +#define JEDEC_DEVICE_ID 0x9F +#define JEDEC_PAGE_WRITE 0x02 +#define JEDEC_PROGRAM_EXECUTE 0x10 + +#define JEDEC_DEVICE_RESET 0xFF + +#define JEDEC_BULK_ERASE 0xC7 +#define JEDEC_SECTOR4_ERASE 0x20 // 4k erase +#define JEDEC_BLOCK_ERASE 0xD8 + +#define JEDEC_STATUS_BUSY 0x01 +#define JEDEC_STATUS_WRITEPROTECT 0x02 +#define JEDEC_STATUS_BP0 0x04 +#define JEDEC_STATUS_BP1 0x08 +#define JEDEC_STATUS_BP2 0x10 +#define JEDEC_STATUS_TP 0x20 +#define JEDEC_STATUS_SEC 0x40 +#define JEDEC_STATUS_SRP0 0x80 + +#define W25NXX_STATUS_EFAIL 0x04 +#define W25NXX_STATUS_PFAIL 0x08 + + +/* + flash device IDs taken from betaflight flash_m25p16.c + + Format is manufacturer, memory type, then capacity +*/ +#define JEDEC_ID_UNKNOWN 0x000000 +#define JEDEC_ID_MACRONIX_MX25L3206E 0xC22016 +#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017 +#define JEDEC_ID_MACRONIX_MX25L25635E 0xC22019 +#define JEDEC_ID_MICRON_M25P16 0x202015 +#define JEDEC_ID_MICRON_N25Q064 0x20BA17 +#define JEDEC_ID_MICRON_N25Q128 0x20BA18 +#define JEDEC_ID_WINBOND_W25Q16 0xEF4015 +#define JEDEC_ID_WINBOND_W25Q32 0xEF4016 +#define JEDEC_ID_WINBOND_W25X32 0xEF3016 +#define JEDEC_ID_WINBOND_W25Q64 0xEF4017 +#define JEDEC_ID_WINBOND_W25Q128 0xEF4018 +#define JEDEC_ID_WINBOND_W25Q256 0xEF4019 +#define JEDEC_ID_WINBOND_W25Q128_2 0xEF7018 +#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21 +#define JEDEC_ID_WINBOND_W25N02KV 0xEFAA22 +#define JEDEC_ID_CYPRESS_S25FL128L 0x016018 + +/* Hardware-specific constants */ + +#define W25NXX_PROT_REG 0xA0 +#define W25NXX_CONF_REG 0xB0 +#define W25NXX_STATUS_REG 0xC0 +#define W25NXX_STATUS_EFAIL 0x04 +#define W25NXX_STATUS_PFAIL 0x08 + +#define W25N01G_NUM_BLOCKS 1024 +#define W25N02K_NUM_BLOCKS 2048 + +#define W25NXX_CONFIG_ECC_ENABLE (1 << 4) +#define W25NXX_CONFIG_BUFFER_READ_MODE (1 << 3) + +#define W25NXX_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled) +#define W25NXX_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us +#define W25NXX_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms +#define W25NXX_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms + +bool AP_Filesystem_FlashMemory_LittleFS::is_busy() +{ + WITH_SEMAPHORE(dev_sem); + uint8_t status; +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + uint8_t cmd[2] { JEDEC_READ_STATUS, W25NXX_STATUS_REG }; + dev->transfer(cmd, 2, &status, 1); + return (status & (JEDEC_STATUS_BUSY | W25NXX_STATUS_PFAIL | W25NXX_STATUS_EFAIL)) != 0; +#else + uint8_t cmd = JEDEC_READ_STATUS; + dev->transfer(&cmd, 1, &status, 1); + return (status & (JEDEC_STATUS_BUSY | JEDEC_STATUS_SRP0)) != 0; +#endif +} + +void AP_Filesystem_FlashMemory_LittleFS::send_command_addr(uint8_t command, uint32_t addr) +{ + uint8_t cmd[5]; + cmd[0] = command; + + if (use_32bit_address) { + cmd[1] = (addr >> 24) & 0xff; + cmd[2] = (addr >> 16) & 0xff; + cmd[3] = (addr >> 8) & 0xff; + cmd[4] = (addr >> 0) & 0xff; + } else { + cmd[1] = (addr >> 16) & 0xff; + cmd[2] = (addr >> 8) & 0xff; + cmd[3] = (addr >> 0) & 0xff; + cmd[4] = 0; + } + + dev->transfer(cmd, use_32bit_address ? 5 : 4, nullptr, 0); +} + +void AP_Filesystem_FlashMemory_LittleFS::send_command_page(uint8_t command, uint32_t page) +{ + uint8_t cmd[3]; + cmd[0] = command; + cmd[1] = (page >> 8) & 0xff; + cmd[2] = (page >> 0) & 0xff; + dev->transfer(cmd, 3, nullptr, 0); +} + +bool AP_Filesystem_FlashMemory_LittleFS::wait_until_device_is_ready() +{ + if (dead) { + return false; + } + + uint32_t t = AP_HAL::millis(); + while (is_busy()) { + hal.scheduler->delay_microseconds(100); + if (AP_HAL::millis() - t > 5000) { + mark_dead(); + return false; + } + } + + return true; +} + +void AP_Filesystem_FlashMemory_LittleFS::write_status_register(uint8_t reg, uint8_t bits) +{ + WITH_SEMAPHORE(dev_sem); + uint8_t cmd[3] = { JEDEC_WRITE_STATUS, reg, bits }; + dev->transfer(cmd, 3, nullptr, 0); +} + +uint32_t AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() { + if (!wait_until_device_is_ready()) { + return false; + } + + WITH_SEMAPHORE(dev_sem); + + // Read manufacturer ID + uint8_t cmd = JEDEC_DEVICE_ID; + uint8_t buf[4]; + dev->transfer(&cmd, 1, buf, 4); + +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + uint32_t id = buf[1] << 16 | buf[2] << 8 | buf[3]; + +#else + uint32_t id = buf[0] << 16 | buf[1] << 8 | buf[2]; +#endif + + // Let's specify the terminology here. + // + // 1 block = smallest unit that we can _erase_ in a single operation + // 1 page = smallest unit that we can read or program in a single operation + // + // So, for instance, if we have 4K sectors on the flash chip and we can + // always erase a single 4K sector, the LFS block size will be 4096 bytes, + + // irrespectively of what the flash chip documentation refers to as a "block" + /* Most flash chips are programmable in chunks of 256 bytes and erasable in + * blocks of 4K so we start with these defaults */ + uint32_t block_count = 0; + uint16_t page_size = 256; + uint32_t block_size = 4096; + + switch (id) { +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + case JEDEC_ID_WINBOND_W25N01GV: + /* 128M, programmable in chunks of 2048 bytes, erasable in blocks of 128K */ + page_size = 2048; + block_size = 131072; + block_count = 1024; + break; + case JEDEC_ID_WINBOND_W25N02KV: + /* 256M, programmable in chunks of 2048 bytes, erasable in blocks of 128K */ + page_size = 2048; + block_size = 131072; + block_count = 2048; + break; +#else + case JEDEC_ID_WINBOND_W25Q16: + case JEDEC_ID_MICRON_M25P16: + block_count = 32; /* 128K */ + break; + + case JEDEC_ID_WINBOND_W25Q32: + case JEDEC_ID_WINBOND_W25X32: + case JEDEC_ID_MACRONIX_MX25L3206E: + block_count = 64; /* 256K */ + break; + + case JEDEC_ID_MICRON_N25Q064: + case JEDEC_ID_WINBOND_W25Q64: + case JEDEC_ID_MACRONIX_MX25L6406E: + block_count = 128; /* 512K */ + break; + + case JEDEC_ID_MICRON_N25Q128: + case JEDEC_ID_WINBOND_W25Q128: + case JEDEC_ID_WINBOND_W25Q128_2: + case JEDEC_ID_CYPRESS_S25FL128L: + block_count = 256; /* 1M */ + break; + + case JEDEC_ID_WINBOND_W25Q256: + case JEDEC_ID_MACRONIX_MX25L25635E: + block_count = 512; /* 2M */ + use_32bit_address = true; + break; +#endif + default: + hal.scheduler->delay(2000); + printf("Unknown SPI Flash 0x%08x\n", id); + return 0; + } + + fs_cfg.read_size = page_size; + fs_cfg.prog_size = page_size; + fs_cfg.block_size = block_size; + fs_cfg.block_count = block_count; + + fs_cfg.block_cycles = 500; + fs_cfg.lookahead_size = 16; + + // cache_size has to be the same as the page_size, otherwise we would + // occasionally get read or prog requests in flashmem_read() and + // flashmem_prog() whose size is equal to the cache size, and we do not + // handle that right now + fs_cfg.cache_size = page_size; + + return id; +} + +bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() { + if (dead) { + return false; + } + + if (mounted) { + return true; + } + + EXPECT_DELAY_MS(3000); + + fs_cfg.context = this; + + fs_cfg.read = flashmem_read; + fs_cfg.prog = flashmem_prog; + fs_cfg.erase = flashmem_erase; + fs_cfg.sync = flashmem_sync; + + dev = hal.spi->get_device("dataflash"); + if (!dev) { + mark_dead(); + return false; + } + + dev_sem = dev->get_semaphore(); + + uint32_t id = find_block_size_and_count(); + + if (!id) { + mark_dead(); + return false; + } + + if (!init_flash()) { + mark_dead(); + return false; + } + + if (lfs_mount(&fs, &fs_cfg) < 0) { + /* maybe not formatted? try formatting it */ + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash"); +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + EXPECT_DELAY_MS(3000); +#else + EXPECT_DELAY_MS(30000); +#endif + + if (lfs_format(&fs, &fs_cfg) < 0) { + mark_dead(); + return false; + } + + /* try mounting again */ + if (lfs_mount(&fs, &fs_cfg) < 0) { + /* cannot mount after formatting */ + mark_dead(); + return false; + } + } + +#ifdef HAL_BOARD_STORAGE_DIRECTORY + // try to create the root storage folder. Ignore the error code in case + // the filesystem is corrupted or it already exists. + if (strlen(HAL_BOARD_STORAGE_DIRECTORY) > 0) { + lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY); + } +#endif + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Mounted flash 0x%x as littlefs", unsigned(id)); + mounted = true; + return true; +} + +/* + format sdcard +*/ +bool AP_Filesystem_FlashMemory_LittleFS::format(void) +{ + WITH_SEMAPHORE(fs_sem); + hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FlashMemory_LittleFS::format_handler, void)); + // the format is handled asynchronously, we inform user of success + // via a text message. format_status can be polled for progress + format_status = FormatStatus::PENDING; + return true; +} + +/* + format sdcard +*/ +void AP_Filesystem_FlashMemory_LittleFS::format_handler(void) +{ + if (format_status != FormatStatus::PENDING) { + return; + } + WITH_SEMAPHORE(fs_sem); + format_status = FormatStatus::IN_PROGRESS; + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash using littlefs"); + + int ret = lfs_format(&fs, &fs_cfg); + + /* try mounting */ + if (ret == LFS_ERR_OK) { + ret = lfs_mount(&fs, &fs_cfg); + } + +#ifdef HAL_BOARD_STORAGE_DIRECTORY + // try to create the root storage folder. Ignore the error code in case + // the filesystem is corrupted or it already exists. + if (strlen(HAL_BOARD_STORAGE_DIRECTORY) > 0) { + lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY); + } +#endif + + if (ret == LFS_ERR_OK) { + format_status = FormatStatus::SUCCESS; + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: OK"); + } else { + format_status = FormatStatus::FAILURE; + mark_dead(); + GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: Failed (%d)", int(ret)); + } +} + +// returns true if we are currently formatting the SD card: +AP_Filesystem_Backend::FormatStatus AP_Filesystem_FlashMemory_LittleFS::get_format_status(void) const +{ + // note that format_handler holds sem, so we can't take it here. + return format_status; +} + +uint32_t AP_Filesystem_FlashMemory_LittleFS::lfs_block_and_offset_to_raw_flash_address(lfs_block_t index, lfs_off_t off) +{ + return index * fs_cfg.block_size + off; +} + +uint32_t AP_Filesystem_FlashMemory_LittleFS::lfs_block_to_raw_flash_page_index(lfs_block_t index) +{ + return index * (fs_cfg.block_size / fs_cfg.prog_size); +} + +bool AP_Filesystem_FlashMemory_LittleFS::write_enable() +{ + uint8_t b = JEDEC_WRITE_ENABLE; + + if (!wait_until_device_is_ready()) { + return false; + } + + WITH_SEMAPHORE(dev_sem); + return dev->transfer(&b, 1, nullptr, 0); +} + +bool AP_Filesystem_FlashMemory_LittleFS::init_flash() +{ +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + // reset the device + if (!wait_until_device_is_ready()) { + return false; + } + { + WITH_SEMAPHORE(dev_sem); + uint8_t b = JEDEC_DEVICE_RESET; + dev->transfer(&b, 1, nullptr, 0); + } + hal.scheduler->delay(W25NXX_TIMEOUT_RESET_MS); + + // disable write protection + write_status_register(W25NXX_PROT_REG, 0); + + // enable ECC and buffer mode + write_status_register(W25NXX_CONF_REG, W25NXX_CONFIG_ECC_ENABLE | W25NXX_CONFIG_BUFFER_READ_MODE); +#else + if (use_32bit_address) { + WITH_SEMAPHORE(dev_sem); + + const uint8_t cmd = 0xB7; + dev->transfer(&cmd, 1, nullptr, 0); + } +#endif + + return true; +} + +int AP_Filesystem_FlashMemory_LittleFS::_flashmem_read( + lfs_block_t block, lfs_off_t off, void* buffer, lfs_size_t size +) { + uint32_t address; + + if (dead) { + return LFS_ERR_IO; + } + + address = lfs_block_and_offset_to_raw_flash_address(block, off); +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + /* We need to read an entire page into an internal buffer and then read + * that buffer with JEDEC_READ_DATA later */ + if (!wait_until_device_is_ready()) { + return LFS_ERR_IO; + } + + { + WITH_SEMAPHORE(dev_sem); + send_command_addr(JEDEC_PAGE_DATA_READ, address / fs_cfg.read_size); + address %= fs_cfg.read_size; + } +#endif + if (!wait_until_device_is_ready()) { + return LFS_ERR_IO; + } + + WITH_SEMAPHORE(dev_sem); + + dev->set_chip_select(true); + send_command_addr(JEDEC_READ_DATA, address); + dev->transfer(nullptr, 0, static_cast(buffer), size); + dev->set_chip_select(false); + + return LFS_ERR_OK; +} + +int AP_Filesystem_FlashMemory_LittleFS::_flashmem_prog( + lfs_block_t block, lfs_off_t off, const void* buffer, lfs_size_t size +) { + uint32_t address; + + if (dead) { + return LFS_ERR_IO; + } + + if (!write_enable()) { + return LFS_ERR_IO; + } + + address = lfs_block_and_offset_to_raw_flash_address(block, off); + + WITH_SEMAPHORE(dev_sem); +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + /* First we need to write into the data buffer at column address zero, + * then we need to issue PROGRAM_EXECUTE to commit the internal buffer */ + dev->set_chip_select(true); + send_command_page(JEDEC_PAGE_WRITE, address % fs_cfg.prog_size); + dev->transfer(static_cast(buffer), size, nullptr, 0); + dev->set_chip_select(false); + send_command_addr(JEDEC_PROGRAM_EXECUTE, address / fs_cfg.prog_size); +#else + dev->set_chip_select(true); + send_command_addr(JEDEC_PAGE_WRITE, address); + dev->transfer(static_cast(buffer), size, nullptr, 0); + dev->set_chip_select(false); +#endif + return LFS_ERR_OK; +} + +int AP_Filesystem_FlashMemory_LittleFS::_flashmem_erase(lfs_block_t block) { + if (dead) { + return LFS_ERR_IO; + } + + if (!write_enable()) { + return LFS_ERR_IO; + } + + WITH_SEMAPHORE(dev_sem); +#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX + send_command_addr(JEDEC_BLOCK_ERASE, lfs_block_to_raw_flash_page_index(block)); +#else + send_command_addr(JEDEC_SECTOR4_ERASE, lfs_block_and_offset_to_raw_flash_address(block)); +#endif + + return LFS_ERR_OK; +} + +int AP_Filesystem_FlashMemory_LittleFS::_flashmem_sync() { + if (wait_until_device_is_ready()) { + return LFS_ERR_OK; + } else { + return LFS_ERR_IO; + } +} + +static int flashmem_read( + const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off, + void* buffer, lfs_size_t size +) { + AP_Filesystem_FlashMemory_LittleFS* self = static_cast(cfg->context); + return self->_flashmem_read(block, off, buffer, size); +} + +static int flashmem_prog( + const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off, + const void* buffer, lfs_size_t size +) { + AP_Filesystem_FlashMemory_LittleFS* self = static_cast(cfg->context); + return self->_flashmem_prog(block, off, buffer, size); +} + +static int flashmem_erase(const struct lfs_config *cfg, lfs_block_t block) { + AP_Filesystem_FlashMemory_LittleFS* self = static_cast(cfg->context); + return self->_flashmem_erase(block); +} + +static int flashmem_sync(const struct lfs_config *cfg) { + AP_Filesystem_FlashMemory_LittleFS* self = static_cast(cfg->context); + return self->_flashmem_sync(); +} + +/* ************************************************************************* */ +/* LittleFS to POSIX API conversion functions */ +/* ************************************************************************* */ + +static int errno_from_lfs_error(int lfs_error) +{ + switch (lfs_error) { + case LFS_ERR_OK: return 0; + case LFS_ERR_IO: return EIO; + case LFS_ERR_CORRUPT: return EIO; + case LFS_ERR_NOENT: return ENOENT; + case LFS_ERR_EXIST: return EEXIST; + case LFS_ERR_NOTDIR: return ENOTDIR; + case LFS_ERR_ISDIR: return EISDIR; + case LFS_ERR_NOTEMPTY: return ENOTEMPTY; + case LFS_ERR_BADF: return EBADF; + case LFS_ERR_FBIG: return EFBIG; + case LFS_ERR_INVAL: return EINVAL; + case LFS_ERR_NOSPC: return ENOSPC; + case LFS_ERR_NOMEM: return ENOMEM; +#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL + case LFS_ERR_NOATTR: return ENOATTR; +#endif + case LFS_ERR_NAMETOOLONG: return ENAMETOOLONG; + default: return EIO; + } +} + +static int lfs_flags_from_flags(int flags) +{ + int outflags = 0; + + if (flags & O_WRONLY) { + outflags |= LFS_O_WRONLY; + } else if (flags & O_RDWR) { + outflags |= LFS_O_RDWR; + } else { + outflags |= LFS_O_RDONLY; + } + + if (flags & O_CREAT) { + outflags |= LFS_O_CREAT; + } + + if (flags & O_EXCL) { + outflags |= LFS_O_EXCL; + } + + if (flags & O_TRUNC) { + outflags |= LFS_O_TRUNC; + } + + if (flags & O_APPEND) { + outflags |= LFS_O_APPEND; + } + + return outflags; +} + +#endif // AP_FILESYSTEM_LITTLEFS_ENABLED diff --git a/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.h b/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.h new file mode 100644 index 0000000000000..40b8db4db3cc7 --- /dev/null +++ b/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.h @@ -0,0 +1,113 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +#pragma once + +#include "AP_Filesystem_backend.h" + +#if AP_FILESYSTEM_LITTLEFS_ENABLED + +#include +#include +#include "lfs.h" + +class AP_Filesystem_FlashMemory_LittleFS : public AP_Filesystem_Backend +{ +public: + // functions that closely match the equivalent posix calls + int open(const char *fname, int flags, bool allow_absolute_paths = false) override; + int close(int fd) override; + int32_t read(int fd, void *buf, uint32_t count) override; + int32_t write(int fd, const void *buf, uint32_t count) override; + int fsync(int fd) override; + int32_t lseek(int fd, int32_t offset, int whence) override; + int stat(const char *pathname, struct stat *stbuf) override; + + int unlink(const char *pathname) override; + int mkdir(const char *pathname) override; + + void *opendir(const char *pathname) override; + struct dirent *readdir(void *dirp) override; + int closedir(void *dirp) override; + + int64_t disk_free(const char *path) override; + int64_t disk_space(const char *path) override; + + bool retry_mount(void) override; + void unmount(void) override; + // format flash. This is async, monitor get_format_status for progress + bool format(void) override; + AP_Filesystem_Backend::FormatStatus get_format_status() const override; + + int _flashmem_read(lfs_block_t block, lfs_off_t off, void* buffer, lfs_size_t size); + int _flashmem_prog(lfs_block_t block, lfs_off_t off, const void* buffer, lfs_size_t size); + int _flashmem_erase(lfs_block_t block); + int _flashmem_sync(); + +private: + // JEDEC ID of the flash memory, JEDEC_ID_UNKNOWN if not known or not supported + uint32_t jedec_id; + + // Semaphore to protect against concurrent accesses to fs + HAL_Semaphore fs_sem; + + // The filesystem object + lfs_t fs; + + // The configuration of the filesystem + struct lfs_config fs_cfg; + + // Maximum number of files that may be open at the same time + static constexpr int MAX_OPEN_FILES = 16; + + // Stores whether the filesystem is mounted + bool mounted; + + // Stores whether the filesystem has been marked as dead + bool dead; + + // Array of currently open file descriptors + lfs_file_t* open_files[MAX_OPEN_FILES]; + + // SPI device that handles the raw flash memory + AP_HAL::OwnPtr dev; + + // Semaphore to protect access to the SPI device + AP_HAL::Semaphore *dev_sem; + + // Flag to denote that the underlying flash chip uses 32-bit addresses + bool use_32bit_address; + FormatStatus format_status; + + int allocate_fd(); + int free_fd(int fd); + void free_all_fds(); + lfs_file_t* lfs_file_from_fd(int fd) const; + + uint32_t lfs_block_and_offset_to_raw_flash_address(lfs_block_t block, lfs_off_t off = 0); + uint32_t lfs_block_to_raw_flash_page_index(lfs_block_t block); + uint32_t find_block_size_and_count(); + bool init_flash() WARN_IF_UNUSED; + bool write_enable() WARN_IF_UNUSED; + bool is_busy(); + bool mount_filesystem(); + void send_command_addr(uint8_t command, uint32_t addr); + void send_command_page(uint8_t command, uint32_t page); + bool wait_until_device_is_ready() WARN_IF_UNUSED; + void write_status_register(uint8_t reg, uint8_t bits); + void format_handler(void); + void mark_dead(); +}; + +#endif // #if AP_FILESYSTEM_LITTLEFS_ENABLED diff --git a/libraries/AP_Filesystem/AP_Filesystem_config.h b/libraries/AP_Filesystem/AP_Filesystem_config.h index a23b1f2c1b543..49cc6ec3f8496 100644 --- a/libraries/AP_Filesystem/AP_Filesystem_config.h +++ b/libraries/AP_Filesystem/AP_Filesystem_config.h @@ -2,6 +2,9 @@ #include +#define AP_FILESYSTEM_FLASH_W25QXX 1 +#define AP_FILESYSTEM_FLASH_W25NXX 2 + // backends: #ifndef AP_FILESYSTEM_ESP32_ENABLED @@ -12,6 +15,14 @@ #define AP_FILESYSTEM_FATFS_ENABLED HAL_OS_FATFS_IO #endif +#ifndef AP_FILESYSTEM_LITTLEFS_ENABLED +#define AP_FILESYSTEM_LITTLEFS_ENABLED HAL_OS_LITTLEFS_IO +#endif + +#ifndef AP_FILESYSTEM_LITTLEFS_FLASH_TYPE +#define AP_FILESYSTEM_LITTLEFS_FLASH_TYPE AP_FILESYSTEM_FLASH_W25QXX +#endif + #ifndef AP_FILESYSTEM_PARAM_ENABLED #define AP_FILESYSTEM_PARAM_ENABLED 1 #endif @@ -39,7 +50,7 @@ // upload targets, and also excludes ROMFS (where you can read but not // write!) #ifndef AP_FILESYSTEM_FILE_WRITING_ENABLED -#define AP_FILESYSTEM_FILE_WRITING_ENABLED (AP_FILESYSTEM_ESP32_ENABLED || AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED) +#define AP_FILESYSTEM_FILE_WRITING_ENABLED (AP_FILESYSTEM_ESP32_ENABLED || AP_FILESYSTEM_FATFS_ENABLED || AP_FILESYSTEM_LITTLEFS_ENABLED || AP_FILESYSTEM_POSIX_ENABLED) #endif // AP_FILESYSTEM_FILE_READING_ENABLED is true if you could expect to diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 26a47e2c8cd99..33422fc70e8b1 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -210,6 +210,10 @@ #define HAL_OS_FATFS_IO 0 #endif +#ifndef HAL_OS_LITTLEFS_IO +#define HAL_OS_LITTLEFS_IO 0 +#endif + #ifndef HAL_BARO_DEFAULT #define HAL_BARO_DEFAULT HAL_BARO_NONE #endif diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.h b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.h index 4ed88397bf1df..4f0ff4ca8c1f2 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.h +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.h @@ -21,7 +21,7 @@ #include #include #include "hwdef/common/halconf.h" -#ifdef USE_POSIX +#ifdef USE_POSIX_FATFS #include #endif #include diff --git a/libraries/AP_HAL_ChibiOS/Storage.cpp b/libraries/AP_HAL_ChibiOS/Storage.cpp index 7f8fc2819b9c8..7a6c3b451c2b6 100644 --- a/libraries/AP_HAL_ChibiOS/Storage.cpp +++ b/libraries/AP_HAL_ChibiOS/Storage.cpp @@ -42,8 +42,12 @@ extern const AP_HAL::HAL& hal; #endif #ifndef HAL_STORAGE_BACKUP_COUNT +#if AP_FILESYSTEM_LITTLEFS_ENABLED +#define HAL_STORAGE_BACKUP_COUNT 5 +#else #define HAL_STORAGE_BACKUP_COUNT 100 #endif +#endif #define STORAGE_FLASH_RETRIES 5 @@ -128,7 +132,7 @@ void Storage::_storage_open(void) void Storage::_save_backup(void) { #ifdef USE_POSIX - // allow for fallback to microSD based storage + // allow for fallback to microSD or dataflash based storage // create the backup directory if need be int ret; const char* _storage_bak_directory = HAL_STORAGE_BACKUP_FOLDER; diff --git a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat index 8a7d80b127a8a..1eeeb2ec57781 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/FoxeerF405v2/hwdef.dat @@ -136,7 +136,9 @@ define HAL_GPIO_B_LED_PIN 91 # Dataflash setup SPIDEV dataflash SPI2 DEVID1 FLASH1_CS MODE3 104*MHZ 104*MHZ -define HAL_LOGGING_DATAFLASH_ENABLED 1 +define HAL_OS_LITTLEFS_IO 1 +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # OSD setup SPIDEV osd SPI3 DEVID1 OSD1_CS MODE0 10*MHZ 10*MHZ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat index 5e3a7b1bdbd70..bc6450f3cb005 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7Mini-Nand/hwdef.dat @@ -9,4 +9,8 @@ SPIDEV bmi270 SPI4 DEVID1 MPU6000_CS MODE3 1*MHZ 4*MHZ IMU BMI270 SPI:bmi270 ROTATION_PITCH_180_YAW_90 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX +undef HAL_LOGGING_DATAFLASH_ENABLED +define HAL_OS_LITTLEFS_IO 1 +define AP_FILESYSTEM_LITTLEFS_FLASH_TYPE AP_FILESYSTEM_FLASH_W25NXX +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" diff --git a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat index 2a40cc91f5912..3ed3264e6cb0e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/KakuteH7v2/hwdef.dat @@ -64,7 +64,10 @@ DMA_NOSHARE *UP SPI1* # Motor order implies Betaflight/X for standard ESCs define HAL_FRAME_TYPE_DEFAULT 12 -define HAL_LOGGING_DATAFLASH_ENABLED 1 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX + +# Enable LittleFS filesystem support (needs internal flash memory) +define HAL_OS_LITTLEFS_IO 1 + +define DEFAULT_NTF_LED_TYPES 257 define AP_SCRIPTING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat index 661909c0d7091..290f39f1e47fc 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MambaH743v4/hwdef.dat @@ -26,9 +26,6 @@ FLASH_RESERVE_START_KB 384 STORAGE_FLASH_PAGE 1 define HAL_STORAGE_SIZE 32768 -# enable logging to dataflash -define HAL_LOGGING_DATAFLASH_ENABLED 1 - # one I2C bus I2C_ORDER I2C1 I2C2 @@ -182,7 +179,10 @@ IMU BMI270 SPI:bmi270 ROTATION_PITCH_180 IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180 IMU Invensensev3 SPI:icm42688_2 ROTATION_ROLL_180_YAW_270 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX +define HAL_OS_LITTLEFS_IO 1 +define AP_FILESYSTEM_LITTLEFS_FLASH_TYPE AP_FILESYSTEM_FLASH_W25NXX +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # DPS280 or SPL06 integrated on I2C bus BARO DPS280 I2C:0:0x76 @@ -194,5 +194,3 @@ define HAL_OSD_TYPE_DEFAULT 1 ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin define DEFAULT_NTF_LED_TYPES 257 - -define AP_SCRIPTING_ENABLED 0 diff --git a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat index cb578f84b2aec..021c1c15536ec 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/MatekH7A3/hwdef.dat @@ -36,6 +36,10 @@ define AP_FLASH_STORAGE_DOUBLE_PAGE 1 PA11 OTG_HS_DM OTG1 PA12 OTG_HS_DP OTG1 +# Debug pins, PA14/PA13 are shared with the LEDs so that needs to be disabled +#PA13 JTMS-SWDIO SWD +#PA14 JTCK-SWCLK SWD + # SPI1 for ICM42688P & MAX7456 PA5 SPI1_SCK SPI1 PA6 SPI1_MISO SPI1 @@ -158,9 +162,10 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin SPIDEV sdcard SPI2 DEVID3 SD_CS MODE0 400*KHZ 25*MHZ SPIDEV dataflash SPI2 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ -define HAL_LOGGING_DATAFLASH_ENABLED 1 -define HAL_OS_FATFS_IO 1 -define HAL_LOGGING_DATAFLASH_DRIVER AP_Logger_W25NXX +define HAL_OS_LITTLEFS_IO 1 +define AP_FILESYSTEM_LITTLEFS_FLASH_TYPE AP_FILESYSTEM_FLASH_W25NXX +define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS" +define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN" # ----------------- I2C compass & Baro ----------------- diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c index 97b837b12a480..b733b20e71f9c 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/malloc.c @@ -585,7 +585,7 @@ void __wrap__free_r(void *rptr, void *ptr) return free(ptr); } -#ifdef USE_POSIX +#ifdef USE_POSIX_FATFS /* allocation functions for FATFS */ @@ -615,7 +615,7 @@ void ff_memfree(void* mblock) { free(mblock); } -#endif // USE_POSIX +#endif // USE_POSIX_FATFS /* return true if a memory region is safe for a DMA operation diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 935db8536f8bb..1e72c8b9129ed 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -762,6 +762,13 @@ def enable_can(self, f): f.write('#define HAL_CANFD_SUPPORTED %d\n' % canfd_supported) self.env_vars['HAL_CANFD_SUPPORTED'] = canfd_supported + def has_dataflash_spi(self): + '''check for dataflash connected to spi bus''' + for dev in self.spidev: + if(dev[0] == 'dataflash'): + return True + return False + def has_sdcard_spi(self): '''check for sdcard connected to spi bus''' for dev in self.spidev: @@ -943,13 +950,15 @@ def write_mcu_config(self, f): f.write('#define HAL_STDOUT_BAUDRATE %u\n\n' % self.get_config('STDOUT_BAUDRATE', type=int)) if self.have_type_prefix('SDIO'): f.write('// SDIO available, enable POSIX filesystem support\n') - f.write('#define USE_POSIX\n\n') + f.write('#define USE_POSIX\n') + f.write('#define USE_POSIX_FATFS\n\n') f.write('#define HAL_USE_SDC TRUE\n') self.build_flags.append('USE_FATFS=yes') self.env_vars['WITH_FATFS'] = "1" elif self.have_type_prefix('SDMMC2'): f.write('// SDMMC2 available, enable POSIX filesystem support\n') - f.write('#define USE_POSIX\n\n') + f.write('#define USE_POSIX\n') + f.write('#define USE_POSIX_FATFS\n\n') f.write('#define HAL_USE_SDC TRUE\n') f.write('#define STM32_SDC_USE_SDMMC2 TRUE\n') f.write('#define HAL_USE_SDMMC 1\n') @@ -957,7 +966,8 @@ def write_mcu_config(self, f): self.env_vars['WITH_FATFS'] = "1" elif self.have_type_prefix('SDMMC'): f.write('// SDMMC available, enable POSIX filesystem support\n') - f.write('#define USE_POSIX\n\n') + f.write('#define USE_POSIX\n') + f.write('#define USE_POSIX_FATFS\n\n') f.write('#define HAL_USE_SDC TRUE\n') f.write('#define STM32_SDC_USE_SDMMC1 TRUE\n') f.write('#define HAL_USE_SDMMC 1\n') @@ -965,12 +975,21 @@ def write_mcu_config(self, f): self.env_vars['WITH_FATFS'] = "1" elif self.has_sdcard_spi(): f.write('// MMC via SPI available, enable POSIX filesystem support\n') - f.write('#define USE_POSIX\n\n') + f.write('#define USE_POSIX\n') + f.write('#define USE_POSIX_FATFS\n\n') f.write('#define HAL_USE_MMC_SPI TRUE\n') f.write('#define HAL_USE_SDC FALSE\n') f.write('#define HAL_SDCARD_SPI_HOOK TRUE\n') self.build_flags.append('USE_FATFS=yes') self.env_vars['WITH_FATFS'] = "1" + elif self.has_dataflash_spi(): + f.write('// Dataflash memory via SPI available, enable POSIX filesystem support\n') + f.write('#define USE_POSIX\n') + f.write('#define USE_POSIX_LITTLEFS\n\n') + f.write('#define HAL_USE_SDC FALSE\n') + self.build_flags.append('USE_FATFS=no') + self.env_vars['WITH_LITTLEFS'] = "1" + self.env_vars['DISABLE_SCRIPTING'] = True else: f.write('#define HAL_USE_SDC FALSE\n') self.build_flags.append('USE_FATFS=no') diff --git a/libraries/AP_HAL_ChibiOS/sdcard.cpp b/libraries/AP_HAL_ChibiOS/sdcard.cpp index 922440826b06d..e2750960572be 100644 --- a/libraries/AP_HAL_ChibiOS/sdcard.cpp +++ b/libraries/AP_HAL_ChibiOS/sdcard.cpp @@ -26,7 +26,7 @@ extern const AP_HAL::HAL& hal; -#ifdef USE_POSIX +#ifdef USE_POSIX_FATFS static FATFS SDC_FS; // FATFS object #ifndef HAL_BOOTLOADER_BUILD static HAL_Semaphore sem; @@ -54,7 +54,7 @@ static SPIConfig highspeed; */ bool sdcard_init() { -#ifdef USE_POSIX +#ifdef USE_POSIX_FATFS #ifndef HAL_BOOTLOADER_BUILD WITH_SEMAPHORE(sem); @@ -150,7 +150,7 @@ bool sdcard_init() } #endif sdcard_running = false; -#endif // USE_POSIX +#endif // USE_POSIX_FATFS return false; } @@ -159,7 +159,7 @@ bool sdcard_init() */ void sdcard_stop(void) { -#ifdef USE_POSIX +#ifdef USE_POSIX_FATFS // unmount f_mount(nullptr, "/", 1); #endif @@ -185,7 +185,7 @@ void sdcard_stop(void) bool sdcard_retry(void) { -#ifdef USE_POSIX +#ifdef USE_POSIX_FATFS if (!sdcard_running) { if (sdcard_init()) { #if AP_FILESYSTEM_FILE_WRITING_ENABLED diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 60d4e4a1b2dd0..3d834946edf5c 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -56,6 +56,14 @@ extern const AP_HAL::HAL& hal; #define HAL_LOGGER_ARM_PERSIST 15 #endif +#ifndef HAL_LOGGER_MIN_MB_FREE +#if AP_FILESYSTEM_LITTLEFS_ENABLED +#define HAL_LOGGER_MIN_MB_FREE 1 +#else +#define HAL_LOGGER_MIN_MB_FREE 500 +#endif +#endif + #ifndef HAL_LOGGING_BACKENDS_DEFAULT # if HAL_LOGGING_FILESYSTEM_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL) # define HAL_LOGGING_BACKENDS_DEFAULT Backend_Type::FILESYSTEM @@ -137,7 +145,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = { // @Units: MB // @Range: 10 1000 // @User: Standard - AP_GROUPINFO("_FILE_MB_FREE", 7, AP_Logger, _params.min_MB_free, 500), + AP_GROUPINFO("_FILE_MB_FREE", 7, AP_Logger, _params.min_MB_free, HAL_LOGGER_MIN_MB_FREE), // @Param: _FILE_RATEMAX // @DisplayName: Maximum logging rate for file backend diff --git a/libraries/AP_Logger/AP_Logger_File.cpp b/libraries/AP_Logger/AP_Logger_File.cpp index 4be657072997d..026a92558e461 100644 --- a/libraries/AP_Logger/AP_Logger_File.cpp +++ b/libraries/AP_Logger/AP_Logger_File.cpp @@ -941,6 +941,7 @@ void AP_Logger_File::io_timer(void) // least once per 2 seconds if data is available return; } + if (tnow - _free_space_last_check_time > _free_space_check_interval) { _free_space_last_check_time = tnow; last_io_operation = "disk_space_avail"; @@ -999,6 +1000,12 @@ void AP_Logger_File::io_timer(void) _last_write_ms = tnow; _write_offset += nwritten; _writebuf.advance(nwritten); + + /* + fsync on littlefs is extremely expensive (20% CPU on an H7) and not + required since the whole point of the filesystem is to avoid corruption + */ +#if !AP_FILESYSTEM_LITTLEFS_ENABLED /* the best strategy for minimizing corruption on microSD cards seems to be to write in 4k chunks and fsync the file on each @@ -1010,6 +1017,7 @@ void AP_Logger_File::io_timer(void) AP::FS().fsync(_write_fd); last_io_operation = ""; #endif +#endif // AP_FILESYSTEM_LITTLEFS_ENABLED #if AP_RTC_ENABLED && CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS // ChibiOS does not update mtime on writes, so if we opened diff --git a/libraries/AP_Logger/AP_Logger_File.h b/libraries/AP_Logger/AP_Logger_File.h index 3cfa02b132edf..1b387f1478d0b 100644 --- a/libraries/AP_Logger/AP_Logger_File.h +++ b/libraries/AP_Logger/AP_Logger_File.h @@ -125,7 +125,11 @@ class AP_Logger_File : public AP_Logger_Backend // data and failures-to-boot. uint32_t _free_space_last_check_time; // milliseconds const uint32_t _free_space_check_interval = 1000UL; // milliseconds +#if AP_FILESYSTEM_LITTLEFS_ENABLED + const uint32_t _free_space_min_avail = 4096; // bytes +#else const uint32_t _free_space_min_avail = 8388608; // bytes +#endif // semaphore mediates access to the ringbuffer HAL_Semaphore semaphore; diff --git a/libraries/AP_Logger/AP_Logger_config.h b/libraries/AP_Logger/AP_Logger_config.h index a5a3508043c34..16553f2bde923 100644 --- a/libraries/AP_Logger/AP_Logger_config.h +++ b/libraries/AP_Logger/AP_Logger_config.h @@ -48,7 +48,7 @@ #endif #ifndef HAL_LOGGER_FILE_CONTENTS_ENABLED -#define HAL_LOGGER_FILE_CONTENTS_ENABLED HAL_LOGGING_FILESYSTEM_ENABLED +#define HAL_LOGGER_FILE_CONTENTS_ENABLED HAL_LOGGING_FILESYSTEM_ENABLED && !AP_FILESYSTEM_LITTLEFS_ENABLED #endif // range of IDs to allow for new messages during replay. It is very diff --git a/libraries/AP_Scripting/AP_Scripting_config.h b/libraries/AP_Scripting/AP_Scripting_config.h index 768e751ca7bb1..09f067ae522a6 100644 --- a/libraries/AP_Scripting/AP_Scripting_config.h +++ b/libraries/AP_Scripting/AP_Scripting_config.h @@ -10,7 +10,7 @@ #if AP_SCRIPTING_ENABLED #include // enumerate all of the possible places we can read a script from. - #if !AP_FILESYSTEM_POSIX_ENABLED && !AP_FILESYSTEM_FATFS_ENABLED && !AP_FILESYSTEM_ESP32_ENABLED && !AP_FILESYSTEM_ROMFS_ENABLED + #if !AP_FILESYSTEM_POSIX_ENABLED && !AP_FILESYSTEM_FATFS_ENABLED && !AP_FILESYSTEM_ESP32_ENABLED && !AP_FILESYSTEM_ROMFS_ENABLED && !AP_FILESYSTEM_LITTLEFS_ENABLED #error "Scripting requires a filesystem" #endif #endif diff --git a/modules/littlefs b/modules/littlefs new file mode 160000 index 0000000000000..d01280e64934a --- /dev/null +++ b/modules/littlefs @@ -0,0 +1 @@ +Subproject commit d01280e64934a09ba16cac60cf9d3a37e228bb66 diff --git a/wscript b/wscript index fff0a563f2111..803f7dbaf57f9 100644 --- a/wscript +++ b/wscript @@ -565,6 +565,7 @@ def configure(cfg): if cfg.options.enable_benchmarks: cfg.load('gbenchmark') cfg.load('gtest') + cfg.load('littlefs') cfg.load('static_linking') cfg.load('build_summary') @@ -795,6 +796,8 @@ def _build_common_taskgens(bld): ap_libraries=bld.ap_get_all_libraries(), ) + bld.littlefs() + if bld.env.HAS_GTEST: bld.libgtest(cxxflags=['-include', 'ap_config.h'])