summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/arch/arm/src/lpc43xx/Make.defs4
-rw-r--r--nuttx/arch/arm/src/lpc43xx/chip/lpc4310203050_pinconfig.h12
-rw-r--r--nuttx/arch/arm/src/lpc43xx/chip/lpc43_cgu.h4
-rw-r--r--nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h250
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_debug.c8
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c320
-rw-r--r--nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h84
-rw-r--r--nuttx/configs/lpc4330-xplorer/README.txt3
-rw-r--r--nuttx/configs/lpc4330-xplorer/include/board.h30
-rw-r--r--nuttx/configs/lpc4330-xplorer/nsh/defconfig3
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_nsh.c68
-rwxr-xr-xnuttx/configs/lpcxpresso-lpc1768/README.txt32
13 files changed, 763 insertions, 57 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 5ca5aebcc..e33bee750 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3016,4 +3016,6 @@
* arch/arm/src/stm32/stm32_exti_alarm.c: Add initial logic to attached the
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).
diff --git a/nuttx/arch/arm/src/lpc43xx/Make.defs b/nuttx/arch/arm/src/lpc43xx/Make.defs
index 1dbb3e957..4b75afffc 100644
--- a/nuttx/arch/arm/src/lpc43xx/Make.defs
+++ b/nuttx/arch/arm/src/lpc43xx/Make.defs
@@ -82,6 +82,10 @@ ifeq ($(CONFIG_LPC43_SPI),y)
CHIP_CSRCS += lpc43_spi.c
endif
+ifeq ($(CONFIG_LPC43_SPIFI),y)
+CHIP_CSRCS += lpc43_spifi.c
+endif
+
ifeq ($(CONFIG_LPC43_SSP0),y)
CHIP_CSRCS += lpc43_ssp.c
else
diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc4310203050_pinconfig.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc4310203050_pinconfig.h
index 375b0ceb7..c1c710e0c 100644
--- a/nuttx/arch/arm/src/lpc43xx/chip/lpc4310203050_pinconfig.h
+++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc4310203050_pinconfig.h
@@ -707,12 +707,12 @@
#define PINCONF_SGPIO15_2 (PINCONF_FUNC6|PINCONF_PINS1|PINCONF_PIN_5)
#define PINCONF_SGPIO15_3 (PINCONF_FUNC7|PINCONF_PINS4|PINCONF_PIN_10)
-#define PINCONF_SPIFI_CS (PINCONF_FUNC3|PINCONF_PINS3|PINCONF_PIN_8)
-#define PINCONF_SPIFI_MISO (PINCONF_FUNC3|PINCONF_PINS3|PINCONF_PIN_6)
-#define PINCONF_SPIFI_MOSI (PINCONF_FUNC3|PINCONF_PINS3|PINCONF_PIN_7)
-#define PINCONF_SPIFI_SCK (PINCONF_FUNC3|PINCONF_PINS3|PINCONF_PIN_3)
-#define PINCONF_SPIFI_SIO2 (PINCONF_FUNC3|PINCONF_PINS3|PINCONF_PIN_5)
-#define PINCONF_SPIFI_SIO3 (PINCONF_FUNC3|PINCONF_PINS3|PINCONF_PIN_4)
+#define PINCONF_SPIFI_CS (PINCONF_FUNC3|PINCONF_SLEW_FAST|PINCONF_PINS3|PINCONF_PIN_8)
+#define PINCONF_SPIFI_MISO (PINCONF_FUNC3|PINCONF_SLEW_FAST|PINCONF_INBUFFER|PINCONF_GLITCH|PINCONF_PINS3|PINCONF_PIN_6)
+#define PINCONF_SPIFI_MOSI (PINCONF_FUNC3|PINCONF_SLEW_FAST|PINCONF_INBUFFER|PINCONF_GLITCH|PINCONF_PINS3|PINCONF_PIN_7)
+#define PINCONF_SPIFI_SCK (PINCONF_FUNC3|PINCONF_SLEW_FAST|PINCONF_INBUFFER|PINCONF_GLITCH|PINCONF_PINS3|PINCONF_PIN_3)
+#define PINCONF_SPIFI_SIO2 (PINCONF_FUNC3|PINCONF_SLEW_FAST|PINCONF_INBUFFER|PINCONF_GLITCH|PINCONF_PINS3|PINCONF_PIN_5)
+#define PINCONF_SPIFI_SIO3 (PINCONF_FUNC3|PINCONF_SLEW_FAST|PINCONF_INBUFFER|PINCONF_GLITCH|PINCONF_PINS3|PINCONF_PIN_4)
#define PINCONF_SPI_MISO (PINCONF_FUNC1|PINCONF_PINS3|PINCONF_PIN_6)
#define PINCONF_SPI_MOSI (PINCONF_FUNC1|PINCONF_PINS3|PINCONF_PIN_7)
diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_cgu.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_cgu.h
index a71954153..61fa3be0b 100644
--- a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_cgu.h
+++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_cgu.h
@@ -356,7 +356,7 @@
/* Bit 1: Reserved */
#define IDIVBCD_CTRL_IDIV_SHIFT (2) /* Bits 2-5: Integer divider A divider values (1/(IDIV + 1)) */
#define IDIVBCD_CTRL_IDIV_MASK (15 << IDIVBCD_CTRL_IDIV_SHIFT)
-# define IDIVBCD_CTRL_IDIV_DIV(n) (((n)-1) << IDIVBCD_CTRL_IDIV_SHIFT) /* n=1..16 */
+# define IDIVBCD_CTRL_IDIV(n) (((n)-1) << IDIVBCD_CTRL_IDIV_SHIFT) /* n=1..16 */
/* Bits 6-10: Reserved */
#define IDIVBCD_CTRL_AUTOBLOCK (1 << 11) /* Bit 11: Block clock during frequency change */
/* Bits 12-23: Reserved */
@@ -378,7 +378,7 @@
/* Bit 1: Reserved */
#define IDIVE_CTRL_IDIV_SHIFT (2) /* Bits 2-9: Integer divider A divider values (1/(IDIV + 1)) */
#define IDIVE_CTRL_IDIV_MASK (0xff << IDIVE_CTRL_IDIV_SHIFT)
-# define IDIVE_CTRL_IDIV_DIV(n) (((n)-1) << IDIVE_CTRL_IDIV_SHIFT) /* n=1..256 */
+# define IDIVE_CTRL_IDIV(n) (((n)-1) << IDIVE_CTRL_IDIV_SHIFT) /* n=1..256 */
/* Bit 10: Reserved */
#define IDIVE_CTRL_AUTOBLOCK (1 << 11) /* Bit 11: Block clock during frequency change */
/* Bits 12-23: Reserved */
diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h
new file mode 100644
index 000000000..711f10ac3
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_spifi.h
@@ -0,0 +1,250 @@
+/****************************************************************************
+ * arch/arm/src/lpc43/chip/lpc43_spifi.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************
+ *
+ * NOTE: The SPIFI ROM interface is not defined in the LPC43xx user manual.
+ * Some information in this file drivers from the NXP header file
+ * spifi_rom_api.h. I do not believe that any copyright restrictions apply.
+ * But just to be certain:
+ *
+ * Copyright(C) 2011, NXP Semiconductor
+ * All rights reserved.
+ *
+ * Software that is described herein is for illustrative purposes only which
+ * provides customers with programming information regarding the products.
+ * This software is supplied "AS IS" without any warranties. NXP
+ * Semiconductors assumes no responsibility or liability for the use of the
+ * software, conveys no license or title under any patent, copyright, or
+ * mask work right to the product. NXP Semiconductors reserves the right to
+ * make changes in the software without notification. NXP Semiconductors
+ * also make no representation or warranty that such application will be
+ * suitable for the specified use without further testing or modification.
+ * Permission to use, copy, modify, and distribute this software and its
+ * documentation is hereby granted, under NXP Semiconductors' relevant
+ * copyright in the software, without fee, provided that it is used in
+ * conjunction with NXP Semiconductors microcontrollers. This copyright,
+ * permission, and disclaimer notice must appear in all copies of this code.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_SPIFI_H
+#define __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_SPIFI_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* The largest protection block of any serial flash that the ROM driver
+ * can handle
+ */
+
+#define SPIFI_LONGEST_PROTBLOCK 68
+
+/* Protection flag bit definitions */
+
+#define SPIFI_RWPROT (1 << 0)
+
+/* Instruction classes for wait_busy */
+
+#define SPIFI_STAT_INST 0
+#define SPIFI_BLOCK_ERASE 1
+#define SPIFI_PROG_INST 2
+#define SPIFI_CHIP_ERASE 3
+
+/* Bit definitions in options operands (MODE3, RCVCLK, and FULLCLK
+ * 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)
+
+/* The length of a standard program command is 256 on all devices */
+
+#define PROG_SIZE 256
+
+/* SPI ROM driver table pointer */
+
+#define SPIFI_ROM_PTR LPC43_ROM_DRIVER_TABLE6
+#define pSPIFI *((struct spifi_driver_s **)SPIFI_ROM_PTR)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Protection/sector descriptors */
+
+struct spfi_desc_s
+{
+ uint32_t base;
+ uint8_t flags;
+ int8_t log2;
+ uint16_t rept;
+};
+
+/* The SPFI device state structure, passed to all ROM driver methods. */
+
+struct spifi_dev_s
+{
+ uint32_t base;
+ uint32_t regbase;
+ uint32_t devsize;
+ uint32_t memsize;
+
+ uint8_t mfger;
+ uint8_t devtype;
+ uint8_t devid;
+ uint8_t busy;
+
+ union
+ {
+ uint16_t h;
+ uint8_t b[2];
+ } stat;
+ uint16_t reserved;
+
+ uint16_t setprot;
+ uint16_t writeprot;
+
+ uint32_t memcmd;
+ uint32_t progcmd;
+
+ uint16_t sectors;
+ uint16_t protbytes;
+
+ uint32_t opts;
+ uint32_t errcheck;
+
+ uint8_t eraseshifts[4];
+ uint8_t eraseops[4];
+
+ struct spfi_desc_s *protents;
+ char prot[SPIFI_LONGEST_PROTBLOCK];
+};
+
+/* Operands of program and erase ROM driver methods */
+
+struct spifi_operands_s
+{
+ char *dest;
+ uint32_t length;
+ char *scratch;
+ int32_t protect;
+ uint32_t options;
+};
+
+/* Interface to SPIFI ROM driver */
+
+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,
+ struct spifi_operands_s *opers);
+ int32_t (*spifi_erase)(struct spifi_dev_s *dev,
+ struct spifi_operands_s *opers);
+
+ /* Mode switching */
+
+ void (*cancel_mem_mode)(struct spifi_dev_s *dev);
+ void (*set_mem_mode)(struct spifi_dev_s *dev);
+
+ /* Mid level functions */
+
+ 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, 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,
+ 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 length);
+
+ /* Low level functions */
+
+ void (*setsize) (struct spifi_dev_s *dev, int32_t value);
+ int32_t (*setdev)(struct spifi_dev_s *dev, uint32_t opts,
+ uint32_t mem_cmd, uint32_t prog_cmd);
+ uint32_t (*cmd)(uint8_t op, uint8_t addrlen, uint8_t intLen, uint16_t len);
+ uint32_t (*readad)(struct spifi_dev_s *dev, uint32_t cmd, uint32_t addr);
+ void (*send04)(struct spifi_dev_s *dev, uint8_t op, uint8_t len,
+ uint32_t value);
+ void (*wren_sendad)(struct spifi_dev_s *dev, uint32_t cmd,
+ uint32_t addr, uint32_t value);
+ int32_t (*write_stat)(struct spifi_dev_s *dev, uint8_t len,
+ uint16_t value);
+ int32_t (*wait_busy)(struct spifi_dev_s *dev, uint8_t prog_or_erase);
+};
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+#endif /* __ARCH_ARM_SRC_LPC43XX_CHIP_LPC43_SPIFI_H */
+
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_debug.c b/nuttx/arch/arm/src/lpc43xx/lpc43_debug.c
index 00e8ebc42..51cf94706 100644
--- a/nuttx/arch/arm/src/lpc43xx/lpc43_debug.c
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_debug.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * arch/arm/src/lpc43/lpc43_pin_config.c
+ * arch/arm/src/lpc43/lpc43_debug.c
*
* Copyright (C) 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -37,13 +37,15 @@
* Included Files
****************************************************************************/
-#include <arch/board/board.h>
#include <nuttx/config.h>
-#include <nuttx/arch.h>
#include <errno.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
#include "lpc43_pinconfig.h"
+#include "lpc43_gpio.h"
#ifdef CONFIG_DEBUG
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c
new file mode 100644
index 000000000..bd97cbd83
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c
@@ -0,0 +1,320 @@
+/****************************************************************************
+ * arch/arm/src/lpc43/lpc43_spifi.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <nuttx/config.h>
+
+#include <sys/types.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <arch/irq.h>
+#include <arch/board/board.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "lpc43_cgu.h"
+#include "lpc43_spifi.h"
+#include "lpc43_pinconfig.h"
+
+#ifdef CONFIG_LPC43_SPIFI
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Select the divider to use as SPIFI input based on definitions in the
+ * board.h header file.
+ */
+
+#if defined(BOARD_SPIFI_PLL1)
+# define BASE_SPIFI_CLKSEL BASE_SPIFI_CLKSEL_PLL1
+#elif defined(BOARD_SPIFI_DIVA)
+# define LPC43_IDIV_CTRL LPC43_IDIVA_CTRL
+# define IDIV_CTRL_PD IDIVA_CTRL_PD
+# define IDIV_CTRL_IDIV_MASK IDIVA_CTRL_IDIV_MASK
+# define IDIV_CTRL_IDIV IDIVA_CTRL_IDIV(BOARD_SPIFI_DIVIDER)
+# define IDIV_CTRL_IDIV_MAX 4
+# define IDIV_CTRL_CLKSEL_MASK IDIVA_CTRL_CLKSEL_MASK
+# define IDIV_CTRL_CLKSEL_PLL1 (IDIVA_CLKSEL_PLL1 | IDIVA_CTRL_AUTOBLOCK)
+# define BASE_SPIFI_CLKSEL BASE_SPIFI_CLKSEL_IDIVA
+#elif defined(BOARD_SPIFI_DIVB)
+# define LPC43_IDIV_CTRL LPC43_IDIVB_CTRL
+# define IDIV_CTRL_PD IDIVBCD_CTRL_PD
+# define IDIV_CTRL_IDIV_MASK IDIVBCD_CTRL_IDIV_MASK
+# define IDIV_CTRL_IDIV IDIVBCD_CTRL_IDIV(BOARD_SPIFI_DIVIDER)
+# define IDIV_CTRL_IDIV_MAX 16
+# define IDIV_CTRL_CLKSEL_MASK IDIVBCD_CTRL_CLKSEL_MASK
+# define IDIV_CTRL_CLKSEL_PLL1 (IDIVBCD_CLKSEL_PLL1 | IDIVBCD_CTRL_AUTOBLOCK)
+# define BASE_SPIFI_CLKSEL BASE_SPIFI_CLKSEL_IDIVB
+#elif defined(BOARD_SPIFI_DIVC)
+# define LPC43_IDIV_CTRL LPC43_IDIVC_CTRL
+# define IDIV_CTRL_PD IDIVBCD_CTRL_PD
+# define IDIV_CTRL_IDIV_MASK IDIVBCD_CTRL_IDIV_MASK
+# define IDIV_CTRL_IDIV IDIVBCD_CTRL_IDIV(BOARD_SPIFI_DIVIDER)
+# define IDIV_CTRL_IDIV_MAX 16
+# define IDIV_CTRL_CLKSEL_MASK IDIVBCD_CTRL_CLKSEL_MASK
+# define IDIV_CTRL_CLKSEL_PLL1 (IDIVBCD_CLKSEL_PLL1 | IDIVBCD_CTRL_AUTOBLOCK)
+# define BASE_SPIFI_CLKSEL BASE_SPIFI_CLKSEL_IDIVC
+#elif defined(BOARD_SPIFI_DIVD)
+# define LPC43_IDIV_CTRL LPC43_IDIVD_CTRL
+# define IDIV_CTRL_PD IDIVBCD_CTRL_PD
+# define IDIV_CTRL_IDIV_MASK IDIVBCD_CTRL_IDIV_MASK
+# define IDIV_CTRL_IDIV IDIVBCD_CTRL_IDIV(BOARD_SPIFI_DIVIDER)
+# define IDIV_CTRL_IDIV_MAX 16
+# define IDIV_CTRL_CLKSEL_MASK IDIVBCD_CTRL_CLKSEL_MASK
+# define IDIV_CTRL_CLKSEL_PLL1 (IDIVBCD_CLKSEL_PLL1 | IDIVBCD_CTRL_AUTOBLOCK)
+# define BASE_SPIFI_CLKSEL BASE_SPIFI_CLKSEL_IDIVD
+#elif defined(BOARD_SPIFI_DIVE)
+# define LPC43_IDIV_CTRL LPC43_IDIVE_CTRL
+# define IDIV_CTRL_PD IDIVE_CTRL_PD
+# define IDIV_CTRL_IDIV_MASK IDIVE_CTRL_IDIV_MASK
+# define IDIV_CTRL_IDIV IDIVE_CTRL_IDIV(BOARD_SPIFI_DIVIDER)
+# define IDIV_CTRL_IDIV_MAX 256
+# define IDIV_CTRL_CLKSEL_MASK IDIVE_CTRL_CLKSEL_MASK
+# define IDIV_CTRL_CLKSEL_PLL1 (IDIVE_CLKSEL_PLL1 | IDIVE_CTRL_AUTOBLOCK)
+# define BASE_SPIFI_CLKSEL BASE_SPIFI_CLKSEL_IDIVE
+#endif
+
+#if BOARD_SPIFI_DIVIDER < 1 || BOARD_SPIFI_DIVIDER > IDIV_CTRL_IDIV_MAX
+# error "Invalid value for BOARD_SPIFI_DIVIDER"
+#endif
+
+/* 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.
+ */
+
+#define SCLK_MHZ (BOARD_SPIFI_FREQUENCY + (1000000 / 2)) / 1000000
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: spifi_idiv_input
+ *
+ * Description:
+ * Configure PLL1 as the input to the selected divider and enable the
+ * divider.
+ *
+ ****************************************************************************/
+
+#ifndef BOARD_SPIFI_PLL1
+static inline void spifi_idiv_input(void)
+{
+ uint32_t regval;
+
+ /* Configure PLL1 as the input to the selected divider */
+
+ regval = getreg32(LPC43_IDIV_CTRL);
+ regval &= ~IDIV_CTRL_CLKSEL_MASK;
+ regval |= IDIV_CTRL_CLKSEL_PLL1;
+ putreg32(regval, LPC43_IDIV_CTRL);
+
+ /* Enable the divider (by making sure that the power down bit is clear) */
+
+ regval &= ~IDIV_CTRL_PD;
+ putreg32(regval, LPC43_IDIV_CTRL);
+
+ /* Set the divider value */
+
+ regval &= ~IDIVA_CTRL_IDIV_MASK;
+ regval |= IDIV_CTRL_IDIV;
+ putreg32(regval, LPC43_IDIV_CTRL);
+}
+#else
+# define spifi_idiv_input()
+#endif
+
+/****************************************************************************
+ * Name: spifi_spifi_input
+ *
+ * Description:
+ * Configure the selected divider (or PLL1) as the input to the SPIFI
+ * and enable the SPIFI clock.
+ *
+ ****************************************************************************/
+
+static inline void spifi_spifi_input(void)
+{
+ uint32_t regval;
+
+ /* Configure the selected divider (or PLL1) as the input to the SPIFI */
+
+ regval = getreg32(LPC43_BASE_SPIFI_CLK);
+ regval &= ~BASE_SPIFI_CLK_CLKSEL_MASK;
+ regval |= BASE_SPIFI_CLKSEL;
+ putreg32(regval, LPC43_BASE_SPIFI_CLK);
+
+ /* Enable the SPIFI clocking (by making sure that the power down bit is
+ * clear)
+ */
+
+ regval &= ~IDIVA_CTRL_PD;
+ putreg32(regval, LPC43_BASE_SPIFI_CLK);
+}
+
+/****************************************************************************
+ * Name: spifi_pinconfig
+ *
+ * Description:
+ * Configure SPIFI pins
+ *
+ ****************************************************************************/
+
+static inline void spifi_pinconfig(void)
+{
+ /* Configure SPIFI pins */
+
+ lpc43_pin_config(PINCONF_SPIFI_CS); /* Input buffering not needed */
+ lpc43_pin_config(PINCONF_SPIFI_MISO); /* High drive for SCLK */
+ lpc43_pin_config(PINCONF_SPIFI_MOSI);
+ lpc43_pin_config(PINCONF_SPIFI_SCK);
+ lpc43_pin_config(PINCONF_SPIFI_SIO2);
+ lpc43_pin_config(PINCONF_SPIFI_SIO3);
+}
+
+/****************************************************************************
+ * Name: spifi_rominit
+ *
+ * Description:
+ * Initialize the SPIFI ROM driver
+ *
+ ****************************************************************************/
+
+static inline int spifi_rominit(void)
+{
+ struct spifi_driver_s *pspifi = *((struct spifi_driver_s **)SPIFI_ROM_PTR);
+ struct spifi_dev_s dev;
+ 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);
+ 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);
+ if (result != 0)
+ {
+ fdbg("ERROR: spifi_init failed: %05x\n", result);
+ return -ENODEV;
+ }
+ }
+
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: lpc43_spifi_initialize
+ *
+ * Description:
+ * Initialize the SPIFI interface 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.
+ *
+ ****************************************************************************/
+
+int lpc43_spifi_initialize(void)
+{
+ irqstate_t flags;
+ int ret = OK;
+
+ flags = irqsave();
+
+ /* The SPIFI will receive clocking from a divider per the settings
+ * provided in the board.h file. Configure PLL1 as the input clock
+ * for the selected divider
+ */
+
+ spifi_idiv_input();
+
+ /* Configure SPIFI to received clocking from the selected divider */
+
+ spifi_spifi_input();
+
+ /* Configure SPIFI pins */
+
+ spifi_pinconfig();
+
+
+ /* Initialize the SPIFI ROM driver */
+
+ ret = spifi_rominit();
+ irqrestore(flags);
+ return ret;
+}
+
+#endif /* CONFIG_LPC43_SPIFI */
diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h
new file mode 100644
index 000000000..7ab1255c9
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.h
@@ -0,0 +1,84 @@
+/****************************************************************************
+ * arch/arm/src/lpc43/lpc43_spifi.h
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_LPC43XX_LPC43_SPIFI_H
+#define __ARCH_ARM_SRC_LPC43XX_LPC43_SPIFI_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+#include "chip/lpc43_spifi.h"
+
+#ifdef CONFIG_LPC43_SPIFI
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Function: lpc43_spifi_initialize
+ *
+ * Description:
+ * Initialize the SPIFI interface 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.
+ *
+ ****************************************************************************/
+
+int 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 13805c0b1..68fe3f396 100644
--- a/nuttx/configs/lpc4330-xplorer/README.txt
+++ b/nuttx/configs/lpc4330-xplorer/README.txt
@@ -901,7 +901,8 @@ Where <subdir> is one of the following:
CONFIG_LPC32_CODEREDW=y : Code Red under Windows
This configuration has some special options that can be used to
- create a block device on the SPIFI FLASH:
+ 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.
diff --git a/nuttx/configs/lpc4330-xplorer/include/board.h b/nuttx/configs/lpc4330-xplorer/include/board.h
index 6901b8d16..052c1a97f 100644
--- a/nuttx/configs/lpc4330-xplorer/include/board.h
+++ b/nuttx/configs/lpc4330-xplorer/include/board.h
@@ -151,6 +151,36 @@
#define LPC43_CCLK BOARD_FCLKOUT_FREQUENCY
+/* SPIFI clocking **********************************************************/
+/* The SPIFI will receive clocking from a divider per the settings provided
+ * in this file. The NuttX code will configure PLL1 as the input clock
+ * for the selected divider
+ */
+
+#if BOARD_FCLKOUT_FREQUENCY < 120000000
+# define BOARD_SPIFI_PLL1 1 /* Use PLL1 directly */
+# undef BOARD_SPIFI_DIVA
+#else
+# undef BOARD_SPIFI_PLL1
+# define BOARD_SPIFI_DIVA 1 /* Use IDIVA */
+#endif
+
+#undef BOARD_SPIFI_DIVB
+#undef BOARD_SPIFI_DIVC
+#undef BOARD_SPIFI_DIVD
+#undef BOARD_SPIFI_DIVE
+
+/* We need to configure the divider so that its output is as close to 120MHz
+ * without exceeding that value.
+ */
+
+#if BOARD_FCLKOUT_FREQUENCY < 120000000
+# define BOARD_SPIFI_FREQUENCY BOARD_FCLKOUT_FREQUENCY /* 72Mhz? */
+#else
+# define BOARD_SPIFI_DIVIDER (2) /* 204MHz / 2 = 102MHz */
+# define BOARD_SPIFI_FREQUENCY (102000000) /* 204MHz / 2 = 102MHz */
+#endif
+
/* UART clocking ***********************************************************/
/* Configure all U[S]ARTs to use the XTAL input frequency */
diff --git a/nuttx/configs/lpc4330-xplorer/nsh/defconfig b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
index 8ab5e33ac..de4d3ff09 100644
--- a/nuttx/configs/lpc4330-xplorer/nsh/defconfig
+++ b/nuttx/configs/lpc4330-xplorer/nsh/defconfig
@@ -659,7 +659,8 @@ CONFIG_MMCSD_HAVECARDDETECT=n
#
# This configuration has some special options that can be used to
-# create a block device on the SPIFI FLASH:
+# 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.
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_nsh.c b/nuttx/configs/lpc4330-xplorer/src/up_nsh.c
index c9284ab5b..032c133f0 100644
--- a/nuttx/configs/lpc4330-xplorer/src/up_nsh.c
+++ b/nuttx/configs/lpc4330-xplorer/src/up_nsh.c
@@ -44,39 +44,31 @@
#include <debug.h>
#include <errno.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"
-#endif
-
-#include "chip.h"
#include <nuttx/ramdisk.h>
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-/* USB Configuration ********************************************************/
-
-/* PORT and SLOT number probably depend on the board configuration */
+#include "chip.h"
-#ifdef CONFIG_ARCH_BOARD_LPC4330_XPLORER
-# define CONFIG_NSH_HAVEUSBDEV 1
-#else
-# error "Unrecognized board"
-# undef CONFIG_NSH_HAVEUSBDEV
-#endif
+#ifdef CONFIG_SPIFI_BLKDRVR
+# include "lpc43_spifi.h"
-/* Can't support USB features if USB is not enabled */
+ /* This should be removed someday when we are confident in SPIFI */
-#ifndef CONFIG_USBDEV
-# undef CONFIG_NSH_HAVEUSBDEV
+# ifdef CONFIG_DEBUG_FS
+# include "up_arch.h"
+# include "chip/lpc43_cgu.h"
+# include "chip/lpc43_ccu.h"
+# endif
#endif
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
/* SPIFI Configuration ******************************************************/
-/* CONFIG_SPIFI_BLKDRVR - Enable to create a block driver on the SPFI device.
+/* 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.
@@ -95,22 +87,31 @@
*/
#ifdef CONFIG_SPIFI_BLKDRVR
+
+# ifndef CONFIG_LPC43_SPIFI=n
+# 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
+
# ifndef CONFIG_SPIFI_NBLOCKS
# error "Need number of SPIFI blocks (CONFIG_SPIFI_NBLOCKS)"
# endif
-#endif
-#define SPIFI_BUFFER \
- (FAR uint8_t *)(LPC43_LOCSRAM_SPIFI_BASE + CONFIG_SPIFI_OFFSET)
+# define SPIFI_BUFFER \
+ (FAR uint8_t *)(LPC43_LOCSRAM_SPIFI_BASE + CONFIG_SPIFI_OFFSET)
+
+#endif
/* Debug ********************************************************************/
@@ -151,6 +152,17 @@
#ifdef CONFIG_SPIFI_BLKDRVR
static int nsh_spifi_initialize(void)
{
+ int ret;
+
+ /* Initialize the SPIFI interface */
+
+ ret = lpc43_spifi_initialize();
+ if (ret < 0)
+ {
+ fdbg("ERROR: lpc43_spifi_initialize failed: %d\n", ret);
+ return ret;
+ }
+
/* This should be removed someday when we are confident in SPIFI */
#ifdef CONFIG_DEBUG_FS
diff --git a/nuttx/configs/lpcxpresso-lpc1768/README.txt b/nuttx/configs/lpcxpresso-lpc1768/README.txt
index b0ead543f..5632d0e82 100755
--- a/nuttx/configs/lpcxpresso-lpc1768/README.txt
+++ b/nuttx/configs/lpcxpresso-lpc1768/README.txt
@@ -646,18 +646,18 @@ LPCXpresso Configuration Options
LPC17xx specific CAN device driver settings. These settings all
require CONFIG_CAN:
- CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
- Standard 11-bit IDs.
- CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined.
- CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
- CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.
- (the CCLK frequency is divided by this number to get the CAN clock).
- Options = {1,2,4,6}. Default: 4.
- CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number.
- (the CCLK frequency is divided by this number to get the CAN clock).
- Options = {1,2,4,6}. Default: 4.
- CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
- CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7
+ CONFIG_CAN_EXTID - Enables support for the 29-bit extended ID. Default
+ Standard 11-bit IDs.
+ CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN1 is defined.
+ CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_LPC17_CAN2 is defined.
+ CONFIG_CAN1_DIVISOR - CAN1 is clocked at CCLK divided by this number.
+ (the CCLK frequency is divided by this number to get the CAN clock).
+ Options = {1,2,4,6}. Default: 4.
+ CONFIG_CAN2_DIVISOR - CAN2 is clocked at CCLK divided by this number.
+ (the CCLK frequency is divided by this number to get the CAN clock).
+ Options = {1,2,4,6}. Default: 4.
+ CONFIG_CAN_TSEG1 - The number of CAN time quanta in segment 1. Default: 6
+ CONFIG_CAN_TSEG2 = the number of CAN time quanta in segment 2. Default: 7
LPC17xx specific PHY/Ethernet device driver settings. These setting
also require CONFIG_NET and CONFIG_LPC17_ETHERNET.
@@ -787,10 +787,10 @@ Where <subdir> is one of the following:
class driver at apps/examples/usbstorage. See apps/examples/README.txt
for more information.
- NOTE: At present, the value for the SD SPI frequency is too
- high and the SD will fail. Setting that frequency to 400000
- removes the problem. TODO: Tune this frequency to some optimal
- value.
+ NOTE: At present, the value for the SD SPI frequency is too
+ high and the SD will fail. Setting that frequency to 400000
+ removes the problem. TODO: Tune this frequency to some optimal
+ value.
Jumpers: J55 must be set to provide chip select PIO1_11 signal as
the SD slot chip select.