From bc3cb304a055da388bd64197942cfcbe23a26ae2 Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 18 Jul 2012 18:38:49 +0000 Subject: [PATCH] Create an MTD driver for SPIFI git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4951 7fd9a85b-ad96-42d3-883c-3090e2eb8679 --- nuttx/ChangeLog | 6 +- nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h | 50 +- nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c | 891 +++++++++++++++++- nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h | 45 +- nuttx/configs/lpc4330-xplorer/README.txt | 36 +- nuttx/configs/lpc4330-xplorer/nsh/defconfig | 48 +- nuttx/configs/lpc4330-xplorer/src/up_nsh.c | 147 +-- 7 files changed, 992 insertions(+), 231 deletions(-) diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index e33bee7500..5487143717 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3017,5 +3017,9 @@ RTC alarm EXTI interrupt. This is work be performed mostly by Diego Sanchez. * include/: More stylistic file clean-up. * arch/arm/src/lpc43xx/lpc43_spifi.c, lpc43_spifi.h, and chip/lpc43_spifi.h: Add - logic to configure and intialize the SPIFI device (does not yet work). + logic to configure and initialize the SPIFI device (does not yet work). + * configs/lpc4330-xplorer/include/board.h: Reduce SPI SCLK value. + * arch/arm/src/lpc43xx/lpc43_spifi.c, lpc43_spifi.h, and chip/lpc43_spifi.h: + Logic completely redesigned. It now creates an MTD driver to access SPIFI... + but the driver still does not work. diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h index 711f10ac30..053b1947e8 100644 --- a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h +++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h @@ -92,24 +92,24 @@ * have the same relationship as in the Control register) */ -#define SPIFI_MODE3 (1 << 0) -#define SPIFI_MODE0 (0) -#define SPIFI_MINIMAL (1 << 1) -#define SPIFI_MAXIMAL (0) -#define SPIFI_FORCE_ERASE (1 << 2) -#define SPIFI_ERASE_NOT_REQD (1 << 3) -#define SPIFI_CALLER_ERASE (1 << 3) -#define SPIFI_ERASE_AS_REQD (0) -#define SPIFI_VERIFY_PROG (1 << 4) -#define SPIFI_VERIFY_ERASE (1 << 5) -#define SPIFI_NO_VERIFY (0) -#define SPIFI_FULLCLK (1 << 6) -#define SPIFI_HALFCLK (0) -#define SPIFI_RCVCLK (1 << 7) -#define SPIFI_INTCLK (0) -#define SPIFI_DUAL (1 << 8) -#define SPIFI_CALLER_PROT (1 << 9) -#define SPIFI_DRIVER_PROT (0) +#define S_MODE3 (1 << 0) +#define S_MODE0 (0) +#define S_MINIMAL (1 << 1) +#define S_MAXIMAL (0) +#define S_FORCE_ERASE (1 << 2) +#define S_ERASE_NOT_REQD (1 << 3) +#define S_CALLER_ERASE (1 << 3) +#define S_ERASE_AS_REQD (0) +#define S_VERIFY_PROG (1 << 4) +#define S_VERIFY_ERASE (1 << 5) +#define S_NO_VERIFY (0) +#define S_FULLCLK (1 << 6) +#define S_HALFCLK (0) +#define S_RCVCLK (1 << 7) +#define S_INTCLK (0) +#define S_DUAL (1 << 8) +#define S_CALLER_PROT (1 << 9) +#define S_DRIVER_PROT (0) /* The length of a standard program command is 256 on all devices */ @@ -178,9 +178,9 @@ struct spifi_dev_s struct spifi_operands_s { - char *dest; + uint8_t *dest; uint32_t length; - char *scratch; + uint8_t *scratch; int32_t protect; uint32_t options; }; @@ -191,7 +191,7 @@ struct spifi_driver_s { int32_t (*spifi_init)(struct spifi_dev_s *dev, uint32_t cshigh, uint32_t options, uint32_t mhz); - int32_t (*spifi_program)(struct spifi_dev_s *dev, char *source, + int32_t (*spifi_program)(struct spifi_dev_s *dev, const uint8_t *source, struct spifi_operands_s *opers); int32_t (*spifi_erase)(struct spifi_dev_s *dev, struct spifi_operands_s *opers); @@ -206,16 +206,16 @@ struct spifi_driver_s int32_t (*checkAd)(struct spifi_dev_s *dev, struct spifi_operands_s *opers); int32_t (*setProt)(struct spifi_dev_s *dev, - struct spifi_operands_s *opers, char *change, char *saveprot); - int32_t (*check_block) (struct spifi_dev_s *dev, char *source, + struct spifi_operands_s *opers, uint8_t *change, uint8_t *saveprot); + int32_t (*check_block) (struct spifi_dev_s *dev, uint8_t *source, struct spifi_operands_s *opers, uint32_t check_program); int32_t (*send_erase_cmd)(struct spifi_dev_s *dev, uint8_t op, uint32_t addr); uint32_t (*ck_erase) (struct spifi_dev_s *dev, uint32_t *addr, uint32_t length); - int32_t (*prog_block)(struct spifi_dev_s *dev, char *source, + int32_t (*prog_block)(struct spifi_dev_s *dev, uint8_t *source, struct spifi_operands_s *opers, uint32_t *left_in_page); - uint32_t (*ck_prog)(struct spifi_dev_s *dev, char *source, char *dest, + uint32_t (*ck_prog)(struct spifi_dev_s *dev, uint8_t *source, uint8_t *dest, uint32_t length); /* Low level functions */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c index bd97cbd83b..937840b801 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c @@ -40,9 +40,19 @@ #include #include +#include +#include +#include +#include +#include +#include #include #include +#include +#include +#include + #include #include @@ -56,8 +66,88 @@ #ifdef CONFIG_LPC43_SPIFI /**************************************************************************** - * Pre-processor Definitions + * Pre-Processor Definitions ****************************************************************************/ +/* SPIFI Configuration ******************************************************/ +/* This logic supports some special options that can be used to create an + * mtd device on the SPIFI FLASH. NOTE: CONFIG_LPC43_SPIFI=y must also + * be defined to enable SPIFI setup support: + * + * CONFIG_SPIFI_RDONLY - Create a read only device on SPIFI. + * CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this many + * bytes into the device address space. This offset must be an exact + * multiple of the erase block size. Default 0. + * CONFIG_SPIFI_SECTOR512 - If defined, then the driver will report a more + * FAT friendly 512 byte sector size and will manage the read-modify-write + * operations on the larger erase block. + * CONFIG_SPIFI_READONLY - Define to support only read-only operations. + */ + +/* This is where the LPC43xx address where random-access reads begin */ + +#define SPIFI_BASE \ + (FAR uint8_t *)(LPC43_LOCSRAM_SPIFI_BASE + CONFIG_SPIFI_OFFSET) + +/* Check if we are using a hard-coded block size */ + +#ifdef CONFIG_SPIFI_BLKSIZE +# if CONFIG_SPIFI_BLKSIZE < 512 +# error "CONFIG_SPIFI_BLKSIZE is too small" +# elif CONFIG_SPIFI_BLKSIZE == 512 +# define SPIFI_BLKSHIFT 9 +# elif CONFIG_SPIFI_BLKSIZE == 1024 +# define SPIFI_BLKSHIFT 10 +# elif CONFIG_SPIFI_BLKSIZE == (2*1024) +# define SPIFI_BLKSHIFT 11 +# elif CONFIG_SPIFI_BLKSIZE == (4*1024) +# define SPIFI_BLKSHIFT 12 +# elif CONFIG_SPIFI_BLKSIZE == (8*1024) +# define SPIFI_BLKSHIFT 13 +# elif CONFIG_SPIFI_BLKSIZE == (16*1024) +# define SPIFI_BLKSHIFT 14 +# elif CONFIG_SPIFI_BLKSIZE == (32*1024) +# define SPIFI_BLKSHIFT 15 +# elif CONFIG_SPIFI_BLKSIZE == (64*1024) +# define SPIFI_BLKSHIFT 16 +# elif CONFIG_SPIFI_BLKSIZE == (128*1024) +# define SPIFI_BLKSHIFT 17 +# elif CONFIG_SPIFI_BLKSIZE == (256*1024) +# define SPIFI_BLKSHIFT 18 +# else +# error "Unsupported value of CONFIG_SPIFI_BLKSIZE +# endif +# define SPIFI_BLKSIZE CONFIG_SPIFI_BLKSIZE +#else +# define SPIFI_BLKSIZE priv->blksize +# define SPIFI_BLKSHIFT priv->blkshift +#endif + +/* 512 byte sector simulation */ + +#ifdef CONFIG_SPIFI_SECTOR512 /* Emulate a 512 byte sector */ +# define SPIFI_512SHIFT 9 /* Sector size 1 << 9 = 512 bytes */ +# define SPIFI_512SIZE 512 /* Sector size = 512 bytes */ +#endif + +#define SPIFI_ERASED_STATE 0xff /* State of FLASH when erased */ + +/* Cache flags */ + +#define SST25_CACHE_VALID (1 << 0) /* 1=Cache has valid data */ +#define SST25_CACHE_DIRTY (1 << 1) /* 1=Cache is dirty */ +#define SST25_CACHE_ERASED (1 << 2) /* 1=Backing FLASH is erased */ + +#define IS_VALID(p) ((((p)->flags) & SST25_CACHE_VALID) != 0) +#define IS_DIRTY(p) ((((p)->flags) & SST25_CACHE_DIRTY) != 0) +#define IS_ERASED(p) ((((p)->flags) & SST25_CACHE_DIRTY) != 0) + +#define SET_VALID(p) do { (p)->flags |= SST25_CACHE_VALID; } while (0) +#define SET_DIRTY(p) do { (p)->flags |= SST25_CACHE_DIRTY; } while (0) +#define SET_ERASED(p) do { (p)->flags |= SST25_CACHE_DIRTY; } while (0) + +#define CLR_VALID(p) do { (p)->flags &= ~SST25_CACHE_VALID; } while (0) +#define CLR_DIRTY(p) do { (p)->flags &= ~SST25_CACHE_DIRTY; } while (0) +#define CLR_ERASED(p) do { (p)->flags &= ~SST25_CACHE_DIRTY; } while (0) /* Select the divider to use as SPIFI input based on definitions in the * board.h header file. @@ -116,6 +206,19 @@ # error "Invalid value for BOARD_SPIFI_DIVIDER" #endif +/* SPIFI_CSHIGH should be one less than the minimum number of clock cycles + * with the CS pin high, that the SPIFI should maintain between commands. + * Compute this from the SPIFI clock period and the minimum high time of CS + * from the serial flash data sheet: + * + * csHigh = ceiling( min CS high / SPIFI clock period ) - 1 + * + * where ceiling means round up to the next higher integer if the argument + * isn’t an integer. + */ + +#define SPIFI_CSHIGH 9 + /* The final parameter of the spifi_init() ROM driver call should be the * serial clock rate divided by 1000000, rounded to an integer. The SPIFI * supports transfer rates of up to SPIFI_CLK/2 bytes per second. The SPIF_CLK @@ -125,16 +228,577 @@ #define SCLK_MHZ (BOARD_SPIFI_FREQUENCY + (1000000 / 2)) / 1000000 +/**************************************************************************** + * 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 lpc43_dev_s. + */ + +struct lpc43_dev_s +{ + struct mtd_dev_s mtd; /* MTD interface */ + FAR struct spifi_driver_s *spifi; /* Pointer to ROM driver table */ + FAR struct spifi_dev_s rom; /* Needed for communication with ROM driver */ + struct spifi_operands_s operands; /* Needed for program and erase ROM calls */ + uint16_t nblocks; /* Number of blocks of size blksize */ +#ifndef CONFIG_SPIFI_BLKSIZE + uint8_t blkshift; /* Log2 of erase block size */ + uint32_t blksize; /* Size of one erase block (up to 256K) */ +#endif + +#if defined(CONFIG_SPIFI_SECTOR512) && !defined(CONFIG_SPIFI_READONLY) + uint8_t flags; /* Buffered sector flags */ + uint16_t blkno; /* Erase block number in the cache */ + FAR uint8_t *cache; /* Allocated sector data */ +#endif +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* Helpers */ + +static void lpc43_blockerase(FAR struct lpc43_dev_s *priv, off_t offset); +static inline int lpc43_chiperase(FAR struct lpc43_dev_s *priv); +static inline void lpc43_pageread(FAR struct lpc43_dev_s *priv, + FAR uint8_t *dest, FAR const uint8_t *src, + size_t nbytes); +#ifndef CONFIG_SPIFI_READONLY +static int lpc43_pagewrite(FAR struct lpc43_dev_s *priv, FAR uint8_t *dest, + FAR const uint8_t *src, size_t nbytes); +#ifdef CONFIG_SPIFI_SECTOR512 +static void lpc43_cacheflush(struct lpc43_dev_s *priv); +static FAR uint8_t *lpc43_cacheread(struct lpc43_dev_s *priv, off_t sector); +static void lpc43_cacheerase(struct lpc43_dev_s *priv, off_t sector); +static void lpc43_cachewrite(FAR struct lpc43_dev_s *priv, FAR const uint8_t *buffer, + off_t sector, size_t nsectors); +#endif +#endif + +/* MTD driver methods */ + +static int lpc43_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks); +static ssize_t lpc43_bread(FAR struct mtd_dev_s *dev, off_t startblock, + size_t nblocks, FAR uint8_t *buf); +static ssize_t lpc43_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, + size_t nblocks, FAR const uint8_t *buf); +static ssize_t lpc43_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, + FAR uint8_t *buffer); +static int lpc43_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg); + +/* Initialization */ + +#ifndef BOARD_SPIFI_PLL1 +static inline void lpc43_idiv_clkconfig(void); +#endif + +static inline void lpc43_spifi_clkconfig(void); +static inline void lpc43_spifi_pinconfig(void); +static inline int lpc43_rominit(FAR struct lpc43_dev_s *priv); + /**************************************************************************** * Private Data ****************************************************************************/ +/* Only a single SPIFI driver instance is supported */ + +static struct lpc43_dev_s g_spifi; + /**************************************************************************** * Private Functions ****************************************************************************/ /**************************************************************************** - * Name: spifi_idiv_input + * Name: lpc43_blockerase + ****************************************************************************/ + +static void lpc43_blockerase(struct lpc43_dev_s *priv, off_t sector) +{ + int result; + + /* Erase one block on the chip: + * + * dest - Specifies the first address to be programmed or erased, either in + * the SPIFI memory area or as a zero-based device address. It must + * be at an offset that is an exact multiple of the erase block size. + * length - The number of bytes to be programmed or erased + */ + + priv->operands.dest = SPIFI_BASE + (sector << SPIFI_BLKSHIFT); + priv->operands.length = SPIFI_BLKSIZE; + + result = priv->spifi->spifi_erase(&priv->rom, &priv->operands); + if (result != 0) + { + fdbg("ERROR: spifi_erase failed: %05x\n", result); + } +} + +/**************************************************************************** + * Name: lpc43_chiperase + ****************************************************************************/ + +static inline int lpc43_chiperase(struct lpc43_dev_s *priv) +{ + int result; + + /* Erase the entire chip: + * + * dest - Specifies the first address to be programmed or erased, either in + * the SPIFI memory area or as a zero-based device address. It must + * be at an offset that is an exact multiple of the erase block size. + * length - The number of bytes to be programmed or erased + */ + + priv->operands.dest = SPIFI_BASE; + priv->operands.length = SPIFI_BLKSIZE * priv->nblocks; + + result = priv->spifi->spifi_erase(&priv->rom, &priv->operands); + if (result != 0) + { + fdbg("ERROR: spifi_erase failed: %05x\n", result); + return -EIO; + } + + return OK; +} + +/**************************************************************************** + * Name: lpc43_pagewrite + ****************************************************************************/ + +#ifndef CONFIG_SPIFI_READONLY +static int lpc43_pagewrite(FAR struct lpc43_dev_s *priv, FAR uint8_t *dest, + FAR const uint8_t *src, size_t nbytes) +{ + int result; + + /* Write FLASH pages: + * + * dest - Specifies the first address to be programmed or erased, either in + * the SPIFI memory area or as a zero-based device address. It must + * be at an offset that is an exact multiple of the erase block size. + * length - The number of bytes to be programmed or erased + */ + + priv->operands.dest = dest; + priv->operands.length = nbytes; + + result = priv->spifi->spifi_program(&priv->rom, src, &priv->operands); + if (result != 0) + { + fdbg("ERROR: spifi_program failed: %05x\n", result); + return -EIO; + } + + return OK; +} +#endif + +/**************************************************************************** + * Name: lpc43_pageread + ****************************************************************************/ + +static inline void lpc43_pageread(FAR struct lpc43_dev_s *priv, + FAR uint8_t *dest, FAR const uint8_t *src, + size_t nbytes) +{ + memcpy(dest, src, nbytes); +} + +/**************************************************************************** + * Name: lpc43_cacheflush + ****************************************************************************/ + +#if defined(CONFIG_SPIFI_SECTOR512) && !defined(CONFIG_SPIFI_READONLY) +static void lpc43_cacheflush(struct lpc43_dev_s *priv) +{ + FAR uint8_t *dest; + int ret; + + /* If the cached is dirty (meaning that it no longer matches the old FLASH contents) + * or was erased (with the cache containing the correct FLASH contents), then write + * the cached erase block to FLASH. + */ + + if (IS_DIRTY(priv) || IS_ERASED(priv)) + { + /* Get the SPIFI address corresponding to the cached erase block */ + + dest = SPIFI_BASE + (priv->blkno << SPIFI_BLKSHIFT); + + /* Write entire erase block to FLASH */ + + ret = lpc43_pagewrite(priv, dest, priv->cache, SPIFI_BLKSIZE); + if (ret < 0) + { + fdbg("ERROR: lpc43_pagewrite failed: %d\n", ret); + } + + /* The case is no long dirty and the FLASH is no longer erased */ + + CLR_DIRTY(priv); + CLR_ERASED(priv); + } +} +#endif + +/**************************************************************************** + * Name: lpc43_cacheread + ****************************************************************************/ + +#if defined(CONFIG_SPIFI_SECTOR512) && !defined(CONFIG_SPIFI_READONLY) +static FAR uint8_t *lpc43_cacheread(struct lpc43_dev_s *priv, off_t sector) +{ + FAR const uint8_t *src; + off_t blkno; + int index; + + /* Convert from the 512 byte sector to the erase sector size of the device. For + * exmample, if the actual erase sector size if 4Kb (1 << 12), then we first + * shift to the right by 3 to get the sector number in 4096 increments. + */ + + blkno = sector >> (SPIFI_BLKSHIFT - SPIFI_512SHIFT); + fvdbg("sector: %ld blkno: %d\n", sector, blkno); + + /* Check if the requested erase block is already in the cache */ + + if (!IS_VALID(priv) || blkno != priv->blkno) + { + /* No.. Flush any dirty erase block currently in the cache */ + + lpc43_cacheflush(priv); + + /* Read the erase block into the cache */ + /* Get the SPIFI address corresponding to the cached erase block */ + + src = SPIFI_BASE + (priv->blkno << SPIFI_BLKSHIFT); + + /* Write entire erase block to FLASH */ + + lpc43_pageread(priv, priv->cache, src, SPIFI_BLKSIZE); + + /* Mark the sector as cached */ + + priv->blkno = blkno; + + SET_VALID(priv); /* The data in the cache is valid */ + CLR_DIRTY(priv); /* It should match the FLASH contents */ + CLR_ERASED(priv); /* The underlying FLASH has not been erased */ + } + + /* Get the index to the 512 sector in the erase block that holds the argument */ + + index = sector & ((1 << (SPIFI_BLKSHIFT - SPIFI_512SHIFT)) - 1); + + /* Return the address in the cache that holds this sector */ + + return &priv->cache[index << SPIFI_512SHIFT]; +} +#endif + +/**************************************************************************** + * Name: lpc43_cacheerase + ****************************************************************************/ + +#if defined(CONFIG_SPIFI_SECTOR512) && !defined(CONFIG_SPIFI_READONLY) +static void lpc43_cacheerase(struct lpc43_dev_s *priv, off_t sector) +{ + FAR uint8_t *dest; + + /* First, make sure that the erase block containing the 512 byte sector is in + * the cache. + */ + + dest = lpc43_cacheread(priv, sector); + + /* Erase the block containing this sector if it is not already erased. + * The erased indicated will be cleared when the data from the erase sector + * is read into the cache and set here when we erase the block. + */ + + if (!IS_ERASED(priv)) + { + off_t blkno = sector >> (SPIFI_BLKSHIFT - SPIFI_512SHIFT); + fvdbg("sector: %ld blkno: %d\n", sector, blkno); + + lpc43_blockerase(priv, blkno); + SET_ERASED(priv); + } + + /* Put the cached sector data into the erase state and mart the cache as dirty + * (but don't update the FLASH yet. The caller will do that at a more optimal + * time). + */ + + memset(dest, SPIFI_ERASED_STATE, SPIFI_512SIZE); + SET_DIRTY(priv); +} +#endif + +/**************************************************************************** + * Name: lpc43_cachewrite + ****************************************************************************/ + +#if defined(CONFIG_SPIFI_SECTOR512) && !defined(CONFIG_SPIFI_READONLY) +static void lpc43_cachewrite(FAR struct lpc43_dev_s *priv, FAR const uint8_t *buffer, + off_t sector, size_t nsectors) +{ + FAR uint8_t *dest; + + for (; nsectors > 0; nsectors--) + { + /* First, make sure that the erase block containing 512 byte sector is in + * memory. + */ + + dest = lpc43_cacheread(priv, sector); + + /* Erase the block containing this sector if it is not already erased. + * The erased indicated will be cleared when the data from the erase sector + * is read into the cache and set here when we erase the sector. + */ + + if (!IS_ERASED(priv)) + { + off_t blkno = sector >> (SPIFI_BLKSHIFT - SPIFI_512SHIFT); + fvdbg("sector: %ld blkno: %d\n", sector, blkno); + + lpc43_blockerase(priv, blkno); + SET_ERASED(priv); + } + + /* Copy the new sector data into cached erase block */ + + memcpy(dest, buffer, SPIFI_512SIZE); + SET_DIRTY(priv); + + /* Set up for the next 512 byte sector */ + + buffer += SPIFI_512SIZE; + sector++; + } + + /* Flush the last erase block left in the cache */ + + lpc43_cacheflush(priv); +} +#endif + +/**************************************************************************** + * Name: lpc43_erase + ****************************************************************************/ + +static int lpc43_erase(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks) +{ +#ifdef CONFIG_SPIFI_READONLY + return -EACESS +#else + FAR struct lpc43_dev_s *priv = (FAR struct lpc43_dev_s *)dev; + size_t blocksleft = nblocks; + + fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + while (blocksleft-- > 0) + { + /* Erase each sector */ + +#ifdef CONFIG_SPIFI_SECTOR512 + lpc43_cacheerase(priv, startblock); +#else + lpc43_blockerase(priv, startblock); +#endif + startblock++; + } + +#ifdef CONFIG_SPIFI_SECTOR512 + /* Flush the last erase block left in the cache */ + + lpc43_cacheflush(priv); +#endif + + return (int)nblocks; +#endif +} + +/**************************************************************************** + * Name: lpc43_bread + ****************************************************************************/ + +static ssize_t lpc43_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, + FAR uint8_t *buffer) +{ +#ifdef CONFIG_SPIFI_SECTOR512 + ssize_t nbytes; + + fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + /* On this device, we can handle the block read just like the byte-oriented read */ + + nbytes = lpc43_read(dev, startblock << SPIFI_512SHIFT, nblocks << SPIFI_512SHIFT, buffer); + if (nbytes > 0) + { + return nbytes >> SPIFI_512SHIFT; + } + + return (int)nbytes; +#else + FAR struct lpc43_dev_s *priv = (FAR struct lpc43_dev_s *)dev; + ssize_t nbytes; + + fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + /* On this device, we can handle the block read just like the byte-oriented read */ + + nbytes = lpc43_read(dev, startblock << SPIFI_BLKSHIFT, + nblocks << SPIFI_BLKSHIFT, buffer); + if (nbytes > 0) + { + return nbytes >> SPIFI_BLKSHIFT; + } + + return (int)nbytes; +#endif +} + +/**************************************************************************** + * Name: lpc43_bwrite + ****************************************************************************/ + +static ssize_t lpc43_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t nblocks, + FAR const uint8_t *buffer) +{ +#if defined(CONFIG_SPIFI_READONLY) + + return -EACCESS; + +#elif defined(CONFIG_SPIFI_SECTOR512) + + FAR struct lpc43_dev_s *priv = (FAR struct lpc43_dev_s *)dev; + + fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + lpc43_cachewrite(priv, buffer, startblock, nblocks); + return nblocks; + +#else + + FAR struct lpc43_dev_s *priv = (FAR struct lpc43_dev_s *)dev; + FAR uint8_t *dest; + + fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks); + + /* Get the SPIFI address corresponding to the erase block */ + + dest = SPIFI_BASE + (startblock << SPIFI_BLKSHIFT); + + /* Write all of the erase blocks to FLASH */ + + ret = lpc43_pagewrite(priv, dest, buffer, nblocks << SPIFI_512SHIFT); + if (ret < 0) + { + fdbg("ERROR: lpc43_pagewrite failed: %d\n", ret); + return ret; + } + + return nblocks; + +#endif +} + +/**************************************************************************** + * Name: lpc43_read + ****************************************************************************/ + +static ssize_t lpc43_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbytes, + FAR uint8_t *buffer) +{ + FAR struct lpc43_dev_s *priv = (FAR struct lpc43_dev_s *)dev; + FAR const uint8_t *src; + + fvdbg("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); + + /* Get the SPIFI address corresponding sector */ + + src = SPIFI_BASE + offset; + + /* Read FLASH contents into the user buffer */ + + lpc43_pageread(priv, buffer, src, nbytes); + + fvdbg("return nbytes: %d\n", (int)nbytes); + return nbytes; +} + +/**************************************************************************** + * Name: lpc43_ioctl + ****************************************************************************/ + +static int lpc43_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) +{ + FAR struct lpc43_dev_s *priv = (FAR struct lpc43_dev_s *)dev; + int ret = -EINVAL; /* Assume good command with bad parameters */ + + fvdbg("cmd: %d \n", cmd); + + switch (cmd) + { + case MTDIOC_GEOMETRY: + { + FAR struct mtd_geometry_s *geo = (FAR struct mtd_geometry_s *)((uintptr_t)arg); + if (geo) + { + /* Populate the geometry structure with information need 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. + */ + +#ifdef CONFIG_SPIFI_SECTOR512 + geo->blocksize = 512; + geo->erasesize = 512; + geo->neraseblocks = priv->nblocks << (SPIFI_BLKSHIFT - SPIFI_512SHIFT); +#else + geo->blocksize = SPIFI_BLKSIZE; + geo->erasesize = SPIFI_BLKSIZE; + geo->neraseblocks = priv->nblocks; +#endif + ret = OK; + + fvdbg("blocksize: %d erasesize: %d neraseblocks: %d\n", + geo->blocksize, geo->erasesize, geo->neraseblocks); + } + } + break; + + case MTDIOC_BULKERASE: + { + /* Erase the entire device */ + + ret = lpc43_chiperase(priv); + } + break; + + case MTDIOC_XIPBASE: + default: + ret = -ENOTTY; /* Bad command */ + break; + } + + fvdbg("return %d\n", ret); + return ret; +} + +/**************************************************************************** + * Name: lpc43_idiv_clkconfig * * Description: * Configure PLL1 as the input to the selected divider and enable the @@ -143,7 +807,7 @@ ****************************************************************************/ #ifndef BOARD_SPIFI_PLL1 -static inline void spifi_idiv_input(void) +static inline void lpc43_idiv_clkconfig(void) { uint32_t regval; @@ -166,11 +830,11 @@ static inline void spifi_idiv_input(void) putreg32(regval, LPC43_IDIV_CTRL); } #else -# define spifi_idiv_input() +# define lpc43_idiv_clkconfig() #endif /**************************************************************************** - * Name: spifi_spifi_input + * Name: lpc43_spifi_clkconfig * * Description: * Configure the selected divider (or PLL1) as the input to the SPIFI @@ -178,7 +842,7 @@ static inline void spifi_idiv_input(void) * ****************************************************************************/ -static inline void spifi_spifi_input(void) +static inline void lpc43_spifi_clkconfig(void) { uint32_t regval; @@ -198,14 +862,14 @@ static inline void spifi_spifi_input(void) } /**************************************************************************** - * Name: spifi_pinconfig + * Name: lpc43_spifi_pinconfig * * Description: * Configure SPIFI pins * ****************************************************************************/ -static inline void spifi_pinconfig(void) +static inline void lpc43_spifi_pinconfig(void) { /* Configure SPIFI pins */ @@ -218,46 +882,57 @@ static inline void spifi_pinconfig(void) } /**************************************************************************** - * Name: spifi_rominit + * Name: lpc43_rominit * * Description: * Initialize the SPIFI ROM driver * ****************************************************************************/ -static inline int spifi_rominit(void) +static inline int lpc43_rominit(FAR struct lpc43_dev_s *priv) { - struct spifi_driver_s *pspifi = *((struct spifi_driver_s **)SPIFI_ROM_PTR); - struct spifi_dev_s dev; + FAR struct spifi_driver_s *spifi; +#ifndef CONFIG_SPIFI_BLKSIZE + FAR struct spfi_desc_s *desc; + uint16_t sectors; + uint8_t log2; +#endif int32_t result; - /* The final parameter of the spifi_init() ROM driver call should be the - * serial clock rate divided by 1000000, rounded to an integer. The SPIFI - * supports transfer rates of up to SPIFI_CLK/2 bytes per second. The SPIF_CLK - * is the output of the LPC43_BASE_SPIFI_CLK configured above; The frequency should - * be given by BOARD_SPIFI_FREQUENCY as provided by the board.h header file. - * - * A return value of zero frp spifi_init() indicates success. Non-zero error - * codes include: - * - * 0x2000A No operative serial flash (JEDEC ID all zeroes or all ones) - * 0x20009 Unknown manufacturer code - * 0x20008 Unknown device type code - * 0x20007 Unknown device ID code - * 0x20006 Unknown extended device ID value (only for Spansion 25FL12x - * in the initial API) - * 0x20005 Device status error - * 0x20004 Operand error: S_MODE3+S_FULLCLK+S_RCVCLK in options - */ - - result = pspifi->spifi_init(&dev, 9, SPIFI_RCVCLK | SPIFI_FULLCLK, SCLK_MHZ); + /* Get the pointer to the SPIFI ROM driver table. */ + + spifi = *((struct spifi_driver_s **)SPIFI_ROM_PTR); + priv->spifi = spifi; + + /* The final parameter of the spifi_init() ROM driver call should be the + * serial clock rate divided by 1000000, rounded to an integer. The SPIFI + * supports transfer rates of up to SPIFI_CLK/2 bytes per second. The SPIF_CLK + * is the output of the LPC43_BASE_SPIFI_CLK configured above; The frequency should + * be given by BOARD_SPIFI_FREQUENCY as provided by the board.h header file. + * + * A return value of zero frp spifi_init() indicates success. Non-zero error + * codes include: + * + * 0x2000A No operative serial flash (JEDEC ID all zeroes or all ones) + * 0x20009 Unknown manufacturer code + * 0x20008 Unknown device type code + * 0x20007 Unknown device ID code + * 0x20006 Unknown extended device ID value (only for Spansion 25FL12x + * in the initial API) + * 0x20005 Device status error + * 0x20004 Operand error: S_MODE3+S_FULLCLK+S_RCVCLK in options + */ + + result = spifi->spifi_init(&priv->rom, SPIFI_CSHIGH, + S_RCVCLK | S_FULLCLK, SCLK_MHZ); if (result != 0) { fdbg("ERROR: spifi_init failed: %05x\n", result); /* Try again */ - result = pspifi->spifi_init(&dev, 9, SPIFI_RCVCLK | SPIFI_FULLCLK, SCLK_MHZ); + result = spifi->spifi_init(&priv->rom, SPIFI_CSHIGH, + S_RCVCLK | S_FULLCLK, SCLK_MHZ); if (result != 0) { fdbg("ERROR: spifi_init failed: %05x\n", result); @@ -265,6 +940,80 @@ static inline int spifi_rominit(void) } } + fvdbg("SPFI:\n"); + fvdbg(" base: %08x\n", priv->rom.base); + fvdbg(" regbase: %08x\n", priv->rom.regbase); + fvdbg(" devsize: %08x\n", priv->rom.devsize); + fvdbg(" memsize: %08x\n", priv->rom.memsize); + fvdbg(" mfger: %02x\n", priv->rom.mfger); + fvdbg(" devtype: %02x\n", priv->rom.devtype); + fvdbg(" devid: %02x\n", priv->rom.devid); + fvdbg(" busy: %02x\n", priv->rom.busy); + fvdbg(" stat: %04x\n", priv->rom.stat.h); + fvdbg(" setprot: %04x\n", priv->rom.setprot); + fvdbg(" writeprot: %04x\n", priv->rom.writeprot); + fvdbg(" memcmd: %08x\n", priv->rom.memcmd); + fvdbg(" progcmd: %08x\n", priv->rom.progcmd); + fvdbg(" sectors: %04x\n", priv->rom.sectors); + fvdbg(" protbytes: %04x\n", priv->rom.protbytes); + fvdbg(" opts: %08x\n", priv->rom.opts); + fvdbg(" errcheck: %08x\n", priv->rom.errcheck); + + /* Get the largest erase block size */ + +#ifndef CONFIG_SPIFI_BLKSIZE + + desc = priv->rom.protents; + sectors = priv->rom.sectors; + log2 = 0; + + fvdbg("FLASH Geometry:\n"); + + while (sectors > 0) + { + fvdbg(" log2: %d rept: %d\n", desc->log2, desc->rept); + + /* Check if this is the largest erase block size seen */ + + if (desc->log2 > log2) + { + log2 = desc->log2; + } + + /* Decrement the count of sectors we have checked */ + + sectors -= desc->rept; + } + + DEBUGASSERT(log2 > 0); + + /* Save the digested FLASH geometry info */ + + priv->blkshift = log2; + priv->blksize = (1 << log2); + priv->nblocks = priv->rom.memsize / priv->blksize; + + fvdbg("Driver FLASH Geometry:\n"); + fvdbg(" blkshift: %d\n", priv->blkshift); + fvdbg(" blksize: %08x\n", priv->blksize); + fvdbg(" nblocks: %d\n", priv->nblocks); + +#if CONFIG_SPIFI_SECTOR512 + DEBUGASSERT(log2 > 9); +#endif + +#else + + /* Save the digested FLASH geometry info */ + + priv->nblocks = (priv->rom.memsize >> SPIFI_BLKSHIFT); + + fvdbg("Driver FLASH Geometry:\n"); + fvdbg(" blkshift: %d\n", SPIFI_BLKSHIFT); + fvdbg(" blksize: %08x\n", SPIFI_BLKSIZE); + fvdbg(" nblocks: %d\n", priv->nblocks); +#endif + return OK; } @@ -273,24 +1022,49 @@ static inline int spifi_rominit(void) ****************************************************************************/ /**************************************************************************** - * Function: lpc43_spifi_initialize + * Name: lpc43_spifi_initialize * * Description: - * Initialize the SPIFI interface per settings in the board.h file + * Create an initialized MTD device instance for the SPIFI device. 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). + * + * SPIFI interface clocking is configured per settings in the board.h file. * * Input Parameters: * None * - * Returned Value: - * Zero is returned on success; on failure, a negated errno value is - * returned. + * Returned value: + * One success, a reference to the initialized MTD device instance is + * returned; NULL is returned on any failure. * ****************************************************************************/ -int lpc43_spifi_initialize(void) +FAR struct mtd_dev_s *lpc43_spifi_initialize(void) { + /* At present, only a single instance of the SPIFI driver is supported */ + + FAR struct lpc43_dev_s *priv = &g_spifi; irqstate_t flags; - int ret = OK; + int ret; + + /* Initialize the SPIFI driver structure. Since the driver instance lies + * in .bss, it should have been already cleared to zero. + */ + + priv->mtd.erase = lpc43_erase; + priv->mtd.bread = lpc43_bread; + priv->mtd.bwrite = lpc43_bwrite; + priv->mtd.read = lpc43_read; + priv->mtd.ioctl = lpc43_ioctl; + + priv->operands.protect = -1; /* Save and restore protection */ + priv->operands.options = S_CALLER_ERASE; /* This driver will do erasure */ + + /* Initialize the SPIFI. Interrupts must be disabled here because shared + * CGU registers will be modified. + */ flags = irqsave(); @@ -299,22 +1073,45 @@ int lpc43_spifi_initialize(void) * for the selected divider */ - spifi_idiv_input(); + lpc43_idiv_clkconfig(); /* Configure SPIFI to received clocking from the selected divider */ - spifi_spifi_input(); + lpc43_spifi_clkconfig(); /* Configure SPIFI pins */ - spifi_pinconfig(); - + lpc43_spifi_pinconfig(); + irqrestore(flags); /* Initialize the SPIFI ROM driver */ - ret = spifi_rominit(); - irqrestore(flags); - return ret; + ret = lpc43_rominit(priv); + if (ret != OK) + { + return NULL; + } + + /* Check if we need to emulator a 512 byte sector */ + +#ifdef CONFIG_SPIFI_SECTOR512 + + /* Allocate a buffer for the erase block cache */ + + priv->cache = (FAR uint8_t *)kmalloc(SPIFI_BLKSIZE); + if (!priv->cache) + { + /* Allocation failed! Discard all of that work we just did and return NULL */ + + fdbg("ERROR: Allocation failed\n"); + return NULL; + } +#endif + + /* Return the implementation-specific state structure as the MTD device */ + + fvdbg("Return %p\n", priv); + return (FAR struct mtd_dev_s *)priv; } #endif /* CONFIG_LPC43_SPIFI */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h index 7ab1255c9e..8c2023f142 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h @@ -41,6 +41,7 @@ ****************************************************************************/ #include +#include #include "chip.h" #include "chip/lpc43_spifi.h" @@ -50,6 +51,33 @@ /**************************************************************************** * Pre-processor Definitions ****************************************************************************/ +/* SPIFI Configuration ******************************************************/ +/* This logic supports some special options that can be used to create an + * MTD device on the SPIFI FLASH. + * + * CONFIG_LPC43_SPIFI - Enable SPIFI support + * + * SPIFI device geometry: + * + * CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this many + * bytes into the device address space. This offset must be an exact + * multiple of the erase block size (CONFIG_SPIFI_BLKSIZE). Default 0. + * CONFIG_SPIFI_BLKSIZE - The size of one device erase block. If not defined + * then the driver will try to determine the correct erase block size by + * examining that data returned from spifi_initialize (which sometimes + * seems bad). + * + * Other SPIFI options + * + * CONFIG_SPIFI_SECTOR512 - If defined, then the driver will report a more + * FAT friendly 512 byte sector size and will manage the read-modify-write + * operations on the larger erase block. + * CONFIG_SPIFI_READONLY - Define to support only read-only operations. + */ + +#ifndef CONFIG_SPIFI_OFFSET +# define CONFIG_SPIFI_OFFSET 0 +#endif /**************************************************************************** * Private Data @@ -63,21 +91,26 @@ * Public Functions ****************************************************************************/ /**************************************************************************** - * Function: lpc43_spifi_initialize + * Name: lpc43_spifi_initialize * * Description: - * Initialize the SPIFI interface per settings in the board.h file + * Create an initialized MTD device instance for the SPIFI device. 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). + * + * SPIFI interface clocking is configured per settings in the board.h file. * * Input Parameters: * None * - * Returned Value: - * Zero is returned on success; on failure, a negated errno value is - * returned. + * Returned value: + * One success, a reference to the initialized MTD device instance is + * returned; NULL is returned on any failure. * ****************************************************************************/ -int lpc43_spifi_initialize(void); +FAR struct mtd_dev_s *lpc43_spifi_initialize(void); #endif /* CONFIG_LPC43_SPIFI */ #endif /* __ARCH_ARM_SRC_LPC43XX_LPC43_SPIFI_H */ diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index 68fe3f396c..cf60ca0ec9 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -903,22 +903,20 @@ Where is one of the following: This configuration has some special options that can be used to create a block device on the SPIFI FLASH. NOTE: CONFIG_LPC43_SPIFI=y must also be defined to enable SPIFI setup support: - - CONFIG_SPIFI_BLKDRVR - Enable to create a block driver on the SPFI - device. - CONFIG_SPIFI_DEVNO - SPIFI minor device number. The SPFI device will - be at /dev/ramN, where N is the value of CONFIG_SPIFI_DEVNO. - Default: 0. - CONFIG_SPIFI_RDONLY - Create a read only device on SPIFI. - CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this - many bytes into the device address space. Default 0. - CONFIG_SPIFI_BLKSIZE - The size of one block. SPIFI is not block - oriented, so most any size of the block used in the SPIFI block - device can be used. NOTE: FAT will support only sector sizes of - 512, 1024, 2048, or 4096. Default: 512 - CONFIG_SPIFI_NBLOCKS - The number of blocks in the file system, - each of size CONFIG_SPIFI_BLKSIZE. The end of the file system - will be at device offset: - CONFIG_SPIFI_OFFSET + CONFIG_SPIFI_BLKSIZE*CONFIG_SPIFI_NBLOCKS - The must assure that this does offset does not go beyond the end - of the FLASH memory. + + SPIFI device geometry: + + CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this many + bytes into the device address space. This offset must be an exact + multiple of the erase block size (CONFIG_SPIFI_BLKSIZE). Default 0. + CONFIG_SPIFI_BLKSIZE - The size of one device erase block. If not defined + then the driver will try to determine the correct erase block size by + examining that data returned from spifi_initialize (which sometimes + seems bad). + + Other SPIFI options + + CONFIG_SPIFI_SECTOR512 - If defined, then the driver will report a more + FAT friendly 512 byte sector size and will manage the read-modify-write + operations on the larger erase block. + CONFIG_SPIFI_READONLY - Define to support only read-only operations. diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig index de4d3ff093..e6db818ca1 100644 --- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig +++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig @@ -658,35 +658,31 @@ CONFIG_MMCSD_MMCSUPPORT=n CONFIG_MMCSD_HAVECARDDETECT=n # -# This configuration has some special options that can be used to -# create a block device on the SPIFI FLASH. NOTE: CONFIG_LPC43_SPIFI=y +# The SPIFI drvier has some special options that can be used to +# create an MTD device on the SPIFI FLASH. NOTE: CONFIG_LPC43_SPIFI=y # must also be defined to enable SPIFI setup support: # -# CONFIG_SPIFI_BLKDRVR - Enable to create a block driver on the SPFI -# device. -# CONFIG_SPIFI_DEVNO - SPIFI minor device number. The SPFI device will -# be at /dev/rdN, where N is the value of CONFIG_SPIFI_DEVNO. -# Default: 0. -# CONFIG_SPIFI_RDONLY - Create a read only device on SPIFI. -# CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this -# many bytes into the device address space. Default 0. -# CONFIG_SPIFI_BLKSIZE - The size of one block. SPIFI is not block -# oriented, so most any size of the block used in the SPIFI block -# device can be used. NOTE: FAT will support only sector sizes of 512, -# 1024, 2048, or 4096. Default: 512 -# CONFIG_SPIFI_NBLOCKS - The number of blocks in the file system, -# each of size CONFIG_SPIFI_BLKSIZE. The end of the file system -# will be at device offset: -# CONFIG_SPIFI_OFFSET + CONFIG_SPIFI_BLKSIZE*CONFIG_SPIFI_NBLOCKS -# The must assure that this does offset does not go beyond the end -# of the FLASH memory. -# -CONFIG_SPIFI_BLKDRVR=n -CONFIG_SPIFI_DEVNO=0 -CONFIG_SPIFI_RDONLY=n +# SPIFI device geometry: +# +# CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this many +# bytes into the device address space. This offset must be an exact +# multiple of the erase block size (CONFIG_SPIFI_BLKSIZE). Default 0. +# CONFIG_SPIFI_BLKSIZE - The size of one device erase block. If not defined +# then the driver will try to determine the correct erase block size by +# examining that data returned from spifi_initialize (which sometimes +# seems bad). +# +# Other SPIFI options +# +# CONFIG_SPIFI_SECTOR512 - If defined, then the driver will report a more +# FAT friendly 512 byte sector size and will manage the read-modify-write +# operations on the larger erase block. +# CONFIG_SPIFI_READONLY - Define to support only read-only operations. +# CONFIG_SPIFI_OFFSET=0 -CONFIG_SPIFI_BLKSIZE=512 -CONFIG_SPIFI_NBLOCKS=(1024*1024/512) +CONFIG_SPIFI_BLKSIZE=4096 +CONFIG_SPIFI_SECTOR512=y +CONFIG_SPIFI_RDONLY=n # TCP/IP and UDP support via uIP # CONFIG_NET - Enable or disable all network features diff --git a/nuttx/configs/lpc4330-xplorer/src/up_nsh.c b/nuttx/configs/lpc4330-xplorer/src/up_nsh.c index 4656a43f87..a09acd771c 100644 --- a/nuttx/configs/lpc4330-xplorer/src/up_nsh.c +++ b/nuttx/configs/lpc4330-xplorer/src/up_nsh.c @@ -44,89 +44,25 @@ #include #include -#include - #include "chip.h" -#ifdef CONFIG_SPIFI_BLKDRVR +#ifdef CONFIG_LPC43_SPIFI +# include # include "lpc43_spifi.h" - /* This should be removed someday when we are confident in SPIFI */ - -# ifdef CONFIG_DEBUG_FS -# include "up_arch.h" -# include "chip/lpc43_cgu.h" -# include "chip/lpc43_ccu.h" +# ifdef CONFIG_SPFI_NXFFS +# include +# include # endif #endif /**************************************************************************** * Pre-Processor Definitions ****************************************************************************/ -/* SPIFI Configuration ******************************************************/ -/* This logic supports some special options that can be used to create a - * block device on the SPIFI FLASH. NOTE: CONFIG_LPC43_SPIFI=y must also - * be defined to enable SPIFI setup support: - * - * CONFIG_SPIFI_BLKDRVR - Enable to create a block driver on the SPFI device. - * CONFIG_SPIFI_DEVNO - SPIFI minor device number. The SPFI device will be - * at /dev/ramN, where N is the value of CONFIG_SPIFI_DEVNO. Default: 0. - * CONFIG_SPIFI_RDONLY - Create a read only device on SPIFI. - * CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this many - * bytes into the device address space. Default 0. - * CONFIG_SPIFI_BLKSIZE - The size of one block. SPIFI is not block oriented, - * so most any size of the block used in the SPIFI block device can be - * used. NOTE: FAT will support only sector sizes of 512, 1024, 2048, or - * 4096. Default: 512 - * CONFIG_SPIFI_NBLOCKS - The number of blocks in the file system, each of - * size CONFIG_SPIFI_BLKSIZE. The end of the file system will be at - * device offset: - * CONFIG_SPIFI_OFFSET + CONFIG_SPIFI_BLKSIZE*CONFIG_SPIFI_NBLOCKS - * The must assure that this does offset does not go beyond the end of - * the FLASH memory. - */ - -#ifdef CONFIG_SPIFI_BLKDRVR - -# ifndef CONFIG_LPC43_SPIFI -# error "SPIFI support is not enabled (CONFIG_LPC43_SPIFI)" -# endif - -# ifndef CONFIG_SPIFI_DEVNO -# define CONFIG_SPIFI_DEVNO 0 -# endif - -# ifndef CONFIG_SPIFI_OFFSET -# define CONFIG_SPIFI_OFFSET 0 -# endif - -# ifndef CONFIG_SPIFI_BLKSIZE -# define CONFIG_SPIFI_BLKSIZE 512 -# endif +/* Configuration ************************************************************/ -# ifndef CONFIG_SPIFI_NBLOCKS -# error "Need number of SPIFI blocks (CONFIG_SPIFI_NBLOCKS)" -# endif - -# define SPIFI_BUFFER \ - (FAR uint8_t *)(LPC43_LOCSRAM_SPIFI_BASE + CONFIG_SPIFI_OFFSET) - -#endif - -/* Debug ********************************************************************/ - -#ifdef CONFIG_CPP_HAVE_VARARGS -# ifdef CONFIG_DEBUG -# define message(...) lib_lowprintf(__VA_ARGS__) -# else -# define message(...) printf(__VA_ARGS__) -# endif -#else -# ifdef CONFIG_DEBUG -# define message lib_lowprintf -# else -# define message printf -# endif +#ifndef CONFIG_SPIFI_DEVNO +# define CONFIG_SPIFI_DEVNO 0 #endif /**************************************************************************** @@ -140,56 +76,53 @@ * Make the SPIFI (or part of it) into a block driver that can hold a * file system. * - * SPIFI AHB register clock: - * Base clock = BASE_M4_CLK - * Branch clock = CLK_M4_SPIFI - * SPIFI serial clock input: - * Base clock = BASE_SPIFI_CLK - * Branch clock = SPIFI_CLK - * ****************************************************************************/ -#ifdef CONFIG_SPIFI_BLKDRVR +#ifdef CONFIG_LPC43_SPIFI static int nsh_spifi_initialize(void) { + FAR struct mtd_dev_s *mtd; int ret; - /* Initialize the SPIFI interface */ + /* Initialize the SPIFI interface and create the MTD driver instance */ - ret = lpc43_spifi_initialize(); - if (ret < 0) + mtd = lpc43_spifi_initialize(); + if (!mtd) { - fdbg("ERROR: lpc43_spifi_initialize failed: %d\n", ret); - return ret; + fdbg("ERROR: lpc43_spifi_initialize failed\n"); + return -ENODEV; } - /* This should be removed someday when we are confident in SPIFI */ +#ifndef CONFIG_SPFI_NXFFS + /* And finally, use the FTL layer to wrap the MTD driver as a block driver */ -#ifdef CONFIG_DEBUG_FS - fdbg("BASE_SPIFI_CLK=%08x\n", - getreg32(LPC43_BASE_SPIFI_CLK)); - fdbg("SPFI CFG=%08x STAT=%08x\n", - getreg32(LPC43_CCU1_SPIFI_CFG), getreg32(LPC43_CCU1_SPIFI_STAT)); - fdbg("M4 SPFI CFG=%08x STAT=%08x\n", - getreg32(LPC43_CCU1_M4_SPIFI_CFG), getreg32(LPC43_CCU1_M4_SPIFI_STAT)); -#endif + ret = ftl_initialize(CONFIG_SPIFI_DEVNO, mtd); + if (ret < 0) + { + fdbg("ERROR: Initializing the FTL layer: %d\n", ret); + return ret; + } +#else + /* Initialize to provide NXFFS on the MTD interface */1G -#ifdef CONFIG_SPIFI_RDONLY - /* Register a read-only SPIFI RAM disk at /dev/ramN, where N is the - * value of CONFIG_SPIFI_DEVNO. - */ + ret = nxffs_initialize(mtd); + if (ret < 0) + { + fdbg("ERROR: NXFFS initialization failed: %d\n", ret); + return ret; + } - return romdisk_register(CONFIG_SPIFI_DEVNO, SPIFI_BUFFER, - CONFIG_SPIFI_NBLOCKS, CONFIG_SPIFI_BLKSIZE); -#else - /* Register a write-able SPIFI RAM disk at /dev/ramN, where N is the - * value of CONFIG_SPIFI_DEVNO. - */ + /* Mount the file system at /mnt/spifi */ - return ramdisk_register(CONFIG_SPIFI_DEVNO, SPIFI_BUFFER, - CONFIG_SPIFI_NBLOCKS, CONFIG_SPIFI_BLKSIZE, - true); + ret = mount(NULL, "/mnt/spifi", "nxffs", 0, NULL); + if (ret < 0) + { + fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno); + return ret; + } #endif + + return OK; } #else # define nsh_spifi_initialize() (OK)