AP_Filesystem: support QURT with posix filesystem

some features disabled
This commit is contained in:
Andrew Tridgell 2024-07-06 09:17:46 +10:00
parent 3a6024e8ab
commit f8ce4183b8
8 changed files with 113 additions and 13 deletions

View File

@ -16,6 +16,9 @@
#include "AP_Filesystem.h"
#include "AP_Filesystem_config.h"
#if AP_FILESYSTEM_FILE_READING_ENABLED
#include <AP_HAL/HAL.h>
#include <AP_HAL/Util.h>
#include <AP_Math/AP_Math.h>
@ -202,7 +205,9 @@ AP_Filesystem::DirHandle *AP_Filesystem::opendir(const char *pathname)
(strlen(pathname) == 1 && pathname[0] == '/')) {
virtual_dirent.backend_ofs = 0;
virtual_dirent.d_off = 0;
#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE
virtual_dirent.de.d_type = DT_DIR;
#endif
} else {
virtual_dirent.backend_ofs = 255;
}
@ -430,3 +435,4 @@ AP_Filesystem &FS()
}
}
#endif // AP_FILESYSTEM_FILE_READING_ENABLED

View File

@ -54,7 +54,7 @@ struct dirent {
#define AP_FILESYSTEM_FORMAT_ENABLED 1
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_QURT
#include "AP_Filesystem_posix.h"
#endif

View File

@ -192,11 +192,14 @@ struct dirent *AP_Filesystem_ROMFS::readdir(void *dirp)
const char* slash = strchr(name, '/');
if (slash == nullptr) {
// File
#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE
dir[idx].de.d_type = DT_REG;
#endif
} else {
// Directory
#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE
dir[idx].de.d_type = DT_DIR;
#endif
// Add null termination after directory name
const size_t index = slash - name;

View File

@ -244,7 +244,9 @@ struct dirent *AP_Filesystem_Sys::readdir(void *dirp)
// we have reached end of list
return nullptr;
}
#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE
dtracker->curr_file.d_type = DT_REG;
#endif
size_t max_length = ARRAY_SIZE(dtracker->curr_file.d_name);
strncpy_noterm(dtracker->curr_file.d_name, sysfs_file_list[dtracker->file_offset].name, max_length);
dtracker->file_offset++;

View File

@ -23,7 +23,7 @@
#endif
#ifndef AP_FILESYSTEM_POSIX_ENABLED
#define AP_FILESYSTEM_POSIX_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX)
#define AP_FILESYSTEM_POSIX_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_QURT)
#endif
#ifndef AP_FILESYSTEM_ROMFS_ENABLED
@ -34,6 +34,11 @@
#define AP_FILESYSTEM_SYS_ENABLED 1
#endif
#ifndef AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC
// this requires AP_FILESYSTEM_POSIX_MAP_FILENAME_BASEDIR
#define AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC 0
#endif
// AP_FILESYSTEM_FILE_WRITING_ENABLED is true if you could expect to
// be able to open and write a non-virtual file. Notably this
// excludes virtual files like SYSFS, and the magic param/mission
@ -47,7 +52,7 @@
// be able to open and read a non-virtual file. Notably this excludes
// virtual files like SYSFS, and the magic param/mission upload targets.
#ifndef AP_FILESYSTEM_FILE_READING_ENABLED
#define AP_FILESYSTEM_FILE_READING_ENABLED (AP_FILESYSTEM_FILE_WRITING_ENABLED || AP_FILESYSTEM_ROMFS_ENABLED)
#define AP_FILESYSTEM_FILE_READING_ENABLED (AP_FILESYSTEM_FILE_WRITING_ENABLED || AP_FILESYSTEM_ROMFS_ENABLED || AP_FILESYSTEM_SYS_ENABLED || AP_FILESYSTEM_PARAM_ENABLED)
#endif
#ifndef AP_FILESYSTEM_SYS_FLASH_ENABLED

View File

@ -26,18 +26,29 @@
#if defined(__APPLE__)
#include <sys/mount.h>
#else
#elif CONFIG_HAL_BOARD != HAL_BOARD_QURT
#include <sys/vfs.h>
#endif
#if AP_FILESYSTEM_POSIX_HAVE_UTIME
#include <utime.h>
#endif
extern const AP_HAL::HAL& hal;
/*
map a filename for SITL so operations are relative to the current directory
map a filename so operations are relative to the current directory if needed
*/
static const char *map_filename(const char *fname)
{
#if AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC
// this system needs to add a prefix to the filename, which means
// memory allocation. This is needed for QURT which lacks chdir()
char *fname2 = nullptr;
asprintf(&fname2, "%s/%s", AP_FILESYSTEM_POSIX_MAP_FILENAME_BASEDIR, fname);
return fname2;
#else
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL && !APM_BUILD_TYPE(APM_BUILD_Replay)
// on SITL only allow paths under subdirectory. Users can still
// escape with .. if they want to
@ -50,6 +61,14 @@ static const char *map_filename(const char *fname)
#endif
// on Linux allow original name
return fname;
#endif // AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC
}
static void map_filename_free(const char *fname)
{
#if AP_FILESYSTEM_POSIX_MAP_FILENAME_ALLOC
::free(const_cast<char*>(fname));
#endif
}
int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_paths)
@ -62,10 +81,18 @@ int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_
if (::stat(fname, &st) == 0 &&
((st.st_mode & S_IFMT) != S_IFREG && (st.st_mode & S_IFMT) != S_IFLNK)) {
// only allow links and files
if (!allow_absolute_paths) {
map_filename_free(fname);
}
return -1;
}
// we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage
return ::open(fname, flags | O_CLOEXEC, 0644);
auto ret = ::open(fname, flags | O_CLOEXEC, 0644);
if (!allow_absolute_paths) {
map_filename_free(fname);
}
return ret;
}
int AP_Filesystem_Posix::close(int fd)
@ -88,8 +115,14 @@ int32_t AP_Filesystem_Posix::write(int fd, const void *buf, uint32_t count)
int AP_Filesystem_Posix::fsync(int fd)
{
#if AP_FILESYSTEM_POSIX_HAVE_FSYNC
FS_CHECK_ALLOWED(-1);
return ::fsync(fd);
#else
// we have to pass success here as otherwise it is assumed to be
// failed IO and the caller may close the fd and give up
return 0;
#endif
}
int32_t AP_Filesystem_Posix::lseek(int fd, int32_t offset, int seek_from)
@ -102,7 +135,9 @@ int AP_Filesystem_Posix::stat(const char *pathname, struct stat *stbuf)
{
FS_CHECK_ALLOWED(-1);
pathname = map_filename(pathname);
return ::stat(pathname, stbuf);
auto ret = ::stat(pathname, stbuf);
map_filename_free(pathname);
return ret;
}
int AP_Filesystem_Posix::unlink(const char *pathname)
@ -111,10 +146,11 @@ int AP_Filesystem_Posix::unlink(const char *pathname)
pathname = map_filename(pathname);
// we match the FATFS interface and use unlink
// for both files and directories
int ret = ::rmdir(pathname);
int ret = ::rmdir(const_cast<char*>(pathname));
if (ret == -1) {
ret = ::unlink(pathname);
}
map_filename_free(pathname);
return ret;
}
@ -122,14 +158,18 @@ int AP_Filesystem_Posix::mkdir(const char *pathname)
{
FS_CHECK_ALLOWED(-1);
pathname = map_filename(pathname);
return ::mkdir(pathname, 0775);
auto ret = ::mkdir(const_cast<char*>(pathname), 0775);
map_filename_free(pathname);
return ret;
}
void *AP_Filesystem_Posix::opendir(const char *pathname)
{
FS_CHECK_ALLOWED(nullptr);
pathname = map_filename(pathname);
return (void*)::opendir(pathname);
auto *ret = (void*)::opendir(pathname);
map_filename_free(pathname);
return ret;
}
struct dirent *AP_Filesystem_Posix::readdir(void *dirp)
@ -149,31 +189,46 @@ int AP_Filesystem_Posix::rename(const char *oldpath, const char *newpath)
FS_CHECK_ALLOWED(-1);
oldpath = map_filename(oldpath);
newpath = map_filename(newpath);
return ::rename(oldpath, newpath);
auto ret = ::rename(oldpath, newpath);
map_filename_free(oldpath);
map_filename_free(newpath);
return ret;
}
// return free disk space in bytes
int64_t AP_Filesystem_Posix::disk_free(const char *path)
{
#if AP_FILESYSTEM_POSIX_HAVE_STATFS
FS_CHECK_ALLOWED(-1);
path = map_filename(path);
struct statfs stats;
if (::statfs(path, &stats) < 0) {
map_filename_free(path);
return -1;
}
map_filename_free(path);
return (((int64_t)stats.f_bavail) * stats.f_bsize);
#else
return -1;
#endif
}
// return total disk space in bytes
int64_t AP_Filesystem_Posix::disk_space(const char *path)
{
#if AP_FILESYSTEM_POSIX_HAVE_STATFS
FS_CHECK_ALLOWED(-1);
path = map_filename(path);
struct statfs stats;
if (::statfs(path, &stats) < 0) {
map_filename_free(path);
return -1;
}
map_filename_free(path);
return (((int64_t)stats.f_blocks) * stats.f_bsize);
#else
return -1;
#endif
}
@ -182,13 +237,19 @@ int64_t AP_Filesystem_Posix::disk_space(const char *path)
*/
bool AP_Filesystem_Posix::set_mtime(const char *filename, const uint32_t mtime_sec)
{
#if AP_FILESYSTEM_POSIX_HAVE_UTIME
FS_CHECK_ALLOWED(false);
filename = map_filename(filename);
struct utimbuf times {};
times.actime = mtime_sec;
times.modtime = mtime_sec;
return utime(filename, &times) == 0;
auto ret = utime(filename, &times) == 0;
map_filename_free(filename);
return ret;
#else
return false;
#endif
}
#endif // AP_FILESYSTEM_POSIX_ENABLED

