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_ROMFS.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*/14/*15ArduPilot filesystem interface for ROMFS16*/1718#include "AP_Filesystem_config.h"1920#if AP_FILESYSTEM_ROMFS_ENABLED2122#include "AP_Filesystem.h"23#include "AP_Filesystem_ROMFS.h"24#include <AP_HAL/AP_HAL.h>25#include <AP_Math/AP_Math.h>26#include <AP_ROMFS/AP_ROMFS.h>2728int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_paths)29{30if ((flags & O_ACCMODE) != O_RDONLY) {31errno = EROFS;32return -1;33}34uint8_t idx;35for (idx=0; idx<max_open_file; idx++) {36if (file[idx].data == nullptr) {37break;38}39}40if (idx == max_open_file) {41errno = ENFILE;42return -1;43}44if (file[idx].data != nullptr) {45errno = EBUSY;46return -1;47}48file[idx].data = AP_ROMFS::find_decompress(fname, file[idx].size);49if (file[idx].data == nullptr) {50errno = ENOENT;51return -1;52}53file[idx].ofs = 0;54return idx;55}5657int AP_Filesystem_ROMFS::close(int fd)58{59if (fd < 0 || fd >= max_open_file || file[fd].data == nullptr) {60errno = EBADF;61return -1;62}63AP_ROMFS::free(file[fd].data);64file[fd].data = nullptr;65return 0;66}6768int32_t AP_Filesystem_ROMFS::read(int fd, void *buf, uint32_t count)69{70if (fd < 0 || fd >= max_open_file || file[fd].data == nullptr) {71errno = EBADF;72return -1;73}74count = MIN(file[fd].size - file[fd].ofs, count);75if (count == 0) {76return 0;77}78memcpy(buf, &file[fd].data[file[fd].ofs], count);79file[fd].ofs += count;80return count;81}8283int32_t AP_Filesystem_ROMFS::write(int fd, const void *buf, uint32_t count)84{85errno = EROFS;86return -1;87}8889int AP_Filesystem_ROMFS::fsync(int fd)90{91return 0;92}9394int32_t AP_Filesystem_ROMFS::lseek(int fd, int32_t offset, int seek_from)95{96if (fd < 0 || fd >= max_open_file || file[fd].data == nullptr) {97errno = EBADF;98return -1;99}100switch (seek_from) {101case SEEK_SET:102if (offset < 0) {103errno = EINVAL;104return -1;105}106file[fd].ofs = MIN(file[fd].size, (uint32_t)offset);107break;108case SEEK_CUR:109file[fd].ofs = MIN(file[fd].size, offset+file[fd].ofs);110break;111case SEEK_END:112file[fd].ofs = file[fd].size;113break;114}115return file[fd].ofs;116}117118int AP_Filesystem_ROMFS::stat(const char *name, struct stat *stbuf)119{120uint32_t size;121if (!AP_ROMFS::find_size(name, size)) {122errno = ENOENT;123return -1;124}125memset(stbuf, 0, sizeof(*stbuf));126stbuf->st_size = size;127return 0;128}129130int AP_Filesystem_ROMFS::unlink(const char *pathname)131{132errno = EROFS;133return -1;134}135136int AP_Filesystem_ROMFS::mkdir(const char *pathname)137{138errno = EROFS;139return -1;140}141142void *AP_Filesystem_ROMFS::opendir(const char *pathname)143{144uint8_t idx;145for (idx=0; idx<max_open_dir; idx++) {146if (dir[idx].path == nullptr) {147break;148}149}150if (idx == max_open_dir) {151errno = ENFILE;152return nullptr;153}154dir[idx].ofs = 0;155dir[idx].path = strdup(pathname);156if (!dir[idx].path) {157return nullptr;158}159160// Take a sneak peek and reset161const char *name = AP_ROMFS::dir_list(dir[idx].path, dir[idx].ofs);162dir[idx].ofs = 0;163if (!name) {164// Directory does not exist165return nullptr;166}167168return (void*)&dir[idx];169}170171struct dirent *AP_Filesystem_ROMFS::readdir(void *dirp)172{173uint32_t idx = ((rdir*)dirp) - &dir[0];174if (idx >= max_open_dir) {175errno = EBADF;176return nullptr;177}178const char *name = AP_ROMFS::dir_list(dir[idx].path, dir[idx].ofs);179if (!name) {180return nullptr;181}182const uint32_t plen = strlen(dir[idx].path);183if (plen > 0) {184// Offset to get just file/directory name185name += plen + 1;186}187188// Copy full name189strncpy(dir[idx].de.d_name, name, sizeof(dir[idx].de.d_name));190191const char* slash = strchr(name, '/');192if (slash == nullptr) {193// File194#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE195dir[idx].de.d_type = DT_REG;196#endif197} else {198// Directory199#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE200dir[idx].de.d_type = DT_DIR;201#endif202203// Add null termination after directory name204const size_t index = slash - name;205dir[idx].de.d_name[index] = 0;206}207208return &dir[idx].de;209}210211int AP_Filesystem_ROMFS::closedir(void *dirp)212{213uint32_t idx = ((rdir *)dirp) - &dir[0];214if (idx >= max_open_dir) {215errno = EBADF;216return -1;217}218free(dir[idx].path);219dir[idx].path = nullptr;220return 0;221}222223// return free disk space in bytes224int64_t AP_Filesystem_ROMFS::disk_free(const char *path)225{226return 0;227}228229// return total disk space in bytes230int64_t AP_Filesystem_ROMFS::disk_space(const char *path)231{232return 0;233}234235/*236set mtime on a file237*/238bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_sec)239{240return false;241}242243/*244Load a file's contents into memory. Returned object must be `delete`d to free245the data. The data is guaranteed to be null-terminated such that it can be246treated as a string. Overridden in ROMFS to avoid taking twice the memory.247*/248FileData *AP_Filesystem_ROMFS::load_file(const char *filename)249{250FileData *fd = NEW_NOTHROW FileData(this);251if (!fd) {252return nullptr;253}254// AP_ROMFS adds the guaranteed termination so we don't have to.255fd->data = AP_ROMFS::find_decompress(filename, fd->length);256if (fd->data == nullptr) {257delete fd;258return nullptr;259}260return fd;261}262263// unload data from load_file()264void AP_Filesystem_ROMFS::unload_file(FileData *fd)265{266AP_ROMFS::free(fd->data);267}268269#endif // AP_FILESYSTEM_ROMFS_ENABLED270271272