mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
HAL_F4Light: added support for DataFlash chips large than 128MBit
This commit is contained in:
parent
04dedd77d7
commit
b9dd569edd
@ -869,6 +869,9 @@ void sd_timerproc (void)
|
|||||||
#define JEDEC_DEVICE_ID 0x9F
|
#define JEDEC_DEVICE_ID 0x9F
|
||||||
#define JEDEC_PAGE_WRITE 0x02
|
#define JEDEC_PAGE_WRITE 0x02
|
||||||
|
|
||||||
|
#define JEDEC_WREAR 0xC5
|
||||||
|
#define JEDEC_ENTER_4B_MODE 0xB7
|
||||||
|
|
||||||
#define JEDEC_BULK_ERASE 0xC7 // full chip erase
|
#define JEDEC_BULK_ERASE 0xC7 // full chip erase
|
||||||
#define JEDEC_SECTOR_ERASE 0x20 // 4k erase
|
#define JEDEC_SECTOR_ERASE 0x20 // 4k erase
|
||||||
#define JEDEC_PAGE_ERASE 0xD8 // 64K erase
|
#define JEDEC_PAGE_ERASE 0xD8 // 64K erase
|
||||||
@ -891,6 +894,9 @@ static bool flash_died=false;
|
|||||||
static uint8_t df_manufacturer;
|
static uint8_t df_manufacturer;
|
||||||
static uint16_t df_device;
|
static uint16_t df_device;
|
||||||
static uint32_t erase_size = BOARD_DATAFLASH_ERASE_SIZE;
|
static uint32_t erase_size = BOARD_DATAFLASH_ERASE_SIZE;
|
||||||
|
static uint8_t addr_cmd_length = 4;
|
||||||
|
static uint8_t addr_cmd_start = 1;
|
||||||
|
static bool addr_4bit = 0;
|
||||||
|
|
||||||
#if BOARD_DATAFLASH_ERASE_SIZE >= 65536
|
#if BOARD_DATAFLASH_ERASE_SIZE >= 65536
|
||||||
static uint8_t erase_cmd=JEDEC_PAGE_ERASE;
|
static uint8_t erase_cmd=JEDEC_PAGE_ERASE;
|
||||||
@ -900,7 +906,7 @@ static uint32_t erase_size = BOARD_DATAFLASH_ERASE_SIZE;
|
|||||||
|
|
||||||
#pragma pack(push,1)
|
#pragma pack(push,1)
|
||||||
static struct {
|
static struct {
|
||||||
uint8_t cmd[4]; // for DMA transfer
|
uint8_t cmd[5]; // for DMA transfer
|
||||||
uint8_t sector[DF_PAGE_SIZE]; // we ALWAYS can use DMA!
|
uint8_t sector[DF_PAGE_SIZE]; // we ALWAYS can use DMA!
|
||||||
} buf;
|
} buf;
|
||||||
#pragma pack(pop)
|
#pragma pack(pop)
|
||||||
@ -1006,7 +1012,7 @@ static void ReadManufacturerID()
|
|||||||
// Read manufacturer and ID command...
|
// Read manufacturer and ID command...
|
||||||
buf.cmd[0] = JEDEC_DEVICE_ID;
|
buf.cmd[0] = JEDEC_DEVICE_ID;
|
||||||
|
|
||||||
spi_spiTransfer(buf.cmd, 1, buf.cmd, 4);
|
spi_spiTransfer(buf.cmd, 1, buf.cmd, addr_cmd_length);
|
||||||
|
|
||||||
df_manufacturer = buf.cmd[0];
|
df_manufacturer = buf.cmd[0];
|
||||||
df_device = (buf.cmd[1] << 8) | buf.cmd[2]; //capacity
|
df_device = (buf.cmd[1] << 8) | buf.cmd[2]; //capacity
|
||||||
@ -1077,6 +1083,15 @@ static void Flash_Jedec_WriteEnable(void){
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static void Flash_Enter4B_Mode(){
|
||||||
|
if (!wait_ready(500)) return; /* Wait for card ready */
|
||||||
|
|
||||||
|
if (!cs_assert()) return;
|
||||||
|
spi_write(JEDEC_ENTER_4B_MODE);
|
||||||
|
cs_release();
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
static bool read_page( uint8_t *ptr, uint32_t pageNum){
|
static bool read_page( uint8_t *ptr, uint32_t pageNum){
|
||||||
uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
|
uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
|
||||||
|
|
||||||
@ -1084,23 +1099,28 @@ static bool read_page( uint8_t *ptr, uint32_t pageNum){
|
|||||||
|
|
||||||
if (!cs_assert()) return 0;
|
if (!cs_assert()) return 0;
|
||||||
|
|
||||||
buf.cmd[0] = JEDEC_READ_DATA;
|
{
|
||||||
buf.cmd[1] = (PageAdr >> 16) & 0xff;
|
uint8_t i = 0;
|
||||||
buf.cmd[2] = (PageAdr >> 8) & 0xff;
|
|
||||||
buf.cmd[3] = (PageAdr >> 0) & 0xff;
|
|
||||||
|
|
||||||
|
buf.cmd[i++] = JEDEC_READ_DATA;
|
||||||
|
if(addr_4bit) {
|
||||||
|
buf.cmd[i++] = (PageAdr >> 24) & 0xff;
|
||||||
|
}
|
||||||
|
buf.cmd[i++] = (PageAdr >> 16) & 0xff;
|
||||||
|
buf.cmd[i++] = (PageAdr >> 8) & 0xff;
|
||||||
|
buf.cmd[i++] = (PageAdr >> 0) & 0xff;
|
||||||
|
}
|
||||||
|
|
||||||
spi_spiTransfer(buf.cmd, 4, buf.sector, DF_PAGE_SIZE);
|
spi_spiTransfer(&buf.cmd[0], addr_cmd_length, buf.sector, DF_PAGE_SIZE);
|
||||||
|
|
||||||
cs_release();
|
cs_release();
|
||||||
|
|
||||||
uint16_t i;
|
uint16_t i;
|
||||||
for(i=0; i<DF_PAGE_SIZE;i++){
|
for(i=0; i<DF_PAGE_SIZE;i++){
|
||||||
ptr[i] = ~buf.sector[i]; // let filesystem will be inverted, this allows extend files without having to Read-Modify-Write on FAT
|
ptr[i] = ~buf.sector[i]; // let filesystem will be inverted, this allows extend files without having to Read-Modify-Write on FAT
|
||||||
// original: 0xFF is clear and 0 can be programmed any time
|
} // original: 0xFF is clear and 0 can be programmed any time
|
||||||
// inverted: 0 is clear and 1 can be programmed any time
|
// inverted: 0 is clear and 1 can be programmed any time
|
||||||
// to mark cluster as used it should be set 1 in the FAT. Also new entries in dirs can be created without RMW
|
// to mark cluster as used it should be set 1 in the FAT. Also new entries in dirs can be created without RMW
|
||||||
}
|
|
||||||
|
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1108,25 +1128,32 @@ static bool read_page( uint8_t *ptr, uint32_t pageNum){
|
|||||||
static bool write_page(const uint8_t *ptr, uint32_t pageNum){
|
static bool write_page(const uint8_t *ptr, uint32_t pageNum){
|
||||||
uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
|
uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
|
||||||
|
|
||||||
|
{
|
||||||
uint16_t i;
|
uint16_t i;
|
||||||
for(i=0; i<DF_PAGE_SIZE;i++){
|
for(i=0; i<DF_PAGE_SIZE;i++){
|
||||||
buf.sector[i] = ~ptr[i]; // let filesystem will be inverted, this allows extend files without having to Read-Modify-Write on FAT
|
buf.sector[i] = ~ptr[i]; // let filesystem will be inverted, this allows extend files without having to Read-Modify-Write on FAT
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
Flash_Jedec_WriteEnable();
|
Flash_Jedec_WriteEnable();
|
||||||
|
|
||||||
if (!cs_assert()) return 0;
|
if (!cs_assert()) return 0;
|
||||||
|
|
||||||
buf.cmd[0] = JEDEC_PAGE_WRITE;
|
uint8_t i = addr_cmd_start;
|
||||||
buf.cmd[1] = (PageAdr >> 16) & 0xff;
|
|
||||||
buf.cmd[2] = (PageAdr >> 8) & 0xff;
|
buf.cmd[i++] = JEDEC_PAGE_WRITE;
|
||||||
buf.cmd[3] = (PageAdr >> 0) & 0xff;
|
if(addr_4bit) {
|
||||||
|
buf.cmd[i++] = (PageAdr >> 16) & 0xff;
|
||||||
|
}
|
||||||
|
buf.cmd[i++] = (PageAdr >> 16) & 0xff;
|
||||||
|
buf.cmd[i++] = (PageAdr >> 8) & 0xff;
|
||||||
|
buf.cmd[i++] = (PageAdr >> 0) & 0xff;
|
||||||
|
|
||||||
#if 0
|
#if 0
|
||||||
write_spi_multi(buf.cmd, 4);
|
write_spi_multi(&buf.cmd[addr_cmd_start], addr_cmd_length);
|
||||||
write_spi_multi(buf.sector, DF_PAGE_SIZE);
|
write_spi_multi(buf.sector, DF_PAGE_SIZE);
|
||||||
#else
|
#else
|
||||||
write_spi_multi(buf.cmd, 4 + DF_PAGE_SIZE);
|
write_spi_multi(&buf.cmd[addr_cmd_start], addr_cmd_length + DF_PAGE_SIZE);
|
||||||
#endif
|
#endif
|
||||||
cs_release();
|
cs_release();
|
||||||
return 1;
|
return 1;
|
||||||
@ -1139,13 +1166,17 @@ static bool erase_page(uint16_t pageNum)
|
|||||||
|
|
||||||
uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
|
uint32_t PageAdr = pageNum * DF_PAGE_SIZE;
|
||||||
|
|
||||||
buf.cmd[0] = erase_cmd;
|
uint8_t i=0;
|
||||||
buf.cmd[1] = (PageAdr >> 16) & 0xff;
|
buf.cmd[i++] = erase_cmd;
|
||||||
buf.cmd[2] = (PageAdr >> 8) & 0xff;
|
if(addr_4bit) {
|
||||||
buf.cmd[3] = (PageAdr >> 0) & 0xff;
|
buf.cmd[i++] = (PageAdr >> 24) & 0xff;
|
||||||
|
}
|
||||||
|
buf.cmd[i++] = (PageAdr >> 16) & 0xff;
|
||||||
|
buf.cmd[i++] = (PageAdr >> 8) & 0xff;
|
||||||
|
buf.cmd[i++] = (PageAdr >> 0) & 0xff;
|
||||||
|
|
||||||
if (!cs_assert()) return 0;
|
if (!cs_assert()) return 0;
|
||||||
write_spi_multi(buf.cmd, 4);
|
write_spi_multi(buf.cmd, addr_cmd_length);
|
||||||
cs_release();
|
cs_release();
|
||||||
return 1;
|
return 1;
|
||||||
}
|
}
|
||||||
@ -1234,6 +1265,13 @@ uint8_t sd_getSectorCount(uint32_t *ptr){
|
|||||||
size = BOARD_DATAFLASH_PAGES; // as defined
|
size = BOARD_DATAFLASH_PAGES; // as defined
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if(size>65537) {
|
||||||
|
addr_cmd_length = 5;
|
||||||
|
addr_cmd_start = 0;
|
||||||
|
addr_4bit = true;
|
||||||
|
Flash_Enter4B_Mode();
|
||||||
|
}
|
||||||
|
|
||||||
if(erase_size > MAX_ERASE_SIZE) size -= (erase_size/DF_PAGE_SIZE); // reserve for RMW ops
|
if(erase_size > MAX_ERASE_SIZE) size -= (erase_size/DF_PAGE_SIZE); // reserve for RMW ops
|
||||||
|
|
||||||
*ptr = size / (FAT_SECTOR_SIZE/DF_PAGE_SIZE); // in 512b blocks
|
*ptr = size / (FAT_SECTOR_SIZE/DF_PAGE_SIZE); // in 512b blocks
|
||||||
@ -1264,12 +1302,6 @@ DSTATUS sd_initialize () {
|
|||||||
|
|
||||||
initialized=1;
|
initialized=1;
|
||||||
|
|
||||||
#if 0
|
|
||||||
void *task = hal_register_task(sd_flash_eraser, 512); // only for one context
|
|
||||||
hal_set_task_priority(task, 110); // 5 higher than IO
|
|
||||||
_flash_erase_task=task;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
Stat=0;
|
Stat=0;
|
||||||
return Stat;
|
return Stat;
|
||||||
}
|
}
|
||||||
@ -1625,35 +1657,6 @@ DRESULT sd_ioctl (
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
static void sd_flash_eraser(){
|
|
||||||
while(fe_read_ptr != fe_write_ptr) { // there are samples
|
|
||||||
|
|
||||||
uint32_t start_sector = flash_erase_queue[fe_read_ptr].b;
|
|
||||||
uint32_t end_sector = flash_erase_queue[fe_read_ptr].e;
|
|
||||||
|
|
||||||
fe_read_ptr++;
|
|
||||||
if(fe_read_ptr >= FLASH_ERASE_QUEUE_SIZE) { // move read pointer
|
|
||||||
fe_read_ptr=0; // ring
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t block, last_block=-1;
|
|
||||||
|
|
||||||
uint32_t sector;
|
|
||||||
for(sector=start_sector; sector <= end_sector;sector++){
|
|
||||||
uint32_t df_sect = sector * (FAT_SECTOR_SIZE/DF_PAGE_SIZE); // sector in DataFlash
|
|
||||||
block = df_sect / (erase_size/DF_PAGE_SIZE); // number of EraseBlock
|
|
||||||
if(last_block!=block){
|
|
||||||
last_block=block;
|
|
||||||
erase_page(df_sect);
|
|
||||||
putch('.');
|
|
||||||
// extern void digitalToggle(uint8_t pin);
|
|
||||||
// digitalToggle(HAL_GPIO_A_LED_PIN);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
/*-----------------------------------------------------------------------*/
|
/*-----------------------------------------------------------------------*/
|
||||||
/* Device timer function */
|
/* Device timer function */
|
||||||
/*-----------------------------------------------------------------------*/
|
/*-----------------------------------------------------------------------*/
|
||||||
|
Loading…
Reference in New Issue
Block a user