CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Filesystem/AP_Filesystem.cpp
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
16
#include "AP_Filesystem.h"
17
18
#include "AP_Filesystem_config.h"
19
20
#if AP_FILESYSTEM_FILE_READING_ENABLED
21
22
#include <AP_HAL/HAL.h>
23
#include <AP_HAL/Util.h>
24
#include <AP_Math/AP_Math.h>
25
26
static AP_Filesystem fs;
27
28
// create exactly one "local" filesystem:
29
#if AP_FILESYSTEM_FATFS_ENABLED
30
#include "AP_Filesystem_FATFS.h"
31
static AP_Filesystem_FATFS fs_local;
32
#elif AP_FILESYSTEM_ESP32_ENABLED
33
#include "AP_Filesystem_ESP32.h"
34
static AP_Filesystem_ESP32 fs_local;
35
#elif AP_FILESYSTEM_POSIX_ENABLED
36
#include "AP_Filesystem_posix.h"
37
static AP_Filesystem_Posix fs_local;
38
#else
39
static AP_Filesystem_Backend fs_local;
40
int errno;
41
#endif
42
43
#if AP_FILESYSTEM_ROMFS_ENABLED
44
#include "AP_Filesystem_ROMFS.h"
45
static AP_Filesystem_ROMFS fs_romfs;
46
#endif
47
48
#if AP_FILESYSTEM_PARAM_ENABLED
49
#include "AP_Filesystem_Param.h"
50
static AP_Filesystem_Param fs_param;
51
#endif
52
53
#if AP_FILESYSTEM_SYS_ENABLED
54
#include "AP_Filesystem_Sys.h"
55
static AP_Filesystem_Sys fs_sys;
56
#endif
57
58
#if AP_FILESYSTEM_MISSION_ENABLED
59
#include "AP_Filesystem_Mission.h"
60
static AP_Filesystem_Mission fs_mission;
61
#endif
62
63
/*
64
mapping from filesystem prefix to backend
65
*/
66
const AP_Filesystem::Backend AP_Filesystem::backends[] = {
67
{ nullptr, fs_local },
68
#if AP_FILESYSTEM_ROMFS_ENABLED
69
{ "@ROMFS", fs_romfs },
70
#endif
71
#if AP_FILESYSTEM_PARAM_ENABLED
72
{ "@PARAM", fs_param },
73
#endif
74
#if AP_FILESYSTEM_SYS_ENABLED
75
{ "@SYS", fs_sys },
76
#endif
77
#if AP_FILESYSTEM_MISSION_ENABLED
78
{ "@MISSION", fs_mission },
79
#endif
80
};
81
82
extern const AP_HAL::HAL& hal;
83
84
#define MAX_FD_PER_BACKEND 256U
85
#define NUM_BACKENDS ARRAY_SIZE(backends)
86
#define LOCAL_BACKEND backends[0]
87
#define BACKEND_IDX(backend) (&(backend) - &backends[0])
88
89
/*
90
find backend by path
91
*/
92
const AP_Filesystem::Backend &AP_Filesystem::backend_by_path(const char *&path) const
93
{
94
// ignore leading slashes:
95
const char *path_with_no_leading_slash = path;
96
if (path_with_no_leading_slash[0] == '/') {
97
path_with_no_leading_slash = &path_with_no_leading_slash[1];
98
}
99
for (uint8_t i=1; i<NUM_BACKENDS; i++) {
100
const uint8_t plen = strlen(backends[i].prefix);
101
if (strncmp(path_with_no_leading_slash, backends[i].prefix, plen) == 0) {
102
path = path_with_no_leading_slash;
103
path += plen;
104
if (strlen(path) > 0 && path[0] == '/') {
105
path++;
106
}
107
return backends[i];
108
}
109
}
110
// default to local filesystem
111
return LOCAL_BACKEND;
112
}
113
114
/*
115
return backend by file descriptor
116
*/
117
const AP_Filesystem::Backend &AP_Filesystem::backend_by_fd(int &fd) const
118
{
119
if (fd < 0 || uint32_t(fd) >= NUM_BACKENDS*MAX_FD_PER_BACKEND) {
120
return LOCAL_BACKEND;
121
}
122
const uint8_t idx = uint32_t(fd) / MAX_FD_PER_BACKEND;
123
fd -= idx * MAX_FD_PER_BACKEND;
124
return backends[idx];
125
}
126
127
int AP_Filesystem::open(const char *fname, int flags, bool allow_absolute_paths)
128
{
129
const Backend &backend = backend_by_path(fname);
130
int fd = backend.fs.open(fname, flags, allow_absolute_paths);
131
if (fd < 0) {
132
return -1;
133
}
134
if (uint32_t(fd) >= MAX_FD_PER_BACKEND) {
135
backend.fs.close(fd);
136
errno = ERANGE;
137
return -1;
138
}
139
// offset fd so we can recognise the backend
140
const uint8_t idx = (&backend - &backends[0]);
141
fd += idx * MAX_FD_PER_BACKEND;
142
return fd;
143
}
144
145
int AP_Filesystem::close(int fd)
146
{
147
const Backend &backend = backend_by_fd(fd);
148
return backend.fs.close(fd);
149
}
150
151
int32_t AP_Filesystem::read(int fd, void *buf, uint32_t count)
152
{
153
const Backend &backend = backend_by_fd(fd);
154
return backend.fs.read(fd, buf, count);
155
}
156
157
int32_t AP_Filesystem::write(int fd, const void *buf, uint32_t count)
158
{
159
const Backend &backend = backend_by_fd(fd);
160
return backend.fs.write(fd, buf, count);
161
}
162
163
int AP_Filesystem::fsync(int fd)
164
{
165
const Backend &backend = backend_by_fd(fd);
166
return backend.fs.fsync(fd);
167
}
168
169
int32_t AP_Filesystem::lseek(int fd, int32_t offset, int seek_from)
170
{
171
const Backend &backend = backend_by_fd(fd);
172
return backend.fs.lseek(fd, offset, seek_from);
173
}
174
175
int AP_Filesystem::stat(const char *pathname, struct stat *stbuf)
176
{
177
const Backend &backend = backend_by_path(pathname);
178
return backend.fs.stat(pathname, stbuf);
179
}
180
181
int AP_Filesystem::unlink(const char *pathname)
182
{
183
const Backend &backend = backend_by_path(pathname);
184
return backend.fs.unlink(pathname);
185
}
186
187
int AP_Filesystem::mkdir(const char *pathname)
188
{
189
const Backend &backend = backend_by_path(pathname);
190
return backend.fs.mkdir(pathname);
191
}
192
193
int AP_Filesystem::rename(const char *oldpath, const char *newpath)
194
{
195
const Backend &oldbackend = backend_by_path(oldpath);
196
197
// Don't need the backend again, but we also need to remove the backend pre-fix from the new path.
198
const Backend &newbackend = backend_by_path(newpath);
199
200
// Don't try and rename between backends.
201
if (&oldbackend != &newbackend) {
202
return -1;
203
}
204
205
return oldbackend.fs.rename(oldpath, newpath);
206
}
207
208
AP_Filesystem::DirHandle *AP_Filesystem::opendir(const char *pathname)
209
{
210
// support reading a list of "@" filesystems (e.g. @SYS) in
211
// listing of root directory. Note that backend_by_path modifies
212
// its parameter.
213
if (strlen(pathname) == 0 ||
214
(strlen(pathname) == 1 && pathname[0] == '/')) {
215
virtual_dirent.backend_ofs = 0;
216
virtual_dirent.d_off = 0;
217
#if AP_FILESYSTEM_HAVE_DIRENT_DTYPE
218
virtual_dirent.de.d_type = DT_DIR;
219
#endif
220
} else {
221
virtual_dirent.backend_ofs = 255;
222
}
223
224
const Backend &backend = backend_by_path(pathname);
225
DirHandle *h = NEW_NOTHROW DirHandle;
226
if (!h) {
227
return nullptr;
228
}
229
h->dir = backend.fs.opendir(pathname);
230
if (h->dir == nullptr) {
231
delete h;
232
return nullptr;
233
}
234
h->fs_index = BACKEND_IDX(backend);
235
236
return h;
237
}
238
239
struct dirent *AP_Filesystem::readdir(DirHandle *dirp)
240
{
241
if (!dirp) {
242
return nullptr;
243
}
244
const Backend &backend = backends[dirp->fs_index];
245
struct dirent * ret = backend.fs.readdir(dirp->dir);
246
if (ret != nullptr) {
247
return ret;
248
}
249
250
// virtual directory entries in the root directory (e.g. @SYS, @MISSION)
251
for (; ret == nullptr && virtual_dirent.backend_ofs < ARRAY_SIZE(AP_Filesystem::backends); virtual_dirent.backend_ofs++) {
252
const char *prefix = backends[virtual_dirent.backend_ofs].prefix;
253
if (prefix == nullptr) {
254
continue;
255
}
256
if (prefix[0] != '@') {
257
continue;
258
}
259
260
// only return @ entries in root if we can successfully opendir them:
261
auto *d = backends[virtual_dirent.backend_ofs].fs.opendir("");
262
if (d == nullptr) {
263
continue;
264
}
265
backends[virtual_dirent.backend_ofs].fs.closedir(d);
266
267
// found a virtual directory we haven't returned yet
268
strncpy_noterm(virtual_dirent.de.d_name, prefix, sizeof(virtual_dirent.de.d_name));
269
virtual_dirent.d_off++;
270
ret = &virtual_dirent.de;
271
}
272
return ret;
273
}
274
275
int AP_Filesystem::closedir(DirHandle *dirp)
276
{
277
if (!dirp) {
278
return -1;
279
}
280
const Backend &backend = backends[dirp->fs_index];
281
int ret = backend.fs.closedir(dirp->dir);
282
delete dirp;
283
return ret;
284
}
285
286
// return free disk space in bytes
287
int64_t AP_Filesystem::disk_free(const char *path)
288
{
289
const Backend &backend = backend_by_path(path);
290
return backend.fs.disk_free(path);
291
}
292
293
// return total disk space in bytes
294
int64_t AP_Filesystem::disk_space(const char *path)
295
{
296
const Backend &backend = backend_by_path(path);
297
return backend.fs.disk_space(path);
298
}
299
300
301
/*
302
set mtime on a file
303
*/
304
bool AP_Filesystem::set_mtime(const char *filename, const uint32_t mtime_sec)
305
{
306
const Backend &backend = backend_by_path(filename);
307
return backend.fs.set_mtime(filename, mtime_sec);
308
}
309
310
// if filesystem is not running then try a remount
311
bool AP_Filesystem::retry_mount(void)
312
{
313
return LOCAL_BACKEND.fs.retry_mount();
314
}
315
316
// unmount filesystem for reboot
317
void AP_Filesystem::unmount(void)
318
{
319
return LOCAL_BACKEND.fs.unmount();
320
}
321
322
/*
323
Load a file's contents into memory. Returned object must be `delete`d to free
324
the data. The data is guaranteed to be null-terminated such that it can be
325
treated as a string.
326
*/
327
FileData *AP_Filesystem::load_file(const char *filename)
328
{
329
const Backend &backend = backend_by_path(filename);
330
return backend.fs.load_file(filename);
331
}
332
333
// returns null-terminated string; cr or lf terminates line
334
bool AP_Filesystem::fgets(char *buf, uint8_t buflen, int fd)
335
{
336
const Backend &backend = backend_by_fd(fd);
337
338
// we will need to seek back to the right location at the end
339
auto offset_start = backend.fs.lseek(fd, 0, SEEK_CUR);
340
if (offset_start < 0) {
341
return false;
342
}
343
344
auto n = backend.fs.read(fd, buf, buflen);
345
if (n <= 0) {
346
return false;
347
}
348
349
uint8_t i = 0;
350
for (; i < n; i++) {
351
if (buf[i] == '\r' || buf[i] == '\n') {
352
break;
353
}
354
}
355
buf[i] = '\0';
356
357
// get back to the right offset
358
if (backend.fs.lseek(fd, offset_start+i+1, SEEK_SET) != offset_start+i+1) {
359
// we need to fail if we can't seek back or the caller may loop or get corrupt data
360
return false;
361
}
362
363
return true;
364
}
365
366
// run crc32 over file with given name, returns true if successful
367
bool AP_Filesystem::crc32(const char *fname, uint32_t& checksum)
368
{
369
// Ensure value is initialized
370
checksum = 0;
371
372
// Open file in readonly mode
373
int fd = open(fname, O_RDONLY);
374
if (fd == -1) {
375
return false;
376
}
377
378
// Buffer to store data temporarily
379
const ssize_t buff_len = 64;
380
uint8_t buf[buff_len];
381
382
// Read into buffer and run crc
383
ssize_t read_size;
384
do {
385
read_size = read(fd, buf, buff_len);
386
if (read_size == -1) {
387
// Read error, note that we have changed the checksum value in this case
388
close(fd);
389
return false;
390
}
391
checksum = crc_crc32(checksum, buf, MIN(read_size, buff_len));
392
} while (read_size > 0);
393
394
close(fd);
395
396
return true;
397
}
398
399
400
#if AP_FILESYSTEM_FORMAT_ENABLED
401
// format filesystem
402
bool AP_Filesystem::format(void)
403
{
404
if (hal.util->get_soft_armed()) {
405
return false;
406
}
407
return LOCAL_BACKEND.fs.format();
408
}
409
AP_Filesystem_Backend::FormatStatus AP_Filesystem::get_format_status(void) const
410
{
411
return LOCAL_BACKEND.fs.get_format_status();
412
}
413
#endif
414
415
/*
416
stat wrapper for scripting
417
*/
418
bool AP_Filesystem::stat(const char *pathname, stat_t &stbuf)
419
{
420
struct stat st;
421
if (fs.stat(pathname, &st) != 0) {
422
return false;
423
}
424
stbuf.size = st.st_size;
425
stbuf.mode = st.st_mode;
426
// these wrap in 2038
427
stbuf.atime = st.st_atime;
428
stbuf.ctime = st.st_ctime;
429
stbuf.mtime = st.st_mtime;
430
return true;
431
}
432
433
// get_singleton for scripting
434
AP_Filesystem *AP_Filesystem::get_singleton(void)
435
{
436
return &fs;
437
}
438
439
namespace AP
440
{
441
AP_Filesystem &FS()
442
{
443
return fs;
444
}
445
}
446
447
#endif // AP_FILESYSTEM_FILE_READING_ENABLED
448
449