summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-07-01 16:50:16 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-07-01 16:50:16 -0600
commitaeebc7eb724e902efd4bbb6dc34fc57e2a66c9d4 (patch)
treec3ec8297022067b2071f1fd3fd404a50959eceac /nuttx
parent47335ab4bab269c35774964642b823d0367f79ed (diff)
downloadpx4-nuttx-aeebc7eb724e902efd4bbb6dc34fc57e2a66c9d4.tar.gz
px4-nuttx-aeebc7eb724e902efd4bbb6dc34fc57e2a66c9d4.tar.bz2
px4-nuttx-aeebc7eb724e902efd4bbb6dc34fc57e2a66c9d4.zip
Add a general bit-bang SPI lower-half driver and implement the bit-bang driver for the Arduino ITEAD TFT shield
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog10
-rw-r--r--nuttx/configs/arduino-due/README.txt119
-rwxr-xr-xnuttx/configs/arduino-due/nsh/setenv.sh5
-rwxr-xr-xnuttx/configs/arduino-due/ostest/setenv.sh5
-rw-r--r--nuttx/configs/arduino-due/src/Makefile6
-rw-r--r--nuttx/configs/arduino-due/src/arduino-due.h56
-rw-r--r--nuttx/configs/arduino-due/src/sam_mmcsd.c266
-rw-r--r--nuttx/configs/arduino-due/src/sam_nsh.c115
-rw-r--r--nuttx/configs/sam4l-xplained/src/sam_nsh.c4
-rw-r--r--nuttx/drivers/spi/Make.defs52
-rwxr-xr-xnuttx/drivers/spi/spi_bitbang.c88
-rwxr-xr-xnuttx/include/nuttx/spi/spi_bitbang.c552
-rwxr-xr-xnuttx/include/nuttx/spi/spi_bitbang.h24
13 files changed, 1189 insertions, 113 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index dcc7d15cf..cc4767aea 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -5019,7 +5019,7 @@
controlling SPI-related discrete inputs and outputs. Taken from
work by Alan Carvalho de Assis (2013-6-20).
* arch/arm/src/kl/kl_dumpgpio.c: Now compiles (2013-6-20).
- * configs/: Several defconfig files were changed that had
+ * configs/: Several defconfig files were changed that had
CONFIG_HAVE_CXXINITIALIZE=y. Because of recent changes to
apps/examples, these configurations may need to have
CONFIG_EXAMPLES_NSH_CXXINITIALIZE=y so that they behave as they did
@@ -5091,7 +5091,7 @@
fix to the sam3u_gpio.c write protection also fixed the touchscreen
problem (2013-6-28).
* confgis/sam3u_ek/nxwm: Created a configuration for the NxWM
- window manager for the SAM3U-EK board.
+ window manager for the SAM3U-EK board (2013-6-29).
* drivers/spi and include/nuttx/spi: New sub-directories to hold
SPI-related files. includes/nuttx/spi.h moved to include/nuttx/spi/.;
SPI-related Kconfig info moved from drivers/Kconfig to drivers/spi/kconfig
@@ -5099,4 +5099,8 @@
* drivers/spi/spi_bitbang.c and include/nuttx/spi/spi_bitbang.h: Add
support for a generic bit-bang SPI driver. This checkout is the
common upper-half logic. Still missing the lower half (2013-7-1).
-
+ * include/nuttx/spi/spi_bitbang.c: This is the common lower-half bit-
+ bang SPI logic (2013-7-1).
+ * configs/arduino-due/src/sam_nsh.c and sam_mmcsd.c: Add NSH customize
+ initialization. If so configured, initialize the SPI bit bang
+ interface to the MMC/SD slot on the ITEAD shield (2013-7-1).
diff --git a/nuttx/configs/arduino-due/README.txt b/nuttx/configs/arduino-due/README.txt
index 35b9b20f3..457686da3 100644
--- a/nuttx/configs/arduino-due/README.txt
+++ b/nuttx/configs/arduino-due/README.txt
@@ -890,55 +890,70 @@ Configuration sub-directories
This configuration directory will built the NuttShell. See NOTES above.
NOTES:
- 1. The configuration configuration can be modified to include support
- for the on-board SRAM (1MB).
-
- System Type -> External Memory Configuration
- CONFIG_ARCH_EXTSRAM0=y : Select SRAM on CS0
- CONFIG_ARCH_EXTSRAM0SIZE=1048576 : Size=1MB
-
- Now what are you going to do with the SRAM. There are two choices:
-
- a) To enable the NuttX RAM test that may be used to verify the
- external SRAM:
-
- System Type -> External Memory Configuration
- CONFIG_ARCH_EXTSRAM0HEAP=n : Don't add to heap
-
- Application Configuration -> System NSH Add-Ons
- CONFIG_SYSTEM_RAMTEST=y : Enable the RAM test built-in
-
- In this configuration, the SDRAM is not added to heap and so is
- not excessible to the applications. So the RAM test can be
- freely executed against the SRAM memory beginning at address
- 0x6000:0000 (CS0).
-
- nsh> ramtest -h
- Usage: <noname> [-w|h|b] <hex-address> <decimal-size>
-
- Where:
- <hex-address> starting address of the test.
- <decimal-size> number of memory locations (in bytes).
- -w Sets the width of a memory location to 32-bits.
- -h Sets the width of a memory location to 16-bits (default).
- -b Sets the width of a memory location to 8-bits.
-
- To test the entire external SRAM:
-
- nsh> ramtest 60000000 1048576
- RAMTest: Marching ones: 60000000 1048576
- RAMTest: Marching zeroes: 60000000 1048576
- RAMTest: Pattern test: 60000000 1048576 55555555 aaaaaaaa
- RAMTest: Pattern test: 60000000 1048576 66666666 99999999
- RAMTest: Pattern test: 60000000 1048576 33333333 cccccccc
- RAMTest: Address-in-address test: 60000000 1048576
-
- b) To add this RAM to the NuttX heap, you would need to change the
- configuration as follows:
-
- System Type -> External Memory Configuration
- CONFIG_ARCH_EXTSRAM0HEAP=y : Add external RAM to heap
-
- Memory Management
- -CONFIG_MM_REGIONS=1 : Only the internal SRAM
- +CONFIG_MM_REGIONS=2 : Also include external SRAM
+ 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:
+
+ Board Selection -> Peripheral
+ CONFIG_SAM34_UART0=n : Disable UART0. Can't use with this shield
+ CONFIG_SAM34_USART0=y : Enable USART0
+ CONFIG_USART0_ISUART=y
+
+ Device Drivers -> Serial
+ CONFIG_USART0_SERIAL_CONSOLE=y : Configure the console on USART0
+ CONFIG_USART0_RXBUFSIZE=256
+ CONFIG_USART0_TXBUFSIZE=256
+ CONFIG_USART0_BAUD=115200
+ CONFIG_USART0_BITS=8
+ CONFIG_USART0_PARITY=0
+ CONFIG_USART0_2STOP=0
+
+ NOTE: USART0 TTL levels are available on COMM 5 (TXD0) and
+ COMM 6 (RXD0)
+
+ Board Selection -> Board-Specific Options:
+ 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.
+
+ File Systems:
+ CONFIG_DISABLE_MOUNTPOINT=n : Mountpoint support is needed
+ CONFIG_FS_FAT=y : Enable the FAT file system
+ CONFIG_FAT_LCNAMES=y : Enable upper/lower case 8.3 file names (Optional, see below)
+ CONFIG_FAT_LFN=y : Enable long file named (Optional, see below)
+ CONFIG_FAT_MAXFNAME=32 : Maximum supported file name length
+
+ There are issues related to patents that Microsoft holds on FAT long
+ 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
+ CONFIG_SPI_OWNBUS=y : Smaller code if this is the only SPI device
+ CONFIG_SPI_BITBANG=y : Enable SPI bit-bang support
+
+ CONFIG_MMCSD=y : Enable MMC/SD support
+ CONFIG_MMCSD_NSLOTS=1 : Only one MMC/SD card slot
+ CONFIG_MMCSD_MULTIBLOCK_DISABLE=n : Should not need to disable multi-block transfers
+ CONFIG_MMCSD_HAVECARDDETECT=y : I/O1 module as a card detect GPIO
+ CONFIG_MMCSD_SPI=y : Use the SPI interface to the MMC/SD card
+ CONFIG_MMCSD_SPICLOCK=20000000 : This is a guess for the optimal MMC/SD frequency
+ CONFIG_MMCSD_SPIMODE=0 : Mode 0 is required
+
+ Board Selection -> Common Board Options
+ CONFIG_NSH_ARCHINIT=y : Initialize the MMC/SD slot when NSH starts
+ 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
diff --git a/nuttx/configs/arduino-due/nsh/setenv.sh b/nuttx/configs/arduino-due/nsh/setenv.sh
index 9e7a288df..22cf17ce7 100755
--- a/nuttx/configs/arduino-due/nsh/setenv.sh
+++ b/nuttx/configs/arduino-due/nsh/setenv.sh
@@ -69,7 +69,10 @@ fi
# toolchain.
export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+# This is the Cygwin path to the location where I have the Arduino BOSSA program
+export BOSSA_BIN="/cygdrive/c/Program Files (x86)/Arduino/arduino-1.5.2/hardware/tools"
+
# Add the path to the toolchain to the PATH varialble
-export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+export PATH="${TOOLCHAIN_BIN}:${BOSSA_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/arduino-due/ostest/setenv.sh b/nuttx/configs/arduino-due/ostest/setenv.sh
index 2f0fdac1b..a3396c1c2 100755
--- a/nuttx/configs/arduino-due/ostest/setenv.sh
+++ b/nuttx/configs/arduino-due/ostest/setenv.sh
@@ -69,7 +69,10 @@ fi
# toolchain.
export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+# This is the Cygwin path to the location where I have the Arduino BOSSA program
+export BOSSA_BIN="/cygdrive/c/Program Files (x86)/Arduino/arduino-1.5.2/hardware/tools"
+
# Add the path to the toolchain to the PATH varialble
-export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+export PATH="${TOOLCHAIN_BIN}:${BOSSA_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/arduino-due/src/Makefile b/nuttx/configs/arduino-due/src/Makefile
index 3e09e46af..1ea60b65a 100644
--- a/nuttx/configs/arduino-due/src/Makefile
+++ b/nuttx/configs/arduino-due/src/Makefile
@@ -55,7 +55,7 @@ endif
ifeq ($(CONFIG_ARDUINO_ITHEAD_TFT),y)
ifeq ($(CONFIG_SPI_BITBANG),y)
-ifeq ($(CONFIG_MMC_SPI),y)
+ifeq ($(CONFIG_MMCSD_SPI),y)
CSRCS += sam_mmcsd.c
endif
@@ -69,6 +69,10 @@ CSRCS += sam_lcd.c
endif
endif
+ifeq ($(CONFIG_NSH_ARCHINIT),y)
+CSRCS += sam_nsh.c
+endif
+
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/arduino-due/src/arduino-due.h b/nuttx/configs/arduino-due/src/arduino-due.h
index 4be9a7963..6233b3d12 100644
--- a/nuttx/configs/arduino-due/src/arduino-due.h
+++ b/nuttx/configs/arduino-due/src/arduino-due.h
@@ -173,7 +173,7 @@
* SPI bit-bang driver as well as support for SPI-based MMC/SD cards.
*/
-# if defined(CONFIG_SPI_BITBANG) && defined(CONFIG_MMC_SPI)
+# if defined(CONFIG_SPI_BITBANG) && defined(CONFIG_MMCSD_SPI)
/* The SD slot shares the pin with LED "L" so LED support must be disabled
* to use the MMC/SD card on the ITEAD shield.
@@ -183,13 +183,13 @@
# error LEDs may not be used with the ITEAD SD card
# endif
-# define GPIO_SD_SCK (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_SD_SCK (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOB | GPIO_PIN27)
-# define GPIO_SD_MISO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_SD_MISO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOD | GPIO_PIN8)
-# define GPIO_SD_MOSI (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_SD_MOSI (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOD | GPIO_PIN7)
-# define GPIO_SD_CS (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_CLR | \
+# define GPIO_SD_CS (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIO? | GPIO_PIN?)
# endif
@@ -198,13 +198,13 @@
*/
# if defined(CONFIG_SPI_BITBANG) && defined(CONFIG_INPUT)
-# define GPIO_TSC_SCK (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# 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_CLR | \
+# define GPIO_TSC_MISO (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOC | GPIO_PIN21)
-# define GPIO_TSC_MOSI (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_TSC_MOSI (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOA | GPIO_PIN16)
-# define GPIO_TSC_CS (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_CLR | \
+# define GPIO_TSC_CS (GPIO_OUTPUT | GPIO_CFG_PULLUP | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIO? | GPIO_PIN?)
# define GPIO_TSC_IRQ (GPIO_INPUT | GPIO_CFG_PULLUP | GPIO_INT_BOTHEDGES | \
GPIO_PORT_PIOC | GPIO_PIN22)
@@ -227,29 +227,29 @@
* either inputs or outputs as needed.
*/
-# define GPIO_LCD_D0IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D0IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOA | GPIO_PIN8)
-# define GPIO_LCD_D1IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D1IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOA | GPIO_PIN9)
-# define GPIO_LCD_D2IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D2IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOB | GPIO_PIN25)
-# define GPIO_LCD_D3IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D3IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOC | GPIO_PIN28)
-# define GPIO_LCD_D4IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D4IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOC | GPIO_PIN26)
-# define GPIO_LCD_D5IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D5IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOC | GPIO_PIN25)
-# define GPIO_LCD_D6IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D6IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOC | GPIO_PIN24)
-# define GPIO_LCD_D7IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D7IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOC | GPIO_PIN23)
-# define GPIO_LCD_D7IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_D7IN (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOC | GPIO_PIN23)
-# define GPIO_LCD_CS (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_CS (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOA | GPIO_PIN22)
-# define GPIO_LCD_WR (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_WR (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOA | GPIO_PIN6)
-# define GPIO_LCD_RS (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLR | \
+# define GPIO_LCD_RS (GPIO_OUTPUT | GPIO_CFG_DEFAULT | GPIO_OUTPUT_CLEAR | \
GPIO_PORT_PIOA | GPIO_PIN4)
# endif
#endif
@@ -288,6 +288,20 @@ void sam_sram_initialize(void);
void up_ledinit(void);
#endif
+/****************************************************************************
+ * Name: sam_sdinitialize
+ *
+ * Description:
+ * Initialize the SPI-based SD card.
+ *
+ *****************************************************************************/
+
+#if defined(CONFIG_ARDUINO_ITHEAD_TFT) && defined(CONFIG_SPI_BITBANG) && \
+ defined(CONFIG_MMCSD_SPI)
+int sam_sdinitialize(int minor);
+#endif
+
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_ARDUINO_DUE_SRC_ARDUNO_DUE_H */
diff --git a/nuttx/configs/arduino-due/src/sam_mmcsd.c b/nuttx/configs/arduino-due/src/sam_mmcsd.c
new file mode 100644
index 000000000..b834a97ec
--- /dev/null
+++ b/nuttx/configs/arduino-due/src/sam_mmcsd.c
@@ -0,0 +1,266 @@
+/****************************************************************************
+ * configs/sam3u-ek/src/up_mmcsd.c
+ *
+ * Copyright (C) 2010, 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 <errno.h>
+#include <debug.h>
+
+#include <nuttx/mmcsd.h>
+#include <nuttx/spi/spi.h>
+#include <nuttx/spi/spi_bitbang.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 MMC/SD cards.
+ */
+
+#if defined(CONFIG_ARDUINO_ITHEAD_TFT) && defined(CONFIG_SPI_BITBANG) && \
+ defined(CONFIG_MMCSD_SPI)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Configuration ************************************************************/
+
+#ifdef CONFIG_DISABLE_MOUNTPOINT
+# error Mountpoints are disabled (CONFIG_DISABLE_MOUNTPOINT=y)
+#endif
+
+/* Definitions for include/nuttx/spi/spi_bitbang.c. */
+
+#define SPI_SETSCK putreg32(1 << 27, SAM_PIOB_SODR)
+#define SPI_CLRSCK putreg32(1 << 27, SAM_PIOB_CODR)
+#define SPI_SETMOSI putreg32(1 << 7, SAM_PIOD_SODR)
+#define SPI_CLRMOSI putreg32(1 << 7, SAM_PIOD_CODR)
+#define SPI_GETMISO ((getreg32(SAM_PIOD_PDSR) >> 8) & 1)
+
+/* 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.
+ *
+ * This value came from selecting 400KHz and increasing SPI_PERBIT_NSEC
+ * until a frequency close to 400KHz was achieved. This is what was
+ * reported by the software: frequency=400000 holdtime=1 actual=298507.
+ * I measured a frequency of approximately 305KHz.
+ *
+ * NOTE that there are really only two frequencies possible: hold time=1
+ * (305KHz) and hold time = 0 (probably around 781KHz)
+ */
+
+#define SPI_PERBIT_NSEC 1350 /* Calibrated at 400KHz */
+
+/* Misc definitions */
+
+#define SAM34_MMCSDSLOTNO 0 /* There is only one slot */
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+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
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Include the bit-band skeleton logic
+ ****************************************************************************/
+
+#include <nuttx/spi/spi_bitbang.c>
+
+/****************************************************************************
+ * Name: sam_mmcsd_spiinitialize
+ *
+ * Description:
+ * Initialize the SPI bitband driver
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * A non-NULL reference to the SPI driver on success
+ *
+ ****************************************************************************/
+
+static void spi_select(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
+ bool selected)
+{
+# warning Still need CS GPIO pin
+}
+
+/****************************************************************************
+ * Name: sam_mmcsd_spiinitialize
+ *
+ * Description:
+ * Initialize the SPI bitband driver
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * A non-NULL reference to the SPI driver on success
+ *
+ ****************************************************************************/
+
+static uint8_t spi_status(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid)
+{
+ if (devid = SPIDEV_MMCSD)
+ {
+ return SPI_STATUS_PRESENT;
+ }
+
+ 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
+
+/****************************************************************************
+ * Name: sam_mmcsd_spiinitialize
+ *
+ * Description:
+ * Initialize the SPI bitband driver
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * A non-NULL reference to the SPI driver on success
+ *
+ ****************************************************************************/
+
+static FAR struct spi_dev_s *sam_mmcsd_spiinitialize(void)
+{
+ /* Initialize GPIOs */
+
+ sam_configgpio(GPIO_SD_SCK);
+ sam_configgpio(GPIO_SD_MISO);
+ sam_configgpio(GPIO_SD_MOSI);
+ // sam_configgpio(GPIO_SD_CS);
+ # warning Still need CS GPIO pin
+
+ /* Create the SPI driver instance */
+
+ return spi_create_bitbang(&g_spiops);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_sdinitialize
+ *
+ * Description:
+ * Initialize the SPI-based SD card.
+ *
+ *****************************************************************************/
+
+int sam_sdinitialize(int minor)
+{
+ FAR struct spi_dev_s *spi;
+ int ret;
+
+ /* Get the SPI driver instance for the SD chip select */
+
+ fvdbg("Initializing bit bang SPI for the MMC/SD slot\n");
+
+ spi = sam_mmcsd_spiinitialize();
+ if (!spi)
+ {
+ fdbg("Failed to bit bang SPI for the MMC/SD slot\n");
+ return -ENODEV;
+ }
+
+ fvdbg("Successfully initialized bit bang SPI for the MMC/SD slot\n");
+
+ /* Bind the SPI device for the chip select to the slot */
+
+ fvdbg("Binding bit bang SPI device to MMC/SD slot %d\n",
+ SAM34_MMCSDSLOTNO);
+
+ ret = mmcsd_spislotinitialize(minor, SAM34_MMCSDSLOTNO, spi);
+ if (ret < 0)
+ {
+ fdbg("Failed to bind bit bang SPI device to MMC/SD slot %d: %d\n",
+ SAM34_MMCSDSLOTNO, ret);
+ return ret;
+ }
+
+ fvdbg("Successfuly bound bit bang SPI device to MMC/SD slot %d\n",
+ SAM34_MMCSDSLOTNO);
+
+ return OK;
+}
+
+#endif /* CONFIG_ARDUINO_ITHEAD_TFT && CONFIG_SPI_BITBANG && CONFIG_MMC_SPI */
diff --git a/nuttx/configs/arduino-due/src/sam_nsh.c b/nuttx/configs/arduino-due/src/sam_nsh.c
new file mode 100644
index 000000000..283bfde76
--- /dev/null
+++ b/nuttx/configs/arduino-due/src/sam_nsh.c
@@ -0,0 +1,115 @@
+/****************************************************************************
+ * config/arduino-due/src/sam_nsh.c
+ *
+ * Copyright (C) 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 <stdio.h>
+#include <debug.h>
+
+#include "arduino-due.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+#if defined(CONFIG_ARDUINO_ITHEAD_TFT) && defined(CONFIG_SPI_BITBANG) && \
+ defined(CONFIG_MMCSD_SPI)
+/* Support for the SD card slot on the ITEAD TFT shield */
+/* Verify NSH PORT and SLOT settings */
+
+# define SAM34_MMCSDSLOTNO 0 /* There is only one slot */
+
+# if defined(CONFIG_NSH_MMCSDSLOTNO) && CONFIG_NSH_MMCSDSLOTNO != SAM34_MMCSDSLOTNO
+# error Only one MMC/SD slot: Slot 0 (CONFIG_NSH_MMCSDSLOTNO)
+# endif
+
+/* Default MMC/SD minor number */
+
+# ifndef CONFIG_NSH_MMCSDMINOR
+# define CONFIG_NSH_MMCSDMINOR 0
+# endif
+#endif
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lowsyslog(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lowsyslog
+# else
+# define message printf
+# endif
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+#if defined(CONFIG_ARDUINO_ITHEAD_TFT) && defined(CONFIG_SPI_BITBANG) && \
+ defined(CONFIG_MMCSD_SPI)
+ /* Initialize the SPI-based MMC/SD slot */
+
+ {
+ int ret = sam_sdinitialize(CONFIG_NSH_MMCSDMINOR);
+ if (ret < 0)
+ {
+ message("nsh_archinitialize: Failed to initialize MMC/SD slot: %d\n",
+ ret);
+ return ret;
+ }
+ }
+#endif
+
+ return OK;
+}
diff --git a/nuttx/configs/sam4l-xplained/src/sam_nsh.c b/nuttx/configs/sam4l-xplained/src/sam_nsh.c
index 15e6203d3..2e4a5709f 100644
--- a/nuttx/configs/sam4l-xplained/src/sam_nsh.c
+++ b/nuttx/configs/sam4l-xplained/src/sam_nsh.c
@@ -1,7 +1,7 @@
/****************************************************************************
- * config/shenzhou/src/sam_nsh.c
+ * config/sam4l-xplained/src/sam_nsh.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/drivers/spi/Make.defs b/nuttx/drivers/spi/Make.defs
new file mode 100644
index 000000000..9581a2736
--- /dev/null
+++ b/nuttx/drivers/spi/Make.defs
@@ -0,0 +1,52 @@
+############################################################################
+# drivers/spi/Make.defs
+#
+# Copyright (C) 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.
+#
+############################################################################
+
+# Don't build anything if there is no SPI support
+
+ifeq ($(CONFIG_SPI),y)
+
+# Include the selected SPI drivers
+
+ifeq ($(CONFIG_SPI_BITBANG),y)
+ CSRCS += spi_bitbang.c
+endif
+
+# Include SPI device driver build support
+
+DEPPATH += --dep-path spi
+VPATH += :spi
+CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)spi}
+endif
+
diff --git a/nuttx/drivers/spi/spi_bitbang.c b/nuttx/drivers/spi/spi_bitbang.c
index 27022c375..813292b77 100755
--- a/nuttx/drivers/spi/spi_bitbang.c
+++ b/nuttx/drivers/spi/spi_bitbang.c
@@ -42,6 +42,7 @@
#include <semaphore.h>
#include <assert.h>
#include <errno.h>
+#include <debug.h>
#include <nuttx/spi/spi.h>
#include <nuttx/spi/spi_bitbang.h>
@@ -123,17 +124,17 @@ static uint16_t spi_send(FAR struct spi_dev_s *dev, uint16_t ch);
static void spi_exchange(FAR struct spi_dev_s *dev,
FAR const void *txbuffer, FAR void *rxbuffer,
size_t nwords);
-static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
-#ifdef CONFIG_SPI_CMDDATA
-static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
- bool cmd);
-#endif
#ifndef CONFIG_SPI_EXCHANGE
static void spi_sndblock(FAR struct spi_dev_s *dev,
FAR const void *buffer, size_t nwords);
static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer,
size_t nwords);
#endif
+static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);
+#ifdef CONFIG_SPI_CMDDATA
+static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
+ bool cmd);
+#endif
/****************************************************************************
* Private Data
@@ -259,22 +260,12 @@ static void spi_select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
{
FAR struct spi_bitbang_s *priv = (FAR struct spi_bitbang_s *)dev;
+ uint32_t actual;
- /* SPI frequency cannot be precisely controlled with a bit-bang interface.
- * Freqency corresponds to delay in toggle the SPI clock line: Set high,
- * wait, set low, wait, set high, wait, etc.
- *
- * Here we calcalute the half period of the frequency in nanoseconds (i.e.,
- * the amount of time that the clock should remain in the high or low state).
- *
- * frequency = psec / 1 sec - psec = full period in seconds
- * psec = 1 sec / frequency
- * hpsec = 1 sec / (2 * frequency) - hpsec = half period in seconds
- * hpnsec = 1000000000 / (2 * frequency) - hpnsec = half period in nanoseconds
- */
-
- priv->hpnsec = (1000000000ul + frequency) / (frequency << 2);
- return frequency;
+ DEBUGASSERT(priv && priv->low->setfrequency);
+ actual = priv->low->setfrequency(priv, frequency);
+ spivdbg("frequency=%d holdtime=%d actual=%d\n",
+ frequency, priv->holdtime, actual);
}
/****************************************************************************
@@ -297,6 +288,7 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
FAR struct spi_bitbang_s *priv = (FAR struct spi_bitbang_s *)dev;
DEBUGASSERT(priv && priv->low->setmode);
priv->low->setmode(priv, mode);
+ spivdbg("mode=%d exchange=%p\n", mode, priv->exchange);
}
/****************************************************************************
@@ -327,6 +319,7 @@ static void spi_setbits(FAR struct spi_dev_s *dev, int nbits)
DEBUGASSERT(nbits == 8);
#endif
}
+
/****************************************************************************
* Name: spi_send
*
@@ -382,6 +375,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev,
uint16_t dataout;
uint16_t datain;
+ spivdbg("txbuffer=%p rxbuffer=%p nwords=%d\n", txbuffer, rxbuffer, nwords);
DEBUGASSERT(priv && priv->low && priv->low->exchange);
/* If there is no data source, send 0xff */
@@ -497,6 +491,56 @@ static void spi_recvblock(FAR struct spi_dev_s *dev, FAR void *buffer, size_t nw
#endif
/****************************************************************************
+ * Name: spi_status
+ *
+ * Description:
+ * Get status bits associated with the device associated with 'devid'
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * devid - Identifies the device of interest
+ *
+ * Returned Value:
+ * Bit encoded status byte
+ *
+ ****************************************************************************/
+
+static uint8_t spi_status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ FAR struct spi_bitbang_s *priv = (FAR struct spi_bitbang_s *)dev;
+ DEBUGASSERT(priv && priv->low && priv->low->status);
+
+ return priv->low->status(priv, devid);
+}
+
+/****************************************************************************
+ * Name: spi_cmddata
+ *
+ * Description:
+ * Control the SPI CMD/DATA like for the device associated with 'devid'
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * devid - Identifies the device of interest
+ * cmd - True:CMD False:DATA
+ *
+ * Returned Value:
+ * OK on success; a negated errno value on failure
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SPI_CMDDATA
+static int spi_cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
+ bool cmd)
+{
+ FAR struct spi_bitbang_s *priv = (FAR struct spi_bitbang_s *)dev;
+ DEBUGASSERTcmddata(priv && priv->low && priv->low->status);
+
+ return priv->low->cmddata(priv, devid, cmd);
+}
+#endif
+
+/****************************************************************************
* Public Functions
****************************************************************************/
@@ -531,10 +575,12 @@ FAR struct spi_dev_s *spi_create_bitbang(FAR const struct spi_bitbang_ops_s *low
priv->nbits = 8;
#endif
+ sem_init(&priv->exclsem, 0, 1);
+
/* Select an initial state of mode 0, 8-bits, and 400KHz */
low->setmode(priv, SPIDEV_MODE0);
- spi_setfrequency(&priv->dev, 400000);
+ low->setfrequency(priv, 400000);
/* And return the initialized driver structure */
diff --git a/nuttx/include/nuttx/spi/spi_bitbang.c b/nuttx/include/nuttx/spi/spi_bitbang.c
new file mode 100755
index 000000000..8b1cee173
--- /dev/null
+++ b/nuttx/include/nuttx/spi/spi_bitbang.c
@@ -0,0 +1,552 @@
+/****************************************************************************
+ * configs/nuttx/spi/spi_bitbang.c
+ *
+ * Copyright (C) 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 <nuttx/spi/spi_bitbang.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* Usage ********************************************************************/
+/* To use this logic, you should provide a C file that does the following:
+ *
+ * - Defines SPI_SETSCK and SPI_CLRSCK to set and clear the SCK signal
+ * - Defines SPI_SETMOSI and SPI_CLRMOSI to set and clear the MISO signal
+ * - Defines SPI_GETMISO to sample the MISO state
+ * - Defines SPI_PERBIT_NSEC which is the minimum time to transfer one bit.
+ * This determines the maximum frequency.
+ * - Provide implementations of spi_select(), spi_status(), and spi_cmddata().
+ * - Then include this file
+ * - Provide an initialization function that initializes the GPIO pins used
+ * in the bit bang interface and calls spi_create_bitbang().
+ */
+
+/* Debug ********************************************************************/
+/* Check if SPI debut is enabled (non-standard.. no support in
+ * include/debug.h
+ */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_DEBUG_VERBOSE
+# undef CONFIG_DEBUG_SPI
+#endif
+
+#ifdef CONFIG_DEBUG_SPI
+# define spidbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void spi_select(FAR struct spi_bitbang_s *priv,
+ enum spi_dev_e devid, bool selected);
+static uint32_t spi_setfrequency(FAR struct spi_bitbang_s *priv,
+ uint32_t frequency);
+static void spi_setmode(FAR struct spi_bitbang_s *priv,
+ enum spi_mode_e mode);
+static uint16_t spi_bitexchange0(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout);
+static uint16_t spi_bitexchange1(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout);
+static uint16_t spi_bitexchange2(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout);
+static uint16_t spi_bitexchange3(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout);
+static uint16_t spi_exchange(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout);
+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
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct spi_bitbang_ops_s g_spiops =
+{
+ spi_select, /* select */
+ spi_setfrequency, /* setfrequency */
+ spi_setmode, /* setmode */
+ spi_exchange, /* exchange */
+ spi_status, /* status */
+#ifdef CONFIG_SPI_CMDDATA
+ spi_cmddata, /* cmddata */
+#endif
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+ /****************************************************************************
+ * Name: spi_setfrequency
+ *
+ * Description:
+ * Set the SPI frequency.
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * frequency - The SPI frequency requested
+ *
+ * Returned Value:
+ * Returns the actual frequency selected
+ *
+ ****************************************************************************/
+
+static uint32_t spi_setfrequency(FAR struct spi_bitbang_s *priv, uint32_t frequency)
+{
+ uint32_t pnsec;
+
+ /* SPI frequency cannot be precisely controlled with a bit-bang interface.
+ * Freqency corresponds to delay in toggle the SPI clock line: Set high,
+ * wait, set low, wait, set high, wait, etc.
+ *
+ * Here we calcalute the half period of the frequency in nanoseconds (i.e.,
+ * the amount of time that the clock should remain in the high or low state).
+ *
+ * frequency = psec / 1 sec psec = full period in seconds
+ * psec = 1 sec / frequency
+ * pnsec = 1000000000 nsec / (2 * frequency) pnsec = full period in nsec
+ *
+ * As examples:
+ * 1) frequency = 400KHz; SPI_PERBIT_NSEC = 100
+ * pnsec = 2500 - 100 = 2400
+ * holdtime = ((2401) >> 1) + 500) / 1000 = 1
+ * 2) frequency = 20MHz; SPI_PERBIT_NSEC = 100
+ * pnsec = 50 - 100 -> 0
+ * holdtime = ((0) >> 1) + 500) / 1000 = 0
+ */
+
+ pnsec = (1000000000ul + (frequency >> 1)) / frequency;
+
+ /* Minus the bit transfer overhead */
+
+ if (pnsec > SPI_PERBIT_NSEC)
+ {
+ pnsec -= SPI_PERBIT_NSEC;
+ }
+ else
+ {
+ pnsec = 0;
+ }
+
+ /* The hold time in microseconds is half of this (in microseconds) */
+
+ priv->holdtime = (((pnsec + 1) >> 1) + 500) / 1000;
+
+ /* Let's do our best to calculate the actual frequency
+ *
+ * As examples:
+ * 1) frequency = 400KHz; SPI_PERBIT_NSEC = 100; holdtime = 1
+ * pnsec = 2000 * 1 + 100 = 2100
+ * frequency = 476KHz
+ * 2) frequency = 20MHz; SPI_PERBIT_NSEC = 100; holdtime = 0
+ * pnsec = 2000 * 0 + 100 = 100
+ * frequency = 10MHz
+ */
+
+ pnsec = 2000 * priv->holdtime + SPI_PERBIT_NSEC;
+ frequency = 1000000000ul / pnsec;
+ return frequency;
+}
+
+/****************************************************************************
+ * Name: spi_setmode
+ *
+ * Description:
+ * Select the current SPI mode
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * mode - the new SPI mode
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void spi_setmode(FAR struct spi_bitbang_s *priv,
+ enum spi_mode_e mode)
+{
+ spivdbg("mode=%d\n", mode);
+
+ switch (mode)
+ {
+ case SPIDEV_MODE0: /* CPOL=0; CPHA=0 */
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE0
+ SPI_CLRSCK; /* Resting level of the clock is low */
+ priv->exchange = spi_bitexchange0;
+#else
+ DEBUGPANIC();
+#endif
+ break;
+
+ case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE1
+ SPI_CLRSCK; /* Resting level of the clock is low */
+ priv->exchange = spi_bitexchange1;
+#else
+ DEBUGPANIC();
+#endif
+ break;
+
+ case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE2
+ SPI_SETSCK; /* Resting level of the clock is high */
+ priv->exchange = spi_bitexchange2;
+#else
+ DEBUGPANIC();
+#endif
+ break;
+
+ case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE3
+ SPI_SETSCK; /* Resting level of the clock is high */
+ priv->exchange = spi_bitexchange3;
+#else
+ DEBUGPANIC();
+#endif
+ break;
+
+ default:
+ DEBUGPANIC();
+ break;
+ }
+}
+
+/****************************************************************************
+ * Name: spi_bitexchange0
+ *
+ * Description:
+ * Exchange one bit in mode 0
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * lock - true: Lock spi bus, false: unlock SPI bus
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE0
+static uint16_t spi_bitexchange0(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout)
+{
+ uint16_t datain;
+ /* No clock transition before setting MOSI */
+ if (dataout != 0)
+ {
+ SPI_SETMOSI; /* Set MISO if the bit is set */
+ }
+ else
+ {
+ SPI_CLRMOSI; /* Clear MISO if the bit is not set */
+ }
+
+ SPI_SETSCK; /* Clock transition before getting MISO */
+ datain = (uint16_t)SPI_GETMISO; /* Get bit 0 = MOSI value */
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ SPI_CLRSCK; /* Return clock to the resting state after getting MISO */
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ return datain;
+}
+#endif
+
+/****************************************************************************
+ * Name: spi_bitexchange1
+ *
+ * Description:
+ * Exchange one bit in mode 1
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * lock - true: Lock spi bus, false: unlock SPI bus
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE1
+static uint16_t spi_bitexchange1(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout)
+{
+ uint16_t datain;
+
+ SPI_SETSCK; /* Clock transition before setting MOSI */
+ if (dataout != 0)
+ {
+ SPI_SETMOSI; /* Set MISO if the bit is set */
+ }
+ else
+ {
+ SPI_CLRMOSI; /* Clear MISO if the bit is not set */
+ }
+
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ SPI_CLRSCK; /* Clock transition before getting MISO */
+ datain = (uint16_t)SPI_GETMISO; /* Get bit 0 = MOSI value */
+ /* Clock is in resting state after getting MISO */
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ return datain;
+}
+#endif
+
+/****************************************************************************
+ * Name: spi_bitexchange2
+ *
+ * Description:
+ * Exchange one bit in mode 2
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * lock - true: Lock spi bus, false: unlock SPI bus
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE2
+static uint16_t spi_bitexchange2(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout)
+{
+ uint16_t datain;
+ /* No clock transition before setting MOSI */
+ if (dataout != 0)
+ {
+ SPI_SETMOSI; /* Set MISO if the bit is set */
+ }
+ else
+ {
+ SPI_CLRMOSI; /* Clear MISO if the bit is not set */
+ }
+
+ SPI_CLRSCK; /* Clock transition before getting MISO */
+ datain = (uint16_t)SPI_GETMISO; /* Get bit 0 = MOSI value */
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ SPI_SETSCK; /* Return clock to the resting state after getting MISO */
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ return datain;
+}
+#endif
+
+/****************************************************************************
+ * Name: spi_bitexchange3
+ *
+ * Description:
+ * Exchange one bit in mode 3
+ *
+ * Input Parameters:
+ * dev - Device-specific state data
+ * lock - true: Lock spi bus, false: unlock SPI bus
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifndef CONFIG_SPI_BITBANG_DISABLEMODE3
+static uint16_t spi_bitexchange3(FAR struct spi_bitbang_s *priv,
+ uint16_t dataout)
+{
+ uint16_t datain;
+
+ SPI_CLRSCK; /* Clock transition before setting MOSI */
+ if (dataout != 0)
+ {
+ SPI_SETMOSI; /* Set MISO if the bit is set */
+ }
+ else
+ {
+ SPI_CLRMOSI; /* Clear MISO if the bit is not set */
+ }
+
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ SPI_SETSCK; /* Clock transition before getting MISO */
+ datain = (uint16_t)SPI_GETMISO; /* Get bit 0 = MOSI value */
+ /* Clock is in resting state after getting MISO */
+ if (priv->holdtime)
+ {
+ up_udelay(priv->holdtime);
+ }
+
+ return datain;
+}
+#endif
+
+/****************************************************************************
+ * Name: spi_exchange
+ *
+ * Description:
+ * Exahange on word of data on SPI
+ *
+ * Input Parameters:
+ * priv - Device-specific state data
+ * data - The TX data to be exchanged with the slave
+ *
+ * Returned Value:
+ * The RX data received from the slave
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SPI_BITBANG_VARWIDTH
+static uint16_t spi_exchange(FAR struct spi_bitbang_s *priv, uint16_t dataout)
+{
+ uint16_t datain;
+ uint16_t bit;
+ int shift;
+
+ /* Transfer each bit. This might be better done with straight-line
+ * logic because the loop overhead will limit our maximum transfer
+ * rate.
+ */
+
+ shift = priv->nbits - 1
+ for (bit = 1 << shift; bit != 0; bit >>= 1)
+ {
+ /* Shift to make space for the next, less significant bit.
+ * Then exchange bits with the slave an OR in the new, returned
+ * bit.
+ */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & bit);
+ }
+
+ return datain;
+}
+
+#else
+static uint16_t spi_exchange(FAR struct spi_bitbang_s *priv, uint16_t dataout)
+{
+ uint8_t datain;
+
+ /* Transfer each bit. This is better done with straight-line logic
+ * when possible because the loop overhead will limit our maximum transfer
+ * rate.
+ */
+
+ /* Exchange bit 7 with the slave */
+
+ datain = priv->exchange(priv, dataout & (1 << 7));
+
+ /* Exchange bit 6 with the slave */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & (1 << 6));
+
+ /* Exchange bit 5 with the slave */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & (1 << 5));
+
+ /* Exchange bit 4 with the slave */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & (1 << 4));
+
+ /* Exchange bit 3 with the slave */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & (1 << 3));
+
+ /* Exchange bit 2 with the slave */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & (1 << 2));
+
+ /* Exchange bit 1 with the slave */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & (1 << 1));
+
+ /* Exchange bit 0 with the slave */
+
+ datain <<= 1;
+ datain |= priv->exchange(priv, dataout & (1 << 0));
+
+ return datain;
+}
+#endif
diff --git a/nuttx/include/nuttx/spi/spi_bitbang.h b/nuttx/include/nuttx/spi/spi_bitbang.h
index 22a44494b..dee4463d1 100755
--- a/nuttx/include/nuttx/spi/spi_bitbang.h
+++ b/nuttx/include/nuttx/spi/spi_bitbang.h
@@ -42,6 +42,8 @@
#include <nuttx/config.h>
+#include <semaphore.h>
+
#include <nuttx/spi/spi.h>
#ifdef CONFIG_SPI_BITBANG
@@ -49,15 +51,6 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
-/* Configuration ************************************************************/
-#ifndef SPI_BITBANG_MODE <<< NOOOO.. Needs to be programmable
-# define SPI_BITBANG_MODE SPI_MODE0
-#endif
-
-#ifndef CONFIG_SPI_BITBANG_FREQUENCY <<< NOOOO.. Needs to be programmable
-# define CONFIG_SPI_BITBANG_FREQUENCY 1000000
-#endif
-
/* Debug ********************************************************************/
/* Check if SPI debut is enabled (non-standard.. no support in
* include/debug.h
@@ -97,6 +90,11 @@ struct spi_bitbang_ops_s
void (*select)(FAR struct spi_bitbang_s *priv, enum spi_dev_e devid,
bool selected);
+ /* Platform-specific, SPI frequency function */
+
+ uint32_t (*setfrequency)(FAR struct spi_bitbang_s *priv,
+ uint32_t frequency);
+
/* Platform-specific, SPI mode function */
void (*setmode)(FAR struct spi_bitbang_s *priv, enum spi_mode_e mode);
@@ -117,20 +115,24 @@ struct spi_bitbang_ops_s
#endif
};
+/* This is the type of the function that can exchange one bit */
+
+typedef uint8_t (*bitexchange_t)(FAR struct spi_bitbang_s *priv, uint8_t dataout);
+
/* This structure provides the state of the SPI bit-bang driver */
struct spi_bitbang_s
{
struct spi_dev_s dev; /* Publicly visible version of SPI driver */
FAR const struct spi_bitbang_ops_s *low; /* Low-level operations */
- uint32_t hpnsec; /* Number of microseconds in a half cycle */
+ uint32_t holdtime; /* SCK hold time to achieve requested frequency */
+ bitexchange_t exchange; /* The select bit exchange function */
#ifndef CONFIG_SPI_OWNBUS
sem_t exclsem; /* Supports mutually exclusive access to SPI */
#endif
#ifdef CONFIG_SPI_BITBANG_VARWIDTH
uint8_t nbits; /* Number of bits in the transfer */
#endif
- FAR void *priv; /* For use by the lower half driver */
};
/****************************************************************************