summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rwxr-xr-xnuttx/arch/arm/src/lpc313x/lpc313x_internal.h108
-rwxr-xr-xnuttx/configs/ea3131/src/ea3131_internal.h8
-rwxr-xr-xnuttx/configs/ea3131/src/up_spi.c13
3 files changed, 84 insertions, 45 deletions
diff --git a/nuttx/arch/arm/src/lpc313x/lpc313x_internal.h b/nuttx/arch/arm/src/lpc313x/lpc313x_internal.h
index 47d7ca82a..ab8e3caf9 100755
--- a/nuttx/arch/arm/src/lpc313x/lpc313x_internal.h
+++ b/nuttx/arch/arm/src/lpc313x/lpc313x_internal.h
@@ -1,7 +1,7 @@
/************************************************************************************
* arch/arm/src/lpc313x/lpc313x_internal.h
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,7 +47,9 @@
#include <stdbool.h>
#include "up_internal.h"
+#include "up_arch.h"
#include "chip.h"
+#include "lpc313x_ioconfig.h"
/************************************************************************************
* Definitions
@@ -80,72 +82,92 @@ extern "C" {
#endif
/************************************************************************************
- * Public Function Prototypes
+ * Inline Functions
************************************************************************************/
-/************************************************************************************
- * Name: lpc313x_lowsetup
- *
- * Description:
- * Called early in up_boot. Performs chip-common low level initialization.
- *
- ************************************************************************************/
+/* Configure a pin as an input */
-EXTERN void lpc313x_lowsetup(void);
+static inline void gpio_configinput(uint32_t ioconfig, uint32_t bit)
+{
+ uint32_t regaddr;
-/************************************************************************************
- * Name: lpc313x_clockconfig
- *
- * Description:
- * Called to change to new clock based on settings in board.h
- *
- ************************************************************************************/
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE0RESET_OFFSET;
+ putreg32(bit, regaddr);
-EXTERN void lpc313x_clockconfig(void);
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE1RESET_OFFSET;
+ putreg32(bit, regaddr);
+}
-/************************************************************************************
- * Name: lpc313x_configgpio
- *
- * Description:
- * Configure a GPIO pin based on bit-encoded description of the pin.
- *
- ************************************************************************************/
+/* Return the current state of an input GPIO pin */
+
+static inline bool lpc313x_gpioread(uint32_t ioconfig, uint32_t bit)
+{
+ uint32_t regaddr = ioconfig + LPC313X_IOCONFIG_PINS_OFFSET;
+ return (getreg32(regaddr) & bit) != 0;
+}
+
+/* Configure the pin so that it is driven by the device */
-EXTERN int lpc313x_configgpio(uint32_t cfgset);
+static inline void gpio_configdev(uint32_t ioconfig, uint32_t bit)
+{
+ uint32_t regaddr;
+
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE1RESET_OFFSET;
+ putreg32(bit, regaddr);
+
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE0SET_OFFSET;
+ putreg32(bit, regaddr);
+}
+
+/* Configure a pin as a low output */
+
+static inline void gpio_outputlow(uint32_t ioconfig, uint32_t bit)
+{
+ uint32_t regaddr;
+
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE1SET_OFFSET;
+ putreg32(bit, regaddr);
+
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE0RESET_OFFSET;
+ putreg32(bit, regaddr);
+}
+
+/* Configure a pin as a high output */
+
+static inline void gpio_outputhigh(uint32_t ioconfig, uint32_t bit)
+{
+ uint32_t regaddr;
+
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE1SET_OFFSET;
+ putreg32(bit, regaddr);
+
+ regaddr = ioconfig + LPC313X_IOCONFIG_MODE0SET_OFFSET;
+ putreg32(bit, regaddr);
+}
/************************************************************************************
- * Name: lpc313x_gpiowrite
- *
- * Description:
- * Write one or zero to the selected GPIO pin
- *
+ * Public Function Prototypes
************************************************************************************/
-EXTERN void lpc313x_gpiowrite(uint32_t pinset, bool value);
-
/************************************************************************************
- * Name: lpc313x_gpioread
+ * Name: lpc313x_lowsetup
*
* Description:
- * Read one or zero from the selected GPIO pin
+ * Called early in up_boot. Performs chip-common low level initialization.
*
************************************************************************************/
-EXTERN bool lpc313x_gpioread(uint32_t pinset);
+EXTERN void lpc313x_lowsetup(void);
/************************************************************************************
- * Function: lpc313x_dumpgpio
+ * Name: lpc313x_clockconfig
*
* Description:
- * Dump all GPIO registers associated with the provided base address
+ * Called to change to new clock based on settings in board.h
*
************************************************************************************/
-#ifdef CONFIG_DEBUG
-EXTERN int lpc313x_dumpgpio(uint32_t pinset, const char *msg);
-#else
-# define lpc313x_dumpgpio(p,m)
-#endif
+EXTERN void lpc313x_clockconfig(void);
/************************************************************************************
* Name: lpc313x_spiselect and lpc313x_spistatus
diff --git a/nuttx/configs/ea3131/src/ea3131_internal.h b/nuttx/configs/ea3131/src/ea3131_internal.h
index 58368e80e..0f28ea1cc 100755
--- a/nuttx/configs/ea3131/src/ea3131_internal.h
+++ b/nuttx/configs/ea3131/src/ea3131_internal.h
@@ -45,20 +45,24 @@
#include <nuttx/compiler.h>
#include <stdint.h>
+#include "lpc313x_ioconfig.h"
+
/************************************************************************************
* Definitions
************************************************************************************/
/* EA3131L GPIOs ********************************************************************/
-/* LEDs */
+/* LEDs -- interface through an I2C GPIO expander */
/* BUTTONS -- NOTE that some have EXTI interrupts configured */
/* SPI Chip Selects */
+/* SPI NOR flash is the only device on SPI. SPI_CS_OUT0 is its chip select */
-/* USB Soft Connect Pullup*/
+#define SPINOR_CS IOCONFIG_SPI_CSOUT0
+/* USB Soft Connect Pullup -- NONE */
/************************************************************************************
* Public Types
diff --git a/nuttx/configs/ea3131/src/up_spi.c b/nuttx/configs/ea3131/src/up_spi.c
index 7eef2db66..66c9d228f 100755
--- a/nuttx/configs/ea3131/src/up_spi.c
+++ b/nuttx/configs/ea3131/src/up_spi.c
@@ -100,6 +100,7 @@ void weak_function lpc313x_spiinitialize(void)
* architecture.
*/
+ gpio_outputhigh(LPC313X_IOCONFIG_SPI, SPINOR_CS);
}
/****************************************************************************
@@ -130,6 +131,18 @@ void weak_function lpc313x_spiinitialize(void)
void lpc313x_spiselect(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+
+ if (devid == SPIDEV_FLASH)
+ {
+ if (selected)
+ {
+ gpio_outputlow(LPC313X_IOCONFIG_SPI, SPINOR_CS);
+ }
+ else
+ {
+ gpio_outputhigh(LPC313X_IOCONFIG_SPI, SPINOR_CS);
+ }
+ }
}
uint8_t lpc313x_spistatus(FAR struct spi_dev_s *dev, enum spi_dev_e devid)