summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-07-02 08:25:53 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-07-02 08:25:53 -0600
commitf3d584b423679a3d51924a38b088b5bc8bb372b8 (patch)
tree2ceba537539996c0ba8e09b78abd8d609e0bd4dc
parent0592a8115275eed1c42438f880ee49dc79e33bbe (diff)
downloadpx4-nuttx-f3d584b423679a3d51924a38b088b5bc8bb372b8.tar.gz
px4-nuttx-f3d584b423679a3d51924a38b088b5bc8bb372b8.tar.bz2
px4-nuttx-f3d584b423679a3d51924a38b088b5bc8bb372b8.zip
Add support for touchscreen on ITEAD Arduino shield. Untested
-rw-r--r--nuttx/configs/arduino-due/README.txt80
-rw-r--r--nuttx/configs/arduino-due/src/Makefile2
-rw-r--r--nuttx/configs/arduino-due/src/arduino-due.h4
-rw-r--r--nuttx/configs/arduino-due/src/sam_mmcsd.c21
-rw-r--r--nuttx/configs/arduino-due/src/sam_touchscreen.c434
-rw-r--r--nuttx/drivers/spi/Kconfig2
6 files changed, 518 insertions, 25 deletions
diff --git a/nuttx/configs/arduino-due/README.txt b/nuttx/configs/arduino-due/README.txt
index 457686da3..24a266956 100644
--- a/nuttx/configs/arduino-due/README.txt
+++ b/nuttx/configs/arduino-due/README.txt
@@ -890,9 +890,24 @@ Configuration sub-directories
This configuration directory will built the NuttShell. See NOTES above.
NOTES:
- 1. If the ITEAD TFT shield is connected to the Arduino Due, then
- support for the SD card slot can be enabled by making the following
- changes to the configuration:
+ 1. NSH built-in applications are supported. However, there are
+ no built-in applications built with the default configuration.
+
+ Binary Formats:
+ CONFIG_BUILTIN=y : Enable support for built-in programs
+
+ Applicaton Configuration:
+ CONFIG_NSH_BUILTIN_APPS=y : Enable starting apps from NSH command line
+
+ 2. By default, this configuration uses UART0 and has support LEDs
+ enabled. UART0 output is available on the USB debugging port or
+ on pins 0-1 of the PWML connector.
+
+ This configuration can be modified to use peripherals on the ITEAD
+ TFT shield as described below. However, in that case the UART0 and
+ LED "L" GPIO pins conflict with the pin usage by the ITEAD TFT
+ Shield. In this case you need to switch to USART0 and disable LEDs
+ by modifying the configuration as follows:
Board Selection -> Peripheral
CONFIG_SAM34_UART0=n : Disable UART0. Can't use with this shield
@@ -915,7 +930,15 @@ Configuration sub-directories
CONFIG_ARCH_LEDS=n : Can't support LEDs with this shield installed
CONFIG_ARDUINO_ITHEAD_TFT=y : Enable support for the Shield
- NOTE: You cannot use UART0 or LEDs with this ITEAD module.
+ 3. If the ITEAD TFT shield is connected to the Arduino Due, then
+ support for the SD card slot can be enabled by making the following
+ changes to the configuration:
+
+ NOTE: You cannot use UART0 or LEDs with this ITEAD module. You must
+ switch to USART0 and disable LED support as described above.
+
+ Board Selection -> Board-Specific Options:
+ CONFIG_ARDUINO_ITHEAD_TFT=y : Enable support for the Shield
File Systems:
CONFIG_DISABLE_MOUNTPOINT=n : Mountpoint support is needed
@@ -928,9 +951,6 @@ Configuration sub-directories
file name technologies. See the top level COPYING file for further
details.
- System Type -> Peripherals:
- CONFIG_SAM34_SPI0=y : Enable the SAM4L SPI peripheral
-
Device Drivers
CONFIG_SPI=y : Enable SPI support
CONFIG_SPI_EXCHANGE=y : The exchange() method is supported
@@ -950,10 +970,46 @@ Configuration sub-directories
CONFIG_NSH_MMCSDSLOTNO=0 : Only one MMC/SD slot, slot 0
CONFIG_NSH_MMCSDSPIPORTNO=0 : (does not really matter in this case)
- Board Selection -> SAM4L Xplained Pro Modules
- CONFIG_SAM4L_XPLAINED_IOMODULE=y : I/O1 module is connected
- CONFIG_SAM4L_XPLAINED_IOMODULE_EXT1=y : In EXT1, or EXT2
- CONFIG_SAM4L_XPLAINED_IOMODULE_EXT2=y
-
Application Configuration -> NSH Library
CONFIG_NSH_ARCHINIT=y : Board has architecture-specific initialization
+
+ 3. This configuration has been used for verifying the touchscreen on
+ on the ITEAD TFT Shield. With the modifications below, you can
+ include the touchscreen test program at apps/examples/touchscreen as
+ an NSH built-in application. You can enable the touchscreen and test
+ by modifying the default configuration in the following ways:
+
+ NOTE: You cannot use UART0 or LEDs with this ITEAD module. You must
+ switch to USART0 and disable LED support as described above.
+
+ Board Selection -> Board-Specific Options:
+ CONFIG_ARDUINO_ITHEAD_TFT=y : Enable support for the Shield
+
+ Device Drivers
+ CONFIG_SPI=y : Enable SPI support
+ CONFIG_SPI_EXCHANGE=y : The exchange() method is supported
+ CONFIG_SPI_OWNBUS=y : Smaller code if this is the only SPI device
+ CONFIG_SPI_BITBANG=y : Enable SPI bit-bang support
+
+ CONFIG_INPUT=y : Enable support for input devices
+
+ System Type:
+ CONFIG_GPIO_IRQ=y : GPIO interrupt support
+ CONFIG_GPIOACIRQ=y : Enable GPIO interrupts from port C
+
+ RTOS Features:
+ CONFIG_DISABLE_SIGNALS=n : Signals are required
+
+ Library Support:
+ CONFIG_SCHED_WORKQUEUE=y : Work queue support required
+
+ Applicaton Configuration:
+ CONFIG_EXAMPLES_TOUCHSCREEN=y : Enable the touchscreen built-int test
+
+ Defaults should be okay for related touchscreen settings. Touchscreen
+ debug output on USART0 can be enabled with:
+
+ Build Setup:
+ CONFIG_DEBUG=y : Enable debug features
+ CONFIG_DEBUG_VERBOSE=y : Enable verbose debug output
+ CONFIG_DEBUG_INPUT=y : Enable debug output from input devices
diff --git a/nuttx/configs/arduino-due/src/Makefile b/nuttx/configs/arduino-due/src/Makefile
index 1ea60b65a..7f7844c8c 100644
--- a/nuttx/configs/arduino-due/src/Makefile
+++ b/nuttx/configs/arduino-due/src/Makefile
@@ -59,7 +59,7 @@ ifeq ($(CONFIG_MMCSD_SPI),y)
CSRCS += sam_mmcsd.c
endif
-ifeq ($(CONFIG_INPUT),y)
+ifeq ($(CONFIG_INPUT_ADS7843E),y)
CSRCS += sam_touchscreen.c
endif
endif
diff --git a/nuttx/configs/arduino-due/src/arduino-due.h b/nuttx/configs/arduino-due/src/arduino-due.h
index 6233b3d12..47a506cce 100644
--- a/nuttx/configs/arduino-due/src/arduino-due.h
+++ b/nuttx/configs/arduino-due/src/arduino-due.h
@@ -194,10 +194,10 @@
# endif
/* In order to use the touchscreen on the ITEAD shield, you must enable the
- * SPI bit-bang driver and INPUT device support.
+ * SPI bit-bang driver and ADS7843E/XPT2046 device support.
*/
-# if defined(CONFIG_SPI_BITBANG) && defined(CONFIG_INPUT)
+# if defined(CONFIG_SPI_BITBANG) && defined(CONFIG_INPUT_ADS7843E)
# define GPIO_TSC_SCK (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOA | GPIO_PIN24)
# define GPIO_TSC_MISO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
diff --git a/nuttx/configs/arduino-due/src/sam_mmcsd.c b/nuttx/configs/arduino-due/src/sam_mmcsd.c
index 765523fed..42c03989f 100644
--- a/nuttx/configs/arduino-due/src/sam_mmcsd.c
+++ b/nuttx/configs/arduino-due/src/sam_mmcsd.c
@@ -125,16 +125,18 @@ static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
#include <nuttx/spi/spi_bitbang.c>
/****************************************************************************
- * Name: sam_mmcsd_spiinitialize
+ * Name: spi_select
*
* Description:
- * Initialize the SPI bitband driver
+ * Select or de-selected the SPI device specified by 'devid'
*
* Input Parameters:
- * None
+ * priv - An instance of the bit-bang driver structure
+ * devid - The device to select or de-select
+ * selected - True:select false:de-select
*
* Returned Value:
- * A non-NULL reference to the SPI driver on success
+ * None
*
****************************************************************************/
@@ -145,16 +147,17 @@ static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
}
/****************************************************************************
- * Name: sam_mmcsd_spiinitialize
+ * Name: spi_status
*
* Description:
- * Initialize the SPI bitband driver
+ * Return status of the SPI device specified by 'devid'
*
* Input Parameters:
- * None
+ * priv - An instance of the bit-bang driver structure
+ * devid - The device to select or de-select
*
* Returned Value:
- * A non-NULL reference to the SPI driver on success
+ * An 8-bit, bit-encoded status byte
*
****************************************************************************/
@@ -196,7 +199,7 @@ static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
* Name: sam_mmcsd_spiinitialize
*
* Description:
- * Initialize the SPI bitband driver
+ * Initialize the SPI bit-bang driver
*
* Input Parameters:
* None
diff --git a/nuttx/configs/arduino-due/src/sam_touchscreen.c b/nuttx/configs/arduino-due/src/sam_touchscreen.c
new file mode 100644
index 000000000..cad3d3cda
--- /dev/null
+++ b/nuttx/configs/arduino-due/src/sam_touchscreen.c
@@ -0,0 +1,434 @@
+/************************************************************************************
+ * configs/sam3u-ek/src/up_touchscreen.c
+ *
+ * Copyright (C) 2011-2013 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 <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <nuttx/spi/spi.h>
+#include <nuttx/spi/spi_bitbang.h>
+#include <nuttx/input/touchscreen.h>
+#include <nuttx/input/ads7843e.h>
+
+#include "up_arch.h"
+#include "sam_gpio.h"
+#include "chip/sam3u_pio.h"
+
+#include "arduino-due.h"
+
+/* In order to use the SD card on the ITEAD shield, you must enable the SPI
+ * bit-bang driver as well as support for SPI-based ADS7843E/XPT2046
+ * touchscreen controller.
+ */
+
+#if defined(CONFIG_ARDUINO_ITHEAD_TFT) && defined(CONFIG_SPI_BITBANG) && \
+ defined(CONFIG_INPUT_ADS7843E)
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifndef CONFIG_GPIOC_IRQ
+# error "Touchscreen support requires CONFIG_GPIOC_IRQ"
+#endif
+
+#ifndef CONFIG_ADS7843E_FREQUENCY
+# define CONFIG_ADS7843E_FREQUENCY 500000
+#endif
+
+#ifndef CONFIG_ADS7843E_SPIDEV
+# define CONFIG_ADS7843E_SPIDEV 0
+#endif
+
+#ifndef CONFIG_ADS7843E_DEVMINOR
+# define CONFIG_ADS7843E_DEVMINOR 0
+#endif
+
+/* Definitions for include/nuttx/spi/spi_bitbang.c. */
+
+#define SPI_SETSCK putreg32(1 << 24, SAM_PIOA_SODR)
+#define SPI_CLRSCK putreg32(1 << 24, SAM_PIOA_CODR)
+#define SPI_SETMOSI putreg32(1 << 16, SAM_PIOA_SODR)
+#define SPI_CLRMOSI putreg32(1 << 16, SAM_PIOA_CODR)
+#define SPI_GETMISO ((getreg32(SAM_PIOC_PDSR) >> 21) & 1)
+#define SPI_SETCS putreg32(1 << ?, SAM_PIO?_SODR)
+#define SPI_CLRCS putreg32(1 << ?, SAM_PIO?_CODR)
+
+/* Only mode 0 */
+
+#undef SPI_BITBANG_DISABLEMODE0
+#define SPI_BITBANG_DISABLEMODE1 1
+#define SPI_BITBANG_DISABLEMODE2 1
+#define SPI_BITBANG_DISABLEMODE3 1
+
+/* Only 8-bit data width */
+
+#undef SPI_BITBANG_VARWIDTH
+
+/* Calibration value for timing loop */
+
+#define SPI_BITBAND_LOOPSPERMSEC CONFIG_BOARD_LOOPSPERMSEC
+
+/* SPI_PERBIT_NSEC is the minimum time to transfer one bit. This determines
+ * the maximum frequency and is also used to calculate delays to achieve
+ * other SPI frequencies.
+ */
+
+#define SPI_PERBIT_NSEC 100
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+/* Lower-half SPI */
+
+static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
+ bool selected);
+static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
+ bool cmd);
+#endif
+
+/* 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. The
+ * memory must be writable because, under certain circumstances, the driver
+ * may modify frequency or X plate resistance values.
+ */
+
+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
+ ****************************************************************************/
+/****************************************************************************
+ * Include the bit-band skeleton logic
+ ****************************************************************************/
+
+#include <nuttx/spi/spi_bitbang.c>
+
+/****************************************************************************
+ * Name: spi_select
+ *
+ * Description:
+ * Select or de-selected the SPI device specified by 'devid'
+ *
+ * Input Parameters:
+ * priv - An instance of the bit-bang driver structure
+ * devid - The device to select or de-select
+ * selected - True:select false:de-select
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
+ bool selected)
+{
+# warning Still need CS GPIO pin
+}
+
+/****************************************************************************
+ * Name: spi_status
+ *
+ * Description:
+ * Return status of the SPI device specified by 'devid'
+ *
+ * Input Parameters:
+ * priv - An instance of the bit-bang driver structure
+ * devid - The device to select or de-select
+ *
+ * Returned Value:
+ * An 8-bit, bit-encoded status byte
+ *
+ ****************************************************************************/
+
+static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid)
+{
+ return 0;
+}
+
+/****************************************************************************
+ * Name: spi_cmddata
+ *
+ * Description:
+ * If there were was a CMD/DATA line, this function would manage it
+ *
+ * Input Parameters:
+ * priv - An instance of the bit-bang driver structure
+ * devid - The device to use
+ * cmd - True=MCD false=DATA
+ *
+ * Returned Value:
+ * OK
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SPI_CMDDATA
+static int spi_cmddata(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
+ bool cmd)
+{
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * 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)
+{
+ /* Attach the ADS7843E interrupt */
+
+ ivdbg("Attaching %p to IRQ %d\n", isr, SAM_TCS_IRQ);
+ return irq_attach(SAM_TCS_IRQ, isr);
+}
+
+static void tsc_enable(FAR struct ads7843e_config_s *state, bool enable)
+{
+ /* Attach and enable, or detach and disable */
+
+ ivdbg("IRQ:%d enable:%d\n", SAM_TCS_IRQ, enable);
+ if (enable)
+ {
+ sam_gpioirqenable(SAM_TCS_IRQ);
+ }
+ else
+ {
+ sam_gpioirqdisable(SAM_TCS_IRQ);
+ }
+}
+
+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
+
+ /* BUSY is high impedance when CS is high (not selected). When CS is
+ * is low, BUSY is active high.
+ */
+
+ bool busy = sam_gpioread(GPIO_TCS_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)
+{
+ /* The /PENIRQ value is active low */
+
+ bool pendown = !sam_gpioread(GPIO_TCS_IRQ);
+ ivdbg("pendown:%d\n", pendown);
+ return pendown;
+}
+
+/****************************************************************************
+ * Name: sam_tsc_spiinitialize
+ *
+ * Description:
+ * Initialize the SPI bit-bang driver
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * A non-NULL reference to the SPI driver on success
+ *
+ ****************************************************************************/
+
+static FAR struct spi_dev_s *sam_tsc_spiinitialize(void)
+{
+ /* Configure the SPI bit-bang pins */
+
+ sam_configgpio(GPIO_TSC_SCK);
+ sam_configgpio(GPIO_TSC_MISO);
+ sam_configgpio(GPIO_TSC_MOSI);
+ sam_configgpio(GPIO_TSC_CS);
+
+ /* Create the SPI driver instance */
+
+ return spi_create_bitbang(&g_spiops);
+}
+
+/****************************************************************************
+ * 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 interrupt pin as an input */
+
+ (void)sam_configgpio(GPIO_TSC_IRQ);
+ (void)sam_configgpio(GPIO_TCS_IRQ);
+
+ /* Configure the PIO interrupt */
+
+ sam_gpioirq(SAM_TCS_IRQ);
+
+ /* Get an instance of the SPI interface for the touchscreen chip select */
+
+ dev = sam_tsc_spiinitialize();
+ if (!dev)
+ {
+ idbg("Failed to initialize bit bang SPI\n");
+ return -ENODEV;
+ }
+
+ /* Initialize and register the SPI touschscreen device */
+
+ ret = ads7843e_register(dev, &g_tscinfo, CONFIG_ADS7843E_DEVMINOR);
+ if (ret < 0)
+ {
+ idbg("Failed to register touchscreen device\n");
+ /* 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_ARDUINO_ITHEAD_TFT && CONFIG_SPI_BITBANG && CONFIG_INPUT_ADS7843E */
diff --git a/nuttx/drivers/spi/Kconfig b/nuttx/drivers/spi/Kconfig
index 2dd09bd5b..b7a59a865 100644
--- a/nuttx/drivers/spi/Kconfig
+++ b/nuttx/drivers/spi/Kconfig
@@ -42,7 +42,7 @@ config SPI_BITBANG_VARWIDTH
bool "SPI bit-bang variable width transfers"
default n
---help---
- Enable support for a variable dat width transfers. Default: 8-bit
+ Enable support for a variable data width transfers. Default: 8-bit
only.
endif