From 624f28e66b785245650c96e6ca2375cf37f505ff Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Mon, 20 May 2013 12:47:54 -0600 Subject: Internal FLASH MTD driver for TI/Stellaris from Max Holtzberg --- nuttx/ChangeLog | 4 + nuttx/arch/arm/src/lm/Kconfig | 16 ++ nuttx/arch/arm/src/lm/Make.defs | 6 +- nuttx/arch/arm/src/lm/chip/lm_flash.h | 31 ++- nuttx/arch/arm/src/lm/lm_flash.c | 346 ++++++++++++++++++++++++++++++++++ nuttx/include/nuttx/mtd.h | 12 +- 6 files changed, 412 insertions(+), 3 deletions(-) create mode 100644 nuttx/arch/arm/src/lm/lm_flash.c diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index cf56b7291..fc2da4af3 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -4749,3 +4749,7 @@ and jVS1053 driver to NuttX. Contributed by Ken Pettit (2013-5-19). * configs/miroe-stm32f4/: Add audio logic to NSH configuration. From Ken Petty (2013-5-19). + * nuttx/arch/arm/src/lm/chip/lm_flash.h and nuttx/arch/arm/src/lm/lm_flash.c: + Add support for TI/Stellaris internal FLASH MTD driver. From Max + Holtzberg (2013-5-20). + diff --git a/nuttx/arch/arm/src/lm/Kconfig b/nuttx/arch/arm/src/lm/Kconfig index 676773d69..061fab52a 100644 --- a/nuttx/arch/arm/src/lm/Kconfig +++ b/nuttx/arch/arm/src/lm/Kconfig @@ -122,6 +122,12 @@ config LM_ETHERNET ---help--- This must be set (along with NET) to build the Stellaris Ethernet driver. +config LM_FLASH + bool "Stellaris internal FLASH" + default n + ---help--- + Enable MTD driver support for internal FLASH. + endmenu menu "Disable GPIO Interrupts" @@ -245,4 +251,14 @@ config SSI_TXLIMIT endmenu endif +if LM_FLASH +menu "Stellaris Internal Flash Driver Configuration" +config LM_FLASH_STARTPAGE + int "First page accessible by the MTD driver" + default 250 + ---help--- + To prevent accessing FLASH sections where code is stored. + +endmenu +endif diff --git a/nuttx/arch/arm/src/lm/Make.defs b/nuttx/arch/arm/src/lm/Make.defs index 8884554d9..1267e6cf9 100644 --- a/nuttx/arch/arm/src/lm/Make.defs +++ b/nuttx/arch/arm/src/lm/Make.defs @@ -68,7 +68,7 @@ ifeq ($(CONFIG_ELF),y) CMN_CSRCS += up_elf.c endif -CHIP_ASRCS = +CHIP_ASRCS = CHIP_CSRCS = lm_allocateheap.c lm_start.c lm_syscontrol.c lm_irq.c CHIP_CSRCS += lm_gpio.c lm_gpioirq.c lm_timerisr.c lm_lowputc.c lm_serial.c CHIP_CSRCS += lm_ssi.c lm_dumpgpio.c @@ -80,3 +80,7 @@ endif ifdef CONFIG_NET CHIP_CSRCS += lm_ethernet.c endif + +ifdef CONFIG_LM_FLASH +CHIP_CSRCS += lm_flash.c +endif diff --git a/nuttx/arch/arm/src/lm/chip/lm_flash.h b/nuttx/arch/arm/src/lm/chip/lm_flash.h index e5869bb0e..dc21e641f 100644 --- a/nuttx/arch/arm/src/lm/chip/lm_flash.h +++ b/nuttx/arch/arm/src/lm/chip/lm_flash.h @@ -46,6 +46,18 @@ * Pre-processor Definitions ************************************************************************************/ +/* FLASH dimensions ****************************************************************/ + +#if defined(CONFIG_ARCH_CHIP_LM3S6965) +# define LM_FLASH_NPAGES 256 +# define LM_FLASH_PAGESIZE 1024 +#else +# error "No flash dimensions defined for selected chip." +#endif + +#define LM_FLASH_SIZE (LM_FLASH_NPAGES * LM_FLASH_PAGESIZE) + + /* FLASH register offsets ***********************************************************/ /* The FMA, FMD, FMC, FCRIS, FCIM, and FCMISC registers are relative to the Flash @@ -111,7 +123,24 @@ #define LM_FLASH_FMPPE3 (LM_SYSCON_BASE + LM_FLASH_FMPPE3_OFFSET) /* FLASH register bit defitiions ****************************************************/ -/* To be provided */ + +#define FLASH_FMA_OFFSET_SHIFT 0 /* Bits 17-0: Address Offset */ +#define FLASH_FMA_OFFSET_MASK (0x0003ffff << FLASH_FMA_OFFSET_SHIFT) + +#define FLASH_FMC_WRITE (1 << 0) /* Write a Word into Flash Memory */ +#define FLASH_FMC_ERASE (1 << 1) /* Erase a Page of Flash Memory */ +#define FLASH_FMC_MERASE (1 << 2) /* Mass Erase Flash Memory */ +#define FLASH_FMC_COMT (1 << 3) /* Commit Register Value */ + +/* This field contains a write key, which is used to minimize the incidence + * of accidental flash writes. The value 0xA442 must be written into this + * field for a write to occur. Writes to the FMC register without this WRKEY + * value are ignored. A read of this field returns the value 0 + */ +#define FLASH_FMC_WRKEY_SHIFT 16 /* Bits 16-31: Flash Write Key */ +#define FLASH_FMC_WRKEY_MASK (0xffff << FLASH_FMC_WRKEY_SHIFT) +#define FLASH_FMC_WRKEY (0xa442 << FLASH_FMC_WRKEY_SHIFT) /* Magic write key */ + /************************************************************************************ * Public Types diff --git a/nuttx/arch/arm/src/lm/lm_flash.c b/nuttx/arch/arm/src/lm/lm_flash.c new file mode 100644 index 000000000..ca14f45d5 --- /dev/null +++ b/nuttx/arch/arm/src/lm/lm_flash.c @@ -0,0 +1,346 @@ +/**************************************************************************** + * arch/arm/src/lm/lm_flash.c + * + * Copyright (c) 2013 Max Holtzberg. All rights reserved. + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * + * Authors: Max Holtzberg + * Gregory Nutt + * + * This code is derived from drivers/mtd/skeleton.c + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include + +#include +#include + +#include "up_arch.h" +#include "chip.h" + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define LM_VIRTUAL_NPAGES (LM_FLASH_NPAGES - CONFIG_LM_FLASH_STARTPAGE) +#define LM_VIRTUAL_BASE (LM_FLASH_BASE \ + + CONFIG_LM_FLASH_STARTPAGE * LM_FLASH_PAGESIZE) + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* This type represents the state of the MTD device. The struct mtd_dev_s + * must appear at the beginning of the definition so that you can freely + * cast between pointers to struct mtd_dev_s and struct lm_dev_s. + */ + +struct lm_dev_s +{ + struct mtd_dev_s mtd; + + /* Other implementation specific data may follow here */ +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* MTD driver methods */ + +static int lm_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks); +static ssize_t lm_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, + FAR uint8_t *buf); +static ssize_t lm_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, + FAR const uint8_t *buf); +static ssize_t lm_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, + FAR uint8_t *buf); +#ifdef CONFIG_MTD_BYTE_WRITE +static ssize_t lm_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, + FAR const uint8_t *buf); +#endif +static int lm_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Data + ****************************************************************************/ +/* This structure holds the state of the MTD driver */ + +static struct lm_dev_s g_lmdev = +{ + { lm_erase, + lm_bread, + lm_bwrite, + lm_read, +#ifdef CONFIG_MTD_BYTE_WRITE + lm_write, +#endif + lm_ioctl + }, + /* Initialization of any other implementation specific data goes here */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lm_erase + * + * Description: + * Erase several blocks, each of the size previously reported. + * + ****************************************************************************/ + +static int lm_erase(FAR struct mtd_dev_s *dev, off_t startblock, + size_t nblocks) +{ + int curpage; + uint32_t pageaddr; + + DEBUGASSERT(nblocks <= LM_VIRTUAL_NPAGES); + + for (curpage = startblock; curpage < nblocks; curpage++) + { + pageaddr = LM_VIRTUAL_BASE + curpage * LM_FLASH_PAGESIZE; + + fvdbg("Erase page at %08x\n", pageaddr); + + /* set page address */ + + putreg32((pageaddr << FLASH_FMA_OFFSET_SHIFT) & FLASH_FMA_OFFSET_MASK, + LM_FLASH_FMA); + + /* set flash write key and erase bit */ + + putreg32(FLASH_FMC_WRKEY | FLASH_FMC_ERASE, LM_FLASH_FMC); + + /* wait until erase has finished */ + + while (getreg32(LM_FLASH_FMC) & FLASH_FMC_ERASE); + } + + return OK; +} + +/**************************************************************************** + * Name: lm_bread + * + * Description: + * Read the specified number of blocks into the user provided buffer. + * + ****************************************************************************/ + +static ssize_t lm_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, + FAR uint8_t *buf) +{ + DEBUGASSERT(startblock + nblocks <= LM_VIRTUAL_NPAGES); + + memcpy(buf, (void*)(LM_VIRTUAL_BASE + startblock * LM_FLASH_PAGESIZE), + nblocks * LM_FLASH_PAGESIZE); + + return nblocks; +} + +/**************************************************************************** + * Name: lm_bwrite + * + * Description: + * Write the specified number of blocks from the user provided buffer. + * + ****************************************************************************/ + +static ssize_t lm_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, + FAR const uint8_t *buf) +{ + FAR uint32_t *src = (uint32_t*)buf; + FAR uint32_t *dst = (uint32_t*)(LM_VIRTUAL_BASE + startblock * LM_FLASH_PAGESIZE); + int i; + + DEBUGASSERT(nblocks <= LM_VIRTUAL_NPAGES); + + for (i = 0; i < (nblocks * LM_FLASH_PAGESIZE) >> 2; i++) + { + /* set data to write */ + + putreg32(*src++, LM_FLASH_FMD); + + /* set destination address */ + + putreg32((uint32_t)dst++, LM_FLASH_FMA); + + /* start write */ + + putreg32(FLASH_FMC_WRKEY | FLASH_FMC_WRITE, LM_FLASH_FMC); + + /* wait until write has finished */ + + while(getreg32(LM_FLASH_FMC) & FLASH_FMC_WRITE); + } + + return nblocks; +} + +/**************************************************************************** + * Name: lm_read + * + * Description: + * Read the specified number of bytes to the user provided buffer. + * + ****************************************************************************/ + +static ssize_t lm_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, + FAR uint8_t *buf) +{ + DEBUGASSERT(offset + nbytes < LM_VIRTUAL_NPAGES * LM_FLASH_PAGESIZE); + + memcpy(buf, (void*)(LM_VIRTUAL_BASE + offset), nbytes); + + return nbytes; +} + +/**************************************************************************** + * Name: lm_write + * + * Description: + * Some FLASH parts have the ability to write an arbitrary number of + * bytes to an arbitrary offset on the device. + * + ****************************************************************************/ + +#ifdef CONFIG_MTD_BYTE_WRITE +static ssize_t lm_write(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, + FAR const uint8_t *buf) +{ + return -ENOSYS; +} +#endif + +/**************************************************************************** + * Name: lm_ioctl + ****************************************************************************/ + +static int lm_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) +{ + int ret = -EINVAL; /* Assume good command with bad parameters */ + + switch (cmd) + { + case MTDIOC_GEOMETRY: + { + FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)arg; + if (geo) + { + /* Populate the geometry structure with information needed to know + * the capacity and how to access the device. + * + * NOTE: that the device is treated as though it where just an array + * of fixed size blocks. That is most likely not true, but the client + * will expect the device logic to do whatever is necessary to make it + * appear so. + */ + + geo->blocksize = LM_FLASH_PAGESIZE; /* Size of one read/write block */ + geo->erasesize = LM_FLASH_PAGESIZE; /* Size of one erase block */ + geo->neraseblocks = LM_VIRTUAL_NPAGES; + ret = OK; + } + } + break; + + case MTDIOC_XIPBASE: + { + FAR void **ppv = (FAR void**)arg; + + if (ppv) + { + /* If media is directly acccesible, return (void*) base address + * of device memory. NULL otherwise. It is acceptable to omit + * this case altogether and simply return -ENOTTY. + */ + + *ppv = (void*)LM_VIRTUAL_BASE; + ret = OK; + } + } + break; + + case MTDIOC_BULKERASE: + { + /* Erase the entire device */ + + lm_erase(dev, 0, LM_VIRTUAL_NPAGES); + + ret = OK; + } + break; + + default: + ret = -ENOTTY; /* Bad command */ + break; + } + + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lm_initialize + * + * Description: + * Create and initialize an MTD device instance. MTD devices are not + * registered in the file system, but are created as instances that can + * be bound to other functions (such as a block or character driver front + * end). + * + ****************************************************************************/ + +FAR struct mtd_dev_s *up_flashinitialize(void) +{ + /* Return the implementation-specific state structure as the MTD device */ + + return (FAR struct mtd_dev_s *)&g_lmdev; +} diff --git a/nuttx/include/nuttx/mtd.h b/nuttx/include/nuttx/mtd.h index a528d0003..e59213832 100644 --- a/nuttx/include/nuttx/mtd.h +++ b/nuttx/include/nuttx/mtd.h @@ -138,7 +138,7 @@ struct mtd_dev_s * - MTDIOC_GEOMETRY: Get MTD geometry * - MTDIOC_XIPBASE: Convert block to physical address for eXecute-In-Place * - MTDIOC_BULKERASE: Erase the entire device - * (see include/nuttx/fs/ioctl.h) + * (see include/nuttx/fs/ioctl.h) */ int (*ioctl)(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg); @@ -318,6 +318,16 @@ FAR struct mtd_dev_s *w25_initialize(FAR struct spi_dev_s *dev); FAR struct mtd_dev_s *at25_initialize(FAR struct spi_dev_s *dev); +/**************************************************************************** + * Name: up_flashinitialize + * + * Description: + * Create an initialized MTD device instance for internal flash. + * + ****************************************************************************/ + +FAR struct mtd_dev_s *up_flashinitialize(void); + #undef EXTERN #ifdef __cplusplus } -- cgit v1.2.3