@ -106,10 +106,10 @@ const AP_Filesystem::Backend &AP_Filesystem::backend_by_fd(int &fd) const
return backends[idx];
}
int AP_Filesystem::open(const char *fname, int flags)
int AP_Filesystem::open(const char *fname, int flags, bool allow_absolute_paths)
{
const Backend &backend = backend_by_path(fname);
int fd = backend.fs.open(fname, flags);
int fd = backend.fs.open(fname, flags, allow_absolute_paths);
if (fd < 0) {
return -1;
@ -80,7 +80,7 @@ public:
AP_Filesystem() {}
// functions that closely match the equivalent posix calls
int open(const char *fname, int flags);
int open(const char *fname, int flags, bool allow_absolute_paths = false);
int close(int fd);
int32_t read(int fd, void *buf, uint32_t count);
int32_t write(int fd, const void *buf, uint32_t count);
@ -21,7 +21,7 @@ class AP_Filesystem_ESP32 : public AP_Filesystem_Backend
public:
int open(const char *fname, int flags) override;
int open(const char *fname, int flags, bool allow_absolute_paths = false) override;
int close(int fd) override;
int32_t read(int fd, void *buf, uint32_t count) override;
int32_t write(int fd, const void *buf, uint32_t count) override;
@ -279,7 +279,7 @@ static bool remount_file_system(void)
return true;
int AP_Filesystem_FATFS::open(const char *pathname, int flags)
int AP_Filesystem_FATFS::open(const char *pathname, int flags, bool allow_absolute_path)
int fileno;
int fatfs_modes;
@ -20,7 +20,7 @@ class AP_Filesystem_FATFS : public AP_Filesystem_Backend
@ -30,7 +30,7 @@ extern int errno;
#define IDLE_TIMEOUT_MS 30000
int AP_Filesystem_Mission::open(const char *fname, int flags)
int AP_Filesystem_Mission::open(const char *fname, int flags, bool allow_absolute_paths)
enum MAV_MISSION_TYPE mtype;
@ -23,7 +23,7 @@ class AP_Filesystem_Mission : public AP_Filesystem_Backend
int32_t lseek(int fd, int32_t offset, int whence) override;
@ -26,7 +26,7 @@
extern const AP_HAL::HAL& hal;
extern int errno;
int AP_Filesystem_Param::open(const char *fname, int flags)
int AP_Filesystem_Param::open(const char *fname, int flags, bool allow_absolute_path)
if (!check_file_name(fname)) {
errno = ENOENT;
@ -24,7 +24,7 @@ class AP_Filesystem_Param : public AP_Filesystem_Backend
@ -23,7 +23,7 @@
#if defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H)
int AP_Filesystem_ROMFS::open(const char *fname, int flags)
int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_paths)
if ((flags & O_ACCMODE) != O_RDONLY) {
errno = EROFS;
@ -21,7 +21,7 @@ class AP_Filesystem_ROMFS : public AP_Filesystem_Backend
@ -60,7 +60,7 @@ int8_t AP_Filesystem_Sys::file_in_sysfs(const char *fname) {
int AP_Filesystem_Sys::open(const char *fname, int flags)
int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_paths)
@ -23,7 +23,7 @@ class AP_Filesystem_Sys : public AP_Filesystem_Backend
@ -43,7 +43,7 @@ class AP_Filesystem_Backend {
virtual int open(const char *fname, int flags) {
virtual int open(const char *fname, int flags, bool allow_absolute_paths = false) {
virtual int close(int fd) { return -1; }
@ -49,10 +49,12 @@ static const char *map_filename(const char *fname)
return fname;
int AP_Filesystem_Posix::open(const char *fname, int flags)
int AP_Filesystem_Posix::open(const char *fname, int flags, bool allow_absolute_paths)
FS_CHECK_ALLOWED(-1);
fname = map_filename(fname);
if (! allow_absolute_paths) {
// we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage
return ::open(fname, flags | O_CLOEXEC, 0644);
@ -29,7 +29,7 @@ class AP_Filesystem_Posix : public AP_Filesystem_Backend