FAT emulation of onboard flash for MSC (#5650)

This commit is contained in:
jflyper 2018-04-11 08:29:56 +09:00 committed by Michael Keller
parent c305833c8b
commit d749879cf6
15 changed files with 1423 additions and 11 deletions

View File

@ -214,5 +214,12 @@ MCU_COMMON_SRC += \
drivers/sdio_f4xx.c
endif
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_emfat.c \
msc/emfat.c \
msc/emfat_file.c
endif
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4

View File

@ -196,5 +196,12 @@ MSC_SRC += \
msc/usbd_storage_sd_spi.c
endif
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
MSC_SRC += \
msc/usbd_storage_emfat.c \
msc/emfat.c \
msc/emfat_file.c
endif
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7

View File

@ -374,7 +374,8 @@ ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
SRC += \
drivers/flash_m25p16.c \
io/flashfs.c \
pg/flash.c
pg/flash.c \
$(MSC_SRC)
endif
SRC += $(COMMON_SRC)

View File

@ -90,6 +90,12 @@ uint8_t mscStart(void)
USBD_STORAGE_fops = &USBD_MSC_MICRO_SDIO_fops;
break;
#endif
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
USBD_STORAGE_fops = &USBD_MSC_EMFAT_fops;
break;
#endif
default:
return 1;
}

View File

@ -85,6 +85,13 @@ uint8_t mscStart(void)
USBD_MSC_RegisterStorage(&USBD_Device, &USBD_MSC_MICRO_SDIO_fops);
break;
#endif
#ifdef USE_FLASHFS
case BLACKBOX_DEVICE_FLASH:
USBD_MSC_RegisterStorage(&USBD_Device, &USBD_MSC_EMFAT_fops);
break;
#endif
default:
return 1;
}

View File

@ -3746,7 +3746,14 @@ static void cliMsc(char *cmdline)
{
UNUSED(cmdline);
if (sdcard_isFunctional()) {
if (false
#ifdef USE_SDCARD
|| sdcard_isFunctional()
#endif
#ifdef USE_FLASHFS
|| flashfsGetSize() > 0
#endif
) {
cliPrintHashLine("restarting in mass storage mode");
cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter);
@ -3766,7 +3773,7 @@ static void cliMsc(char *cmdline)
__disable_irq();
NVIC_SystemReset();
} else {
cliPrint("\r\nSD Card not present or failed to initialize!");
cliPrint("\r\nStorage not present or failed to initialize!");
bufWriterFlush(cliWriter);
}
}

735
src/main/msc/emfat.c Normal file
View File

