From 87590afa9ca772243c261e6c1b8478565bd2771a Mon Sep 17 00:00:00 2001 From: patacongo Date: Mon, 1 Apr 2013 22:00:37 +0000 Subject: More naming changes associated with earlier renaming of LP17xx up_spiinitialize; LPC178x SSP support; Open1788 SSP and touchscreen support git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5811 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/configs/open1788/README.txt | 59 +++- nuttx/configs/open1788/include/board.h | 26 ++ nuttx/configs/open1788/src/Makefile | 6 +- nuttx/configs/open1788/src/lpc17_boardinitialize.c | 14 +- nuttx/configs/open1788/src/lpc17_lcd.c | 4 +- nuttx/configs/open1788/src/lpc17_nandinitialize.c | 4 +- nuttx/configs/open1788/src/lpc17_norinitialize.c | 4 +- nuttx/configs/open1788/src/lpc17_nsh.c | 1 + nuttx/configs/open1788/src/lpc17_sdraminitialize.c | 4 +- nuttx/configs/open1788/src/lpc17_ssp.c | 205 ++++++++++++++ nuttx/configs/open1788/src/lpc17_touchscreen.c | 298 +++++++++++++++++++++ nuttx/configs/open1788/src/open1788.h | 42 ++- 12 files changed, 638 insertions(+), 29 deletions(-) create mode 100644 nuttx/configs/open1788/src/lpc17_ssp.c create mode 100644 nuttx/configs/open1788/src/lpc17_touchscreen.c (limited to 'nuttx/configs/open1788') diff --git a/nuttx/configs/open1788/README.txt b/nuttx/configs/open1788/README.txt index 45d5ae167..61a01c3a7 100644 --- a/nuttx/configs/open1788/README.txt +++ b/nuttx/configs/open1788/README.txt @@ -324,7 +324,17 @@ CONFIGURATION CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y : Buildroot toolchain CONFIG_ARMV7M_OABI_TOOLCHAIN=y : Older, OABI toolchain - 3. At the end of the build, there will be several files in the top-level + 3. This configuration has DMA-based SD card support enabled by + default. That support can be disabled as follow: + + CONFIG_LPC17_GPDMA=n : No DMA + CONFIG_ARCH_DMA=n + CONFIG_LPC17_SDCARD=n : No SD card driver + CONFIG_SDIO_DMA=n : No SD card DMA + CONFIG_MMCSD=n : No MMC/SD driver support + CONFIG_FS_FAT=n : No FAT file system support + + 4. At the end of the build, there will be several files in the top-level NuttX build directory: PASS1: @@ -346,7 +356,7 @@ CONFIGURATION load objects twice to account for write failures. I have not yet found a simple foolproof way to reliably get the code into FLASH. - 4. Combining .hex files. If you plan to use the .hex files with your + 5. Combining .hex files. If you plan to use the .hex files with your debugger or FLASH utility, then you may need to combine the two hex files into a single .hex file. Here is how you can do that. @@ -415,7 +425,17 @@ CONFIGURATION 3. This NSH has support for built-in applications enabled, however, no built-in configurations are built in the defulat configuration. - 4. This configuration has been used for verifying SDRAM by modifying + 4. This configuration has DMA-based SD card support enabled by + default. That support can be disabled as follow: + + CONFIG_LPC17_GPDMA=n : No DMA + CONFIG_ARCH_DMA=n + CONFIG_LPC17_SDCARD=n : No SD card driver + CONFIG_SDIO_DMA=n : No SD card DMA + CONFIG_MMCSD=n : No MMC/SD driver support + CONFIG_FS_FAT=n : No FAT file system support + + 5. This configuration has been used for verifying SDRAM by modifying the configuration in the following ways: CONFIG_LPC17_EMC=y : Enable the EMC @@ -428,6 +448,39 @@ CONFIGURATION freely executed against the SRAM memory beginning at address 0xa000:0000 (CS0). + 6. This configuration has been used for verifying the touchscreen on + on the 4.3" LCD module by modifying the configuration in the + following ways: + + CONFIG_INPUT=y : Enable support for input devices + CONFIG_GPIO_IRQ=y : GPIO interrupt support + CONFIG_INPUT_ADS7843E=y : Enable support for the XPT2048 + CONFIG_SPI=y : Enable SPI support + CONFIG_SPI_EXCHANGE=n : exchange() method is not supported + CONFIG_LPC17_SSP1=y : Enable support for SSP1 + CONFIG_EXAMPLES_TOUCHSCREEN=y : Enable the touchscreen built-int test + CONFIG_EXAMPLES_TOUCHSCREEN_BUILTIN=y + + Defaults should be okay for related touchscreen settings. + + You will also have to disable SD card support to use this test. The + SD card detect (CD) signal is on P0[13]. This signal is shared. It + is also used for MOSI1 and USB_UP_LED. The CD pin may be disconnected. + There is a jumper on board that enables the CD pin. + + CONFIG_LPC17_GPDMA=n : No DMA + CONFIG_ARCH_DMA=n + CONFIG_LPC17_SDCARD=n : No SD card driver + CONFIG_SDIO_DMA=n : No SD card DMA + CONFIG_MMCSD=n : No MMC/SD driver support + CONFIG_FS_FAT=n : No FAT file system support + + For touchscreen debug output: + + CONFIG_DEBUG=y + CONFIG_DEBUG_VERBOSE=y + CONFIG_DEBUG_INPUT=y + nxlines ------- Configures the graphics example located at examples/nsh. This diff --git a/nuttx/configs/open1788/include/board.h b/nuttx/configs/open1788/include/board.h index 9a3995077..421476cab 100644 --- a/nuttx/configs/open1788/include/board.h +++ b/nuttx/configs/open1788/include/board.h @@ -387,6 +387,32 @@ * PWR --- Connected to P2[0] */ +/* XPT2046 Touchscreen: + * + * -------------- -------------------- ------------ -------------- + * XTPT2046 Module Module Open1788 LED + * Signal Connector Connector + * -------------- -------------------- ------------ -------------- + * Pin 11 PENIRQ\ PENIRQ (pulled high) PORT3 Pin 1 P2.15 PENIRQ + * Pin 12 DOUT MISO PORT3 Pin 4 P1.18 MISO1 + * Pin 13 BUSY BUSY (pulled high) PORT3 Pin 9 P2.14 BUSY + * Pin 14 DIN MOSI PORT3 Pin 3 P0.13 MOSI1 + * Pin 15 CS\ SSEL (pulled high) PORT3 Pin 6 P1.8 GPIO + * Pin 16 DCLK SCK PORT3 Pin 5 P1.19 SCK1 + * -------------- -------------------- ------------ -------------- + */ + + +#define GPIO_SSP1_MISO GPIO_SSP1_MISO_3 +#define GPIO_SSP1_MOSI GPIO_SSP1_MOSI_2 +#define GPIO_SSP1_SCK GPIO_SSP1_SCK_2 + +#define GPIO_SSP1_SSEL_1 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN6) +#define GPIO_SSP1_SSEL_2 (GPIO_ALT2 | GPIO_PULLUP | GPIO_PORT0 | GPIO_PIN14) +#define GPIO_SSP1_SSEL_3 (GPIO_ALT5 | GPIO_PULLUP | GPIO_PORT1 | GPIO_PIN26) +#define GPIO_SSP1_SSEL_4 (GPIO_ALT3 | GPIO_PULLUP | GPIO_PORT4 | GPIO_PIN21) + + /************************************************************************************ * Public Types ************************************************************************************/ diff --git a/nuttx/configs/open1788/src/Makefile b/nuttx/configs/open1788/src/Makefile index af8272263..e25402ba9 100644 --- a/nuttx/configs/open1788/src/Makefile +++ b/nuttx/configs/open1788/src/Makefile @@ -38,7 +38,7 @@ CFLAGS += -I$(TOPDIR)/sched ASRCS = -CSRCS = lpc17_boardinitialize.c +CSRCS = lpc17_boardinitialize.c lpc17_ssp.c ifeq ($(CONFIG_ARCH_EXTNOR),y) CSRCS += lpc17_norinitialize.c @@ -70,6 +70,10 @@ ifeq ($(CONFIG_ARCH_BUTTONS),y) CSRCS += lpc17_buttons.c endif +ifeq ($(CONFIG_INPUT_ADS7843E),y) + CSRCS += lpc17_touchscreen.c +endif + AOBJS = $(ASRCS:.S=$(OBJEXT)) COBJS = $(CSRCS:.c=$(OBJEXT)) diff --git a/nuttx/configs/open1788/src/lpc17_boardinitialize.c b/nuttx/configs/open1788/src/lpc17_boardinitialize.c index 896c38cf6..3a696fe04 100644 --- a/nuttx/configs/open1788/src/lpc17_boardinitialize.c +++ b/nuttx/configs/open1788/src/lpc17_boardinitialize.c @@ -80,24 +80,24 @@ void lpc17_boardinitialize(void) #ifdef CONFIG_LPC17_EMC lpc17_emcinitialize(); #ifdef CONFIG_ARCH_EXTDRAM - lpc17_sdram_initialize(); + open1788_sdram_initialize(); #endif #ifdef CONFIG_ARCH_EXTNOR - lpc17_nor_initialize(); + open1788_nor_initialize(); #endif #ifdef CONFIG_ARCH_EXTNAND - lpc17_nand_initialize(); + open1788_nand_initialize(); #endif #endif /* Configure SSP chip selects if 1) at least one SSP is enabled, and 2) the weak - * function lpc17_sspinitialize() has been brought into the link. + * function open1788_sspinitialize() has been brought into the link. */ #if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1) - if (lpc17_sspinitialize) + if (open1788_sspinitialize) { - lpc17_sspinitialize(); + open1788_sspinitialize(); } #endif @@ -110,7 +110,7 @@ void lpc17_boardinitialize(void) /* Configure the LCD GPIOs if LCD support has been selected. */ #ifdef CONFIG_LPC17_LCD - lpc17_lcdinitialize(); + open1788_lcd_initialize(); #endif } diff --git a/nuttx/configs/open1788/src/lpc17_lcd.c b/nuttx/configs/open1788/src/lpc17_lcd.c index 7c70e2ebd..934f20525 100644 --- a/nuttx/configs/open1788/src/lpc17_lcd.c +++ b/nuttx/configs/open1788/src/lpc17_lcd.c @@ -63,14 +63,14 @@ ************************************************************************************/ /************************************************************************************ - * Name: lpc17_lcdinitialize + * Name: open1788_lcd_initialize * * Description: * Initialize the LCD. Setup backlight (initially off) * ************************************************************************************/ -void lpc17_lcdinitialize(void) +void open1788_lcd_initialize(void) { /* Configure the LCD backlight (and turn the backlight off) */ diff --git a/nuttx/configs/open1788/src/lpc17_nandinitialize.c b/nuttx/configs/open1788/src/lpc17_nandinitialize.c index aa66b0d41..a0d658759 100644 --- a/nuttx/configs/open1788/src/lpc17_nandinitialize.c +++ b/nuttx/configs/open1788/src/lpc17_nandinitialize.c @@ -64,14 +64,14 @@ ************************************************************************************/ /************************************************************************************ - * Name: lpc17_nand_initialize + * Name: open1788_nand_initialize * * Description: * Initialize NAND FLASH * ************************************************************************************/ -void lpc17_nand_initialize(void) +void open1788_nand_initialize(void) { uint32_t regval; diff --git a/nuttx/configs/open1788/src/lpc17_norinitialize.c b/nuttx/configs/open1788/src/lpc17_norinitialize.c index 5c4e4714a..8cf21d540 100644 --- a/nuttx/configs/open1788/src/lpc17_norinitialize.c +++ b/nuttx/configs/open1788/src/lpc17_norinitialize.c @@ -64,14 +64,14 @@ ************************************************************************************/ /************************************************************************************ - * Name: lpc17_nor_initialize + * Name: open1788_nor_initialize * * Description: * Initialize NOR FLASH * ************************************************************************************/ -void lpc17_nor_initialize(void) +void open1788_nor_initialize(void) { uint32_t regval; diff --git a/nuttx/configs/open1788/src/lpc17_nsh.c b/nuttx/configs/open1788/src/lpc17_nsh.c index 6611e601a..559909a42 100644 --- a/nuttx/configs/open1788/src/lpc17_nsh.c +++ b/nuttx/configs/open1788/src/lpc17_nsh.c @@ -45,6 +45,7 @@ #include #include +#include #include #include #include diff --git a/nuttx/configs/open1788/src/lpc17_sdraminitialize.c b/nuttx/configs/open1788/src/lpc17_sdraminitialize.c index 10196b18c..818f1ade4 100644 --- a/nuttx/configs/open1788/src/lpc17_sdraminitialize.c +++ b/nuttx/configs/open1788/src/lpc17_sdraminitialize.c @@ -99,14 +99,14 @@ ************************************************************************************/ /************************************************************************************ - * Name: lpc17_sdram_initialize + * Name: open1788_sdram_initialize * * Description: * Initialize SDRAM * ************************************************************************************/ -void lpc17_sdram_initialize(void) +void open1788_sdram_initialize(void) { uint32_t regval; #ifdef CONFIG_ARCH_SDRAM_16BIT diff --git a/nuttx/configs/open1788/src/lpc17_ssp.c b/nuttx/configs/open1788/src/lpc17_ssp.c new file mode 100644 index 000000000..e27894e72 --- /dev/null +++ b/nuttx/configs/open1788/src/lpc17_ssp.c @@ -0,0 +1,205 @@ +/**************************************************************************** + * configs/open1788/src/lpc17_ssp.c + * arch/arm/src/board/lpc17_ssp.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include + +#include + +#include "up_arch.h" +#include "chip.h" +#include "lpc17_gpio.h" +#include "lpc17_ssp.h" +#include "open1788.h" + +#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1) || \ + defined(CONFIG_LPC17_SSP2) + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Debug ********************************************************************/ + +#ifdef CONFIG_DEBUG_SPI +# define sspdbg lldbg +# ifdef CONFIG_DEBUG_VERBOSE +# define sspvdbg lldbg +# else +# define sspvdbg(x...) +# endif +#else +# define sspdbg(x...) +# define sspvdbg(x...) +#endif + +/* Dump GPIO registers */ + +#ifdef CONFIG_DEBUG_VERBOSE +# define ssp_dumpgpio(p,m) lpc17_dumpgpio(p,m) +#else +# define ssp_dumpgpio(p,m) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: open1788_sspinitialize + * + * Description: + * Called to configure SPI chip select GPIO pins for the LPC1766-STK. + * + ****************************************************************************/ + +void weak_function open1788_sspinitialize(void) +{ + /* Configure the SSP0 chip select GPIOs. */ + +#ifdef CONFIG_LPC17_SSP0 +#endif + + /* Configure SSP1 chip select GPIOs. This includes the touchscreen on the + * the LCD module. + */ + +#ifdef CONFIG_LPC17_SSP1 + ssp_dumpgpio(GPIO_TC_CS, "BEFORE SSP1 Initialization"); + lpc17_configgpio(GPIO_TC_CS); + ssp_dumpgpio(GPIO_TC_CS, "AFTER SSP1 Initialization"); +#endif + + /* Configure the SSP2 chip select GPIOs. */ + +#ifdef CONFIG_LPC17_SSP2 +#endif +} + +/************************************************************************************ + * Name: lpc17_ssp0/1/2select and lpc17_ssp0/1/2status + * + * Description: + * The external functions, lpc17_ssp0/1/2select and lpc17_ssp0/1/2status + * must be provided by board-specific logic. They are implementations of the select + * and status methods of the SPI interface defined by struct spi_ops_s (see + * include/nuttx/spi.h). All other methods (including lpc17_sspinitialize()) + * are provided by common LPC17xx logic. To use this common SPI logic on your + * board: + * + * 1. Provide logic in lpc17_boardinitialize() to configure SPI/SSP chip select + * pins. + * 2. Provide lpc17_ssp0/1/2select() and lpc17_ssp0/1/2status() functions + * in your board-specific logic. These functions will perform chip selection + * and status operations using GPIOs in the way your board is configured. + * 3. Add a calls to lpc17_sspinitialize() in your low level application + * initialization logic + * 4. The handle returned by lpc17_sspinitialize() may then be used to bind the + * SPI driver to higher level logic (e.g., calling + * mmcsd_spislotinitialize(), for example, will bind the SPI driver to + * the SPI MMC/SD driver). + * + ************************************************************************************/ + +#ifdef CONFIG_LPC17_SSP0 +void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); +} + +uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + sspdbg("Returning nothing\n"); + return 0; +} +#endif + +#ifdef CONFIG_LPC17_SSP1 +void lpc17_ssp1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); + if (devid == SPIDEV_TOUCHSCREEN) + { + /* Assert/de-assert the CS pin to the card */ + + ssp_dumpgpio(GPIO_TC_CS, "lpc17_ssp1select() Entry"); + lpc17_gpiowrite(GPIO_TC_CS, !selected); + ssp_dumpgpio(GPIO_TC_CS, "lpc17_ssp1select() Exit"); + } +} + +uint8_t lpc17_ssp1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + sspdbg("Returning nothing\n"); + return 0; +} +#endif + +#ifdef CONFIG_LPC17_SSP2 +void lpc17_ssp2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected) +{ + sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert"); +} + +uint8_t lpc17_ssp2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid) +{ + sspdbg("Returning nothing\n"); + return 0; +} +#endif + +#endif /* CONFIG_LPC17_SSP0 || CONFIG_LPC17_SSP1 || CONFIG_LPC17_SSP2 */ diff --git a/nuttx/configs/open1788/src/lpc17_touchscreen.c b/nuttx/configs/open1788/src/lpc17_touchscreen.c new file mode 100644 index 000000000..1ee8d6237 --- /dev/null +++ b/nuttx/configs/open1788/src/lpc17_touchscreen.c @@ -0,0 +1,298 @@ +/************************************************************************************ + * configs/open1788/src/lpc17_touchscreen.c + * arch/arm/src/board/lpc17_touchscreen.c + * + * Copyright (C) 2013 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ************************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "lpc17_gpio.h" +#include "lpc17_ssp.h" +#include "open1788.h" + +#ifdef CONFIG_INPUT_ADS7843E + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ +/* Configuration ************************************************************/ + +#ifndef CONFIG_INPUT +# error "Touchscreen support requires CONFIG_INPUT" +#endif + +#ifndef CONFIG_LPC17_SSP1 +# error "Touchscreen support requires CONFIG_LPC17_SSP1" +#endif + +#ifndef CONFIG_GPIO_IRQ +# error "Touchscreen support requires CONFIG_GPIO_IRQ" +#endif + +#ifndef CONFIG_ADS7843E_FREQUENCY +# define CONFIG_ADS7843E_FREQUENCY 500000 +#endif + +#ifndef CONFIG_ADS7843E_SPIDEV +# define CONFIG_ADS7843E_SPIDEV 3 +#endif + +#if CONFIG_ADS7843E_SPIDEV != 3 +# error "CONFIG_ADS7843E_SPIDEV must be three" +#endif + +#ifndef CONFIG_ADS7843E_DEVMINOR +# define CONFIG_ADS7843E_DEVMINOR 0 +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the ADS7843E driver from differences in GPIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the ADS7843E interrupt handler to the GPIO interrupt + * enable - Enable or disable the GPIO interrupt + * clear - Acknowledge/clear any pending GPIO interrupt + * pendown - Return the state of the pen down GPIO input + */ + +static int tsc_attach(FAR struct ads7843e_config_s *state, xcpt_t isr); +static void tsc_enable(FAR struct ads7843e_config_s *state, bool enable); +static void tsc_clear(FAR struct ads7843e_config_s *state); +static bool tsc_busy(FAR struct ads7843e_config_s *state); +static bool tsc_pendown(FAR struct ads7843e_config_s *state); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* A reference to a structure of this type must be passed to the ADS7843E + * driver. This structure provides information about the configuration + * of the ADS7843E and provides some board-specific hooks. + * + * Memory for this structure is provided by the caller. It is not copied + * by the driver and is presumed to persist while the driver is active. + */ + +static struct ads7843e_config_s g_tscinfo = +{ + .frequency = CONFIG_ADS7843E_FREQUENCY, + .attach = tsc_attach, + .enable = tsc_enable, + .clear = tsc_clear, + .busy = tsc_busy, + .pendown = tsc_pendown, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/* IRQ/GPIO access callbacks. These operations all hidden behind + * callbacks to isolate the ADS7843E driver from differences in GPIO + * interrupt handling by varying boards and MCUs. If possible, + * interrupts should be configured on both rising and falling edges + * so that contact and loss-of-contact events can be detected. + * + * attach - Attach the ADS7843E interrupt handler to the GPIO interrupt + * enable - Enable or disable the GPIO interrupt + * clear - Acknowledge/clear any pending GPIO interrupt + * pendown - Return the state of the pen down GPIO input + */ + +static int tsc_attach(FAR struct ads7843e_config_s *state, xcpt_t handler) +{ + /* Attach then enable the touchscreen interrupt handler */ + + (void)irq_attach(LPC17_IRQ_PENIRQ, handler); + return OK; +} + +static void tsc_enable(FAR struct ads7843e_config_s *state, bool enable) +{ + ivdbg("enable:%d\n", enable); + if (enable) + { + up_enable_irq(LPC17_IRQ_PENIRQ); + } + else + { + up_disable_irq(LPC17_IRQ_PENIRQ); + } +} + +static void tsc_clear(FAR struct ads7843e_config_s *state) +{ + /* Does nothing */ +} + +static bool tsc_busy(FAR struct ads7843e_config_s *state) +{ +#if defined(CONFIG_DEBUG_INPUT) && defined(CONFIG_DEBUG_VERBOSE) + static bool last = (bool)-1; +#endif + + /* REVISIT: This might need to be inverted */ + + bool busy = lpc17_gpioread(GPIO_TC_BUSY); +#if defined(CONFIG_DEBUG_INPUT) && defined(CONFIG_DEBUG_VERBOSE) + if (busy != last) + { + ivdbg("busy:%d\n", busy); + last = busy; + } +#endif + + return busy; +} + +static bool tsc_pendown(FAR struct ads7843e_config_s *state) +{ + /* XPT2046 uses an an internal pullup resistor. The PENIRQ output goes low + * due to the current path through the touch screen to ground, which + * initiates an interrupt to the processor via TP_INT. + */ + + bool pendown = !lpc17_gpioread(GPIO_TC_PENIRQ); + ivdbg("pendown:%d\n", pendown); + return pendown; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: arch_tcinitialize + * + * Description: + * Each board that supports a touchscreen device must provide this + * function. This function is called by application-specific, setup logic + * to configure the touchscreen device. This function will register the + * driver as /dev/inputN where N is the minor device number. + * + * Input Parameters: + * minor - The input device minor number + * + * Returned Value: + * Zero is returned on success. Otherwise, a negated errno value is + * returned to indicate the nature of the failure. + * + ****************************************************************************/ + +int arch_tcinitialize(int minor) +{ + FAR struct spi_dev_s *dev; + int ret; + + idbg("minor %d\n", minor); + DEBUGASSERT(minor == 0); + + /* Configure and enable the ADS7843E PENIRQ pin as an interrupting input. */ + + (void)lpc17_configgpio(GPIO_TC_PENIRQ); + + /* Configure the ADS7843E BUSY pin as a normal input. */ + + (void)lpc17_configgpio(GPIO_TC_BUSY); + + /* Get an instance of the SPI interface */ + + dev = lpc17_sspinitialize(CONFIG_ADS7843E_SPIDEV); + if (!dev) + { + idbg("Failed to initialize SPI bus %d\n", CONFIG_ADS7843E_SPIDEV); + return -ENODEV; + } + + /* Initialize and register the SPI touschscreen device */ + + ret = ads7843e_register(dev, &g_tscinfo, CONFIG_ADS7843E_DEVMINOR); + if (ret < 0) + { + idbg("Failed to initialize SPI bus %d\n", CONFIG_ADS7843E_SPIDEV); + /* up_spiuninitialize(dev); */ + return -ENODEV; + } + + return OK; +} + +/**************************************************************************** + * Name: arch_tcuninitialize + * + * Description: + * Each board that supports a touchscreen device must provide this function. + * This function is called by application-specific, setup logic to + * uninitialize the touchscreen device. + * + * Input Parameters: + * None + * + * Returned Value: + * None. + * + ****************************************************************************/ + +void arch_tcuninitialize(void) +{ + /* No support for un-initializing the touchscreen ADS7843E device yet */ +} + +#endif /* CONFIG_INPUT_ADS7843E */ + diff --git a/nuttx/configs/open1788/src/open1788.h b/nuttx/configs/open1788/src/open1788.h index b1349eae4..e70eebe5d 100644 --- a/nuttx/configs/open1788/src/open1788.h +++ b/nuttx/configs/open1788/src/open1788.h @@ -116,6 +116,28 @@ #define GPIO_LCD_BL (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN1) +/* XPT2046 Touchscreen **************************************************************/ +/* -------------- -------------------- ------------ -------------- + * XTPT2046 Module Module Open1788 LED + * Signal Connector Connector + * -------------- -------------------- ------------ -------------- + * Pin 11 PENIRQ\ PENIRQ (pulled high) PORT3 Pin 1 P2.15 PENIRQ + * Pin 12 DOUT MISO PORT3 Pin 4 P1.18 MISO1 + * Pin 13 BUSY BUSY (pulled high) PORT3 Pin 9 P2.14 BUSY + * Pin 14 DIN MOSI PORT3 Pin 3 P0.13 MOSI1 + * Pin 15 CS\ SSEL (pulled high) PORT3 Pin 6 P1.8 GPIO + * Pin 16 DCLK SCK PORT3 Pin 5 P1.19 SCK1 + * -------------- -------------------- ------------ -------------- + * + * Pins are configured as floating because there are pullups on the module. + */ + +#define GPIO_TC_PENIRQ (GPIO_INTBOTH | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN15) +#define GPIO_TC_BUSY (GPIO_INPUT | GPIO_FLOAT | GPIO_PORT2 | GPIO_PIN14) +#define GPIO_TC_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT1 | GPIO_PIN8) + +#define LPC17_IRQ_PENIRQ LPC17_IRQ_P2p15 + /************************************************************************************ * Public Types ************************************************************************************/ @@ -131,17 +153,17 @@ ************************************************************************************/ /************************************************************************************ - * Name: lpc17_sspinitialize + * Name: open1788_sspinitialize * * Description: * Called to configure SPI chip select GPIO pins for the WaveShare Open1788 board. * ************************************************************************************/ -void weak_function lpc17_sspinitialize(void); +void weak_function open1788_sspinitialize(void); /************************************************************************************ - * Name: lpc17_sdram_initialize + * Name: open1788_sdram_initialize * * Description: * Initialize SDRAM @@ -150,11 +172,11 @@ void weak_function lpc17_sspinitialize(void); #ifdef CONFIG_LPC17_EMC #ifdef CONFIG_ARCH_EXTDRAM -void lpc17_sdram_initialize(void); +void open1788_sdram_initialize(void); #endif /************************************************************************************ - * Name: lpc17_nor_initialize + * Name: open1788_nor_initialize * * Description: * Initialize NOR FLASH @@ -162,11 +184,11 @@ void lpc17_sdram_initialize(void); ************************************************************************************/ #ifdef CONFIG_ARCH_EXTNOR -void lpc17_nor_initialize(void); +void open1788_nor_initialize(void); #endif /************************************************************************************ - * Name: lpc17_nand_initialize + * Name: open1788_nand_initialize * * Description: * Initialize NAND FLASH @@ -174,12 +196,12 @@ void lpc17_nor_initialize(void); ************************************************************************************/ #ifdef CONFIG_ARCH_EXTNAND -void lpc17_nand_initialize(void); +void open1788_nand_initialize(void); #endif #endif /* CONFIG_LPC17_EMC */ /************************************************************************************ - * Name: lpc17_lcdinitialize + * Name: open1788_lcd_initialize * * Description: * Initialize the LCD. Setup backlight (initially off) @@ -187,7 +209,7 @@ void lpc17_nand_initialize(void); ************************************************************************************/ #ifdef CONFIG_LPC17_LCD -void lpc17_lcdinitialize(void); +void open1788_lcd_initialize(void); #endif /************************************************************************************ -- cgit v1.2.3