forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 23
/
AP_Filesystem.cpp
294 lines (254 loc) · 7.08 KB
/
AP_Filesystem.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
/*
This program is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
This program is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#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_ESP32
#include "AP_Filesystem_ESP32.h"
static AP_Filesystem_ESP32 fs_local;
#endif // HAL_BOARD_ESP32
#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
#include "AP_Filesystem_Param.h"
static AP_Filesystem_Param fs_param;
#include "AP_Filesystem_Sys.h"
static AP_Filesystem_Sys fs_sys;
#include <AP_Mission/AP_Mission.h>
#if HAL_MISSION_ENABLED
#include "AP_Filesystem_Mission.h"
static AP_Filesystem_Mission fs_mission;
#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
{ "@PARAM/", fs_param },
{ "@SYS/", fs_sys },
{ "@SYS", fs_sys },
#if HAL_MISSION_ENABLED
{ "@MISSION/", fs_mission },
#endif
};
extern const AP_HAL::HAL& hal;
#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);
}
// returns null-terminated string; cr or lf terminates line
bool AP_Filesystem::fgets(char *buf, uint8_t buflen, int fd)
{
const Backend &backend = backend_by_fd(fd);
uint8_t i = 0;
for (; i<buflen-1; i++) {
if (backend.fs.read(fd, &buf[i], 1) != 1) {
break;
}
if (buf[i] == '\r' || buf[i] == '\n') {
break;
}
}
buf[i] = '\0';
return i != 0;
}
// format filesystem
bool AP_Filesystem::format(void)
{
#if AP_FILESYSTEM_FORMAT_ENABLED
if (hal.util->get_soft_armed()) {
return false;
}
return LOCAL_BACKEND.fs.format();
#else
return false;
#endif
}
namespace AP
{
AP_Filesystem &FS()
{
return fs;
}
}