Path: blob/master/libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp
9353 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 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}3435WITH_SEMAPHORE(record_sem); // search for free file record36uint8_t idx;37for (idx=0; idx<max_open_file; idx++) {38if (file[idx].data == nullptr) {39break;40}41}42if (idx == max_open_file) {43errno = ENFILE;44return -1;45}46file[idx].data = AP_ROMFS::find_decompress(fname, file[idx].size);47if (file[idx].data == nullptr) {48errno = ENOENT;49return -1;50}51file[idx].ofs = 0;52return idx;53}5455int AP_Filesystem_ROMFS::close(int fd)56{57if (fd < 0 || fd >= max_open_file || file[fd].data == nullptr) {58errno = EBADF;59return -1;60}6162WITH_SEMAPHORE(record_sem); // release file record63AP_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{144WITH_SEMAPHORE(record_sem); // search for free directory record145uint8_t idx;146for (idx=0; idx<max_open_dir; idx++) {147if (dir[idx].path == nullptr) {148break;149}150}151if (idx == max_open_dir) {152errno = ENFILE;153return nullptr;154}155dir[idx].ofs = 0;156dir[idx].path = strdup(pathname);157if (!dir[idx].path) {158return nullptr;159}160161// Take a sneak peek and reset162const char *name = AP_ROMFS::dir_list(dir[idx].path, dir[idx].ofs);163dir[idx].ofs = 0;164if (!name) {165// Directory does not exist166return nullptr;167}168169return (void*)&dir[idx];170}171172struct dirent *AP_Filesystem_ROMFS::readdir(void *dirp)173{174uint32_t idx = ((rdir*)dirp) - &dir[0];175if (idx >= max_open_dir) {176errno = EBADF;177return nullptr;178}179const char *name = AP_ROMFS::dir_list(dir[idx].path, dir[idx].ofs);180if (!name) {181return nullptr;182}183const uint32_t plen = strlen(dir[idx].path);184if (plen > 0) {185// Offset to get just file/directory name186name += plen + 1;187}188189// Copy full name190strncpy(dir[idx].de.d_name, name, sizeof(dir[idx].de.d_name));191192const char* slash = strchr(name, '/');193if (slash == nullptr) {194// File195#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE196dir[idx].de.d_type = DT_REG;197#endif198} else {199// Directory200#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE201dir[idx].de.d_type = DT_DIR;202#endif203204// Add null termination after directory name205const size_t index = slash - name;206dir[idx].de.d_name[index] = 0;207}208209return &dir[idx].de;210}211212int AP_Filesystem_ROMFS::closedir(void *dirp)213{214uint32_t idx = ((rdir *)dirp) - &dir[0];215if (idx >= max_open_dir) {216errno = EBADF;217return -1;218}219220WITH_SEMAPHORE(record_sem); // release directory record221free(dir[idx].path);222dir[idx].path = nullptr;223return 0;224}225226// return free disk space in bytes227int64_t AP_Filesystem_ROMFS::disk_free(const char *path)228{229return 0;230}231232// return total disk space in bytes233int64_t AP_Filesystem_ROMFS::disk_space(const char *path)234{235return 0;236}237238/*239set mtime on a file240*/241bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_sec)242{243return false;244}245246/*247Load a file's contents into memory. Returned object must be `delete`d to free248the data. The data is guaranteed to be null-terminated such that it can be249treated as a string. Overridden in ROMFS to avoid taking twice the memory.250*/251FileData *AP_Filesystem_ROMFS::load_file(const char *filename)252{253FileData *fd = NEW_NOTHROW FileData(this);254if (!fd) {255return nullptr;256}257// AP_ROMFS adds the guaranteed termination so we don't have to.258fd->data = AP_ROMFS::find_decompress(filename, fd->length);259if (fd->data == nullptr) {260delete fd;261return nullptr;262}263return fd;264}265266// unload data from load_file()267void AP_Filesystem_ROMFS::unload_file(FileData *fd)268{269AP_ROMFS::free(fd->data);270}271272#endif // AP_FILESYSTEM_ROMFS_ENABLED273274275