summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-23 20:08:56 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-23 20:08:56 +0000
commitbbae2a800dec1c8f22c3a2bf1d95affb68112746 (patch)
treed615dde5d538e1b79e5c58d2e2c3cd963c49a9a1
parent6355e50a2289d7d764ac9de87ddd1528c510bd8f (diff)
downloadpx4-nuttx-bbae2a800dec1c8f22c3a2bf1d95affb68112746.tar.gz
px4-nuttx-bbae2a800dec1c8f22c3a2bf1d95affb68112746.tar.bz2
px4-nuttx-bbae2a800dec1c8f22c3a2bf1d95affb68112746.zip
LP43xx SPIFI MTD driver update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4971 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog8
-rw-r--r--nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h24
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c79
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h17
-rw-r--r--nuttx/configs/lpc4330-xplorer/README.txt6
-rw-r--r--nuttx/configs/lpc4330-xplorer/nsh/defconfig11
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/Makefile18
7 files changed, 150 insertions, 13 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 7445e62e1..fd9859555 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3052,6 +3052,10 @@
Bxxx definitions are again encoded; cf[set|get][o|i]speed now deal with only the
encoded values. If the encoed baud is set to BOTHER, then the values in the (non-
standard) c_ispeed and c_ospeed baud values may be accessed directly.
-
-
+ * arch/arm/src/stm32/stm32_serial.c: Add minimal termios support for the STM32
+ (BOTHER style baud settings only). Contributed by Mike Smith.
+* configs/lpc4343-xplorer/src: Clean up SPIFI-library based build to that it
+ actually works.
+* arch/arm/src/lpc43xx/lpc43_spifi.c: Add support for verification to writes.
+ Add debug option to dump buffers. Several bugfixes... almost works.
diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h
index 3b9913061..a0bec7592 100644
--- a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h
+++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h
@@ -124,6 +124,12 @@
* Pre-processor Definitions
****************************************************************************/
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
/* Protection/sector descriptors */
struct spfi_desc_s
@@ -237,25 +243,33 @@ struct spifi_driver_s
#endif
/****************************************************************************
- * Private Data
+ * Public Data
****************************************************************************/
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
/****************************************************************************
* Public Functions
****************************************************************************/
-#ifdef CONFIG_SPIFI_LIBRARY
EXTERN int32_t spifi_init(struct spifi_dev_s *dev, uint32_t cshigh,
uint32_t options, uint32_t mhz);
EXTERN int32_t spifi_program(struct spifi_dev_s *dev, const uint8_t *source,
struct spifi_operands_s *opers);
EXTERN int32_t spifi_erase(struct spifi_dev_s *dev,
struct spifi_operands_s *opers);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
#endif
+#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_SPIFI_H */
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c
index d52b26cec..fe26fabc5 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c
@@ -81,6 +81,14 @@
* 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_LIBRARY - Don't use the LPC43xx ROM routines but, instead,
+ * use an external library implementation of the SPIFI interface.
+ * CONFIG_SPIFI_VERIFY - Verify all spi_program() operations by reading
+ * from the SPI address space after each write.
+ * CONFIG_DEBUG_SPIFI_DUMP - Debug option to dump read/write buffers. You
+ * probably do not want to enable this unless you want to dig through a
+ * *lot* of debug output! Also required CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE,
+ * and CONFIG_DEBUG_FS,
*/
/* This is where the LPC43xx address where random-access reads begin */
@@ -157,15 +165,15 @@
#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 IS_ERASED(p) ((((p)->flags) & SST25_CACHE_ERASED) != 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 SET_ERASED(p) do { (p)->flags |= SST25_CACHE_ERASED; } 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)
+#define CLR_ERASED(p) do { (p)->flags &= ~SST25_CACHE_ERASED; } while (0)
/* Select the divider to use as SPIFI input based on definitions in the
* board.h header file.
@@ -246,6 +254,20 @@
#define SCLK_MHZ (BOARD_SPIFI_FREQUENCY + (1000000 / 2)) / 1000000
+/* DEBUG options to dump read/write buffers. You probably do not want to
+ * enable this unless you want to dig through a *lot* of debug output!
+ */
+
+#if !defined(CONFIG_DEBUG) || !defined(CONFIG_DEBUG_VERBOSE) || !defined(CONFIG_DEBUG_FS)
+# undef CONFIG_DEBUG_SPIFI_DUMP
+#endif
+
+#ifdef CONFIG_DEBUG_SPIFI_DUMP
+# define lpc43_dumpbuffer(m,b,n) lib_dumpbuffer(m,b,n);
+#else
+# define lpc43_dumpbuffer(m,b,n)
+#endif
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -288,6 +310,10 @@ 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
+#ifdef CONFIG_SPIFI_VERIFY
+static int lpc43_verify(FAR struct lpc43_dev_s *priv, FAR uint8_t *dest,
+ FAR const uint8_t *src, size_t nbytes);
+#endif
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
@@ -351,6 +377,9 @@ static void lpc43_blockerase(struct lpc43_dev_s *priv, off_t sector)
priv->operands.dest = SPIFI_BASE + (sector << SPIFI_BLKSHIFT);
priv->operands.length = SPIFI_BLKSIZE;
+ fvdbg("SPIFI_ERASE: dest=%p length=%d\n",
+ priv->operands.dest, priv->operands.length);
+
result = SPIFI_ERASE(priv, &priv->rom, &priv->operands);
if (result != 0)
{
@@ -377,6 +406,9 @@ static inline int lpc43_chiperase(struct lpc43_dev_s *priv)
priv->operands.dest = SPIFI_BASE;
priv->operands.length = SPIFI_BLKSIZE * priv->nblocks;
+ fvdbg("SPIFI_ERASE: dest=%p length=%d\n",
+ priv->operands.dest, priv->operands.length);
+
result = SPIFI_ERASE(priv, &priv->rom, &priv->operands);
if (result != 0)
{
@@ -391,6 +423,18 @@ static inline int lpc43_chiperase(struct lpc43_dev_s *priv)
* Name: lpc43_pagewrite
****************************************************************************/
+#if !defined(CONFIG_SPIFI_READONLY) && defined(CONFIG_SPIFI_VERIFY)
+static int lpc43_verify(FAR struct lpc43_dev_s *priv, FAR uint8_t *dest,
+ FAR const uint8_t *src, size_t nbytes)
+{
+ return memcmp(src, dest, nbytes) != 0 ? -EIO : OK;
+}
+#endif
+
+/****************************************************************************
+ * 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)
@@ -408,6 +452,9 @@ static int lpc43_pagewrite(FAR struct lpc43_dev_s *priv, FAR uint8_t *dest,
priv->operands.dest = dest;
priv->operands.length = nbytes;
+ fvdbg("SPIFI_PROGRAM: src=%p dest=%p length=%d\n",
+ src, priv->operands.dest, priv->operands.length);
+
result = SPIFI_PROGRAM(priv, &priv->rom, src, &priv->operands);
if (result != 0)
{
@@ -415,6 +462,19 @@ static int lpc43_pagewrite(FAR struct lpc43_dev_s *priv, FAR uint8_t *dest,
return -EIO;
}
+ /* Verify the data that was written by comparing to the data visible in the
+ * SPIFI address space.
+ */
+
+#ifdef CONFIG_SPIFI_VERIFY
+ result = lpc43_verify(priv, dest, src, nbytes);
+ if (result != 0)
+ {
+ fdbg("ERROR: lpc43_verify failed: %05x\n", result);
+ return -EIO;
+ }
+#endif
+
return OK;
}
#endif
@@ -427,6 +487,7 @@ static inline void lpc43_pageread(FAR struct lpc43_dev_s *priv,
FAR uint8_t *dest, FAR const uint8_t *src,
size_t nbytes)
{
+ fvdbg("src=%p dest=%p length=%d\n", src, dest, nbytes);
memcpy(dest, src, nbytes);
}
@@ -445,6 +506,7 @@ static void lpc43_cacheflush(struct lpc43_dev_s *priv)
* the cached erase block to FLASH.
*/
+ fvdbg("flags: %02x blkno: %d\n", priv->flags, priv->blkno);
if (IS_DIRTY(priv) || IS_ERASED(priv))
{
/* Get the SPIFI address corresponding to the cached erase block */
@@ -579,6 +641,9 @@ static void lpc43_cachewrite(FAR struct lpc43_dev_s *priv, FAR const uint8_t *bu
dest = lpc43_cacheread(priv, sector);
+ fvdbg("dest=%p src=%p sector: %ld flags: %02x\n",
+ dest, buffer, sector, priv->flags);
+
/* 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.
@@ -660,9 +725,11 @@ static ssize_t lpc43_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t n
/* 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);
+ nbytes = lpc43_read(dev, startblock << SPIFI_512SHIFT,
+ nblocks << SPIFI_512SHIFT, buffer);
if (nbytes > 0)
{
+ lpc43_dumpbuffer(__func__, buffer, nbytes)
return nbytes >> SPIFI_512SHIFT;
}
@@ -679,6 +746,7 @@ static ssize_t lpc43_bread(FAR struct mtd_dev_s *dev, off_t startblock, size_t n
nblocks << SPIFI_BLKSHIFT, buffer);
if (nbytes > 0)
{
+ lpc43_dumpbuffer(__func__, buffer, nbytes)
return nbytes >> SPIFI_BLKSHIFT;
}
@@ -704,6 +772,8 @@ static ssize_t lpc43_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
fvdbg("startblock: %08lx nblocks: %d\n", (long)startblock, (int)nblocks);
lpc43_cachewrite(priv, buffer, startblock, nblocks);
+
+ lpc43_dumpbuffer(__func__, buffer, nblocks << SPIFI_512SHIFT)
return nblocks;
#else
@@ -726,6 +796,7 @@ static ssize_t lpc43_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t
return ret;
}
+ lpc43_dumpbuffer(__func__, buffer, nblocks << SPIFI_BLKSHIFT)
return nblocks;
#endif
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h
index ef2ad842e..f7cc0d775 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h
@@ -92,6 +92,17 @@
/****************************************************************************
* Public Functions
****************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
/****************************************************************************
* Name: lpc43_spifi_initialize
*
@@ -114,6 +125,12 @@
FAR struct mtd_dev_s *lpc43_spifi_initialize(void);
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
#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 bbe954bea..783461704 100644
--- a/nuttx/configs/lpc4330-xplorer/README.txt
+++ b/nuttx/configs/lpc4330-xplorer/README.txt
@@ -926,6 +926,12 @@ Where <subdir> is one of the following:
CONFIG_SPIFI_READONLY - Define to support only read-only operations.
CONFIG_SPIFI_LIBRARY - Don't use the LPC43xx ROM routines but, instead,
use an external library implementation of the SPIFI interface.
+ CONFIG_SPIFI_VERIFY - Verify all spi_program() operations by reading
+ from the SPI address space after each write.
+ CONFIG_DEBUG_SPIFI_DUMP - Debug option to dump read/write buffers. You
+ probably do not want to enable this unless you want to dig through a
+ *lot* of debug output! Also required CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE,
+ and CONFIG_DEBUG_FS,
In my experience, there were some missing function pointers in the LPC43xx
SPIFI ROM routines and the SPIFI configuration could only be built with
diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
index 27c434d53..7ecb76efd 100644
--- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig
+++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
@@ -674,7 +674,7 @@ CONFIG_MMCSD_MMCSUPPORT=n
CONFIG_MMCSD_HAVECARDDETECT=n
#
-# The SPIFI drvier has some special options that can be used to
+# The SPIFI driver 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:
#
@@ -696,13 +696,20 @@ CONFIG_MMCSD_HAVECARDDETECT=n
# CONFIG_SPIFI_READONLY - Define to support only read-only operations.
# CONFIG_SPIFI_LIBRARY - Don't use the LPC43xx ROM routines but, instead,
# use an external library implementation of the SPIFI interface.
+# CONFIG_SPIFI_VERIFY - Verify all spi_program() operations by reading
+# from the SPI address space after each write.
+# CONFIG_DEBUG_SPIFI_DUMP - Debug option to dump read/write buffers. You
+# probably do not want to enable this unless you want to dig through a
+# *lot* of debug output! Also required CONFIG_DEBUG, CONFIG_DEBUG_VERBOSE,
+# and CONFIG_DEBUG_FS,#
#
CONFIG_SPIFI_OFFSET=0
CONFIG_SPIFI_BLKSIZE=4096
CONFIG_SPIFI_SECTOR512=y
CONFIG_SPIFI_RDONLY=n
CONFIG_SPIFI_LIBRARY=n
-
+CONFIG_SPIFI_VERIFY=n
+CONFIG_DEBUG_SPIFI_DUMP=n
# TCP/IP and UDP support via uIP
# CONFIG_NET - Enable or disable all network features
# CONFIG_NET_IPv6 - Build in support for IPv6
diff --git a/nuttx/configs/lpc4330-xplorer/src/Makefile b/nuttx/configs/lpc4330-xplorer/src/Makefile
index 7be95126b..f2a5966d4 100644
--- a/nuttx/configs/lpc4330-xplorer/src/Makefile
+++ b/nuttx/configs/lpc4330-xplorer/src/Makefile
@@ -62,6 +62,24 @@ ifeq ($(CONFIG_USBMSC),y)
CSRCS += up_usbmsc.c
endif
+ifeq ($(CONFIG_SPIFI_LIBRARY),y)
+CFLAGS += -DEUROBIRD
+SPIFI_LIB = spifi_lib
+CSRCS += $(SPIFI_LIB)/spifi_rom_api.c
+#CSRCS += $(SPIFI_LIB)/amic.c
+#CSRCS += $(SPIFI_LIB)/atmel.c
+#CSRCS += $(SPIFI_LIB)/chi.c
+#CSRCS += $(SPIFI_LIB)/eon.c
+#CSRCS += $(SPIFI_LIB)/esmt.c
+#CSRCS += $(SPIFI_LIB)/esmt.c
+#CSRCS += $(SPIFI_LIB)/giga.c
+#CSRCS += $(SPIFI_LIB)/macronix.c
+#CSRCS += $(SPIFI_LIB)/numonyx.c
+CSRCS += $(SPIFI_LIB)/spansion.c
+#CSRCS += $(SPIFI_LIB)/sst.c
+#CSRCS += $(SPIFI_LIB)/winbond.c
+endif
+
AOBJS = $(ASRCS:.S=$(OBJEXT))
COBJS = $(CSRCS:.c=$(OBJEXT))