mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 23:43:58 -04:00
AP_Filesystem: enable @PARAM, @ROMFS and @SYS with no microSD
This commit is contained in:
parent
7cd901fa5b
commit
9b14fa7ed9
@ -15,14 +15,18 @@
|
||||
|
||||
#include "AP_Filesystem.h"
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
|
||||
static AP_Filesystem fs;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
#include "AP_Filesystem_FATFS.h"
|
||||
static AP_Filesystem_FATFS fs_local;
|
||||
#endif
|
||||
#else
|
||||
static AP_Filesystem_Backend fs_local;
|
||||
int errno;
|
||||
#endif // HAVE_FILESYSTEM_SUPPORT
|
||||
#endif // HAL_BOARD_CHIBIOS
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include "AP_Filesystem_posix.h"
|
||||
static AP_Filesystem_Posix fs_local;
|
||||
@ -109,13 +113,13 @@ int AP_Filesystem::close(int fd)
|
||||
return backend.fs.close(fd);
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem::read(int fd, void *buf, size_t count)
|
||||
int32_t AP_Filesystem::read(int fd, void *buf, uint32_t count)
|
||||
{
|
||||
const Backend &backend = backend_by_fd(fd);
|
||||
return backend.fs.read(fd, buf, count);
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem::write(int fd, const void *buf, size_t count)
|
||||
int32_t AP_Filesystem::write(int fd, const void *buf, uint32_t count)
|
||||
{
|
||||
const Backend &backend = backend_by_fd(fd);
|
||||
return backend.fs.write(fd, buf, count);
|
||||
@ -127,7 +131,7 @@ int AP_Filesystem::fsync(int fd)
|
||||
return backend.fs.fsync(fd);
|
||||
}
|
||||
|
||||
off_t AP_Filesystem::lseek(int fd, off_t offset, int seek_from)
|
||||
int32_t AP_Filesystem::lseek(int fd, int32_t offset, int seek_from)
|
||||
{
|
||||
const Backend &backend = backend_by_fd(fd);
|
||||
return backend.fs.lseek(fd, offset, seek_from);
|
||||
@ -205,7 +209,7 @@ int64_t AP_Filesystem::disk_space(const char *path)
|
||||
/*
|
||||
set mtime on a file
|
||||
*/
|
||||
bool AP_Filesystem::set_mtime(const char *filename, const time_t mtime_sec)
|
||||
bool AP_Filesystem::set_mtime(const char *filename, const uint32_t mtime_sec)
|
||||
{
|
||||
const Backend &backend = backend_by_path(filename);
|
||||
return backend.fs.set_mtime(filename, mtime_sec);
|
||||
@ -218,4 +222,4 @@ AP_Filesystem &FS()
|
||||
return fs;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -24,14 +24,31 @@
|
||||
|
||||
#include "AP_Filesystem_Available.h"
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
#include "AP_Filesystem_FATFS.h"
|
||||
#endif
|
||||
#define DT_REG 0
|
||||
#define DT_DIR 1
|
||||
#if defined(FF_MAX_LFN) && FF_USE_LFN != 0
|
||||
#define MAX_NAME_LEN FF_MAX_LFN
|
||||
#else
|
||||
#define MAX_NAME_LEN 13
|
||||
#endif
|
||||
struct dirent {
|
||||
char d_name[MAX_NAME_LEN]; /* filename */
|
||||
uint8_t d_type;
|
||||
};
|
||||
#include <fcntl.h>
|
||||
#include <errno.h>
|
||||
#include <unistd.h>
|
||||
#endif // HAL_BOARD_CHIBIOS
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
#include "AP_Filesystem_posix.h"
|
||||
#endif
|
||||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
|
||||
class AP_Filesystem {
|
||||
private:
|
||||
struct DirHandle {
|
||||
@ -45,10 +62,10 @@ public:
|
||||
// functions that closely match the equivalent posix calls
|
||||
int open(const char *fname, int flags);
|
||||
int close(int fd);
|
||||
ssize_t read(int fd, void *buf, size_t count);
|
||||
ssize_t write(int fd, const void *buf, size_t count);
|
||||
int32_t read(int fd, void *buf, uint32_t count);
|
||||
int32_t write(int fd, const void *buf, uint32_t count);
|
||||
int fsync(int fd);
|
||||
off_t lseek(int fd, off_t offset, int whence);
|
||||
int32_t lseek(int fd, int32_t offset, int whence);
|
||||
int stat(const char *pathname, struct stat *stbuf);
|
||||
int unlink(const char *pathname);
|
||||
int mkdir(const char *pathname);
|
||||
@ -64,7 +81,7 @@ public:
|
||||
int64_t disk_space(const char *path);
|
||||
|
||||
// set modification time on a file
|
||||
bool set_mtime(const char *filename, const time_t mtime_sec);
|
||||
bool set_mtime(const char *filename, const uint32_t mtime_sec);
|
||||
|
||||
private:
|
||||
struct Backend {
|
||||
@ -87,4 +104,4 @@ private:
|
||||
namespace AP {
|
||||
AP_Filesystem &FS();
|
||||
};
|
||||
#endif // HAVE_FILESYSTEM_SUPPORT
|
||||
|
||||
|
@ -382,7 +382,7 @@ int AP_Filesystem_FATFS::close(int fileno)
|
||||
return 0;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_FATFS::read(int fd, void *buf, size_t count)
|
||||
int32_t AP_Filesystem_FATFS::read(int fd, void *buf, uint32_t count)
|
||||
{
|
||||
UINT bytes = count;
|
||||
int res;
|
||||
@ -431,7 +431,7 @@ ssize_t AP_Filesystem_FATFS::read(int fd, void *buf, size_t count)
|
||||
return (ssize_t)total;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_FATFS::write(int fd, const void *buf, size_t count)
|
||||
int32_t AP_Filesystem_FATFS::write(int fd, const void *buf, uint32_t count)
|
||||
{
|
||||
UINT bytes = count;
|
||||
FRESULT res;
|
||||
@ -843,7 +843,7 @@ static void unix_time_to_fat(time_t epoch, uint16_t &date, uint16_t &time)
|
||||
/*
|
||||
set mtime on a file
|
||||
*/
|
||||
bool AP_Filesystem_FATFS::set_mtime(const char *filename, const time_t mtime_sec)
|
||||
bool AP_Filesystem_FATFS::set_mtime(const char *filename, const uint32_t mtime_sec)
|
||||
{
|
||||
FILINFO fno;
|
||||
uint16_t fdate, ftime;
|
||||
|
@ -23,24 +23,16 @@
|
||||
#define MAX_NAME_LEN 13
|
||||
#endif
|
||||
|
||||
#define DT_REG 0
|
||||
#define DT_DIR 1
|
||||
|
||||
struct dirent {
|
||||
char d_name[MAX_NAME_LEN]; /* filename */
|
||||
uint8_t d_type;
|
||||
};
|
||||
|
||||
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 close(int fd) override;
|
||||
ssize_t read(int fd, void *buf, size_t count) override;
|
||||
ssize_t write(int fd, const void *buf, size_t count) override;
|
||||
int32_t read(int fd, void *buf, uint32_t count) override;
|
||||
int32_t write(int fd, const void *buf, uint32_t count) override;
|
||||
int fsync(int fd) override;
|
||||
off_t lseek(int fd, off_t offset, int whence) override;
|
||||
int32_t lseek(int fd, int32_t offset, int whence) override;
|
||||
int stat(const char *pathname, struct stat *stbuf) override;
|
||||
int unlink(const char *pathname) override;
|
||||
int mkdir(const char *pathname) override;
|
||||
@ -55,5 +47,5 @@ public:
|
||||
int64_t disk_space(const char *path) override;
|
||||
|
||||
// set modification time on a file
|
||||
bool set_mtime(const char *filename, const time_t mtime_sec) override;
|
||||
bool set_mtime(const char *filename, const uint32_t mtime_sec) override;
|
||||
};
|
||||
|
@ -22,16 +22,14 @@
|
||||
#include <AP_Param/AP_Param.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
|
||||
#define PACKED_NAME "param.pck"
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
extern int errno;
|
||||
|
||||
int AP_Filesystem_Param::open(const char *fname, int flags)
|
||||
{
|
||||
if ((flags & O_ACCMODE) != O_RDONLY) {
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
}
|
||||
uint8_t idx;
|
||||
@ -159,7 +157,7 @@ bool AP_Filesystem_Param::token_seek(const struct rfile &r, struct cursor &c)
|
||||
return r.file_ofs == c.token_ofs;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_Param::read(int fd, void *buf, size_t count)
|
||||
int32_t AP_Filesystem_Param::read(int fd, void *buf, uint32_t count)
|
||||
{
|
||||
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
|
||||
errno = EBADF;
|
||||
@ -238,18 +236,7 @@ ssize_t AP_Filesystem_Param::read(int fd, void *buf, size_t count)
|
||||
return total;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_Param::write(int fd, const void *buf, size_t count)
|
||||
{
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Param::fsync(int fd)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
off_t AP_Filesystem_Param::lseek(int fd, off_t offset, int seek_from)
|
||||
int32_t AP_Filesystem_Param::lseek(int fd, int32_t offset, int seek_from)
|
||||
{
|
||||
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
|
||||
errno = EBADF;
|
||||
@ -281,55 +268,3 @@ int AP_Filesystem_Param::stat(const char *name, struct stat *stbuf)
|
||||
stbuf->st_size = 65535;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Param::unlink(const char *pathname)
|
||||
{
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Param::mkdir(const char *pathname)
|
||||
{
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
}
|
||||
|
||||
void *AP_Filesystem_Param::opendir(const char *pathname)
|
||||
{
|
||||
errno = EINVAL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
struct dirent *AP_Filesystem_Param::readdir(void *dirp)
|
||||
{
|
||||
errno = EBADF;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Param::closedir(void *dirp)
|
||||
{
|
||||
errno = EBADF;
|
||||
return -1;
|
||||
}
|
||||
|
||||
// return free disk space in bytes
|
||||
int64_t AP_Filesystem_Param::disk_free(const char *path)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
// return total disk space in bytes
|
||||
int64_t AP_Filesystem_Param::disk_space(const char *path)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
set mtime on a file
|
||||
*/
|
||||
bool AP_Filesystem_Param::set_mtime(const char *filename, const time_t mtime_sec)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -17,8 +17,6 @@
|
||||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
||||
class AP_Filesystem_Param : public AP_Filesystem_Backend
|
||||
@ -27,25 +25,9 @@ public:
|
||||
// functions that closely match the equivalent posix calls
|
||||
int open(const char *fname, int flags) override;
|
||||
int close(int fd) override;
|
||||
ssize_t read(int fd, void *buf, size_t count) override;
|
||||
ssize_t write(int fd, const void *buf, size_t count) override;
|
||||
int fsync(int fd) override;
|
||||
off_t lseek(int fd, off_t offset, int whence) override;
|
||||
int32_t read(int fd, void *buf, uint32_t count) override;
|
||||
int32_t lseek(int fd, int32_t offset, int whence) override;
|
||||
int stat(const char *pathname, struct stat *stbuf) override;
|
||||
int unlink(const char *pathname) override;
|
||||
int mkdir(const char *pathname) override;
|
||||
void *opendir(const char *pathname) override;
|
||||
struct dirent *readdir(void *dirp) override;
|
||||
int closedir(void *dirp) override;
|
||||
|
||||
// return free disk space in bytes, -1 on error
|
||||
int64_t disk_free(const char *path) override;
|
||||
|
||||
// return total disk space in bytes, -1 on error
|
||||
int64_t disk_space(const char *path) override;
|
||||
|
||||
// set modification time on a file
|
||||
bool set_mtime(const char *filename, const time_t mtime_sec) override;
|
||||
|
||||
private:
|
||||
// we maintain two cursors per open file to minimise seeking
|
||||
@ -76,5 +58,3 @@ private:
|
||||
uint8_t pack_param(const AP_Param *ap, const char *pname, const char *last_name,
|
||||
enum ap_var_type ptype, uint8_t *buf, uint8_t buflen);
|
||||
};
|
||||
|
||||
#endif // HAVE_FILESYSTEM_SUPPORT
|
||||
|
@ -21,7 +21,7 @@
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_ROMFS/AP_ROMFS.h>
|
||||
|
||||
#if defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H) && HAVE_FILESYSTEM_SUPPORT
|
||||
#if defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H)
|
||||
|
||||
int AP_Filesystem_ROMFS::open(const char *fname, int flags)
|
||||
{
|
||||
@ -63,7 +63,7 @@ int AP_Filesystem_ROMFS::close(int fd)
|
||||
return 0;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_ROMFS::read(int fd, void *buf, size_t count)
|
||||
int32_t AP_Filesystem_ROMFS::read(int fd, void *buf, uint32_t count)
|
||||
{
|
||||
if (fd < 0 || fd >= max_open_file || file[fd].data == nullptr) {
|
||||
errno = EBADF;
|
||||
@ -78,7 +78,7 @@ ssize_t AP_Filesystem_ROMFS::read(int fd, void *buf, size_t count)
|
||||
return count;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_ROMFS::write(int fd, const void *buf, size_t count)
|
||||
int32_t AP_Filesystem_ROMFS::write(int fd, const void *buf, uint32_t count)
|
||||
{
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
@ -89,7 +89,7 @@ int AP_Filesystem_ROMFS::fsync(int fd)
|
||||
return 0;
|
||||
}
|
||||
|
||||
off_t AP_Filesystem_ROMFS::lseek(int fd, off_t offset, int seek_from)
|
||||
int32_t AP_Filesystem_ROMFS::lseek(int fd, int32_t offset, int seek_from)
|
||||
{
|
||||
if (fd < 0 || fd >= max_open_file || file[fd].data == nullptr) {
|
||||
errno = EBADF;
|
||||
@ -203,7 +203,7 @@ int64_t AP_Filesystem_ROMFS::disk_space(const char *path)
|
||||
/*
|
||||
set mtime on a file
|
||||
*/
|
||||
bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const time_t mtime_sec)
|
||||
bool AP_Filesystem_ROMFS::set_mtime(const char *filename, const uint32_t mtime_sec)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
@ -17,18 +17,16 @@
|
||||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
|
||||
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 close(int fd) override;
|
||||
ssize_t read(int fd, void *buf, size_t count) override;
|
||||
ssize_t write(int fd, const void *buf, size_t count) override;
|
||||
int32_t read(int fd, void *buf, uint32_t count) override;
|
||||
int32_t write(int fd, const void *buf, uint32_t count) override;
|
||||
int fsync(int fd) override;
|
||||
off_t lseek(int fd, off_t offset, int whence) override;
|
||||
int32_t lseek(int fd, int32_t offset, int whence) override;
|
||||
int stat(const char *pathname, struct stat *stbuf) override;
|
||||
int unlink(const char *pathname) override;
|
||||
int mkdir(const char *pathname) override;
|
||||
@ -43,7 +41,7 @@ public:
|
||||
int64_t disk_space(const char *path) override;
|
||||
|
||||
// set modification time on a file
|
||||
bool set_mtime(const char *filename, const time_t mtime_sec) override;
|
||||
bool set_mtime(const char *filename, const uint32_t mtime_sec) override;
|
||||
|
||||
private:
|
||||
// only allow up to 4 files at a time
|
||||
@ -62,5 +60,3 @@ private:
|
||||
struct dirent de;
|
||||
} dir[max_open_dir];
|
||||
};
|
||||
|
||||
#endif // HAVE_FILESYSTEM_SUPPORT
|
||||
|
@ -21,8 +21,6 @@
|
||||
#include "AP_Filesystem_Sys.h"
|
||||
#include <AP_Math/AP_Math.h>
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
int AP_Filesystem_Sys::open(const char *fname, int flags)
|
||||
@ -77,7 +75,7 @@ int AP_Filesystem_Sys::close(int fd)
|
||||
return 0;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_Sys::read(int fd, void *buf, size_t count)
|
||||
int32_t AP_Filesystem_Sys::read(int fd, void *buf, uint32_t count)
|
||||
{
|
||||
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
|
||||
errno = EBADF;
|
||||
@ -90,18 +88,7 @@ ssize_t AP_Filesystem_Sys::read(int fd, void *buf, size_t count)
|
||||
return count;
|
||||
}
|
||||
|
||||
ssize_t AP_Filesystem_Sys::write(int fd, const void *buf, size_t count)
|
||||
{
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Sys::fsync(int fd)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
off_t AP_Filesystem_Sys::lseek(int fd, off_t offset, int seek_from)
|
||||
int32_t AP_Filesystem_Sys::lseek(int fd, int32_t offset, int seek_from)
|
||||
{
|
||||
if (fd < 0 || fd >= max_open_file || !file[fd].open) {
|
||||
errno = EBADF;
|
||||
@ -110,7 +97,7 @@ off_t AP_Filesystem_Sys::lseek(int fd, off_t offset, int seek_from)
|
||||
struct rfile &r = file[fd];
|
||||
switch (seek_from) {
|
||||
case SEEK_SET:
|
||||
r.file_ofs = MIN(offset, r.data->length);
|
||||
r.file_ofs = MIN(offset, int32_t(r.data->length));
|
||||
break;
|
||||
case SEEK_CUR:
|
||||
r.file_ofs = MIN(r.data->length, offset+r.file_ofs);
|
||||
@ -129,55 +116,3 @@ int AP_Filesystem_Sys::stat(const char *name, struct stat *stbuf)
|
||||
stbuf->st_size = 1024*1024;
|
||||
return 0;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Sys::unlink(const char *pathname)
|
||||
{
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Sys::mkdir(const char *pathname)
|
||||
{
|
||||
errno = EROFS;
|
||||
return -1;
|
||||
}
|
||||
|
||||
void *AP_Filesystem_Sys::opendir(const char *pathname)
|
||||
{
|
||||
errno = EINVAL;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
struct dirent *AP_Filesystem_Sys::readdir(void *dirp)
|
||||
{
|
||||
errno = EBADF;
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
int AP_Filesystem_Sys::closedir(void *dirp)
|
||||
{
|
||||
errno = EBADF;
|
||||
return -1;
|
||||
}
|
||||
|
||||
// return free disk space in bytes
|
||||
int64_t AP_Filesystem_Sys::disk_free(const char *path)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
// return total disk space in bytes
|
||||
int64_t AP_Filesystem_Sys::disk_space(const char *path)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
set mtime on a file
|
||||
*/
|
||||
bool AP_Filesystem_Sys::set_mtime(const char *filename, const time_t mtime_sec)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -17,33 +17,15 @@
|
||||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
|
||||
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 close(int fd) override;
|
||||
ssize_t read(int fd, void *buf, size_t count) override;
|
||||
ssize_t write(int fd, const void *buf, size_t count) override;
|
||||
int fsync(int fd) override;
|
||||
off_t lseek(int fd, off_t offset, int whence) override;
|
||||
int32_t read(int fd, void *buf, uint32_t count) override;
|
||||
int32_t lseek(int fd, int32_t offset, int whence) override;
|
||||
int stat(const char *pathname, struct stat *stbuf) override;
|
||||
int unlink(const char *pathname) override;
|
||||
int mkdir(const char *pathname) override;
|
||||
void *opendir(const char *pathname) override;
|
||||
struct dirent *readdir(void *dirp) override;
|
||||
int closedir(void *dirp) override;
|
||||
|
||||
// return free disk space in bytes, -1 on error
|
||||
int64_t disk_free(const char *path) override;
|
||||
|
||||
// return total disk space in bytes, -1 on error
|
||||
int64_t disk_space(const char *path) override;
|
||||
|
||||
// set modification time on a file
|
||||
bool set_mtime(const char *filename, const time_t mtime_sec) override;
|
||||
|
||||
private:
|
||||
// only allow up to 4 files at a time
|
||||
@ -60,5 +42,3 @@ private:
|
||||
struct file_data *data;
|
||||
} file[max_open_file];
|
||||
};
|
||||
|
||||
#endif // HAVE_FILESYSTEM_SUPPORT
|
||||
|
@ -22,32 +22,31 @@
|
||||
|
||||
#include "AP_Filesystem_Available.h"
|
||||
|
||||
#if HAVE_FILESYSTEM_SUPPORT
|
||||
class AP_Filesystem_Backend {
|
||||
|
||||
public:
|
||||
// functions that closely match the equivalent posix calls
|
||||
virtual int open(const char *fname, int flags) = 0;
|
||||
virtual int close(int fd) = 0;
|
||||
virtual ssize_t read(int fd, void *buf, size_t count) = 0;
|
||||
virtual ssize_t write(int fd, const void *buf, size_t count) = 0;
|
||||
virtual int fsync(int fd) = 0;
|
||||
virtual off_t lseek(int fd, off_t offset, int whence) = 0;
|
||||
virtual int stat(const char *pathname, struct stat *stbuf) = 0;
|
||||
virtual int unlink(const char *pathname) = 0;
|
||||
virtual int mkdir(const char *pathname) = 0;
|
||||
virtual void *opendir(const char *pathname) = 0;
|
||||
virtual struct dirent *readdir(void *dirp) = 0;
|
||||
virtual int closedir(void *dirp) = 0;
|
||||
virtual int open(const char *fname, int flags) {
|
||||
return -1;
|
||||
}
|
||||
virtual int close(int fd) { return -1; }
|
||||
virtual int32_t read(int fd, void *buf, uint32_t count) { return -1; }
|
||||
virtual int32_t write(int fd, const void *buf, uint32_t count) { return -1; }
|
||||
virtual int fsync(int fd) { return 0; }
|
||||
virtual int32_t lseek(int fd, int32_t offset, int whence) { return -1; }
|
||||
virtual int stat(const char *pathname, struct stat *stbuf) { return -1; }
|
||||
virtual int unlink(const char *pathname) { return -1; }
|
||||
virtual int mkdir(const char *pathname) { return -1; }
|
||||
virtual void *opendir(const char *pathname) { return nullptr; }
|
||||
virtual struct dirent *readdir(void *dirp) { return nullptr; }
|
||||
virtual int closedir(void *dirp) { return -1; }
|
||||
|
||||
// return free disk space in bytes, -1 on error
|
||||
virtual int64_t disk_free(const char *path) = 0;
|
||||
virtual int64_t disk_free(const char *path) { return 0; }
|
||||
|
||||
// return total disk space in bytes, -1 on error
|
||||
virtual int64_t disk_space(const char *path) = 0;
|
||||
virtual int64_t disk_space(const char *path) { return 0; }
|
||||
|
||||
// set modification time on a file
|
||||
virtual bool set_mtime(const char *filename, const time_t mtime_sec) = 0;
|
||||
virtual bool set_mtime(const char *filename, const uint32_t mtime_sec) { return false; }
|
||||
};
|
||||
|
||||
#endif // HAVE_FILESYSTEM_SUPPORT
|
||||
|
@ -75,7 +75,7 @@ int AP_Filesystem_Posix::fsync(int fd)
|
||||
return ::fsync(fd);
|
||||
}
|
||||
|
||||
off_t AP_Filesystem_Posix::lseek(int fd, off_t offset, int seek_from)
|
||||
int32_t AP_Filesystem_Posix::lseek(int fd, int32_t offset, int seek_from)
|
||||
{
|
||||
return ::lseek(fd, offset, seek_from);
|
||||
}
|
||||
@ -146,7 +146,7 @@ int64_t AP_Filesystem_Posix::disk_space(const char *path)
|
||||
/*
|
||||
set mtime on a file
|
||||
*/
|
||||
bool AP_Filesystem_Posix::set_mtime(const char *filename, const time_t mtime_sec)
|
||||
bool AP_Filesystem_Posix::set_mtime(const char *filename, const uint32_t mtime_sec)
|
||||
{
|
||||
filename = map_filename(filename);
|
||||
struct utimbuf times {};
|
||||
|
@ -31,10 +31,10 @@ public:
|
||||
// functions that closely match the equivalent posix calls
|
||||
int open(const char *fname, int flags) override;
|
||||
int close(int fd) override;
|
||||
ssize_t read(int fd, void *buf, size_t count) override;
|
||||
ssize_t write(int fd, const void *buf, size_t count) override;
|
||||
int32_t read(int fd, void *buf, uint32_t count) override;
|
||||
ssize_t write(int fd, const void *buf, uint32_t count) override;
|
||||
int fsync(int fd) override;
|
||||
off_t lseek(int fd, off_t offset, int whence) override;
|
||||
int32_t lseek(int fd, int32_t offset, int whence) override;
|
||||
int stat(const char *pathname, struct stat *stbuf) override;
|
||||
int unlink(const char *pathname) override;
|
||||
int mkdir(const char *pathname) override;
|
||||
@ -49,6 +49,6 @@ public:
|
||||
int64_t disk_space(const char *path) override;
|
||||
|
||||
// set modification time on a file
|
||||
bool set_mtime(const char *filename, const time_t mtime_sec) override;
|
||||
bool set_mtime(const char *filename, const uint32_t mtime_sec) override;
|
||||
};
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user