@ -0,0 +1,735 @@
/*
* Derived from
* https://github.com/fetisov/emfat/blob/master/project/emfat.c
* version: 1.1 (2.04.2017)
*/
/*
* The MIT License (MIT)
*
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#include "common/utils.h"
#include "emfat.h"
#ifdef __cplusplus
extern "C" {
#endif
#define SECT 512
#define CLUST 4096
#define SECT_PER_CLUST (CLUST / SECT)
#define SIZE_TO_NSECT(s) ((s) == 0 ? 1 : ((s) + SECT - 1) / SECT)
#define SIZE_TO_NCLUST(s) ((s) == 0 ? 1 : ((s) + CLUST - 1) / CLUST)
#define CLUST_FREE 0x00000000
#define CLUST_RESERVED 0x00000001
#define CLUST_BAD 0x0FFFFFF7
#define CLUST_ROOT_END 0X0FFFFFF8
#define CLUST_EOF 0x0FFFFFFF
#define MAX_DIR_ENTRY_CNT 16
#define FILE_SYS_TYPE_OFF 82
#define BYTES_PER_SEC_OFF 11
#define SEC_PER_CLUS_OFF 13
#define RES_SEC_CNT_OFF 14
#define FAT_CNT_OFF 16
#define TOT_SEC_CNT_OFF 32
#define SEC_PER_FAT 36
#define ROOT_DIR_STRT_CLUS_OFF 44
#define FS_INFOSECTOR_OFF 48
#define BACKUP_BOOT_SEC_OFF 50
#define NXT_FREE_CLUS_OFF 492
#define FILE_SYS_TYPE_LENGTH 8
#define SHRT_FILE_NAME_LEN 11
#define STRT_CLUS_LOW_OFF 26
#define STRT_CLUS_HIGH_OFF 20
#define FILE_SIZE_OFF 28
#define ATTR_OFF 11
#define FILE_STAT_LEN 21
#define CHECK_SUM_OFF 13
#define FILE_NAME_SHRT_LEN 8
#define FILE_NAME_EXTN_LEN 3
#define LONG_FILE_NAME_LEN 255
#define LOW_CLUSWORD_MASK 0x0000FFFF
#define HIGH_CLUSWORD_MASK 0xFFFF0000
#define LONG_FNAME_MASK 0x0F
#define LAST_ORD_FIELD_SEQ 0x40
#define LFN_END_MARK 0xFFFF
#define LFN_TERM_MARK 0x0000
#define LFN_FIRST_OFF 0x01
#define LFN_SIXTH_OFF 0x0E
#define LFN_TWELVETH_OFF 0x1C
#define LFN_FIRST_SET_CNT 5
#define LFN_SEC_SET_CNT 6
#define LFN_THIRD_SET_CNT 2
#define LFN_FIRST_SET_LEN 10
#define LFN_SEC_SET_LEN 12
#define LFN_THIRD_SET_LEN 4
#define LFN_EMPTY_LEN 2
#define LFN_LEN_PER_ENTRY 13
#define FNAME_EXTN_SEP_OFF 6
#define FNAME_SEQ_NUM_OFF 7
#define BYTES_PER_CLUSTER_ENTRY 4
#define DIR_ENTRY_LEN 32
#define VOL_ID_LEN 4
#define VOL_LABEL_LEN 11
#define RESERV_LEN 12
#define FS_VER_LEN 2
#define OEM_NAME_LEN 8
#define JUMP_INS_LEN 3
#define MAX_FAT_CNT 2
#define SPACE_VAL 32
#define FILE_READ 0x01
#define FILE_WRITE 0X02
#define FILE_CREATE_NEW 0x04
#define FILE_CREATE_ALWAYS 0x08
#define FILE_APPEND 0x10
#define FREE_DIR_ENTRY 0x00
#define DEL_DIR_ENTRY 0xE5
#define DOT_DIR_ENTRY 0x2E
#define ASCII_DIFF 32
#define FILE_SEEK_SET 0
#define FILE_SEEK_CUR 1
#define FILE_SEEK_END 2
#define DELIMITER '/'
#define EXTN_DELIMITER '.'
#define TILDE '~'
#define FULL_SHRT_NAME_LEN 13
#pragma pack(push, 1)
typedef struct
{
uint8_t status; // 0x80 for bootable, 0x00 for not bootable, anything else for invalid
uint8_t start_head; // The head of the start
uint8_t start_sector; // (S | ((C >> 2) & 0xC0)) where S is the sector of the start and C is the cylinder of the start. Note that S is counted from one.
uint8_t start_cylinder; // (C & 0xFF) where C is the cylinder of the start
uint8_t PartType;
uint8_t end_head;
uint8_t end_sector;
uint8_t end_cylinder;
uint32_t StartLBA; // linear address of first sector in partition. Multiply by sector size (usually 512) for real offset
uint32_t EndLBA; // linear address of last sector in partition. Multiply by sector size (usually 512) for real offset
} mbr_part_t;
typedef struct
{
uint8_t Code[440];
uint32_t DiskSig; //This is optional
uint16_t Reserved; //Usually 0x0000
mbr_part_t PartTable[4];
uint8_t BootSignature[2]; //0x55 0xAA for bootable
} mbr_t;
typedef struct
{
uint8_t jump[JUMP_INS_LEN];
uint8_t OEM_name[OEM_NAME_LEN];
uint16_t bytes_per_sec;
uint8_t sec_per_clus;
uint16_t reserved_sec_cnt;
uint8_t fat_cnt;
uint16_t root_dir_max_cnt;
uint16_t tot_sectors;
uint8_t media_desc;
uint16_t sec_per_fat_fat16;
uint16_t sec_per_track;
uint16_t number_of_heads;
uint32_t hidden_sec_cnt;
uint32_t tol_sector_cnt;
uint32_t sectors_per_fat;
uint16_t ext_flags;
uint8_t fs_version[FS_VER_LEN];
uint32_t root_dir_strt_cluster;
uint16_t fs_info_sector;
uint16_t backup_boot_sector;
uint8_t reserved[RESERV_LEN];
uint8_t drive_number;
uint8_t reserved1;
uint8_t boot_sig;
uint8_t volume_id[VOL_ID_LEN];
uint8_t volume_label[VOL_LABEL_LEN];
uint8_t file_system_type[FILE_SYS_TYPE_LENGTH];
} boot_sector;
typedef struct
{
uint32_t signature1; /* 0x41615252L */
uint32_t reserved1[120]; /* Nothing as far as I can tell */
uint32_t signature2; /* 0x61417272L */
uint32_t free_clusters; /* Free cluster count. -1 if unknown */
uint32_t next_cluster; /* Most recently allocated cluster */
uint32_t reserved2[3];
uint32_t signature3;
} fsinfo_t;
typedef struct
{
uint8_t name[FILE_NAME_SHRT_LEN];
uint8_t extn[FILE_NAME_EXTN_LEN];
uint8_t attr;
uint8_t reserved;
uint8_t crt_time_tenth;
uint16_t crt_time;
uint16_t crt_date;
uint16_t lst_access_date;
uint16_t strt_clus_hword;
uint16_t lst_mod_time;
uint16_t lst_mod_date;
uint16_t strt_clus_lword;
uint32_t size;
} dir_entry;
typedef struct
{
uint8_t ord_field;
uint8_t fname0_4[LFN_FIRST_SET_LEN];
uint8_t flag;
uint8_t reserved;
uint8_t chksum;
uint8_t fname6_11[LFN_SEC_SET_LEN];
uint8_t empty[LFN_EMPTY_LEN];
uint8_t fname12_13[LFN_THIRD_SET_LEN];
} lfn_entry;
#pragma pack(pop)
bool emfat_init_entries(emfat_entry_t *entries)
{
emfat_entry_t *e;
int i, n;
e = &entries[0];
if (e->level != 0 || !e->dir || e->name == NULL) return false;
e->priv.top = NULL;
e->priv.next = NULL;
e->priv.sub = NULL;
e->priv.num_subentry = 0;
n = 0;
for (i = 1; entries[i].name != NULL; i++) {
entries[i].priv.top = NULL;
entries[i].priv.next = NULL;
entries[i].priv.sub = NULL;
entries[i].priv.num_subentry = 0;
if (entries[i].level == n - 1) {
if (n == 0) return false;
e = e->priv.top;
n--;
}
if (entries[i].level == n + 1) {
if (!e->dir) return false;
e->priv.sub = &entries[i];
entries[i].priv.top = e;
e = &entries[i];
n++;
continue;
}
if (entries[i].level == n) {
if (n == 0) return false;
e->priv.top->priv.num_subentry++;
entries[i].priv.top = e->priv.top;
e->priv.next = &entries[i];
e = &entries[i];
continue;
}
return false;
}
return true;
}
static void lba_to_chs(int lba, uint8_t *cl, uint8_t *ch, uint8_t *dh)
{
int cylinder, head, sector;
int sectors = 63;
int heads = 255;
int cylinders = 1024;
sector = lba % sectors + 1;
head = (lba / sectors) % heads;
cylinder = lba / (sectors * heads);
if (cylinder >= cylinders) {
*cl = *ch = *dh = 0xff;
return;
}
*cl = sector | ((cylinder & 0x300) >> 2);
*ch = cylinder & 0xFF;
*dh = head;
}
bool emfat_init(emfat_t *emfat, const char *label, emfat_entry_t *entries)
{
uint32_t sect_per_fat;
uint32_t clust;
uint32_t reserved_clust = 0;
emfat_entry_t *e;
int i;
if (emfat == NULL || label == NULL || entries == NULL) {
return false;
}
if (!emfat_init_entries(entries)) {
return false;
}
clust = 2;
for (i = 0; entries[i].name != NULL; i++) {
e = &entries[i];
if (e->dir) {
e->curr_size = 0;
e->max_size = 0;
e->priv.first_clust = clust;
e->priv.last_clust = clust + SIZE_TO_NCLUST(e->priv.num_subentry * sizeof(dir_entry)) - 1;
e->priv.last_reserved = e->priv.last_clust;
} else {
e->priv.first_clust = clust;
e->priv.last_clust = e->priv.first_clust + SIZE_TO_NCLUST(entries[i].curr_size) - 1;
e->priv.last_reserved = e->priv.first_clust + SIZE_TO_NCLUST(entries[i].max_size) - 1;
}
reserved_clust += e->priv.last_reserved - e->priv.last_clust;
clust = e->priv.last_reserved + 1;
}
clust -= 2;
emfat->vol_label = label;
emfat->priv.num_entries = i;
emfat->priv.boot_lba = 62;
emfat->priv.fsinfo_lba = emfat->priv.boot_lba + 1;
emfat->priv.fat1_lba = emfat->priv.fsinfo_lba + 1;
emfat->priv.num_clust = clust;
emfat->priv.free_clust = reserved_clust;
sect_per_fat = SIZE_TO_NSECT((uint64_t)emfat->priv.num_clust * 4);
emfat->priv.fat2_lba = emfat->priv.fat1_lba + sect_per_fat;
emfat->priv.root_lba = emfat->priv.fat2_lba + sect_per_fat;
emfat->priv.entries = entries;
emfat->priv.last_entry = entries;
emfat->disk_sectors = clust * SECT_PER_CLUST + emfat->priv.root_lba;
emfat->vol_size = (uint64_t)emfat->disk_sectors * SECT;
/* calc cyl number */
// i = ((emfat->disk_sectors + 63*255 - 1) / (63*255));
// emfat->disk_sectors = i * 63*255;
return true;
}
void read_mbr_sector(const emfat_t *emfat, uint8_t *sect)
{
mbr_t *mbr;
memset(sect, 0, SECT);
mbr = (mbr_t *)sect;
mbr->DiskSig = 0;
mbr->Reserved = 0;
mbr->PartTable[0].status = 0x80;
mbr->PartTable[0].PartType = 0x0C;
mbr->PartTable[0].StartLBA = emfat->priv.boot_lba;
mbr->PartTable[0].EndLBA = emfat->disk_sectors;
lba_to_chs(mbr->PartTable[0].StartLBA, &mbr->PartTable[0].start_sector, &mbr->PartTable[0].start_cylinder, &mbr->PartTable[0].start_head);
lba_to_chs(emfat->disk_sectors - 1, &mbr->PartTable[0].end_sector, &mbr->PartTable[0].end_cylinder, &mbr->PartTable[0].end_head);
mbr->BootSignature[0] = 0x55;
mbr->BootSignature[1] = 0xAA;
}
void read_boot_sector(const emfat_t *emfat, uint8_t *sect)
{
boot_sector *bs;
memset(sect, 0, SECT);
bs = (boot_sector *)sect;
bs->jump[0] = 0xEB;
bs->jump[1] = 0x58;
bs->jump[2] = 0x90;
memcpy(bs->OEM_name, "MSDOS5.0", 8);
bs->bytes_per_sec = SECT;
bs->sec_per_clus = 8; /* 4 kb per cluster */
bs->reserved_sec_cnt = 2; /* boot sector & fsinfo sector */
bs->fat_cnt = 2; /* two tables */
bs->root_dir_max_cnt = 0;
bs->tot_sectors = 0;
bs->media_desc = 0xF8;
bs->sec_per_fat_fat16 = 0;
bs->sec_per_track = 63;
bs->number_of_heads = 0xFF;
bs->hidden_sec_cnt = 62;
bs->tol_sector_cnt = emfat->disk_sectors - emfat->priv.boot_lba;
bs->sectors_per_fat = emfat->priv.fat2_lba - emfat->priv.fat1_lba;
bs->ext_flags = 0;
bs->fs_version[0] = 0;
bs->fs_version[1] = 0;
bs->root_dir_strt_cluster = 2;
bs->fs_info_sector = 1;
bs->backup_boot_sector = 0; /* not used */
bs->drive_number = 128;
bs->boot_sig = 0x29;
bs->volume_id[0] = 148;
bs->volume_id[1] = 14;
bs->volume_id[2] = 13;
bs->volume_id[3] = 8;
memcpy(bs->volume_label, "NO NAME ", 12);
memcpy(bs->file_system_type, "FAT32 ", 8);
sect[SECT - 2] = 0x55;
sect[SECT - 1] = 0xAA;
}
#define IS_CLUST_OF(clust, entry) ((clust) >= (entry)->priv.first_clust && (clust) <= (entry)->priv.last_reserved)
emfat_entry_t *find_entry(const emfat_t *emfat, uint32_t clust, emfat_entry_t *nearest)
{
if (nearest == NULL) {
nearest = emfat->priv.entries;
}
if (nearest->priv.first_clust > clust) {
while (nearest >= emfat->priv.entries) { // backward finding
if (IS_CLUST_OF(clust, nearest))
return nearest;
nearest--;
}
} else {
while (nearest->name != NULL) { // forward finding
if (IS_CLUST_OF(clust, nearest))
return nearest;
nearest++;
}
}
return NULL;
}
void read_fsinfo_sector(const emfat_t *emfat, uint8_t *sect)
{
UNUSED(emfat);
fsinfo_t *info = (fsinfo_t *)sect;
info->signature1 = 0x41615252L;
info->signature2 = 0x61417272L;
//info->free_clusters = 0;
info->free_clusters = emfat->priv.free_clust;
//info->next_cluster = emfat->priv.num_clust + 2;
info->next_cluster = 0xffffffff;
memset(info->reserved1, 0, sizeof(info->reserved1));
memset(info->reserved2, 0, sizeof(info->reserved2));
info->signature3 = 0xAA550000;
}
void read_fat_sector(emfat_t *emfat, uint8_t *sect, uint32_t index)
{
emfat_entry_t *le;
uint32_t *values;
uint32_t count;
uint32_t curr;
values = (uint32_t *)sect;
curr = index * 128;
count = 128;
if (curr == 0) {
*values++ = CLUST_ROOT_END;
*values++ = 0xFFFFFFFF;
count -= 2;
curr += 2;
}
le = emfat->priv.last_entry;
while (count != 0) {
if (!IS_CLUST_OF(curr, le)) {
le = find_entry(emfat, curr, le);
if (le == NULL) {
le = emfat->priv.last_entry;
*values = CLUST_RESERVED;
values++;
count--;
curr++;
continue;
}
}
if (le->dir) {
if (curr == le->priv.last_clust) {
*values = CLUST_EOF;
} else {
*values = curr + 1;
}
} else {
if (curr == le->priv.last_clust) {
*values = CLUST_EOF;
} else if (curr > le->priv.last_clust) {
*values = CLUST_FREE;
} else {
*values = curr + 1;
}
}
values++;
count--;
curr++;
}
emfat->priv.last_entry = le;
}
void fill_entry(dir_entry *entry, const char *name, uint8_t attr, uint32_t clust, const uint32_t cma[3], uint32_t size)
{
int i, l, l1, l2;
int dot_pos;
memset(entry, 0, sizeof(dir_entry));
if (cma) {
entry->crt_date = cma[0] >> 16;
entry->crt_time = cma[0] & 0xFFFF;
entry->lst_mod_date = cma[1] >> 16;
entry->lst_mod_time = cma[1] & 0xFFFF;
entry->lst_access_date = cma[2] >> 16;
}
l = strlen(name);
dot_pos = -1;
if ((attr & ATTR_DIR) == 0) {
for (i = l - 1; i >= 0; i--) {
if (name[i] == '.')
{
dot_pos = i;
break;
}
}
}
if (dot_pos == -1) {
l1 = l > FILE_NAME_SHRT_LEN ? FILE_NAME_SHRT_LEN : l;
l2 = 0;
} else {
l1 = dot_pos;
l1 = l1 > FILE_NAME_SHRT_LEN ? FILE_NAME_SHRT_LEN : l1;
l2 = l - dot_pos - 1;
l2 = l2 > FILE_NAME_EXTN_LEN ? FILE_NAME_EXTN_LEN : l2;
}
memset(entry->name, ' ', FILE_NAME_SHRT_LEN + FILE_NAME_EXTN_LEN);
memcpy(entry->name, name, l1);
memcpy(entry->extn, name + dot_pos + 1, l2);
for (i = 0; i < FILE_NAME_SHRT_LEN; i++) {
if (entry->name[i] >= 'a' && entry->name[i] <= 'z') {
entry->name[i] -= 0x20;
}
}
for (i = 0; i < FILE_NAME_EXTN_LEN; i++) {
if (entry->extn[i] >= 'a' && entry->extn[i] <= 'z') {
entry->extn[i] -= 0x20;
}
}
entry->attr = attr;
entry->reserved = 24;
entry->strt_clus_hword = clust >> 16;
entry->strt_clus_lword = clust;
entry->size = size;
return;
}
void fill_dir_sector(emfat_t *emfat, uint8_t *data, emfat_entry_t *entry, uint32_t rel_sect)
{
dir_entry *de;
uint32_t avail;
memset(data, 0, SECT);
de = (dir_entry *)data;
avail = SECT;
if (rel_sect == 0) { // 1. first sector of directory
if (entry->priv.top == NULL) {
fill_entry(de++, emfat->vol_label, ATTR_VOL_LABEL, 0, 0, 0);
avail -= sizeof(dir_entry);
} else {
fill_entry(de++, ".", ATTR_DIR | ATTR_READ, entry->priv.first_clust, 0, 0);
if (entry->priv.top->priv.top == NULL) {
fill_entry(de++, "..", ATTR_DIR | ATTR_READ, 0, 0, 0);
} else {
fill_entry(de++, "..", ATTR_DIR | ATTR_READ, entry->priv.top->priv.first_clust, 0, 0);
}
avail -= sizeof(dir_entry) * 2;
}
entry = entry->priv.sub;
} else { // 2. not a first sector
int n;
n = rel_sect * (SECT / sizeof(dir_entry));
n -= entry->priv.top == NULL ? 1 : 2;
entry = entry->priv.sub;
while (n > 0 && entry != NULL) {
entry = entry->priv.next;
n--;
}
}
while (entry != NULL && avail >= sizeof(dir_entry)) {
if (entry->dir) {
fill_entry(de++, entry->name, ATTR_DIR | ATTR_READ, entry->priv.first_clust, entry->cma_time, 0);
} else {
//fill_entry(de++, entry->name, ATTR_ARCHIVE | ATTR_READ, entry->priv.first_clust, entry->cma_time, entry->curr_size);
fill_entry(de++, entry->name, ATTR_ARCHIVE | ATTR_READ | entry->attr, entry->priv.first_clust, entry->cma_time, entry->curr_size);
}
entry = entry->priv.next;
avail -= sizeof(dir_entry);
}
}
void read_data_sector(emfat_t *emfat, uint8_t *data, uint32_t rel_sect)
{
emfat_entry_t *le;
uint32_t cluster;
cluster = rel_sect / 8 + 2;
rel_sect = rel_sect % 8;
le = emfat->priv.last_entry;
if (!IS_CLUST_OF(cluster, le)) {
le = find_entry(emfat, cluster, le);
if (le == NULL) {
int i;
for (i = 0; i < SECT / 4; i++)
((uint32_t *)data)[i] = 0xEFBEADDE;
return;
}
emfat->priv.last_entry = le;
}
if (le->dir) {
fill_dir_sector(emfat, data, le, rel_sect);
return;
}
if (le->readcb == NULL) {
memset(data, 0, SECT);
} else {
uint32_t offset = cluster - le->priv.first_clust;
offset = offset * CLUST + rel_sect * SECT;
le->readcb(data, SECT, offset + le->offset, le);
}
return;
}
void emfat_read(emfat_t *emfat, uint8_t *data, uint32_t sector, int num_sectors)
{
while (num_sectors > 0) {
if (sector >= emfat->priv.root_lba) {
read_data_sector(emfat, data, sector - emfat->priv.root_lba);
} else if (sector == 0) {
read_mbr_sector(emfat, data);
} else if (sector == emfat->priv.fsinfo_lba) {
read_fsinfo_sector(emfat, data);
} else if (sector == emfat->priv.boot_lba) {
read_boot_sector(emfat, data);
} else if (sector >= emfat->priv.fat1_lba && sector < emfat->priv.fat2_lba) {
read_fat_sector(emfat, data, sector - emfat->priv.fat1_lba);
} else if (sector >= emfat->priv.fat2_lba && sector < emfat->priv.root_lba) {
read_fat_sector(emfat, data, sector - emfat->priv.fat2_lba);
} else {
memset(data, 0, SECT);
}
data += SECT;
num_sectors--;
sector++;
}
}
void write_data_sector(emfat_t *emfat, const uint8_t *data, uint32_t rel_sect)
{
emfat_entry_t *le;
uint32_t cluster;
cluster = rel_sect / 8 + 2;
rel_sect = rel_sect % 8;
le = emfat->priv.last_entry;
if (!IS_CLUST_OF(cluster, le)) {
le = find_entry(emfat, cluster, le);
if (le == NULL) return;
emfat->priv.last_entry = le;
}
if (le->dir) {
// TODO: handle changing a filesize
return;
}
if (le->writecb != NULL) {
le->writecb(data, SECT, rel_sect * SECT + le->offset, le);
}
}
#define FEBRUARY 2
#define STARTOFTIME 1970
#define SECDAY 86400L
#define SECYR (SECDAY * 365)
#define leapyear(year) ((year) % 4 == 0)
#define days_in_year(a) (leapyear(a) ? 366 : 365)
#define days_in_month(a) (month_days[(a) - 1])
static int month_days[12] = {
31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31
};
uint32_t emfat_cma_time_from_unix(uint32_t tim)
{
register int i;
register long tmp, day;
int ymd[3];
int hms[3];
day = tim / SECDAY;
tmp = tim % SECDAY;
/* Hours, minutes, seconds are easy */
hms[0] = tmp / 3600;
hms[1] = (tmp % 3600) / 60;
hms[2] = (tmp % 3600) % 60;
/* Number of years in days */
for (i = STARTOFTIME; day >= days_in_year(i); i++)
day -= days_in_year(i);
ymd[0] = i;
/* Number of months in days left */
if (leapyear(ymd[0])) {
days_in_month(FEBRUARY) = 29;
}
for (i = 1; day >= days_in_month(i); i++) {
day -= days_in_month(i);
}
days_in_month(FEBRUARY) = 28;
ymd[1] = i;
/* Days are what is left over (+1) from all that. */
ymd[2] = day + 1;
return EMFAT_ENCODE_CMA_TIME(ymd[2], ymd[1], ymd[0], hms[0], hms[1], hms[2]);
}
#ifdef __cplusplus
}
#endif