View File

@ -29,6 +29,22 @@
#include <errno.h>
#include "AP_Filesystem_backend.h"
#ifndef AP_FILESYSTEM_POSIX_HAVE_UTIME
#define AP_FILESYSTEM_POSIX_HAVE_UTIME 1
#endif
#ifndef AP_FILESYSTEM_POSIX_HAVE_FSYNC
#define AP_FILESYSTEM_POSIX_HAVE_FSYNC 1
#endif
#ifndef AP_FILESYSTEM_POSIX_HAVE_STATFS
#define AP_FILESYSTEM_POSIX_HAVE_STATFS 1
#endif
#ifndef O_CLOEXEC
#define O_CLOEXEC 0
#endif
class AP_Filesystem_Posix : public AP_Filesystem_Backend
{
public:

View File

@ -78,6 +78,12 @@ char *tmpnam(char s[L_tmpnam]);
#endif
#define FILE APFS_FILE
#ifndef __cplusplus
/*
only redefine posix functions for C code (eg. lua).
for C++ use the AP_Filsystem APIs
*/
#define fopen(p,m) apfs_fopen(p,m)
#define fprintf(stream, format, args...) apfs_fprintf(stream, format, ##args)
#define fflush(s) apfs_fflush(s)
@ -101,6 +107,7 @@ char *tmpnam(char s[L_tmpnam]);
#define remove(pathname) apfs_remove(pathname)
int sprintf(char *str, const char *format, ...);
#endif
#endif // __cplusplus
#ifdef __cplusplus
}