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