113
src/main/msc/emfat.h Normal file
View File

@ -0,0 +1,113 @@
/*
* Derived from
* https://github.com/fetisov/emfat/blob/master/project/emfat.c
* version: 1.0 (4.01.2015)
*/
/*
* The MIT License (MIT)
*
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#pragma once
#include <stddef.h>
#include <stdint.h>
#include <string.h>
#include <stdbool.h>
#ifdef __cplusplus
extern "C" {
#endif
struct emfat_entry_s;
typedef void (*emfat_readcb_t)(uint8_t *dest, int size, uint32_t offset, struct emfat_entry_s *entry);
typedef void (*emfat_writecb_t)(const uint8_t *data, int size, uint32_t offset, struct emfat_entry_s *entry);
typedef struct emfat_entry_s {
const char *name;
bool dir;
uint8_t attr;
int level;
uint32_t offset;
uint32_t curr_size;
uint32_t max_size;
long user_data;
uint32_t cma_time[3]; /**< create/mod/access time in unix format */
emfat_readcb_t readcb;
emfat_writecb_t writecb;
struct
{
uint32_t first_clust;
uint32_t last_clust;
uint32_t last_reserved;
uint32_t num_subentry;
struct emfat_entry_s *top;
struct emfat_entry_s *sub;
struct emfat_entry_s *next;
} priv;
} emfat_entry_t;
typedef struct emfat_s {
uint64_t vol_size;
uint32_t disk_sectors;
const char *vol_label;
struct {
uint32_t boot_lba;
uint32_t fsinfo_lba;
uint32_t fat1_lba;
uint32_t fat2_lba;
uint32_t root_lba;
uint32_t num_clust;
uint32_t free_clust;
emfat_entry_t *entries;
emfat_entry_t *last_entry;
int num_entries;
} priv;
} emfat_t;
bool emfat_init(emfat_t *emfat, const char *label, emfat_entry_t *entries);
void emfat_read(emfat_t *emfat, uint8_t *data, uint32_t sector, int num_sectors);
void emfat_write(emfat_t *emfat, const uint8_t *data, uint32_t sector, int num_sectors);
#define EMFAT_ENCODE_CMA_TIME(D,M,Y,h,m,s) \
((((((Y)-1980) << 9) | ((M) << 5) | (D)) << 16) | \
(((h) << 11) | ((m) << 5) | (s >> 1)))
static inline uint32_t emfat_encode_cma_time(int D, int M, int Y, int h, int m, int s)
{
return EMFAT_ENCODE_CMA_TIME(D,M,Y,h,m,s);
}
uint32_t emfat_cma_time_from_unix(uint32_t unix_time);
#define ATTR_READ 0x01
#define ATTR_HIDDEN 0x02
#define ATTR_SYSTEM 0x04
#define ATTR_VOL_LABEL 0x08
#define ATTR_DIR 0x10
#define ATTR_ARCHIVE 0x20
#define ATTR_LONG_FNAME 0x0F
#ifdef __cplusplus
}
#endif

