Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Filesystem/AP_Filesystem_FlashMemory_LittleFS.cpp
4232 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
ArduPilot filesystem interface for systems using the LittleFS filesystem in
17
flash memory
18
19
Original littlefs integration by Tamas Nepusz <[email protected]>
20
Further development by Andy Piper <[email protected]>
21
*/
22
#include "AP_Filesystem_config.h"
23
24
#if AP_FILESYSTEM_LITTLEFS_ENABLED
25
26
#include "AP_Filesystem.h"
27
#include "AP_Filesystem_FlashMemory_LittleFS.h"
28
#include <GCS_MAVLink/GCS.h>
29
#include <AP_RTC/AP_RTC.h>
30
31
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
32
#include "bd/lfs_filebd.h"
33
#include <cstdio>
34
#endif
35
36
//#define AP_LFS_DEBUG
37
#ifdef AP_LFS_DEBUG
38
#define debug(fmt, args ...) do {hal.console->printf("%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
39
#else
40
#define debug(fmt, args ...)
41
#endif
42
43
#define ENSURE_MOUNTED() do { if (!mounted && !mount_filesystem()) { errno = EIO; return -1; }} while (0)
44
#define ENSURE_MOUNTED_NULL() do { if (!mounted && !mount_filesystem()) { errno = EIO; return nullptr; }} while (0)
45
#define LFS_CHECK(func) do { int __retval = func; if (__retval < 0) { errno = errno_from_lfs_error(__retval); return -1; }} while (0)
46
#define LFS_CHECK_NULL(func) do { int __retval = func; if (__retval < 0) { errno = errno_from_lfs_error(__retval); return nullptr; }} while (0)
47
#define LFS_ATTR_MTIME 'M'
48
49
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
50
static int flashmem_read(
51
const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,
52
void* buffer, lfs_size_t size
53
);
54
static int flashmem_prog(
55
const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,
56
const void* buffer, lfs_size_t size
57
);
58
static int flashmem_erase(const struct lfs_config *cfg, lfs_block_t block);
59
static int flashmem_sync(const struct lfs_config *cfg);
60
#endif
61
static int errno_from_lfs_error(int lfs_error);
62
static int lfs_flags_from_flags(int flags);
63
64
const extern AP_HAL::HAL& hal;
65
66
int AP_Filesystem_FlashMemory_LittleFS::open(const char *pathname, int flags, bool allow_absolute_path)
67
{
68
FS_CHECK_ALLOWED(-1);
69
WITH_SEMAPHORE(fs_sem);
70
71
ENSURE_MOUNTED();
72
73
int fd = allocate_fd();
74
if (fd < 0) {
75
return -1;
76
}
77
78
FileDescriptor* fp = lfs_file_from_fd(fd);
79
if (fp == nullptr) {
80
return -1;
81
}
82
83
// file is closed, see if we already have a modification time
84
if (lfs_getattr(&fs, pathname, LFS_ATTR_MTIME, &fp->mtime, sizeof(fp->mtime)) != sizeof(fp->mtime)) {
85
// no attribute, populate from RTC
86
uint64_t utc_usec = 0;
87
AP::rtc().get_utc_usec(utc_usec);
88
fp->mtime = utc_usec/(1000U*1000U);
89
}
90
91
// populate the file config with the mtime attribute, will get written out on first sync or close
92
fp->cfg.attrs = fp->attrs;
93
fp->cfg.attr_count = 1;
94
fp->attrs[0] = {
95
.type = LFS_ATTR_MTIME,
96
.buffer = &fp->mtime,
97
.size = sizeof(fp->mtime)
98
};
99
fp->filename = strdup(pathname);
100
if (fp->filename == nullptr) {
101
errno = ENOMEM;
102
free_fd(fd);
103
return -1;
104
}
105
106
int retval = lfs_file_opencfg(&fs, &fp->file, pathname, lfs_flags_from_flags(flags), &fp->cfg);
107
108
if (retval < 0) {
109
errno = errno_from_lfs_error(retval);
110
free_fd(fd);
111
return -1;
112
}
113
114
115
return fd;
116
}
117
118
int AP_Filesystem_FlashMemory_LittleFS::close(int fileno)
119
{
120
FS_CHECK_ALLOWED(-1);
121
WITH_SEMAPHORE(fs_sem);
122
123
FileDescriptor* fp = lfs_file_from_fd(fileno);
124
if (fp == nullptr) {
125
return -1;
126
}
127
128
int retval = lfs_file_close(&fs, &(fp->file));
129
if (retval < 0) {
130
free_fd(fileno); // ignore error code, we have something else to report
131
errno = errno_from_lfs_error(retval);
132
return -1;
133
}
134
135
if (free_fd(fileno) < 0) {
136
return -1;
137
}
138
139
return 0;
140
}
141
142
int32_t AP_Filesystem_FlashMemory_LittleFS::read(int fd, void *buf, uint32_t count)
143
{
144
FS_CHECK_ALLOWED(-1);
145
WITH_SEMAPHORE(fs_sem);
146
ENSURE_MOUNTED();
147
148
FileDescriptor* fp = lfs_file_from_fd(fd);
149
if (fp == nullptr) {
150
return -1;
151
}
152
153
lfs_ssize_t read = lfs_file_read(&fs, &(fp->file), buf, count);
154
if (read < 0) {
155
errno = errno_from_lfs_error(read);
156
return -1;
157
}
158
159
return read;
160
}
161
162
int32_t AP_Filesystem_FlashMemory_LittleFS::write(int fd, const void *buf, uint32_t count)
163
{
164
FS_CHECK_ALLOWED(-1);
165
WITH_SEMAPHORE(fs_sem);
166
ENSURE_MOUNTED();
167
168
FileDescriptor* fp = lfs_file_from_fd(fd);
169
if (fp == nullptr) {
170
return -1;
171
}
172
173
lfs_ssize_t written = lfs_file_write(&fs, &(fp->file), buf, count);
174
if (written < 0) {
175
errno = errno_from_lfs_error(written);
176
return -1;
177
}
178
179
return written;
180
}
181
182
int AP_Filesystem_FlashMemory_LittleFS::fsync(int fd)
183
{
184
FS_CHECK_ALLOWED(-1);
185
WITH_SEMAPHORE(fs_sem);
186
ENSURE_MOUNTED();
187
188
FileDescriptor* fp = lfs_file_from_fd(fd);
189
if (fp == nullptr) {
190
return -1;
191
}
192
193
if (fp->file.off != fs_cfg.block_size) {
194
debug("misaligned fsync: %lu\n", fp->file.off);
195
}
196
197
LFS_CHECK(lfs_file_sync(&fs, &(fp->file)));
198
return 0;
199
}
200
201
int32_t AP_Filesystem_FlashMemory_LittleFS::lseek(int fd, int32_t position, int whence)
202
{
203
FS_CHECK_ALLOWED(-1);
204
WITH_SEMAPHORE(fs_sem);
205
ENSURE_MOUNTED();
206
207
FileDescriptor* fp = lfs_file_from_fd(fd);
208
if (fp == nullptr) {
209
return -1;
210
}
211
212
int lfs_whence;
213
switch (whence) {
214
case SEEK_END:
215
lfs_whence = LFS_SEEK_SET;
216
break;
217
case SEEK_CUR:
218
lfs_whence = LFS_SEEK_CUR;
219
break;
220
case SEEK_SET:
221
default:
222
lfs_whence = LFS_SEEK_SET;
223
break;
224
}
225
226
lfs_soff_t pos = lfs_file_seek(&fs, &(fp->file), position, lfs_whence);
227
if (pos < 0) {
228
errno = errno_from_lfs_error(pos);
229
return -1;
230
}
231
232
return pos;
233
}
234
235
int AP_Filesystem_FlashMemory_LittleFS::stat(const char *name, struct stat *buf)
236
{
237
FS_CHECK_ALLOWED(-1);
238
WITH_SEMAPHORE(fs_sem);
239
ENSURE_MOUNTED();
240
241
lfs_info info;
242
LFS_CHECK(lfs_stat(&fs, name, &info));
243
244
memset(buf, 0, sizeof(*buf));
245
uint32_t mtime;
246
if (lfs_getattr(&fs, name, LFS_ATTR_MTIME, &mtime, sizeof(mtime)) == sizeof(mtime)) {
247
buf->st_mtime = mtime;
248
buf->st_atime = mtime;
249
buf->st_ctime = mtime;
250
}
251
buf->st_mode = (info.type == LFS_TYPE_DIR ? S_IFDIR : S_IFREG) | 0666;
252
buf->st_nlink = 1;
253
buf->st_size = info.size;
254
buf->st_blksize = fs_cfg.read_size;
255
buf->st_uid=1000;
256
buf->st_gid=1000;
257
buf->st_blocks = (info.size >> 9) + ((info.size & 0x1FF) > 0 ? 1 : 0);
258
259
return 0;
260
}
261
262
// set modification time on a file
263
bool AP_Filesystem_FlashMemory_LittleFS::set_mtime(const char *filename, const uint32_t mtime_sec)
264
{
265
// unfortunately lfs_setattr will not work while the file is open, instead
266
// we need to update the file config, but that means finding the file config
267
for (int fd = 0; fd < MAX_OPEN_FILES; fd++) {
268
if (open_files[fd] != nullptr && strcmp(open_files[fd]->filename, filename) == 0) {
269
open_files[fd]->mtime = mtime_sec;
270
return true;
271
}
272
}
273
return false;
274
}
275
276
int AP_Filesystem_FlashMemory_LittleFS::unlink(const char *pathname)
277
{
278
FS_CHECK_ALLOWED(-1);
279
WITH_SEMAPHORE(fs_sem);
280
ENSURE_MOUNTED();
281
LFS_CHECK(lfs_remove(&fs, pathname));
282
return 0;
283
}
284
285
int AP_Filesystem_FlashMemory_LittleFS::mkdir(const char *pathname)
286
{
287
FS_CHECK_ALLOWED(-1);
288
WITH_SEMAPHORE(fs_sem);
289
ENSURE_MOUNTED();
290
LFS_CHECK(lfs_mkdir(&fs, pathname));
291
return 0;
292
}
293
294
295
struct DirEntry {
296
lfs_dir_t dir;
297
struct dirent entry;
298
};
299
300
void *AP_Filesystem_FlashMemory_LittleFS::opendir(const char *pathdir)
301
{
302
FS_CHECK_ALLOWED(nullptr);
303
WITH_SEMAPHORE(fs_sem);
304
ENSURE_MOUNTED_NULL();
305
306
DirEntry *result = NEW_NOTHROW DirEntry;
307
if (!result) {
308
errno = ENOMEM;
309
return nullptr;
310
}
311
312
int retval = lfs_dir_open(&fs, &result->dir, pathdir);
313
if (retval < 0) {
314
delete result;
315
errno = errno_from_lfs_error(retval);
316
return nullptr;
317
}
318
319
memset(&result->entry, 0, sizeof(result->entry));
320
321
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX || CONFIG_HAL_BOARD == HAL_BOARD_SITL
322
result->entry.d_reclen = sizeof(result->entry);
323
#endif
324
325
// LittleFS has issues with opendir where filesystem operations that trigger
326
// writes while a directory is open can break the iteration and cause
327
// LittleFS to report filesystem corruption. We hope readdir loops don't do
328
// writes (none do in ArduPilot at the time of writing), but also take the
329
// lock again so other threads can't write until the corresponding release
330
// in closedir. This is safe here since the lock is recursive; recursion
331
// also lets the thread with the directory open do reads. Hopefully this
332
// will be fixed upstream so we can remove this quirk.
333
fs_sem.take_blocking();
334
335
return result;
336
}
337
338
#pragma GCC diagnostic push
339
#pragma GCC diagnostic ignored "-Wstringop-truncation"
340
struct dirent *AP_Filesystem_FlashMemory_LittleFS::readdir(void *ptr)
341
{
342
FS_CHECK_ALLOWED(nullptr);
343
WITH_SEMAPHORE(fs_sem);
344
345
DirEntry *pair = static_cast<DirEntry*>(ptr);
346
if (!pair) {
347
errno = EINVAL;
348
return nullptr;
349
}
350
351
lfs_info info;
352
int retval = lfs_dir_read(&fs, &pair->dir, &info);
353
if (retval == 0) {
354
/* no more entries */
355
return nullptr;
356
}
357
if (retval < 0) {
358
// failure
359
errno = errno_from_lfs_error(retval);
360
return nullptr;
361
}
362
363
memset(&pair->entry, 0, sizeof(pair->entry));
364
365
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
366
pair->entry.d_ino = 0;
367
pair->entry.d_seekoff++;
368
#endif
369
370
strncpy(pair->entry.d_name, info.name, MIN(strlen(info.name)+1, sizeof(pair->entry.d_name)));
371
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
372
pair->entry.d_namlen = strlen(info.name);
373
#endif
374
375
pair->entry.d_type = info.type == LFS_TYPE_DIR ? DT_DIR : DT_REG;
376
377
return &pair->entry;
378
}
379
#pragma GCC diagnostic pop
380
381
int AP_Filesystem_FlashMemory_LittleFS::closedir(void *ptr)
382
{
383
FS_CHECK_ALLOWED(-1);
384
WITH_SEMAPHORE(fs_sem);
385
386
DirEntry *pair = static_cast<DirEntry*>(ptr);
387
if (!pair) {
388
errno = EINVAL;
389
return 0;
390
}
391
392
// Before the close, undo the lock we did in opendir so it's released even
393
// if the close fails. We don't undo it above, as the input being nullptr
394
// means we didn't successfully open the directory and lock.
395
fs_sem.give();
396
397
int retval = lfs_dir_close(&fs, &pair->dir);
398
delete pair;
399
400
if (retval < 0) {
401
errno = errno_from_lfs_error(retval);
402
return -1;
403
}
404
405
return 0;
406
}
407
408
// return number of bytes that should be written before fsync for optimal
409
// streaming performance/robustness. if zero, any number can be written.
410
// LittleFS needs to copy the block contents to a new one if fsync is called
411
// in the middle of a block. LittleFS also is guaranteed to not remember any
412
// file contents until fsync is called!
413
uint32_t AP_Filesystem_FlashMemory_LittleFS::bytes_until_fsync(int fd)
414
{
415
FS_CHECK_ALLOWED(0);
416
WITH_SEMAPHORE(fs_sem);
417
418
FileDescriptor* fp = lfs_file_from_fd(fd);
419
if (!mounted || fp == nullptr) {
420
return 0;
421
}
422
423
uint32_t file_pos = fp->file.pos;
424
uint32_t block_size = fs_cfg.block_size;
425
426
// first block exclusively stores data:
427
// https://github.com/littlefs-project/littlefs/issues/564#issuecomment-2555733922
428
if (file_pos < block_size) {
429
return block_size - file_pos; // so block_offset is exactly file_pos
430
}
431
432
// see https://github.com/littlefs-project/littlefs/issues/564#issuecomment-2363032827
433
// n = (N − w/8 ( popcount( N/(B − 2w/8) − 1) + 2))/(B − 2w/8))
434
// off = N − ( B − 2w/8 ) n − w/8popcount( n )
435
#define BLOCK_INDEX(N, B) \
436
(N - sizeof(uint32_t) * (__builtin_popcount(N/(B - 2 * sizeof(uint32_t)) -1) + 2))/(B - 2 * sizeof(uint32_t))
437
438
#define BLOCK_OFFSET(N, B, n) \
439
(N - (B - 2*sizeof(uint32_t)) * n - sizeof(uint32_t) * __builtin_popcount(n))
440
441
uint32_t block_index = BLOCK_INDEX(file_pos, block_size);
442
// offset will be 4 (or bigger) through (block_size-1) as subsequent blocks
443
// start with one or more pointers; offset will never equal block_size
444
uint32_t block_offset = BLOCK_OFFSET(file_pos, block_size, block_index);
445
446
#undef BLOCK_INDEX
447
#undef BLOCK_OFFSET
448
449
return block_size - block_offset;
450
}
451
452
453
int64_t AP_Filesystem_FlashMemory_LittleFS::disk_free(const char *path)
454
{
455
FS_CHECK_ALLOWED(-1);
456
WITH_SEMAPHORE(fs_sem);
457
ENSURE_MOUNTED();
458
459
lfs_ssize_t alloc_size = lfs_fs_size(&fs);
460
if (alloc_size < 0) {
461
errno = errno_from_lfs_error(alloc_size);
462
return -1;
463
}
464
465
return disk_space(path) - alloc_size;
466
}
467
468
int64_t AP_Filesystem_FlashMemory_LittleFS::disk_space(const char *path)
469
{
470
return fs_cfg.block_count * fs_cfg.block_size;
471
}
472
473
bool AP_Filesystem_FlashMemory_LittleFS::retry_mount(void)
474
{
475
FS_CHECK_ALLOWED(false);
476
WITH_SEMAPHORE(fs_sem);
477
478
if (!dead) {
479
if (!mounted && !mount_filesystem()) {
480
errno = EIO;
481
return false;
482
}
483
484
return true;
485
} else {
486
return false;
487
}
488
}
489
490
void AP_Filesystem_FlashMemory_LittleFS::unmount(void)
491
{
492
WITH_SEMAPHORE(fs_sem);
493
494
if (mounted && !dead) {
495
free_all_fds();
496
lfs_unmount(&fs);
497
mounted = false;
498
}
499
}
500
501
/* ************************************************************************* */
502
/* Private functions */
503
/* ************************************************************************* */
504
505
int AP_Filesystem_FlashMemory_LittleFS::allocate_fd()
506
{
507
for (int fd = 0; fd < MAX_OPEN_FILES; fd++) {
508
if (open_files[fd] == nullptr) {
509
open_files[fd] = static_cast<FileDescriptor*>(calloc(1, sizeof(FileDescriptor)));
510
if (open_files[fd] == nullptr) {
511
errno = ENOMEM;
512
return -1;
513
}
514
515
return fd;
516
}
517
}
518
519
errno = ENFILE;
520
return -1;
521
}
522
523
int AP_Filesystem_FlashMemory_LittleFS::free_fd(int fd)
524
{
525
FileDescriptor* fp = lfs_file_from_fd(fd);
526
if (!fp) {
527
return -1;
528
}
529
530
free(fp->filename);
531
free(fp);
532
open_files[fd] = nullptr;
533
534
return 0;
535
}
536
537
void AP_Filesystem_FlashMemory_LittleFS::free_all_fds()
538
{
539
for (int fd = 0; fd < MAX_OPEN_FILES; fd++) {
540
if (open_files[fd] != nullptr) {
541
free_fd(fd);
542
}
543
}
544
}
545
546
AP_Filesystem_FlashMemory_LittleFS::FileDescriptor* AP_Filesystem_FlashMemory_LittleFS::lfs_file_from_fd(int fd) const
547
{
548
if (fd < 0 || fd >= MAX_OPEN_FILES || open_files[fd] == nullptr) {
549
errno = EBADF;
550
return nullptr;
551
}
552
553
return open_files[fd];
554
}
555
556
void AP_Filesystem_FlashMemory_LittleFS::mark_dead()
557
{
558
if (!dead) {
559
printf("FlashMemory_LittleFS: dead\n");
560
free_all_fds();
561
dead = true;
562
}
563
}
564
565
/* ************************************************************************* */
566
/* Low-level flash memory access */
567
/* ************************************************************************* */
568
569
#define JEDEC_WRITE_ENABLE 0x06
570
#define JEDEC_READ_STATUS 0x05
571
#define JEDEC_WRITE_STATUS 0x01
572
#define JEDEC_READ_DATA 0x03
573
#define JEDEC_PAGE_DATA_READ 0x13
574
#define JEDEC_DEVICE_ID 0x9F
575
#define JEDEC_PAGE_WRITE 0x02
576
#define JEDEC_PROGRAM_EXECUTE 0x10
577
578
#define JEDEC_DEVICE_RESET 0xFF
579
580
#define JEDEC_BULK_ERASE 0xC7
581
#define JEDEC_SECTOR4_ERASE 0x20 // 4k erase
582
#define JEDEC_BLOCK_ERASE 0xD8
583
584
#define JEDEC_STATUS_BUSY 0x01
585
#define JEDEC_STATUS_WRITEPROTECT 0x02
586
#define JEDEC_STATUS_BP0 0x04
587
#define JEDEC_STATUS_BP1 0x08
588
#define JEDEC_STATUS_BP2 0x10
589
#define JEDEC_STATUS_TP 0x20
590
#define JEDEC_STATUS_SEC 0x40
591
#define JEDEC_STATUS_SRP0 0x80
592
593
#define W25NXX_STATUS_EFAIL 0x04
594
#define W25NXX_STATUS_PFAIL 0x08
595
596
597
/*
598
flash device IDs taken from betaflight flash_m25p16.c
599
600
Format is manufacturer, memory type, then capacity
601
*/
602
#define JEDEC_ID_UNKNOWN 0x000000
603
#define JEDEC_ID_MACRONIX_MX25L3206E 0xC22016
604
#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
605
#define JEDEC_ID_MACRONIX_MX25L25635E 0xC22019
606
#define JEDEC_ID_MICRON_M25P16 0x202015
607
#define JEDEC_ID_MICRON_N25Q064 0x20BA17
608
#define JEDEC_ID_MICRON_N25Q128 0x20BA18
609
#define JEDEC_ID_WINBOND_W25Q16 0xEF4015
610
#define JEDEC_ID_WINBOND_W25Q32 0xEF4016
611
#define JEDEC_ID_WINBOND_W25X32 0xEF3016
612
#define JEDEC_ID_WINBOND_W25Q64 0xEF4017
613
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
614
#define JEDEC_ID_WINBOND_W25Q256 0xEF4019
615
#define JEDEC_ID_WINBOND_W25Q128_2 0xEF7018
616
#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21
617
#define JEDEC_ID_WINBOND_W25N02KV 0xEFAA22
618
#define JEDEC_ID_CYPRESS_S25FL128L 0x016018
619
#define JEDEC_ID_GIGA_GD25Q16E 0xC84015
620
621
/* Hardware-specific constants */
622
623
#define W25NXX_PROT_REG 0xA0
624
#define W25NXX_CONF_REG 0xB0
625
#define W25NXX_STATUS_REG 0xC0
626
#define W25NXX_STATUS_EFAIL 0x04
627
#define W25NXX_STATUS_PFAIL 0x08
628
629
#define W25N01G_NUM_BLOCKS 1024
630
#define W25N02K_NUM_BLOCKS 2048
631
632
#define W25NXX_CONFIG_ECC_ENABLE (1 << 4)
633
#define W25NXX_CONFIG_BUFFER_READ_MODE (1 << 3)
634
635
#define W25NXX_TIMEOUT_PAGE_READ_US 60 // tREmax = 60us (ECC enabled)
636
#define W25NXX_TIMEOUT_PAGE_PROGRAM_US 700 // tPPmax = 700us
637
#define W25NXX_TIMEOUT_BLOCK_ERASE_MS 10 // tBEmax = 10ms
638
#define W25NXX_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms
639
640
bool AP_Filesystem_FlashMemory_LittleFS::is_busy()
641
{
642
WITH_SEMAPHORE(dev_sem);
643
uint8_t status;
644
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
645
uint8_t cmd[2] { JEDEC_READ_STATUS, W25NXX_STATUS_REG };
646
dev->transfer(cmd, 2, &status, 1);
647
return (status & (JEDEC_STATUS_BUSY | W25NXX_STATUS_PFAIL | W25NXX_STATUS_EFAIL)) != 0;
648
#else
649
uint8_t cmd = JEDEC_READ_STATUS;
650
dev->transfer(&cmd, 1, &status, 1);
651
return (status & (JEDEC_STATUS_BUSY | JEDEC_STATUS_SRP0)) != 0;
652
#endif
653
}
654
655
void AP_Filesystem_FlashMemory_LittleFS::send_command_addr(uint8_t command, uint32_t addr)
656
{
657
uint8_t cmd[5];
658
cmd[0] = command;
659
660
if (use_32bit_address) {
661
cmd[1] = (addr >> 24) & 0xff;
662
cmd[2] = (addr >> 16) & 0xff;
663
cmd[3] = (addr >> 8) & 0xff;
664
cmd[4] = (addr >> 0) & 0xff;
665
} else {
666
cmd[1] = (addr >> 16) & 0xff;
667
cmd[2] = (addr >> 8) & 0xff;
668
cmd[3] = (addr >> 0) & 0xff;
669
cmd[4] = 0;
670
}
671
672
dev->transfer(cmd, use_32bit_address ? 5 : 4, nullptr, 0);
673
}
674
675
void AP_Filesystem_FlashMemory_LittleFS::send_command_page(uint8_t command, uint32_t page)
676
{
677
uint8_t cmd[3];
678
cmd[0] = command;
679
cmd[1] = (page >> 8) & 0xff;
680
cmd[2] = (page >> 0) & 0xff;
681
dev->transfer(cmd, 3, nullptr, 0);
682
}
683
684
bool AP_Filesystem_FlashMemory_LittleFS::wait_until_device_is_ready()
685
{
686
if (dead) {
687
return false;
688
}
689
690
uint32_t t = AP_HAL::millis();
691
while (is_busy()) {
692
hal.scheduler->delay_microseconds(100);
693
if (AP_HAL::millis() - t > 5000) {
694
mark_dead();
695
return false;
696
}
697
}
698
699
return true;
700
}
701
702
void AP_Filesystem_FlashMemory_LittleFS::write_status_register(uint8_t reg, uint8_t bits)
703
{
704
WITH_SEMAPHORE(dev_sem);
705
uint8_t cmd[3] = { JEDEC_WRITE_STATUS, reg, bits };
706
dev->transfer(cmd, 3, nullptr, 0);
707
}
708
709
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
710
const static struct lfs_filebd_config fbd_config {
711
.read_size = 2048,
712
.prog_size = 2048,
713
.erase_size = 131072,
714
.erase_count = 256
715
};
716
#endif
717
718
uint32_t AP_Filesystem_FlashMemory_LittleFS::find_block_size_and_count() {
719
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
720
if (!wait_until_device_is_ready()) {
721
return false;
722
}
723
724
WITH_SEMAPHORE(dev_sem);
725
726
// Read manufacturer ID
727
uint8_t cmd = JEDEC_DEVICE_ID;
728
uint8_t buf[4];
729
dev->transfer(&cmd, 1, buf, 4);
730
731
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
732
uint32_t id = buf[1] << 16 | buf[2] << 8 | buf[3];
733
#else
734
uint32_t id = buf[0] << 16 | buf[1] << 8 | buf[2];
735
#endif
736
737
// Let's specify the terminology here.
738
//
739
// 1 block = smallest unit that we _erase_ in a single operation
740
// 1 page = smallest unit that we read or program in a single operation
741
//
742
// regardless of what the flash chip documentation refers to as a "block"
743
744
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
745
// these NAND chips have 2048 byte pages and 128K erase blocks
746
lfs_size_t page_size = 2048;
747
lfs_size_t block_size = 131072;
748
#else
749
// typical JEDEC-ish NOR flash chips have 256 byte pages and 64K blocks.
750
// many also support smaller erase sizes like 4K "sectors", but the largest
751
// block size is fastest to erase in bytes per second by 3-5X so we use
752
// that. be aware that worst case erase time can be seconds!
753
lfs_size_t page_size = 256;
754
lfs_size_t block_size = 65536;
755
#endif
756
757
lfs_size_t block_count;
758
switch (id) {
759
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
760
case JEDEC_ID_WINBOND_W25N01GV:
761
block_count = 1024; /* 128MiB */
762
break;
763
case JEDEC_ID_WINBOND_W25N02KV:
764
block_count = 2048; /* 256MiB */
765
break;
766
#else
767
case JEDEC_ID_WINBOND_W25Q16:
768
case JEDEC_ID_MICRON_M25P16:
769
case JEDEC_ID_GIGA_GD25Q16E:
770
block_count = 32; /* 2MiB */
771
break;
772
773
case JEDEC_ID_WINBOND_W25Q32:
774
case JEDEC_ID_WINBOND_W25X32:
775
case JEDEC_ID_MACRONIX_MX25L3206E:
776
block_count = 64; /* 4MiB */
777
break;
778
779
case JEDEC_ID_MICRON_N25Q064:
780
case JEDEC_ID_WINBOND_W25Q64:
781
case JEDEC_ID_MACRONIX_MX25L6406E:
782
block_count = 128; /* 8MiB */
783
break;
784
785
case JEDEC_ID_MICRON_N25Q128:
786
case JEDEC_ID_WINBOND_W25Q128:
787
case JEDEC_ID_WINBOND_W25Q128_2:
788
case JEDEC_ID_CYPRESS_S25FL128L:
789
block_count = 256; /* 16MiB */
790
break;
791
792
case JEDEC_ID_WINBOND_W25Q256:
793
case JEDEC_ID_MACRONIX_MX25L25635E:
794
block_count = 512; /* 32MiB */
795
use_32bit_address = true;
796
break;
797
#endif
798
default:
799
block_count = 0;
800
hal.scheduler->delay(2000);
801
printf("Unknown SPI Flash 0x%08x\n", id);
802
return 0;
803
}
804
805
fs_cfg.read_size = page_size;
806
fs_cfg.prog_size = page_size; // we assume this is equal to read_size!
807
fs_cfg.block_size = block_size;
808
fs_cfg.block_count = block_count;
809
810
// larger metadata blocks mean less frequent compaction operations, but each
811
// takes longer. however, the total time spent compacting for a given file
812
// size still goes down with larger metadata blocks. 4096 was chosen to
813
// minimize both frequency and log buffer utilization.
814
fs_cfg.metadata_max = 4096;
815
fs_cfg.compact_thresh = 4096*0.88f;
816
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
817
fs_cfg.metadata_max = page_size * 2;
818
fs_cfg.compact_thresh = fs_cfg.metadata_max * 0.88f;
819
#endif
820
#else
821
// SITL config
822
fs_cfg.read_size = 2048;
823
fs_cfg.prog_size = 2048;
824
fs_cfg.block_size = 131072;
825
fs_cfg.block_count = 256;
826
fs_cfg.metadata_max = 2048;
827
828
char lfsname[L_tmpnam];
829
uint32_t id = 0;
830
if (std::tmpnam(lfsname)) {
831
lfs_filebd_create(&fs_cfg, lfsname, &fbd_config);
832
id = 0xFAFF;
833
}
834
#endif // CONFIG_HAL_BOARD != HAL_BOARD_SITL
835
fs_cfg.block_cycles = 75000;
836
// cache entire flash state in RAM (8 blocks = 1 byte of storage) to
837
// avoid scanning while logging
838
fs_cfg.lookahead_size = fs_cfg.block_count/8;
839
// non-inlined files require their own block, but must be copie. Generally we have requirements for tiny files
840
// (scripting) and very large files (e.g. logging), but not much in-between. Setting the cache size will also
841
// limit the inline size.
842
fs_cfg.cache_size = fs_cfg.prog_size;
843
844
return id;
845
}
846
847
bool AP_Filesystem_FlashMemory_LittleFS::mount_filesystem() {
848
if (dead) {
849
return false;
850
}
851
852
if (mounted) {
853
return true;
854
}
855
856
EXPECT_DELAY_MS(3000);
857
858
fs_cfg.context = this;
859
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
860
fs_cfg.read = flashmem_read;
861
fs_cfg.prog = flashmem_prog;
862
fs_cfg.erase = flashmem_erase;
863
fs_cfg.sync = flashmem_sync;
864
865
dev = hal.spi->get_device("dataflash");
866
867
if (!dev) {
868
mark_dead();
869
return false;
870
}
871
872
dev_sem = dev->get_semaphore();
873
#else
874
fs_cfg.read = lfs_filebd_read;
875
fs_cfg.prog = lfs_filebd_prog;
876
fs_cfg.erase = lfs_filebd_erase;
877
fs_cfg.sync = lfs_filebd_sync;
878
#endif
879
880
uint32_t id = find_block_size_and_count();
881
882
if (!id) {
883
mark_dead();
884
return false;
885
}
886
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
887
if (!init_flash()) {
888
mark_dead();
889
return false;
890
}
891
#endif
892
if (lfs_mount(&fs, &fs_cfg) < 0) {
893
/* maybe not formatted? try formatting it */
894
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash");
895
896
if (lfs_format(&fs, &fs_cfg) < 0) {
897
mark_dead();
898
return false;
899
}
900
901
/* try mounting again */
902
if (lfs_mount(&fs, &fs_cfg) < 0) {
903
/* cannot mount after formatting */
904
mark_dead();
905
return false;
906
}
907
}
908
909
// try to create the root storage folder. Ignore the error code in case
910
// the filesystem is corrupted or it already exists.
911
if (strlen(HAL_BOARD_STORAGE_DIRECTORY) > 0) {
912
lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY);
913
}
914
915
// Force garbage collection to avoid expensive operations after boot
916
lfs_fs_gc(&fs);
917
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Mounted flash 0x%x as littlefs", unsigned(id));
918
mounted = true;
919
return true;
920
}
921
922
/*
923
format sdcard
924
*/
925
bool AP_Filesystem_FlashMemory_LittleFS::format(void)
926
{
927
WITH_SEMAPHORE(fs_sem);
928
hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Filesystem_FlashMemory_LittleFS::format_handler, void));
929
// the format is handled asynchronously, we inform user of success
930
// via a text message. format_status can be polled for progress
931
format_status = FormatStatus::PENDING;
932
return true;
933
}
934
935
/*
936
format sdcard
937
*/
938
void AP_Filesystem_FlashMemory_LittleFS::format_handler(void)
939
{
940
if (format_status != FormatStatus::PENDING) {
941
return;
942
}
943
WITH_SEMAPHORE(fs_sem);
944
format_status = FormatStatus::IN_PROGRESS;
945
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Formatting flash using littlefs");
946
947
int ret = lfs_format(&fs, &fs_cfg);
948
949
/* try mounting */
950
if (ret == LFS_ERR_OK) {
951
ret = lfs_mount(&fs, &fs_cfg);
952
}
953
954
// try to create the root storage folder. Ignore the error code in case
955
// the filesystem is corrupted or it already exists.
956
if (ret == LFS_ERR_OK && strlen(HAL_BOARD_STORAGE_DIRECTORY) > 0) {
957
ret = lfs_mkdir(&fs, HAL_BOARD_STORAGE_DIRECTORY);
958
}
959
960
if (ret == LFS_ERR_OK) {
961
format_status = FormatStatus::SUCCESS;
962
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: OK");
963
} else {
964
format_status = FormatStatus::FAILURE;
965
mark_dead();
966
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Format flash: Failed (%d)", int(ret));
967
}
968
}
969
970
// returns true if we are currently formatting the SD card:
971
AP_Filesystem_Backend::FormatStatus AP_Filesystem_FlashMemory_LittleFS::get_format_status(void) const
972
{
973
// note that format_handler holds sem, so we can't take it here.
974
return format_status;
975
}
976
977
bool AP_Filesystem_FlashMemory_LittleFS::write_enable()
978
{
979
uint8_t b = JEDEC_WRITE_ENABLE;
980
981
if (!wait_until_device_is_ready()) {
982
return false;
983
}
984
985
WITH_SEMAPHORE(dev_sem);
986
return dev->transfer(&b, 1, nullptr, 0);
987
}
988
989
bool AP_Filesystem_FlashMemory_LittleFS::init_flash()
990
{
991
if (!wait_until_device_is_ready()) {
992
return false;
993
}
994
995
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
996
// reset the device
997
{
998
WITH_SEMAPHORE(dev_sem);
999
uint8_t b = JEDEC_DEVICE_RESET;
1000
dev->transfer(&b, 1, nullptr, 0);
1001
}
1002
hal.scheduler->delay(W25NXX_TIMEOUT_RESET_MS);
1003
1004
// disable write protection
1005
write_status_register(W25NXX_PROT_REG, 0);
1006
1007
// enable ECC and buffer mode
1008
write_status_register(W25NXX_CONF_REG, W25NXX_CONFIG_ECC_ENABLE | W25NXX_CONFIG_BUFFER_READ_MODE);
1009
#else
1010
if (use_32bit_address) {
1011
WITH_SEMAPHORE(dev_sem);
1012
// enter 4-byte address mode
1013
const uint8_t cmd = 0xB7;
1014
dev->transfer(&cmd, 1, nullptr, 0);
1015
}
1016
#endif
1017
1018
return true;
1019
}
1020
1021
#ifdef AP_LFS_DEBUG
1022
static uint32_t page_writes;
1023
static uint32_t last_write_msg_ms;
1024
static uint32_t page_reads;
1025
static uint32_t block_erases;
1026
#endif
1027
int AP_Filesystem_FlashMemory_LittleFS::_flashmem_read(
1028
lfs_block_t block, lfs_off_t off, void* buffer, lfs_size_t size
1029
) {
1030
EXPECT_DELAY_MS((25*size)/(fs_cfg.read_size*1000));
1031
1032
// LittleFS always calls us with off aligned to read_size and size a
1033
// multiple of read_size
1034
const uint32_t page_size = fs_cfg.read_size;
1035
uint32_t num_pages = size / page_size;
1036
uint32_t address = (block * fs_cfg.block_size) + off;
1037
uint8_t* p = static_cast<uint8_t*>(buffer);
1038
1039
while (num_pages--) {
1040
#ifdef AP_LFS_DEBUG
1041
page_reads++;
1042
#endif
1043
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
1044
/* We need to read an entire page into an internal buffer and then read
1045
* that buffer with JEDEC_READ_DATA later */
1046
if (!wait_until_device_is_ready()) {
1047
return LFS_ERR_IO;
1048
}
1049
{
1050
WITH_SEMAPHORE(dev_sem);
1051
send_command_addr(JEDEC_PAGE_DATA_READ, address / page_size);
1052
}
1053
#endif
1054
if (!wait_until_device_is_ready()) {
1055
return LFS_ERR_IO;
1056
}
1057
1058
WITH_SEMAPHORE(dev_sem);
1059
1060
dev->set_chip_select(true);
1061
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
1062
send_command_addr(JEDEC_READ_DATA, 0); // read one page internal buffer
1063
#else
1064
send_command_addr(JEDEC_READ_DATA, address);
1065
#endif
1066
dev->transfer(nullptr, 0, p, page_size);
1067
dev->set_chip_select(false);
1068
1069
address += page_size;
1070
p += page_size;
1071
}
1072
return LFS_ERR_OK;
1073
}
1074
1075
1076
int AP_Filesystem_FlashMemory_LittleFS::_flashmem_prog(
1077
lfs_block_t block, lfs_off_t off, const void* buffer, lfs_size_t size
1078
) {
1079
EXPECT_DELAY_MS((250*size)/(fs_cfg.read_size*1000));
1080
1081
// LittleFS always calls us with off aligned to prog_size and size a
1082
// multiple of prog_size (which we set equal to read_size)
1083
const uint32_t page_size = fs_cfg.read_size;
1084
uint32_t num_pages = size / page_size;
1085
uint32_t address = (block * fs_cfg.block_size) + off;
1086
const uint8_t* p = static_cast<const uint8_t*>(buffer);
1087
1088
while (num_pages--) {
1089
if (!write_enable()) {
1090
return LFS_ERR_IO;
1091
}
1092
1093
#ifdef AP_LFS_DEBUG
1094
page_writes++;
1095
if (AP_HAL::millis() - last_write_msg_ms > 5000) {
1096
debug("LFS: writes %lukB/s, pages %lu/s (reads %lu/s, block erases %lu/s)",
1097
(page_writes*page_size)/(5*1024), page_writes/5, page_reads/5, block_erases/5);
1098
page_writes = 0;
1099
page_reads = 0;
1100
block_erases = 0;
1101
last_write_msg_ms = AP_HAL::millis();
1102
}
1103
#endif
1104
1105
WITH_SEMAPHORE(dev_sem);
1106
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
1107
/* First we need to write into the data buffer at column address zero,
1108
* then we need to issue PROGRAM_EXECUTE to commit the internal buffer */
1109
dev->set_chip_select(true);
1110
send_command_page(JEDEC_PAGE_WRITE, 0);
1111
dev->transfer(p, page_size, nullptr, 0);
1112
dev->set_chip_select(false);
1113
send_command_addr(JEDEC_PROGRAM_EXECUTE, address / page_size);
1114
#else
1115
dev->set_chip_select(true);
1116
send_command_addr(JEDEC_PAGE_WRITE, address);
1117
dev->transfer(p, page_size, nullptr, 0);
1118
dev->set_chip_select(false);
1119
#endif
1120
// writing simply means the data is in the internal cache, it will take
1121
// some period to propagate to the flash itself
1122
1123
address += page_size;
1124
p += page_size;
1125
}
1126
return LFS_ERR_OK;
1127
}
1128
1129
int AP_Filesystem_FlashMemory_LittleFS::_flashmem_erase(lfs_block_t block) {
1130
if (!write_enable()) {
1131
return LFS_ERR_IO;
1132
}
1133
1134
#ifdef AP_LFS_DEBUG
1135
block_erases++;
1136
#endif
1137
1138
WITH_SEMAPHORE(dev_sem);
1139
1140
#if AP_FILESYSTEM_LITTLEFS_FLASH_TYPE == AP_FILESYSTEM_FLASH_W25NXX
1141
const uint32_t pages_per_block = fs_cfg.block_size / fs_cfg.read_size;
1142
send_command_addr(JEDEC_BLOCK_ERASE, block * pages_per_block);
1143
#else
1144
send_command_addr(JEDEC_BLOCK_ERASE, block * fs_cfg.block_size);
1145
#endif
1146
1147
// sleep so that other processes get the CPU cycles that the 4ms erase cycle needs.
1148
hal.scheduler->delay(4);
1149
1150
return LFS_ERR_OK;
1151
}
1152
1153
int AP_Filesystem_FlashMemory_LittleFS::_flashmem_sync() {
1154
if (wait_until_device_is_ready()) {
1155
return LFS_ERR_OK;
1156
} else {
1157
return LFS_ERR_IO;
1158
}
1159
}
1160
1161
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
1162
static int flashmem_read(
1163
const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,
1164
void* buffer, lfs_size_t size
1165
) {
1166
AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);
1167
return self->_flashmem_read(block, off, buffer, size);
1168
}
1169
1170
static int flashmem_prog(
1171
const struct lfs_config *cfg, lfs_block_t block, lfs_off_t off,
1172
const void* buffer, lfs_size_t size
1173
) {
1174
AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);
1175
return self->_flashmem_prog(block, off, buffer, size);
1176
}
1177
1178
static int flashmem_erase(const struct lfs_config *cfg, lfs_block_t block) {
1179
AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);
1180
return self->_flashmem_erase(block);
1181
}
1182
1183
static int flashmem_sync(const struct lfs_config *cfg) {
1184
AP_Filesystem_FlashMemory_LittleFS* self = static_cast<AP_Filesystem_FlashMemory_LittleFS*>(cfg->context);
1185
return self->_flashmem_sync();
1186
}
1187
#endif
1188
1189
/* ************************************************************************* */
1190
/* LittleFS to POSIX API conversion functions */
1191
/* ************************************************************************* */
1192
1193
static int errno_from_lfs_error(int lfs_error)
1194
{
1195
switch (lfs_error) {
1196
case LFS_ERR_OK: return 0;
1197
case LFS_ERR_IO: return EIO;
1198
case LFS_ERR_CORRUPT: return EIO;
1199
case LFS_ERR_NOENT: return ENOENT;
1200
case LFS_ERR_EXIST: return EEXIST;
1201
case LFS_ERR_NOTDIR: return ENOTDIR;
1202
case LFS_ERR_ISDIR: return EISDIR;
1203
case LFS_ERR_NOTEMPTY: return ENOTEMPTY;
1204
case LFS_ERR_BADF: return EBADF;
1205
case LFS_ERR_FBIG: return EFBIG;
1206
case LFS_ERR_INVAL: return EINVAL;
1207
case LFS_ERR_NOSPC: return ENOSPC;
1208
case LFS_ERR_NOMEM: return ENOMEM;
1209
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
1210
case LFS_ERR_NOATTR: return ENOATTR;
1211
#endif
1212
case LFS_ERR_NAMETOOLONG: return ENAMETOOLONG;
1213
default: return EIO;
1214
}
1215
}
1216
1217
static int lfs_flags_from_flags(int flags)
1218
{
1219
int outflags = 0;
1220
1221
if (flags & O_WRONLY) {
1222
outflags |= LFS_O_WRONLY | LFS_F_WRUNCHECKED;
1223
} else if (flags & O_RDWR) {
1224
outflags |= LFS_O_RDWR;
1225
} else {
1226
outflags |= LFS_O_RDONLY;
1227
}
1228
1229
if (flags & O_CREAT) {
1230
outflags |= LFS_O_CREAT;
1231
}
1232
1233
if (flags & O_EXCL) {
1234
outflags |= LFS_O_EXCL;
1235
}
1236
1237
if (flags & O_TRUNC) {
1238
outflags |= LFS_O_TRUNC;
1239
}
1240
1241
if (flags & O_APPEND) {
1242
outflags |= LFS_O_APPEND;
1243
}
1244
1245
return outflags;
1246
}
1247
1248
#endif // AP_FILESYSTEM_LITTLEFS_ENABLED
1249
1250