Browse Source

AP_Filesystem: add allow_absolute_paths to open(), implement it for posix backend

apm_2208
Willian Galvani 3 years ago committed by Andrew Tridgell
parent
commit
0e62d561d9
  1. 4
      libraries/AP_Filesystem/AP_Filesystem.cpp
  2. 2
      libraries/AP_Filesystem/AP_Filesystem.h
  3. 2
      libraries/AP_Filesystem/AP_Filesystem_ESP32.h
  4. 2
      libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp
  5. 2
      libraries/AP_Filesystem/AP_Filesystem_FATFS.h
  6. 2
      libraries/AP_Filesystem/AP_Filesystem_Mission.cpp
  7. 2
      libraries/AP_Filesystem/AP_Filesystem_Mission.h
  8. 2
      libraries/AP_Filesystem/AP_Filesystem_Param.cpp
  9. 2
      libraries/AP_Filesystem/AP_Filesystem_Param.h
  10. 2
      libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp
  11. 2
      libraries/AP_Filesystem/AP_Filesystem_ROMFS.h
  12. 2
      libraries/AP_Filesystem/AP_Filesystem_Sys.cpp
  13. 2
      libraries/AP_Filesystem/AP_Filesystem_Sys.h
  14. 2
      libraries/AP_Filesystem/AP_Filesystem_backend.h
  15. 6
      libraries/AP_Filesystem/AP_Filesystem_posix.cpp
  16. 2
      libraries/AP_Filesystem/AP_Filesystem_posix.h

4
libraries/AP_Filesystem/AP_Filesystem.cpp

@ -106,10 +106,10 @@ const AP_Filesystem::Backend &AP_Filesystem::backend_by_fd(int &fd) const @@ -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;
}

2
libraries/AP_Filesystem/AP_Filesystem.h

@ -80,7 +80,7 @@ public: @@ -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);

2
libraries/AP_Filesystem/AP_Filesystem_ESP32.h

@ -21,7 +21,7 @@ class AP_Filesystem_ESP32 : public AP_Filesystem_Backend @@ -21,7 +21,7 @@ class AP_Filesystem_ESP32 : public AP_Filesystem_Backend
{
public:
// functions that closely match the equivalent posix calls
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;

2
libraries/AP_Filesystem/AP_Filesystem_FATFS.cpp

@ -279,7 +279,7 @@ static bool remount_file_system(void) @@ -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;

2
libraries/AP_Filesystem/AP_Filesystem_FATFS.h

@ -20,7 +20,7 @@ class AP_Filesystem_FATFS : public AP_Filesystem_Backend @@ -20,7 +20,7 @@ class AP_Filesystem_FATFS : public AP_Filesystem_Backend
{
public:
// functions that closely match the equivalent posix calls
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;

2
libraries/AP_Filesystem/AP_Filesystem_Mission.cpp

@ -30,7 +30,7 @@ extern int errno; @@ -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;

2
libraries/AP_Filesystem/AP_Filesystem_Mission.h

@ -23,7 +23,7 @@ class AP_Filesystem_Mission : public AP_Filesystem_Backend @@ -23,7 +23,7 @@ class AP_Filesystem_Mission : public AP_Filesystem_Backend
{
public:
// functions that closely match the equivalent posix calls
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 lseek(int fd, int32_t offset, int whence) override;

2
libraries/AP_Filesystem/AP_Filesystem_Param.cpp

@ -26,7 +26,7 @@ @@ -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;

2
libraries/AP_Filesystem/AP_Filesystem_Param.h

@ -24,7 +24,7 @@ class AP_Filesystem_Param : public AP_Filesystem_Backend @@ -24,7 +24,7 @@ class AP_Filesystem_Param : public AP_Filesystem_Backend
{
public:
// functions that closely match the equivalent posix calls
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 lseek(int fd, int32_t offset, int whence) override;

2
libraries/AP_Filesystem/AP_Filesystem_ROMFS.cpp

@ -23,7 +23,7 @@ @@ -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;

2
libraries/AP_Filesystem/AP_Filesystem_ROMFS.h

@ -21,7 +21,7 @@ class AP_Filesystem_ROMFS : public AP_Filesystem_Backend @@ -21,7 +21,7 @@ class AP_Filesystem_ROMFS : public AP_Filesystem_Backend
{
public:
// functions that closely match the equivalent posix calls
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;

2
libraries/AP_Filesystem/AP_Filesystem_Sys.cpp

@ -60,7 +60,7 @@ int8_t AP_Filesystem_Sys::file_in_sysfs(const char *fname) { @@ -60,7 +60,7 @@ int8_t AP_Filesystem_Sys::file_in_sysfs(const char *fname) {
return -1;
}
int AP_Filesystem_Sys::open(const char *fname, int flags)
int AP_Filesystem_Sys::open(const char *fname, int flags, bool allow_absolute_paths)
{
if ((flags & O_ACCMODE) != O_RDONLY) {
errno = EROFS;

2
libraries/AP_Filesystem/AP_Filesystem_Sys.h

@ -23,7 +23,7 @@ class AP_Filesystem_Sys : public AP_Filesystem_Backend @@ -23,7 +23,7 @@ class AP_Filesystem_Sys : public AP_Filesystem_Backend
{
public:
// functions that closely match the equivalent posix calls
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 lseek(int fd, int32_t offset, int whence) override;

2
libraries/AP_Filesystem/AP_Filesystem_backend.h

@ -43,7 +43,7 @@ class AP_Filesystem_Backend { @@ -43,7 +43,7 @@ class AP_Filesystem_Backend {
public:
// functions that closely match the equivalent posix calls
virtual int open(const char *fname, int flags) {
virtual int open(const char *fname, int flags, bool allow_absolute_paths = false) {
return -1;
}
virtual int close(int fd) { return -1; }

6
libraries/AP_Filesystem/AP_Filesystem_posix.cpp

@ -49,10 +49,12 @@ static const char *map_filename(const char *fname) @@ -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) {
fname = map_filename(fname);
}
// we automatically add O_CLOEXEC as we always want it for ArduPilot FS usage
return ::open(fname, flags | O_CLOEXEC, 0644);
}

2
libraries/AP_Filesystem/AP_Filesystem_posix.h

@ -29,7 +29,7 @@ class AP_Filesystem_Posix : public AP_Filesystem_Backend @@ -29,7 +29,7 @@ class AP_Filesystem_Posix : public AP_Filesystem_Backend
{
public:
// functions that closely match the equivalent posix calls
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;

Loading…
Cancel
Save