329
src/main/msc/emfat_file.c Normal file
View File

@ -0,0 +1,329 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight 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.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*
* Author: jflyper@github.com
*/
#include "common/utils.h"
#include "common/printf.h"
#include "emfat.h"
#include "emfat_file.h"
#include "io/flashfs.h"
#define USE_EMFAT_AUTORUN
#define USE_EMFAT_ICON
//#define USE_EMFAT_README
#ifdef USE_EMFAT_AUTORUN
static const char autorun_file[] =
"[autorun]\r\n"
"icon=icon.ico\r\n"
"label=Betaflight Onboard Flash\r\n" ;
#define AUTORUN_SIZE (sizeof(autorun_file) - 1)
#define EMFAT_INCR_AUTORUN 1
#else
#define EMFAT_INCR_AUTORUN 0
#endif
#ifdef USE_EMFAT_README
static const char readme_file[] =
"This is readme file\r\n";
#define README_SIZE (sizeof(readme_file) - 1)
#define EMFAT_INCR_README 1
#else
#define EMFAT_INCR_README 0
#endif
#ifdef USE_EMFAT_ICON
static const char icon_file[] =
{
0x00, 0x00, 0x01, 0x00, 0x01, 0x00, 0x18, 0x18, 0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x28, 0x09,
0x00, 0x00, 0x16, 0x00, 0x00, 0x00, 0x28, 0x00, 0x00, 0x00, 0x18, 0x00, 0x00, 0x00, 0x30, 0x00,
0x00, 0x00, 0x01, 0x00, 0x20, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xfc, 0xfc,
0xfc, 0xde, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xde, 0xfb, 0xfb,
0xfb, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xf4, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf9, 0xfb,
0xfc, 0xff, 0xd7, 0xdd, 0xe1, 0xff, 0xc7, 0xc3, 0xc2, 0xff, 0xce, 0xce, 0xce, 0xff, 0xe2, 0xe4,
0xe5, 0xff, 0xfd, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb0, 0xad, 0xad, 0xff, 0x3a, 0x89,
0xa8, 0xff, 0x03, 0xb5, 0xed, 0xff, 0x20, 0x57, 0x6c, 0xff, 0x36, 0x25, 0x1f, 0xff, 0x34, 0x52,
0x5e, 0xff, 0x4f, 0x65, 0x6e, 0xff, 0x8a, 0x86, 0x84, 0xff, 0xd8, 0xd8, 0xd8, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfa, 0xfa,
0xfa, 0xee, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb2, 0xb1, 0xff, 0x2a, 0x1d, 0x18, 0xff, 0x33, 0x2a,
0x26, 0xff, 0x25, 0x68, 0x7f, 0xff, 0x16, 0x90, 0xbe, 0xff, 0x3a, 0x38, 0x37, 0xff, 0x37, 0x38,
0x38, 0xff, 0x31, 0x35, 0x37, 0xff, 0x29, 0x28, 0x27, 0xff, 0x34, 0x34, 0x34, 0xff, 0x93, 0x93,
0x93, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xfc, 0xf8, 0xff, 0x4f, 0xa0, 0xbf, 0xff, 0x0d, 0x8c, 0xb8, 0xff, 0x2c, 0x62,
0x76, 0xff, 0x3e, 0x31, 0x2e, 0xff, 0x36, 0x46, 0x4d, 0xff, 0x38, 0x41, 0x44, 0xff, 0x3b, 0x39,
0x38, 0xff, 0x37, 0x36, 0x35, 0xff, 0x2c, 0x2c, 0x2c, 0xff, 0x28, 0x28, 0x28, 0xff, 0x83, 0x83,
0x83, 0xff, 0x77, 0x77, 0x77, 0xff, 0xd5, 0xd5, 0xd5, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xfd, 0xfb, 0xff, 0x5f, 0x98, 0xad, 0xff, 0x1a, 0x5c, 0x73, 0xff, 0x30, 0x5a,
0x6a, 0xff, 0x38, 0x42, 0x46, 0xff, 0x3c, 0x35, 0x33, 0xff, 0x39, 0x38, 0x37, 0xff, 0x2b, 0x2b,
0x2b, 0xff, 0x3c, 0x3c, 0x3c, 0xff, 0x83, 0x83, 0x83, 0xff, 0xc2, 0xc2, 0xc2, 0xff, 0xd2, 0xd2,
0xd2, 0xff, 0xa9, 0xa9, 0xa9, 0xff, 0x86, 0x86, 0x86, 0xff, 0xdf, 0xdf, 0xdf, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc3, 0xba, 0xb7, 0xff, 0x2c, 0x21, 0x1d, 0xff, 0x38, 0x30,
0x2d, 0xff, 0x3c, 0x3a, 0x39, 0xff, 0x34, 0x35, 0x35, 0xff, 0x2e, 0x2e, 0x2e, 0xff, 0x78, 0x78,
0x78, 0xff, 0xdf, 0xdf, 0xdf, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xeb, 0xeb, 0xeb, 0xee, 0xfa, 0xfa,
0xfa, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc,
0xfc, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb3, 0xb0, 0xaf, 0xff, 0x3d, 0x31,
0x2c, 0xff, 0x33, 0x30, 0x2f, 0xff, 0x49, 0x4a, 0x4a, 0xff, 0xcb, 0xcb, 0xcb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc,
0xfc, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd3, 0xe2, 0xe8, 0xff, 0x1c, 0x85,
0xae, 0xff, 0x2f, 0x44, 0x4c, 0xff, 0x41, 0x3c, 0x3a, 0xff, 0x9a, 0x9a, 0x9a, 0xff, 0xf9, 0xf9,
0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xf5, 0xf5,
0xf5, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff, 0xff, 0xff, 0x8a, 0xd0, 0xea, 0xff, 0x00, 0xb0,
0xf7, 0xff, 0x36, 0x49, 0x51, 0xff, 0x39, 0x33, 0x31, 0xff, 0x1f, 0x1f, 0x1f, 0xff, 0x98, 0x98,
0x98, 0xff, 0xe2, 0xe2, 0xe2, 0xff, 0x9b, 0x9b, 0x9b, 0xff, 0x71, 0x71, 0x71, 0xff, 0x72, 0x72,
0x72, 0xff, 0x63, 0x63, 0x63, 0xff, 0xef, 0xef, 0xef, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf4, 0xf4,
0xf4, 0xff, 0xae, 0xae, 0xae, 0xff, 0x8c, 0x8c, 0x8c, 0xff, 0x86, 0x86, 0x86, 0xff, 0x84, 0x84,
0x84, 0xff, 0x86, 0x86, 0x86, 0xff, 0x91, 0x8a, 0x87, 0xff, 0x48, 0x7a, 0x8d, 0xff, 0x00, 0x9c,
0xd7, 0xff, 0x3a, 0x3e, 0x3f, 0xff, 0x39, 0x36, 0x35, 0xff, 0x35, 0x35, 0x35, 0xff, 0x42, 0x42,
0x42, 0xff, 0x3b, 0x3b, 0x3b, 0xff, 0x31, 0x31, 0x31, 0xff, 0x92, 0x92, 0x92, 0xff, 0x90, 0x90,
0x90, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xde, 0xde, 0xde, 0xff, 0x80, 0x80,
0x80, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xe6, 0xe6, 0xe6, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff,
0xff, 0xff, 0xea, 0xea, 0xea, 0xff, 0x81, 0x80, 0x80, 0xff, 0x49, 0x42, 0x40, 0xff, 0x55, 0x8e,
0xa3, 0xff, 0x1f, 0x5b, 0x72, 0xff, 0x35, 0x3a, 0x3c, 0xff, 0x43, 0x41, 0x41, 0xff, 0x35, 0x35,
0x35, 0xff, 0x2a, 0x2a, 0x2a, 0xff, 0xbe, 0xbe, 0xbe, 0xff, 0xe8, 0xe8, 0xe8, 0xff, 0x6f, 0x6f,
0x6f, 0xff, 0xe7, 0xe7, 0xe7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xfb, 0xfb,
0xfb, 0xee, 0xff, 0xff, 0xff, 0xff, 0xf5, 0xf5, 0xf5, 0xff, 0x7b, 0x7b, 0x7b, 0xff, 0xe0, 0xe0,
0xe0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xf8, 0xf8, 0xf8, 0xff, 0xb8, 0xb8,
0xb8, 0xff, 0x7d, 0x7d, 0x7d, 0xff, 0xa3, 0xa3, 0xa3, 0xff, 0xd2, 0xd2, 0xd2, 0xff, 0x87, 0x7c,
0x77, 0xff, 0x5a, 0x57, 0x55, 0xff, 0xca, 0xcb, 0xcb, 0xff, 0x82, 0x82, 0x82, 0xff, 0x23, 0x23,
0x23, 0xff, 0x38, 0x38, 0x38, 0xff, 0x43, 0x43, 0x43, 0xff, 0x5d, 0x5d, 0x5d, 0xff, 0xd9, 0xd9,
0xd9, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xff, 0xff, 0xff, 0xff, 0xa1, 0xa1, 0xa1, 0xff, 0xb6, 0xb6, 0xb6, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xb1, 0xb1, 0xb1, 0xff, 0xc7, 0xc7,
0xc7, 0xff, 0xea, 0xea, 0xea, 0xff, 0xa6, 0xa6, 0xa6, 0xff, 0x60, 0x60, 0x60, 0xff, 0x9f, 0x9f,
0x9f, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd1, 0xd1, 0xd1, 0xff, 0x4e, 0x4e,
0x4e, 0xff, 0x29, 0x29, 0x29, 0xff, 0x73, 0x73, 0x73, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xec, 0xec, 0xec, 0xff, 0x90, 0x90, 0x90, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xf3, 0xf3, 0xf3, 0xff, 0xf0, 0xf0, 0xf0, 0xff, 0xff, 0xff, 0xff, 0xff, 0xb7, 0xb7,
0xb7, 0xff, 0x61, 0x61, 0x61, 0xff, 0x89, 0x89, 0x89, 0xff, 0xeb, 0xeb, 0xeb, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xdc, 0xdc, 0xdc, 0xff, 0x99, 0x99,
0x99, 0xff, 0xbc, 0xbc, 0xbc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0x98, 0x98, 0x98, 0xff, 0x9c, 0x9c, 0x9c, 0xff, 0xf9, 0xf9, 0xf9, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xc5, 0xc5, 0xc5, 0xff, 0x66, 0x66, 0x66, 0xff, 0x76, 0x76,
0x76, 0xff, 0xdb, 0xdb, 0xdb, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xff, 0xdd, 0xdd, 0xdd, 0xff, 0xcd, 0xcd, 0xcd, 0xff, 0xf7, 0xf7,
0xf7, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xee, 0xda, 0xda,
0xda, 0xee, 0x48, 0x48, 0x48, 0xff, 0x75, 0x75, 0x75, 0xff, 0xff, 0xff, 0xff, 0xff, 0xd5, 0xd5,
0xd5, 0xff, 0x72, 0x72, 0x72, 0xff, 0x6a, 0x6a, 0x6a, 0xff, 0xc8, 0xc8, 0xc8, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xee, 0xeb, 0xeb,
0xeb, 0xee, 0xaf, 0xaf, 0xaf, 0xff, 0xb0, 0xb0, 0xb0, 0xff, 0x8b, 0x8b, 0x8b, 0xff, 0x60, 0x60,
0x60, 0xff, 0xb3, 0xb3, 0xb3, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe,
0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0x66, 0x66, 0x66, 0xff, 0x54, 0x54, 0x54, 0xff, 0xa0, 0xa0, 0xa0, 0xff, 0xfa, 0xfa,
0xfa, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xfd, 0xfd,
0xfd, 0xff, 0xfc, 0xfc, 0xfc, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xce, 0xce,
0xce, 0xee, 0x98, 0x98, 0x98, 0xff, 0xef, 0xef, 0xef, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xfe, 0xfe, 0xfe, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfd, 0xfd, 0xfd, 0xee, 0xf6, 0xf6,
0xf6, 0xf4, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xfb, 0xfb, 0xfb, 0xf4, 0xfd, 0xfd,
0xfd, 0xde, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfc, 0xfc, 0xfc, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfb, 0xfb, 0xfb, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd,
0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xee, 0xfd, 0xfd, 0xfd, 0xde,
};
#define ICON_SIZE (sizeof(icon_file))
#define EMFAT_INCR_ICON 1
#else
#define EMFAT_INCR_ICON 0
#endif
#define CMA_TIME EMFAT_ENCODE_CMA_TIME(1,1,2018, 13,0,0)
#define CMA { CMA_TIME, CMA_TIME, CMA_TIME }
static void memory_read_proc(uint8_t *dest, int size, uint32_t offset, emfat_entry_t *entry)
{
int len;
if (offset > entry->curr_size) {
return;
}
if (offset + size > entry->curr_size) {
len = entry->curr_size - offset;
} else {
len = size;
}
memcpy(dest, &((char *)entry->user_data)[offset], len);
}
static void bblog_read_proc(uint8_t *dest, int size, uint32_t offset, emfat_entry_t *entry)
{
UNUSED(entry);
flashfsReadAbs(offset, dest, size);
}
static const emfat_entry_t entriesPredefined[] =
{
// name dir attr lvl offset size max_size user time read write
{ "", true, 0, 0, 0, 0, 0, 0, CMA, NULL, NULL, { 0 } },
#ifdef USE_EMFAT_AUTORUN
{ "autorun.inf", false, ATTR_HIDDEN, 1, 0, AUTORUN_SIZE, AUTORUN_SIZE, (long)autorun_file, CMA, memory_read_proc, NULL, { 0 } },
#endif
#ifdef USE_EMFAT_ICON
{ "icon.ico", false, ATTR_HIDDEN, 1, 0, ICON_SIZE, ICON_SIZE, (long)icon_file, CMA, memory_read_proc, NULL, { 0 } },
#endif
#ifdef USE_EMFAT_README
{ "readme.txt", false, 0, 1, 0, README_SIZE, 1024*1024, (long)readme_file, CMA, memory_read_proc, NULL, { 0 } },
#endif
{ "BTFL_ALL.BBL", 0, 0, 1, 0, 0, 0, 0, CMA, bblog_read_proc, NULL, { 0 } },
};
#define ENTRY_INDEX_BBL (1 + EMFAT_INCR_AUTORUN + EMFAT_INCR_ICON + EMFAT_INCR_README)
#define EMFAT_MAX_LOG_ENTRY 100
#define EMFAT_MAX_ENTRY (ENTRY_INDEX_BBL + EMFAT_MAX_LOG_ENTRY)
static emfat_entry_t entries[EMFAT_MAX_ENTRY];
static char logNames[EMFAT_MAX_LOG_ENTRY][8+3];
emfat_t emfat;
static void emfat_add_log(emfat_entry_t *entry, int number, uint32_t offset, uint32_t size)
{
tfp_sprintf(logNames[number], "BTFL_%03d.BBL", number);
entry->name = logNames[number];
entry->level = 1;
entry->offset = offset;
entry->curr_size = size;
entry->max_size = entry->curr_size;
entry->cma_time[0] = CMA_TIME;
entry->cma_time[1] = CMA_TIME;
entry->cma_time[2] = CMA_TIME;
entry->readcb = bblog_read_proc;
}
static void emfat_find_log(emfat_entry_t *entry, int maxCount)
{
uint32_t limit = flashfsIdentifyStartOfFreeSpace();
uint32_t lastOffset = 0;
uint32_t currOffset = 0;
int fileNumber = 0;
uint8_t buffer[18];
for ( ; currOffset < limit ; currOffset += 2048) { // XXX 2048 = FREE_BLOCK_SIZE in io/flashfs.c
flashfsReadAbs(currOffset, buffer, 18);
if (strncmp((char *)buffer, "H Product:Blackbox", 18)) {
continue;
}
if (lastOffset != currOffset) {
emfat_add_log(entry, fileNumber, lastOffset, currOffset - lastOffset);
++fileNumber;
if (fileNumber == maxCount) {
break;
}
++entry;
}
lastOffset = currOffset;
}
if (fileNumber != maxCount && lastOffset != currOffset) {
emfat_add_log(entry, fileNumber, lastOffset, currOffset - lastOffset);
}
}
void emfat_init_files(void)
{
memset(entries, 0, sizeof(entries));
for (size_t i = 0 ; i < ARRAYLEN(entriesPredefined) ; i++) {
entries[i] = entriesPredefined[i];
}
// Singleton
emfat_entry_t *entry = &entries[ENTRY_INDEX_BBL];
entry->curr_size = flashfsIdentifyStartOfFreeSpace();
entry->max_size = flashfsGetSize();
// Detect and list individual power cycle sessions
emfat_find_log(&entries[ENTRY_INDEX_BBL + 1], EMFAT_MAX_ENTRY - (ENTRY_INDEX_BBL + 1));
emfat_init(&emfat, "emfat", entries);
}

