Path: blob/master/libraries/AP_Filesystem/AP_Filesystem.cpp
9413 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*/1415#include "AP_Filesystem.h"1617#include "AP_Filesystem_config.h"1819#if AP_FILESYSTEM_FILE_READING_ENABLED2021#include <AP_HAL/HAL.h>22#include <AP_HAL/Util.h>23#include <AP_Math/AP_Math.h>2425static AP_Filesystem fs;2627// create exactly one "local" filesystem:28#if AP_FILESYSTEM_FATFS_ENABLED29#include "AP_Filesystem_FATFS.h"30static AP_Filesystem_FATFS fs_local;31#elif AP_FILESYSTEM_ESP32_ENABLED32#include "AP_Filesystem_ESP32.h"33static AP_Filesystem_ESP32 fs_local;34#elif AP_FILESYSTEM_LITTLEFS_ENABLED35#include "AP_Filesystem_FlashMemory_LittleFS.h"36static AP_Filesystem_FlashMemory_LittleFS fs_local;37#elif AP_FILESYSTEM_POSIX_ENABLED38#include "AP_Filesystem_posix.h"39static AP_Filesystem_Posix fs_local;40#else41static AP_Filesystem_Backend fs_local;42int errno;43#endif4445#if AP_FILESYSTEM_ROMFS_ENABLED46#include "AP_Filesystem_ROMFS.h"47static AP_Filesystem_ROMFS fs_romfs;48#endif4950#if AP_FILESYSTEM_PARAM_ENABLED51#include "AP_Filesystem_Param.h"52static AP_Filesystem_Param fs_param;53#endif5455#if AP_FILESYSTEM_SYS_ENABLED56#include "AP_Filesystem_Sys.h"57static AP_Filesystem_Sys fs_sys;58#endif5960#if AP_FILESYSTEM_MISSION_ENABLED61#include "AP_Filesystem_Mission.h"62static AP_Filesystem_Mission fs_mission;63#endif6465/*66mapping from filesystem prefix to backend67*/68const AP_Filesystem::Backend AP_Filesystem::backends[] = {69{ nullptr, fs_local },70#if AP_FILESYSTEM_ROMFS_ENABLED71{ "@ROMFS", fs_romfs },72#endif73#if AP_FILESYSTEM_PARAM_ENABLED74{ "@PARAM", fs_param },75#endif76#if AP_FILESYSTEM_SYS_ENABLED77{ "@SYS", fs_sys },78#endif79#if AP_FILESYSTEM_MISSION_ENABLED80{ "@MISSION", fs_mission },81#endif82};8384extern const AP_HAL::HAL& hal;8586#define MAX_FD_PER_BACKEND 256U87#define NUM_BACKENDS ARRAY_SIZE(backends)88#define LOCAL_BACKEND backends[0]89#define BACKEND_IDX(backend) (&(backend) - &backends[0])9091/*92find backend by path93*/94const AP_Filesystem::Backend &AP_Filesystem::backend_by_path(const char *&path) const95{96// ignore leading slashes:97const char *path_with_no_leading_slash = path;98if (path_with_no_leading_slash[0] == '/') {99path_with_no_leading_slash = &path_with_no_leading_slash[1];100}101for (uint8_t i=1; i<NUM_BACKENDS; i++) {102const uint8_t plen = strlen(backends[i].prefix);103if (strncmp(path_with_no_leading_slash, backends[i].prefix, plen) == 0) {104path = path_with_no_leading_slash;105path += plen;106if (strlen(path) > 0 && path[0] == '/') {107path++;108}109return backends[i];110}111}112// default to local filesystem113return LOCAL_BACKEND;114}115116/*117return backend by file descriptor118*/119const AP_Filesystem::Backend &AP_Filesystem::backend_by_fd(int &fd) const120{121if (fd < 0 || uint32_t(fd) >= NUM_BACKENDS*MAX_FD_PER_BACKEND) {122return LOCAL_BACKEND;123}124const uint8_t idx = uint32_t(fd) / MAX_FD_PER_BACKEND;125fd -= idx * MAX_FD_PER_BACKEND;126return backends[idx];127}128129int AP_Filesystem::open(const char *fname, int flags, bool allow_absolute_paths)130{131const Backend &backend = backend_by_path(fname);132int fd = backend.fs.open(fname, flags, allow_absolute_paths);133if (fd < 0) {134return -1;135}136if (uint32_t(fd) >= MAX_FD_PER_BACKEND) {137backend.fs.close(fd);138errno = ERANGE;139return -1;140}141// offset fd so we can recognise the backend142const uint8_t idx = (&backend - &backends[0]);143fd += idx * MAX_FD_PER_BACKEND;144return fd;145}146147int AP_Filesystem::close(int fd)148{149const Backend &backend = backend_by_fd(fd);150return backend.fs.close(fd);151}152153int32_t AP_Filesystem::read(int fd, void *buf, uint32_t count)154{155const Backend &backend = backend_by_fd(fd);156return backend.fs.read(fd, buf, count);157}158159int32_t AP_Filesystem::write(int fd, const void *buf, uint32_t count)160{161const Backend &backend = backend_by_fd(fd);162return backend.fs.write(fd, buf, count);163}164165int AP_Filesystem::fsync(int fd)166{167const Backend &backend = backend_by_fd(fd);168return backend.fs.fsync(fd);169}170171int32_t AP_Filesystem::lseek(int fd, int32_t offset, int seek_from)172{173const Backend &backend = backend_by_fd(fd);174return backend.fs.lseek(fd, offset, seek_from);175}176177int AP_Filesystem::stat(const char *pathname, struct stat *stbuf)178{179const Backend &backend = backend_by_path(pathname);180return backend.fs.stat(pathname, stbuf);181}182183int AP_Filesystem::unlink(const char *pathname)184{185const Backend &backend = backend_by_path(pathname);186return backend.fs.unlink(pathname);187}188189int AP_Filesystem::mkdir(const char *pathname)190{191const Backend &backend = backend_by_path(pathname);192return backend.fs.mkdir(pathname);193}194195int AP_Filesystem::rename(const char *oldpath, const char *newpath)196{197const Backend &oldbackend = backend_by_path(oldpath);198199// Don't need the backend again, but we also need to remove the backend pre-fix from the new path.200const Backend &newbackend = backend_by_path(newpath);201202// Don't try and rename between backends.203if (&oldbackend != &newbackend) {204return -1;205}206207return oldbackend.fs.rename(oldpath, newpath);208}209210AP_Filesystem::DirHandle *AP_Filesystem::opendir(const char *pathname)211{212// support reading a list of "@" filesystems (e.g. @SYS) in213// listing of root directory. Note that backend_by_path modifies214// its parameter.215if (strlen(pathname) == 0 ||216(strlen(pathname) == 1 && pathname[0] == '/')) {217virtual_dirent.backend_ofs = 0;218virtual_dirent.d_off = 0;219#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE220virtual_dirent.de.d_type = DT_DIR;221#endif222} else {223virtual_dirent.backend_ofs = 255;224}225226const Backend &backend = backend_by_path(pathname);227DirHandle *h = NEW_NOTHROW DirHandle;228if (!h) {229return nullptr;230}231h->dir = backend.fs.opendir(pathname);232if (h->dir == nullptr) {233delete h;234return nullptr;235}236h->fs_index = BACKEND_IDX(backend);237238return h;239}240241struct dirent *AP_Filesystem::readdir(DirHandle *dirp)242{243if (!dirp) {244return nullptr;245}246const Backend &backend = backends[dirp->fs_index];247struct dirent * ret = backend.fs.readdir(dirp->dir);248if (ret != nullptr) {249return ret;250}251252// virtual directory entries in the root directory (e.g. @SYS, @MISSION)253for (; ret == nullptr && virtual_dirent.backend_ofs < ARRAY_SIZE(AP_Filesystem::backends); virtual_dirent.backend_ofs++) {254const char *prefix = backends[virtual_dirent.backend_ofs].prefix;255if (prefix == nullptr) {256continue;257}258if (prefix[0] != '@') {259continue;260}261262// only return @ entries in root if we can successfully opendir them:263auto *d = backends[virtual_dirent.backend_ofs].fs.opendir("");264if (d == nullptr) {265continue;266}267backends[virtual_dirent.backend_ofs].fs.closedir(d);268269// found a virtual directory we haven't returned yet270strncpy_noterm(virtual_dirent.de.d_name, prefix, sizeof(virtual_dirent.de.d_name));271virtual_dirent.d_off++;272ret = &virtual_dirent.de;273}274return ret;275}276277int AP_Filesystem::closedir(DirHandle *dirp)278{279if (!dirp) {280return -1;281}282const Backend &backend = backends[dirp->fs_index];283int ret = backend.fs.closedir(dirp->dir);284delete dirp;285return ret;286}287288// return number of bytes that should be written before fsync for optimal289// streaming performance/robustness. if zero, any number can be written.290uint32_t AP_Filesystem::bytes_until_fsync(int fd)291{292const Backend &backend = backend_by_fd(fd);293return backend.fs.bytes_until_fsync(fd);294}295296// return free disk space in bytes297int64_t AP_Filesystem::disk_free(const char *path)298{299const Backend &backend = backend_by_path(path);300return backend.fs.disk_free(path);301}302303// return total disk space in bytes304int64_t AP_Filesystem::disk_space(const char *path)305{306const Backend &backend = backend_by_path(path);307return backend.fs.disk_space(path);308}309310311/*312set mtime on a file313*/314bool AP_Filesystem::set_mtime(const char *filename, const uint32_t mtime_sec)315{316const Backend &backend = backend_by_path(filename);317return backend.fs.set_mtime(filename, mtime_sec);318}319320// if filesystem is not running then try a remount321bool AP_Filesystem::retry_mount(void)322{323return LOCAL_BACKEND.fs.retry_mount();324}325326// unmount filesystem for reboot327void AP_Filesystem::unmount(void)328{329return LOCAL_BACKEND.fs.unmount();330}331332/*333Load a file's contents into memory. Returned object must be `delete`d to free334the data. The data is guaranteed to be null-terminated such that it can be335treated as a string.336*/337FileData *AP_Filesystem::load_file(const char *filename)338{339const Backend &backend = backend_by_path(filename);340return backend.fs.load_file(filename);341}342343// returns null-terminated string; cr or lf terminates line344bool AP_Filesystem::fgets(char *buf, uint8_t buflen, int fd)345{346const Backend &backend = backend_by_fd(fd);347348// we will need to seek back to the right location at the end349auto offset_start = backend.fs.lseek(fd, 0, SEEK_CUR);350if (offset_start < 0) {351return false;352}353354auto n = backend.fs.read(fd, buf, buflen);355if (n <= 0) {356return false;357}358359uint8_t i = 0;360for (; i < n; i++) {361if (buf[i] == '\r' || buf[i] == '\n') {362break;363}364}365buf[i] = '\0';366367// get back to the right offset368if (backend.fs.lseek(fd, offset_start+i+1, SEEK_SET) != offset_start+i+1) {369// we need to fail if we can't seek back or the caller may loop or get corrupt data370return false;371}372373return true;374}375376// run crc32 over file with given name, returns true if successful377bool AP_Filesystem::crc32(const char *fname, uint32_t& checksum)378{379// Ensure value is initialized380checksum = 0;381382// Open file in readonly mode383int fd = open(fname, O_RDONLY);384if (fd == -1) {385return false;386}387388// Buffer to store data temporarily389const ssize_t buff_len = 64;390uint8_t buf[buff_len];391392// Read into buffer and run crc393ssize_t read_size;394do {395read_size = read(fd, buf, buff_len);396if (read_size == -1) {397// Read error, note that we have changed the checksum value in this case398close(fd);399return false;400}401checksum = crc_crc32(checksum, buf, MIN(read_size, buff_len));402} while (read_size > 0);403404close(fd);405406return true;407}408409410#if AP_FILESYSTEM_FORMAT_ENABLED411// format filesystem412bool AP_Filesystem::format(void)413{414if (hal.util->get_soft_armed()) {415return false;416}417return LOCAL_BACKEND.fs.format();418}419AP_Filesystem_Backend::FormatStatus AP_Filesystem::get_format_status(void) const420{421return LOCAL_BACKEND.fs.get_format_status();422}423#endif424425/*426stat wrapper for scripting427*/428bool AP_Filesystem::stat(const char *pathname, stat_t &stbuf)429{430struct stat st;431if (fs.stat(pathname, &st) != 0) {432return false;433}434stbuf.size = st.st_size;435stbuf.mode = st.st_mode;436// these wrap in 2038437stbuf.atime = st.st_atime;438stbuf.ctime = st.st_ctime;439stbuf.mtime = st.st_mtime;440return true;441}442443// get_singleton for scripting444AP_Filesystem *AP_Filesystem::get_singleton(void)445{446return &fs;447}448449namespace AP450{451AP_Filesystem &FS()452{453return fs;454}455}456457#endif // AP_FILESYSTEM_FILE_READING_ENABLED458459460