mirror of https://github.com/ArduPilot/ardupilot
AP_FileSystem: add AP_FILESYSTEM_*_ENABLED
This commit is contained in:
parent
be9e0aefd8
commit
b5165b6d7f
|
@ -15,6 +15,9 @@
|
|||
|
||||
#include "AP_Filesystem.h"
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
#include <AP_HAL/HAL.h>
|
||||
|
||||
static AP_Filesystem fs;
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||
|
@ -37,19 +40,22 @@ static AP_Filesystem_ESP32 fs_local;
|
|||
static AP_Filesystem_Posix fs_local;
|
||||
#endif
|
||||
|
||||
#ifdef HAL_HAVE_AP_ROMFS_EMBEDDED_H
|
||||
#if AP_FILESYSTEM_ROMFS_ENABLED
|
||||
#include "AP_Filesystem_ROMFS.h"
|
||||
static AP_Filesystem_ROMFS fs_romfs;
|
||||
#endif
|
||||
|
||||
#if AP_FILESYSTEM_PARAM_ENABLED
|
||||
#include "AP_Filesystem_Param.h"
|
||||
static AP_Filesystem_Param fs_param;
|
||||
#endif
|
||||
|
||||
#if AP_FILESYSTEM_SYS_ENABLED
|
||||
#include "AP_Filesystem_Sys.h"
|
||||
static AP_Filesystem_Sys fs_sys;
|
||||
#endif
|
||||
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
#if AP_MISSION_ENABLED
|
||||
#if AP_FILESYSTEM_MISSION_ENABLED
|
||||
#include "AP_Filesystem_Mission.h"
|
||||
static AP_Filesystem_Mission fs_mission;
|
||||
#endif
|
||||
|
@ -59,13 +65,17 @@ static AP_Filesystem_Mission fs_mission;
|
|||
*/
|
||||
const AP_Filesystem::Backend AP_Filesystem::backends[] = {
|
||||
{ nullptr, fs_local },
|
||||
#ifdef HAL_HAVE_AP_ROMFS_EMBEDDED_H
|
||||
#if AP_FILESYSTEM_ROMFS_ENABLED
|
||||
{ "@ROMFS/", fs_romfs },
|
||||
#endif
|
||||
#if AP_FILESYSTEM_PARAM_ENABLED
|
||||
{ "@PARAM/", fs_param },
|
||||
#endif
|
||||
#if AP_FILESYSTEM_SYS_ENABLED
|
||||
{ "@SYS/", fs_sys },
|
||||
{ "@SYS", fs_sys },
|
||||
#if AP_MISSION_ENABLED
|
||||
#endif
|
||||
#if AP_FILESYSTEM_MISSION_ENABLED
|
||||
{ "@MISSION/", fs_mission },
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -15,6 +15,11 @@
|
|||
/*
|
||||
ArduPilot filesystem interface for mission/fence/rally
|
||||
*/
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
|
||||
#if AP_FILESYSTEM_MISSION_ENABLED
|
||||
|
||||
#include "AP_Filesystem.h"
|
||||
#include "AP_Filesystem_Mission.h"
|
||||
#include <AP_Mission/AP_Mission.h>
|
||||
|
@ -23,8 +28,6 @@
|
|||
#include <GCS_MAVLink/MissionItemProtocol_Rally.h>
|
||||
#include <GCS_MAVLink/MissionItemProtocol_Fence.h>
|
||||
|
||||
#if AP_MISSION_ENABLED
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
extern int errno;
|
||||
|
||||
|
@ -406,4 +409,4 @@ bool AP_Filesystem_Mission::finish_upload(const rfile &r)
|
|||
return true;
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // AP_FILESYSTEM_MISSION_ENABLED
|
||||
|
|
|
@ -15,6 +15,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
|
||||
#if AP_FILESYSTEM_MISSION_ENABLED
|
||||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
#include <GCS_MAVLink/GCS_MAVLink.h>
|
||||
#include <AP_Common/ExpandingString.h>
|
||||
|
@ -72,3 +76,5 @@ private:
|
|||
// see if a block of memory is all zero
|
||||
bool all_zero(const uint8_t *b, uint8_t size) const;
|
||||
};
|
||||
|
||||
#endif // AP_FILESYSTEM_MISSION_ENABLED
|
||||
|
|
|
@ -15,6 +15,11 @@
|
|||
/*
|
||||
ArduPilot filesystem interface for parameters
|
||||
*/
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
|
||||
#if AP_FILESYSTEM_PARAM_ENABLED
|
||||
|
||||
#include "AP_Filesystem.h"
|
||||
#include "AP_Filesystem_Param.h"
|
||||
#include <AP_Param/AP_Param.h>
|
||||
|
@ -646,3 +651,5 @@ bool AP_Filesystem_Param::finish_upload(const rfile &r)
|
|||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif // AP_FILESYSTEM_PARAM_ENABLED
|
||||
|
|
|
@ -15,6 +15,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
|
||||
#if AP_FILESYSTEM_PARAM_ENABLED
|
||||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
#include <AP_Common/ExpandingString.h>
|
||||
|
||||
|
@ -82,3 +86,5 @@ private:
|
|||
bool finish_upload(const rfile &r);
|
||||
bool param_upload_parse(const rfile &r, bool &need_retry);
|
||||
};
|
||||
|
||||
#endif // AP_FILESYSTEM_PARAM_ENABLED
|
||||
|
|
|
@ -15,14 +15,17 @@
|
|||
/*
|
||||
ArduPilot filesystem interface for ROMFS
|
||||
*/
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
|
||||
#if AP_FILESYSTEM_ROMFS_ENABLED
|
||||
|
||||
#include "AP_Filesystem.h"
|
||||
#include "AP_Filesystem_ROMFS.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_ROMFS/AP_ROMFS.h>
|
||||
|
||||
#if defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H)
|
||||
|
||||
int AP_Filesystem_ROMFS::open(const char *fname, int flags, bool allow_absolute_paths)
|
||||
{
|
||||
if ((flags & O_ACCMODE) != O_RDONLY) {
|
||||
|
@ -236,4 +239,4 @@ void AP_Filesystem_ROMFS::unload_file(FileData *fd)
|
|||
AP_ROMFS::free(fd->data);
|
||||
}
|
||||
|
||||
#endif // HAL_HAVE_AP_ROMFS_EMBEDDED_H
|
||||
#endif // AP_FILESYSTEM_ROMFS_ENABLED
|
||||
|
|
|
@ -15,6 +15,10 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
|
||||
#if AP_FILESYSTEM_ROMFS_ENABLED
|
||||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
|
||||
class AP_Filesystem_ROMFS : public AP_Filesystem_Backend
|
||||
|
@ -68,3 +72,5 @@ private:
|
|||
struct dirent de;
|
||||
} dir[max_open_dir];
|
||||
};
|
||||
|
||||
#endif // AP_FILESYSTEM_ROMFS_ENABLED
|
||||
|
|
|
@ -19,6 +19,9 @@
|
|||
*/
|
||||
#include "AP_Filesystem.h"
|
||||
#include "AP_Filesystem_Sys.h"
|
||||
|
||||
#if AP_FILESYSTEM_SYS_ENABLED
|
||||
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_CANManager/AP_CANManager.h>
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
|
@ -281,3 +284,5 @@ int AP_Filesystem_Sys::stat(const char *pathname, struct stat *stbuf)
|
|||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif // AP_FILESYSTEM_SYS_ENABLED
|
||||
|
|
|
@ -17,6 +17,10 @@
|
|||
|
||||
#include "AP_Filesystem_backend.h"
|
||||
|
||||
#include "AP_Filesystem_config.h"
|
||||
|
||||
#if AP_FILESYSTEM_SYS_ENABLED
|
||||
|
||||
class ExpandingString;
|
||||
|
||||
class AP_Filesystem_Sys : public AP_Filesystem_Backend
|
||||
|
@ -48,3 +52,5 @@ private:
|
|||
ExpandingString *str;
|
||||
} file[max_open_file];
|
||||
};
|
||||
|
||||
#endif // AP_FILESYSTEM_SYS_ENABLED
|
||||
|
|
|
@ -0,0 +1,21 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL_Boards.h>
|
||||
|
||||
#include <AP_Mission/AP_Mission_config.h>
|
||||
|
||||
#ifndef AP_FILESYSTEM_PARAM_ENABLED
|
||||
#define AP_FILESYSTEM_PARAM_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_FILESYSTEM_MISSION_ENABLED
|
||||
#define AP_FILESYSTEM_MISSION_ENABLED AP_MISSION_ENABLED
|
||||
#endif
|
||||
|
||||
#ifndef AP_FILESYSTEM_SYS_ENABLED
|
||||
#define AP_FILESYSTEM_SYS_ENABLED 1
|
||||
#endif
|
||||
|
||||
#ifndef AP_FILESYSTEM_ROMFS_ENABLED
|
||||
#define AP_FILESYSTEM_ROMFS_ENABLED defined(HAL_HAVE_AP_ROMFS_EMBEDDED_H)
|
||||
#endif
|
Loading…
Reference in New Issue