Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added support for scripts in ROMFS in 4.0 #16566

Closed
wants to merge 7 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
13 changes: 13 additions & 0 deletions libraries/AP_Common/AP_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,3 +70,16 @@ bool hex_to_uint8(uint8_t a, uint8_t &res)
}
return true;
}

/*
strncpy without the warning for not leaving room for nul termination
*/
void strncpy_noterm(char *dest, const char *src, size_t n)
{
size_t len = strnlen(src, n);
if (len < n) {
// include nul term if it fits
len++;
}
memcpy(dest, src, len);
}
5 changes: 5 additions & 0 deletions libraries/AP_Common/AP_Common.h
Original file line number Diff line number Diff line change
Expand Up @@ -138,3 +138,8 @@ template<typename s, size_t t> struct assert_storage_size {
bool is_bounded_int32(int32_t value, int32_t lower_bound, int32_t upper_bound);

bool hex_to_uint8(uint8_t a, uint8_t &res); // return the uint8 value of an ascii hex character

/*
strncpy without the warning for not leaving room for nul termination
*/
void strncpy_noterm(char *dest, const char *src, size_t n);
214 changes: 212 additions & 2 deletions libraries/AP_Filesystem/AP_Filesystem.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,9 +15,219 @@

#include "AP_Filesystem.h"

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;
#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;
#endif

#ifdef HAL_HAVE_AP_ROMFS_EMBEDDED_H
#include "AP_Filesystem_ROMFS.h"
static AP_Filesystem_ROMFS fs_romfs;
#endif

/*
mapping from filesystem prefix to backend
*/
const AP_Filesystem::Backend AP_Filesystem::backends[] = {
{ nullptr, fs_local },
#ifdef HAL_HAVE_AP_ROMFS_EMBEDDED_H
{ "@ROMFS/", fs_romfs },
#endif
};

#define MAX_FD_PER_BACKEND 256U
#define NUM_BACKENDS ARRAY_SIZE(backends)
#define LOCAL_BACKEND backends[0]
#define BACKEND_IDX(backend) (&(backend) - &backends[0])

/*
find backend by path
*/
const AP_Filesystem::Backend &AP_Filesystem::backend_by_path(const char *&path) const
{
for (uint8_t i=1; i<NUM_BACKENDS; i++) {
const uint8_t plen = strlen(backends[i].prefix);
if (strncmp(path, backends[i].prefix, plen) == 0) {
path += plen;
return backends[i];
}
}
// default to local filesystem
return LOCAL_BACKEND;
}

/*
return backend by file descriptor
*/
const AP_Filesystem::Backend &AP_Filesystem::backend_by_fd(int &fd) const
{
if (fd < 0 || uint32_t(fd) >= NUM_BACKENDS*MAX_FD_PER_BACKEND) {
return LOCAL_BACKEND;
}
const uint8_t idx = uint32_t(fd) / MAX_FD_PER_BACKEND;
fd -= idx * MAX_FD_PER_BACKEND;
return backends[idx];
}

int AP_Filesystem::open(const char *fname, int flags)
{
const Backend &backend = backend_by_path(fname);
int fd = backend.fs.open(fname, flags);
if (fd < 0) {
return -1;
}
if (uint32_t(fd) >= MAX_FD_PER_BACKEND) {
backend.fs.close(fd);
errno = ERANGE;
return -1;
}
// offset fd so we can recognise the backend
const uint8_t idx = (&backend - &backends[0]);
fd += idx * MAX_FD_PER_BACKEND;
return fd;
}

int AP_Filesystem::close(int fd)
{
const Backend &backend = backend_by_fd(fd);
return backend.fs.close(fd);
}

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);
}

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);
}

int AP_Filesystem::fsync(int fd)
{
const Backend &backend = backend_by_fd(fd);
return backend.fs.fsync(fd);
}

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);
}

int AP_Filesystem::stat(const char *pathname, struct stat *stbuf)
{
const Backend &backend = backend_by_path(pathname);
return backend.fs.stat(pathname, stbuf);
}

int AP_Filesystem::unlink(const char *pathname)
{
const Backend &backend = backend_by_path(pathname);
return backend.fs.unlink(pathname);
}

int AP_Filesystem::mkdir(const char *pathname)
{
const Backend &backend = backend_by_path(pathname);
return backend.fs.mkdir(pathname);
}

AP_Filesystem::DirHandle *AP_Filesystem::opendir(const char *pathname)
{
const Backend &backend = backend_by_path(pathname);
DirHandle *h = new DirHandle;
if (!h) {
return nullptr;
}
h->dir = backend.fs.opendir(pathname);
if (h->dir == nullptr) {
delete h;
return nullptr;
}
h->fs_index = BACKEND_IDX(backend);
return h;
}

struct dirent *AP_Filesystem::readdir(DirHandle *dirp)
{
if (!dirp) {
return nullptr;
}
const Backend &backend = backends[dirp->fs_index];
return backend.fs.readdir(dirp->dir);
}

int AP_Filesystem::closedir(DirHandle *dirp)
{
if (!dirp) {
return -1;
}
const Backend &backend = backends[dirp->fs_index];
int ret = backend.fs.closedir(dirp->dir);
delete dirp;
return ret;
}

// return free disk space in bytes
int64_t AP_Filesystem::disk_free(const char *path)
{
const Backend &backend = backend_by_path(path);
return backend.fs.disk_free(path);
}

// return total disk space in bytes
int64_t AP_Filesystem::disk_space(const char *path)
{
const Backend &backend = backend_by_path(path);
return backend.fs.disk_space(path);
}


/*
set mtime on a file
*/
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);
}

// if filesystem is not running then try a remount
bool AP_Filesystem::retry_mount(void)
{
return LOCAL_BACKEND.fs.retry_mount();
}

// unmount filesystem for reboot
void AP_Filesystem::unmount(void)
{
return LOCAL_BACKEND.fs.unmount();
}

/*
load a file to memory as a single chunk. Use only for small files
*/
FileData *AP_Filesystem::load_file(const char *filename)
{
const Backend &backend = backend_by_path(filename);
return backend.fs.load_file(filename);
}

static AP_Filesystem fs;

namespace AP
{
Expand All @@ -26,4 +236,4 @@ AP_Filesystem &FS()
return fs;
}
}
#endif

69 changes: 60 additions & 9 deletions libraries/AP_Filesystem/AP_Filesystem.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,32 +24,55 @@

#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 {
uint8_t fs_index;
void *dir;
};

public:
AP_Filesystem() {}

// 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);
DIR *opendir(const char *pathname);
struct dirent *readdir(DIR *dirp);
int closedir(DIR *dirp);

DirHandle *opendir(const char *pathname);
struct dirent *readdir(DirHandle *dirp);
int closedir(DirHandle *dirp);

// return free disk space in bytes, -1 on error
int64_t disk_free(const char *path);
Expand All @@ -58,10 +81,38 @@ class AP_Filesystem {
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);

// if filesystem is not running then try a remount. Return true if fs is mounted
bool retry_mount(void);

// unmount filesystem for reboot
void unmount(void);

/*
load a full file. Use delete to free the data
*/
FileData *load_file(const char *filename);

private:
struct Backend {
const char *prefix;
AP_Filesystem_Backend &fs;
};
static const struct Backend backends[];

/*
find backend by path
*/
const Backend &backend_by_path(const char *&path) const;

/*
find backend by open fd
*/
const Backend &backend_by_fd(int &fd) const;
};

namespace AP {
AP_Filesystem &FS();
};
#endif // HAVE_FILESYSTEM_SUPPORT

Loading