Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Filesystem/AP_Filesystem.cpp
Views: 1798
/*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_POSIX_ENABLED35#include "AP_Filesystem_posix.h"36static AP_Filesystem_Posix fs_local;37#else38static AP_Filesystem_Backend fs_local;39int errno;40#endif4142#if AP_FILESYSTEM_ROMFS_ENABLED43#include "AP_Filesystem_ROMFS.h"44static AP_Filesystem_ROMFS fs_romfs;45#endif4647#if AP_FILESYSTEM_PARAM_ENABLED48#include "AP_Filesystem_Param.h"49static AP_Filesystem_Param fs_param;50#endif5152#if AP_FILESYSTEM_SYS_ENABLED53#include "AP_Filesystem_Sys.h"54static AP_Filesystem_Sys fs_sys;55#endif5657#if AP_FILESYSTEM_MISSION_ENABLED58#include "AP_Filesystem_Mission.h"59static AP_Filesystem_Mission fs_mission;60#endif6162/*63mapping from filesystem prefix to backend64*/65const AP_Filesystem::Backend AP_Filesystem::backends[] = {66{ nullptr, fs_local },67#if AP_FILESYSTEM_ROMFS_ENABLED68{ "@ROMFS", fs_romfs },69#endif70#if AP_FILESYSTEM_PARAM_ENABLED71{ "@PARAM", fs_param },72#endif73#if AP_FILESYSTEM_SYS_ENABLED74{ "@SYS", fs_sys },75#endif76#if AP_FILESYSTEM_MISSION_ENABLED77{ "@MISSION", fs_mission },78#endif79};8081extern const AP_HAL::HAL& hal;8283#define MAX_FD_PER_BACKEND 256U84#define NUM_BACKENDS ARRAY_SIZE(backends)85#define LOCAL_BACKEND backends[0]86#define BACKEND_IDX(backend) (&(backend) - &backends[0])8788/*89find backend by path90*/91const AP_Filesystem::Backend &AP_Filesystem::backend_by_path(const char *&path) const92{93// ignore leading slashes:94const char *path_with_no_leading_slash = path;95if (path_with_no_leading_slash[0] == '/') {96path_with_no_leading_slash = &path_with_no_leading_slash[1];97}98for (uint8_t i=1; i<NUM_BACKENDS; i++) {99const uint8_t plen = strlen(backends[i].prefix);100if (strncmp(path_with_no_leading_slash, backends[i].prefix, plen) == 0) {101path = path_with_no_leading_slash;102path += plen;103if (strlen(path) > 0 && path[0] == '/') {104path++;105}106return backends[i];107}108}109// default to local filesystem110return LOCAL_BACKEND;111}112113/*114return backend by file descriptor115*/116const AP_Filesystem::Backend &AP_Filesystem::backend_by_fd(int &fd) const117{118if (fd < 0 || uint32_t(fd) >= NUM_BACKENDS*MAX_FD_PER_BACKEND) {119return LOCAL_BACKEND;120}121const uint8_t idx = uint32_t(fd) / MAX_FD_PER_BACKEND;122fd -= idx * MAX_FD_PER_BACKEND;123return backends[idx];124}125126int AP_Filesystem::open(const char *fname, int flags, bool allow_absolute_paths)127{128const Backend &backend = backend_by_path(fname);129int fd = backend.fs.open(fname, flags, allow_absolute_paths);130if (fd < 0) {131return -1;132}133if (uint32_t(fd) >= MAX_FD_PER_BACKEND) {134backend.fs.close(fd);135errno = ERANGE;136return -1;137}138// offset fd so we can recognise the backend139const uint8_t idx = (&backend - &backends[0]);140fd += idx * MAX_FD_PER_BACKEND;141return fd;142}143144int AP_Filesystem::close(int fd)145{146const Backend &backend = backend_by_fd(fd);147return backend.fs.close(fd);148}149150int32_t AP_Filesystem::read(int fd, void *buf, uint32_t count)151{152const Backend &backend = backend_by_fd(fd);153return backend.fs.read(fd, buf, count);154}155156int32_t AP_Filesystem::write(int fd, const void *buf, uint32_t count)157{158const Backend &backend = backend_by_fd(fd);159return backend.fs.write(fd, buf, count);160}161162int AP_Filesystem::fsync(int fd)163{164const Backend &backend = backend_by_fd(fd);165return backend.fs.fsync(fd);166}167168int32_t AP_Filesystem::lseek(int fd, int32_t offset, int seek_from)169{170const Backend &backend = backend_by_fd(fd);171return backend.fs.lseek(fd, offset, seek_from);172}173174int AP_Filesystem::stat(const char *pathname, struct stat *stbuf)175{176const Backend &backend = backend_by_path(pathname);177return backend.fs.stat(pathname, stbuf);178}179180int AP_Filesystem::unlink(const char *pathname)181{182const Backend &backend = backend_by_path(pathname);183return backend.fs.unlink(pathname);184}185186int AP_Filesystem::mkdir(const char *pathname)187{188const Backend &backend = backend_by_path(pathname);189return backend.fs.mkdir(pathname);190}191192int AP_Filesystem::rename(const char *oldpath, const char *newpath)193{194const Backend &oldbackend = backend_by_path(oldpath);195196// Don't need the backend again, but we also need to remove the backend pre-fix from the new path.197const Backend &newbackend = backend_by_path(newpath);198199// Don't try and rename between backends.200if (&oldbackend != &newbackend) {201return -1;202}203204return oldbackend.fs.rename(oldpath, newpath);205}206207AP_Filesystem::DirHandle *AP_Filesystem::opendir(const char *pathname)208{209// support reading a list of "@" filesystems (e.g. @SYS) in210// listing of root directory. Note that backend_by_path modifies211// its parameter.212if (strlen(pathname) == 0 ||213(strlen(pathname) == 1 && pathname[0] == '/')) {214virtual_dirent.backend_ofs = 0;215virtual_dirent.d_off = 0;216#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE217virtual_dirent.de.d_type = DT_DIR;218#endif219} else {220virtual_dirent.backend_ofs = 255;221}222223const Backend &backend = backend_by_path(pathname);224DirHandle *h = NEW_NOTHROW DirHandle;225if (!h) {226return nullptr;227}228h->dir = backend.fs.opendir(pathname);229if (h->dir == nullptr) {230delete h;231return nullptr;232}233h->fs_index = BACKEND_IDX(backend);234235return h;236}237238struct dirent *AP_Filesystem::readdir(DirHandle *dirp)239{240if (!dirp) {241return nullptr;242}243const Backend &backend = backends[dirp->fs_index];244struct dirent * ret = backend.fs.readdir(dirp->dir);245if (ret != nullptr) {246return ret;247}248249// virtual directory entries in the root directory (e.g. @SYS, @MISSION)250for (; ret == nullptr && virtual_dirent.backend_ofs < ARRAY_SIZE(AP_Filesystem::backends); virtual_dirent.backend_ofs++) {251const char *prefix = backends[virtual_dirent.backend_ofs].prefix;252if (prefix == nullptr) {253continue;254}255if (prefix[0] != '@') {256continue;257}258259// only return @ entries in root if we can successfully opendir them:260auto *d = backends[virtual_dirent.backend_ofs].fs.opendir("");261if (d == nullptr) {262continue;263}264backends[virtual_dirent.backend_ofs].fs.closedir(d);265266// found a virtual directory we haven't returned yet267strncpy_noterm(virtual_dirent.de.d_name, prefix, sizeof(virtual_dirent.de.d_name));268virtual_dirent.d_off++;269ret = &virtual_dirent.de;270}271return ret;272}273274int AP_Filesystem::closedir(DirHandle *dirp)275{276if (!dirp) {277return -1;278}279const Backend &backend = backends[dirp->fs_index];280int ret = backend.fs.closedir(dirp->dir);281delete dirp;282return ret;283}284285// return free disk space in bytes286int64_t AP_Filesystem::disk_free(const char *path)287{288const Backend &backend = backend_by_path(path);289return backend.fs.disk_free(path);290}291292// return total disk space in bytes293int64_t AP_Filesystem::disk_space(const char *path)294{295const Backend &backend = backend_by_path(path);296return backend.fs.disk_space(path);297}298299300/*301set mtime on a file302*/303bool AP_Filesystem::set_mtime(const char *filename, const uint32_t mtime_sec)304{305const Backend &backend = backend_by_path(filename);306return backend.fs.set_mtime(filename, mtime_sec);307}308309// if filesystem is not running then try a remount310bool AP_Filesystem::retry_mount(void)311{312return LOCAL_BACKEND.fs.retry_mount();313}314315// unmount filesystem for reboot316void AP_Filesystem::unmount(void)317{318return LOCAL_BACKEND.fs.unmount();319}320321/*322Load a file's contents into memory. Returned object must be `delete`d to free323the data. The data is guaranteed to be null-terminated such that it can be324treated as a string.325*/326FileData *AP_Filesystem::load_file(const char *filename)327{328const Backend &backend = backend_by_path(filename);329return backend.fs.load_file(filename);330}331332// returns null-terminated string; cr or lf terminates line333bool AP_Filesystem::fgets(char *buf, uint8_t buflen, int fd)334{335const Backend &backend = backend_by_fd(fd);336337// we will need to seek back to the right location at the end338auto offset_start = backend.fs.lseek(fd, 0, SEEK_CUR);339if (offset_start < 0) {340return false;341}342343auto n = backend.fs.read(fd, buf, buflen);344if (n <= 0) {345return false;346}347348uint8_t i = 0;349for (; i < n; i++) {350if (buf[i] == '\r' || buf[i] == '\n') {351break;352}353}354buf[i] = '\0';355356// get back to the right offset357if (backend.fs.lseek(fd, offset_start+i+1, SEEK_SET) != offset_start+i+1) {358// we need to fail if we can't seek back or the caller may loop or get corrupt data359return false;360}361362return true;363}364365// run crc32 over file with given name, returns true if successful366bool AP_Filesystem::crc32(const char *fname, uint32_t& checksum)367{368// Ensure value is initialized369checksum = 0;370371// Open file in readonly mode372int fd = open(fname, O_RDONLY);373if (fd == -1) {374return false;375}376377// Buffer to store data temporarily378const ssize_t buff_len = 64;379uint8_t buf[buff_len];380381// Read into buffer and run crc382ssize_t read_size;383do {384read_size = read(fd, buf, buff_len);385if (read_size == -1) {386// Read error, note that we have changed the checksum value in this case387close(fd);388return false;389}390checksum = crc_crc32(checksum, buf, MIN(read_size, buff_len));391} while (read_size > 0);392393close(fd);394395return true;396}397398399#if AP_FILESYSTEM_FORMAT_ENABLED400// format filesystem401bool AP_Filesystem::format(void)402{403if (hal.util->get_soft_armed()) {404return false;405}406return LOCAL_BACKEND.fs.format();407}408AP_Filesystem_Backend::FormatStatus AP_Filesystem::get_format_status(void) const409{410return LOCAL_BACKEND.fs.get_format_status();411}412#endif413414/*415stat wrapper for scripting416*/417bool AP_Filesystem::stat(const char *pathname, stat_t &stbuf)418{419struct stat st;420if (fs.stat(pathname, &st) != 0) {421return false;422}423stbuf.size = st.st_size;424stbuf.mode = st.st_mode;425// these wrap in 2038426stbuf.atime = st.st_atime;427stbuf.ctime = st.st_ctime;428stbuf.mtime = st.st_mtime;429return true;430}431432// get_singleton for scripting433AP_Filesystem *AP_Filesystem::get_singleton(void)434{435return &fs;436}437438namespace AP439{440AP_Filesystem &FS()441{442return fs;443}444}445446#endif // AP_FILESYSTEM_FILE_READING_ENABLED447448449