AP_Filesystem: make SITL take paths relative to starting directory

this makes SITL filesystem behave more like a real device
This commit is contained in:
Andrew Tridgell 2020-02-11 13:15:03 +11:00
parent f00a39af52
commit 1cb711d35d
1 changed files with 27 additions and 0 deletions

View File

@ -29,8 +29,28 @@
extern const AP_HAL::HAL& hal;
/*
map a filename for SITL so operations are relative to the current directory
*/
static const char *map_filename(const char *fname)
{
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
// on SITL only allow paths under subdirectory. Users can still
// escape with .. if they want to
if (strcmp(fname, "/") == 0) {
return ".";
}
if (*fname == '/') {
fname++;
}
#endif
// on Linux allow original name
return fname;
}
int AP_Filesystem::open(const char *fname, int flags)
{
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);
}
@ -62,11 +82,13 @@ off_t AP_Filesystem::lseek(int fd, off_t offset, int seek_from)
int AP_Filesystem::stat(const char *pathname, struct stat *stbuf)
{
pathname = map_filename(pathname);
return ::stat(pathname, stbuf);
}
int AP_Filesystem::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);
@ -78,11 +100,13 @@ int AP_Filesystem::unlink(const char *pathname)
int AP_Filesystem::mkdir(const char *pathname)
{
pathname = map_filename(pathname);
return ::mkdir(pathname, 0775);
}
DIR *AP_Filesystem::opendir(const char *pathname)
{
pathname = map_filename(pathname);
return ::opendir(pathname);
}
@ -99,6 +123,7 @@ int AP_Filesystem::closedir(DIR *dirp)
// return free disk space in bytes
int64_t AP_Filesystem::disk_free(const char *path)
{
path = map_filename(path);
struct statfs stats;
if (::statfs(path, &stats) < 0) {
return -1;
@ -109,6 +134,7 @@ int64_t AP_Filesystem::disk_free(const char *path)
// return total disk space in bytes
int64_t AP_Filesystem::disk_space(const char *path)
{
path = map_filename(path);
struct statfs stats;
if (::statfs(path, &stats) < 0) {
return -1;
@ -122,6 +148,7 @@ int64_t AP_Filesystem::disk_space(const char *path)
*/
bool AP_Filesystem::set_mtime(const char *filename, const time_t mtime_sec)
{
filename = map_filename(filename);
struct utimbuf times {};
times.actime = mtime_sec;
times.modtime = mtime_sec;