20
src/main/msc/emfat_file.h Normal file
View File

@ -0,0 +1,20 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight 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.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
void emfat_init_files(void);

View File

@ -32,9 +32,15 @@ extern USBD_StorageTypeDef *USBD_STORAGE_fops;
#ifdef USE_SDCARD
extern USBD_StorageTypeDef USBD_MSC_MICRO_SDIO_fops;
#endif
#ifdef USE_FLASHFS
extern USBD_StorageTypeDef USBD_MSC_EMFAT_fops;
#endif
#else
extern USBD_STORAGE_cb_TypeDef *USBD_STORAGE_fops;
#ifdef USE_SDCARD
extern USBD_STORAGE_cb_TypeDef USBD_MSC_MICRO_SDIO_fops;
#endif
#ifdef USE_FLASHFS
extern USBD_STORAGE_cb_TypeDef USBD_MSC_EMFAT_fops;
#endif
#endif

View File

@ -0,0 +1,156 @@
/*
* Derived from github.com/fetisov/emfat/project/StorageMode.c
*/
/*
* The MIT License (MIT)
*
* Copyright (c) 2015 by Sergey Fetisov <fsenok@gmail.com>
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all
* copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#include <stdbool.h>
#include "platform.h"
#include "common/utils.h"
#include "drivers/light_led.h"
#include "drivers/time.h"
#include "drivers/flash_m25p16.h"
#include "io/flashfs.h"
#include "pg/flash.h"
#include "usbd_storage.h"
#include "usbd_storage_emfat.h"
#include "emfat_file.h"
#define STORAGE_LUN_NBR 1
static const uint8_t STORAGE_Inquirydata[] =
{
0x00, 0x80, 0x02, 0x02,
#ifdef USE_HAL_DRIVER
(STANDARD_INQUIRY_DATA_LEN - 5),
#else
(USBD_STD_INQUIRY_LENGTH - 5),
#endif
0x00, 0x00, 0x00,
'B', 'E', 'T', 'A', 'F', 'L', 'T', ' ', // Manufacturer : 8 bytes
'O', 'n', 'b', 'o', 'a', 'r', 'd', ' ', // Product : 16 Bytes
'F', 'l', 'a', 's', 'h', ' ', ' ', ' ', //
' ', ' ', ' ' ,' ', // Version : 4 Bytes
};
static int8_t STORAGE_Init(uint8_t lun)
{
UNUSED(lun);
LED0_ON;
#ifdef USE_FLASHFS
#if defined(USE_FLASH_M25P16)
m25p16_init(flashConfig());
#endif
flashfsInit();
#endif
emfat_init_files();
delay(1000);
LED0_OFF;
return 0;
}
#ifdef USE_HAL_DRIVER
static int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num, uint16_t *block_size)
#else
static int8_t STORAGE_GetCapacity(uint8_t lun, uint32_t *block_num, uint32_t *block_size)
#endif
{
UNUSED(lun);
*block_size = 512;
*block_num = emfat.disk_sectors;
return 0;
}
static int8_t STORAGE_IsReady(uint8_t lun)
{
UNUSED(lun);
return 0;
}
static int8_t STORAGE_IsWriteProtected(uint8_t lun)
{
UNUSED(lun);
return 1;
}
static int8_t STORAGE_Read(
uint8_t lun, // logical unit number
uint8_t *buf, // Pointer to the buffer to save data
uint32_t blk_addr, // address of 1st block to be read
uint16_t blk_len) // nmber of blocks to be read
{
UNUSED(lun);
LED0_ON;
emfat_read(&emfat, buf, blk_addr, blk_len);
LED0_OFF;
return 0;
}
static int8_t STORAGE_Write(uint8_t lun,
uint8_t *buf,
uint32_t blk_addr,
uint16_t blk_len)
{
UNUSED(lun);
UNUSED(buf);
UNUSED(blk_addr);
UNUSED(blk_len);
return 1;
}
static int8_t STORAGE_GetMaxLun(void)
{
return (STORAGE_LUN_NBR - 1);
}
#ifdef USE_HAL_DRIVER
USBD_StorageTypeDef
#else
USBD_STORAGE_cb_TypeDef
#endif
USBD_MSC_EMFAT_fops =
{
STORAGE_Init,
STORAGE_GetCapacity,
STORAGE_IsReady,
STORAGE_IsWriteProtected,
STORAGE_Read,
STORAGE_Write,
STORAGE_GetMaxLun,
(int8_t *)STORAGE_Inquirydata,
};

View File

@ -0,0 +1,25 @@
/*
* This file is part of Cleanflight.
*
* Cleanflight 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.
*
* Cleanflight 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*
* Author: jflyper (https://github.com/jflyper)
*
*/
#pragma once
#include "emfat.h"
extern emfat_t emfat;

View File

@ -33,13 +33,6 @@
#include "platform.h"
#include "common/utils.h"
#ifdef USE_HAL_DRIVER
#include "usbd_msc.h"
#else
#include "usbd_msc_mem.h"
#include "usbd_msc_core.h"
#endif
#include "usbd_storage.h"
#include "drivers/sdcard.h"

View File

@ -103,7 +103,7 @@
#undef USE_ADC_INTERNAL
#endif
#if !defined(USE_SDCARD)
#if !defined(USE_SDCARD) && !defined(USE_FLASHFS)
#undef USE_USB_MSC
#endif