summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/examples/Makefile8
-rw-r--r--apps/examples/README.txt5
-rw-r--r--apps/examples/cc3000/board.c6
-rw-r--r--apps/examples/cc3000/cc3000basic.c12
-rw-r--r--nuttx/configs/freedom-kl25z/README.txt25
-rw-r--r--nuttx/configs/freedom-kl25z/nsh/defconfig26
-rw-r--r--nuttx/configs/freedom-kl25z/src/kl_wifi.c2
-rw-r--r--nuttx/drivers/Makefile1
-rw-r--r--nuttx/drivers/wireless/Kconfig4
-rw-r--r--nuttx/drivers/wireless/Make.defs4
-rw-r--r--nuttx/drivers/wireless/cc3000/cc3000_common.c8
-rw-r--r--nuttx/drivers/wireless/cc3000/evnt_handler.c14
-rw-r--r--nuttx/drivers/wireless/cc3000/hci.c10
-rw-r--r--nuttx/drivers/wireless/cc3000/netapp.c10
-rw-r--r--nuttx/drivers/wireless/cc3000/nvmem.c8
-rw-r--r--nuttx/drivers/wireless/cc3000/security.c2
-rw-r--r--nuttx/drivers/wireless/cc3000/socket.c8
-rw-r--r--nuttx/drivers/wireless/cc3000/spi.c701
-rw-r--r--nuttx/drivers/wireless/cc3000/wlan.c14
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/cc3000_common.h (renamed from nuttx/include/nuttx/cc3000/cc3000_common.h)0
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/evnt_handler.h (renamed from nuttx/include/nuttx/cc3000/evnt_handler.h)5
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/hci.h (renamed from nuttx/include/nuttx/cc3000/hci.h)2
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/host_driver_version.h (renamed from nuttx/include/nuttx/cc3000/host_driver_version.h)0
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/netapp.h (renamed from nuttx/include/nuttx/cc3000/netapp.h)0
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/nvmem.h (renamed from nuttx/include/nuttx/cc3000/nvmem.h)2
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/security.h (renamed from nuttx/include/nuttx/cc3000/security.h)2
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/socket.h (renamed from nuttx/include/nuttx/cc3000/socket.h)0
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/spi.h (renamed from nuttx/include/nuttx/cc3000/spi.h)0
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/spi_version.h (renamed from nuttx/include/nuttx/cc3000/spi_version.h)0
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/wlan.h (renamed from nuttx/include/nuttx/cc3000/wlan.h)2
30 files changed, 457 insertions, 424 deletions
diff --git a/apps/examples/Makefile b/apps/examples/Makefile
index 46e2efd27..4036bc325 100644
--- a/apps/examples/Makefile
+++ b/apps/examples/Makefile
@@ -37,7 +37,7 @@
# Sub-directories
-SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf
+SUBDIRS = adc buttons can cc3000 cdcacm composite cxxtest dhcpd discover elf
SUBDIRS += flash_test ftpc ftpd hello helloxx hidkbd igmp json keypadtest
SUBDIRS += lcdrw mm modbus mount mtdpart nettest nrf24l01_term nsh null
SUBDIRS += nx nxconsole nxffs nxflat nxhello nximage nxlines nxtext ostest
@@ -53,9 +53,9 @@ SUBDIRS += wget wgetjson xmlrpc
CNTXTDIRS = pwm
ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
-CNTXTDIRS += adc can cdcacm composite cxxtest dhcpd discover flash_test ftpd
-CNTXTDIRS += hello helloxx json keypadtestmodbus lcdrw mtdpart nettest nx
-CNTXTDIRS += nxhello nximage nxlines nxtext nrf24l01_term ostest relays
+CNTXTDIRS += adc can cc3000 cdcacm composite cxxtest dhcpd discover flash_test
+CNTXTDIRS += ftpd hello helloxx json keypadtestmodbus lcdrw mtdpart nettest
+CNTXTDIRS += nx nxhello nximage nxlines nxtext nrf24l01_term ostest relays
CNTXTDIRS += qencoder slcd smart_test tcpecho telnetd tiff touchscreen
CNTXTDIRS += usbstorage usbterm watchdog wgetjson
endif
diff --git a/apps/examples/README.txt b/apps/examples/README.txt
index c6f31b034..016a04dd3 100644
--- a/apps/examples/README.txt
+++ b/apps/examples/README.txt
@@ -126,6 +126,11 @@ examples/can
CONFIG_EXAMPLES_CAN_READONLY - Only receive messages
CONFIG_EXAMPLES_CAN_WRITEONLY - Only send messages
+examples/cc3000
+^^^^^^^^^^^^^^^
+
+ This is a test for the TI CC3000 wireless networking module.
+
examples/cdcacm
^^^^^^^^^^^^^^^
diff --git a/apps/examples/cc3000/board.c b/apps/examples/cc3000/board.c
index 1868b061d..2794a7f0e 100644
--- a/apps/examples/cc3000/board.c
+++ b/apps/examples/cc3000/board.c
@@ -26,9 +26,9 @@
#include "board.h"
#include <stdbool.h>
-#include <nuttx/cc3000/wlan.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/spi.h>
+#include <nuttx/wireless/cc3000/wlan.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/spi.h>
#include <arch/board/kl_wifi.h>
diff --git a/apps/examples/cc3000/cc3000basic.c b/apps/examples/cc3000/cc3000basic.c
index 39f8f7c8f..c50b9de86 100644
--- a/apps/examples/cc3000/cc3000basic.c
+++ b/apps/examples/cc3000/cc3000basic.c
@@ -94,12 +94,12 @@ Arduino pin -----> 560 Ohm --+--> 1K Ohm -----> GND
#include <stdlib.h>
#include <stdbool.h>
#include <sys/time.h>
-#include <nuttx/cc3000/nvmem.h>
-#include <nuttx/cc3000/socket.h>
-#include <nuttx/cc3000/wlan.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/security.h>
-#include <nuttx/cc3000/netapp.h>
+#include <nuttx/wireless/cc3000/nvmem.h>
+#include <nuttx/wireless/cc3000/socket.h>
+#include <nuttx/wireless/cc3000/wlan.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/security.h>
+#include <nuttx/wireless/cc3000/netapp.h>
void Initialize(void);
void helpme(void);
diff --git a/nuttx/configs/freedom-kl25z/README.txt b/nuttx/configs/freedom-kl25z/README.txt
index ca71f59f3..c57f1a2ca 100644
--- a/nuttx/configs/freedom-kl25z/README.txt
+++ b/nuttx/configs/freedom-kl25z/README.txt
@@ -409,3 +409,28 @@ Where <subdir> is one of the following:
There is probably enough free memroy to support 3 or 4 application
threads in addition to NSH.
+
+ 5. This configurations has support for NSH built-in applications. However,
+ in the default configuration no built-in applications are enabled.
+
+ 6. This configuration has been used to verify the TI CC3000 wireless
+ networking module. In order to enable this module, you would need to
+ make the following changes to the default configuration files:
+
+ System Type -> Kinetis peripheral support
+ CONFIG_KL_SPI0=y : Enable SPI
+ CONFIG_KL_SPI1=y
+
+ Drivers -> SPI
+ CONFIG_SPI=y : Enable SPI
+ CONFIG_SPI_EXCHANGE=y
+
+ Drivers -> Wireless
+ CONFIG_WIRELESS=y : Enable wireless support
+ CONFIG_WL_CC3000=y : Build the CC3000 driver
+
+ Applications -> Examples
+ CONFIG_EXAMPLES_CC3000BASIC=y : CC3000 test example
+
+ Applications -> NSH Library
+ CONFIG_NSH_ARCHINIT=y : Build in CC3000 initialization logic
diff --git a/nuttx/configs/freedom-kl25z/nsh/defconfig b/nuttx/configs/freedom-kl25z/nsh/defconfig
index 616160844..3a8155366 100644
--- a/nuttx/configs/freedom-kl25z/nsh/defconfig
+++ b/nuttx/configs/freedom-kl25z/nsh/defconfig
@@ -16,7 +16,7 @@ CONFIG_HOST_LINUX=y
#
# Build Configuration
#
-CONFIG_APPS_DIR="../apps"
+# CONFIG_APPS_DIR="../apps"
# CONFIG_BUILD_2PASS is not set
#
@@ -84,6 +84,7 @@ CONFIG_ARCH_CORTEXM0=y
# CONFIG_ARCH_CORTEXM3 is not set
# CONFIG_ARCH_CORTEXM4 is not set
# CONFIG_ARCH_CORTEXA5 is not set
+# CONFIG_ARCH_CORTEXA8 is not set
CONFIG_ARCH_FAMILY="armv6-m"
CONFIG_ARCH_CHIP="kl"
CONFIG_ARCH_HAVE_CMNVECTOR=y
@@ -94,10 +95,10 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y
#
# ARMV6M Configuration Options
#
-# CONFIG_ARMV6M_TOOLCHAIN_BUILDROOT is not set
+CONFIG_ARMV6M_TOOLCHAIN_BUILDROOT=y
# CONFIG_ARMV6M_TOOLCHAIN_CODEREDL is not set
# CONFIG_ARMV6M_TOOLCHAIN_CODESOURCERYL is not set
-CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL=y
+# CONFIG_ARMV6M_TOOLCHAIN_GNU_EABIL is not set
# CONFIG_GPIO_IRQ is not set
#
@@ -116,8 +117,8 @@ CONFIG_KL_UART0=y
# CONFIG_KL_UART2 is not set
# CONFIG_KL_FLEXCAN0 is not set
# CONFIG_KL_FLEXCAN1 is not set
-CONFIG_KL_SPI0=y
-CONFIG_KL_SPI1=y
+# CONFIG_KL_SPI0 is not set
+# CONFIG_KL_SPI1 is not set
# CONFIG_KL_SPI2 is not set
# CONFIG_KL_I2C0 is not set
# CONFIG_KL_I2C1 is not set
@@ -281,11 +282,7 @@ CONFIG_DEV_NULL=y
# CONFIG_CAN is not set
# CONFIG_PWM is not set
# CONFIG_I2C is not set
-CONFIG_SPI=y
-# CONFIG_SPI_OWNBUS is not set
-CONFIG_SPI_EXCHANGE=y
-# CONFIG_SPI_CMDDATA is not set
-# CONFIG_SPI_BITBANG is not set
+# CONFIG_SPI is not set
# CONFIG_RTC is not set
# CONFIG_WATCHDOG is not set
# CONFIG_ANALOG is not set
@@ -327,10 +324,7 @@ CONFIG_UART0_2STOP=0
# CONFIG_SERIAL_OFLOWCONTROL is not set
# CONFIG_USBDEV is not set
# CONFIG_USBHOST is not set
-CONFIG_WIRELESS=y
-# CONFIG_WL_CC1101 is not set
-CONFIG_WL_CC3000=y
-# CONFIG_WL_NRF24L01 is not set
+# CONFIG_WIRELESS is not set
#
# System Logging Device Options
@@ -446,7 +440,7 @@ CONFIG_BUILTIN_PROXY_STACKSIZE=1024
#
# CONFIG_EXAMPLES_BUTTONS is not set
# CONFIG_EXAMPLES_CAN is not set
-CONFIG_EXAMPLES_CC3000BASIC=y
+# CONFIG_EXAMPLES_CC3000BASIC is not set
# CONFIG_EXAMPLES_COMPOSITE is not set
# CONFIG_EXAMPLES_DHCPD is not set
# CONFIG_EXAMPLES_ELF is not set
@@ -601,7 +595,7 @@ CONFIG_NSH_CONSOLE=y
# USB Trace Support
#
# CONFIG_NSH_CONDEV is not set
-CONFIG_NSH_ARCHINIT=y
+# CONFIG_NSH_ARCHINIT is not set
#
# NxWidgets/NxWM
diff --git a/nuttx/configs/freedom-kl25z/src/kl_wifi.c b/nuttx/configs/freedom-kl25z/src/kl_wifi.c
index 034a3485f..42732a590 100644
--- a/nuttx/configs/freedom-kl25z/src/kl_wifi.c
+++ b/nuttx/configs/freedom-kl25z/src/kl_wifi.c
@@ -49,7 +49,7 @@
#include <nuttx/arch.h>
#include <nuttx/fs/fs.h>
-#include <nuttx/cc3000/spi.h>
+#include <nuttx/wireless/cc3000/spi.h>
#include "up_arch.h"
#include "kl_gpio.h"
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index 56d02bfce..cce03cad0 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -67,7 +67,6 @@ include syslog$(DELIM)Make.defs
include usbdev$(DELIM)Make.defs
include usbhost$(DELIM)Make.defs
include wireless$(DELIM)Make.defs
-include wireless$(DELIM)cc3000$(DELIM)Make.defs
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
CSRCS += dev_null.c dev_zero.c loop.c
diff --git a/nuttx/drivers/wireless/Kconfig b/nuttx/drivers/wireless/Kconfig
index 5e6c0d386..bb2b366f7 100644
--- a/nuttx/drivers/wireless/Kconfig
+++ b/nuttx/drivers/wireless/Kconfig
@@ -13,6 +13,10 @@ menuconfig WL_CC3000
default n
select SPI
+if WL_CC3000
+source drivers/wireless/cc3000/Kconfig
+endif
+
config WL_NRF24L01
bool "nRF24l01+ transceiver support"
default n
diff --git a/nuttx/drivers/wireless/Make.defs b/nuttx/drivers/wireless/Make.defs
index 3e7126acc..b75c48764 100644
--- a/nuttx/drivers/wireless/Make.defs
+++ b/nuttx/drivers/wireless/Make.defs
@@ -45,6 +45,10 @@ ifeq ($(CONFIG_WL_NRF24L01),y)
CSRCS += nrf24l01.c
endif
+ifeq ($(CONFIG_WL_CC3000),y)
+include wireless$(DELIM)cc3000$(DELIM)Make.defs
+endif
+
# Include wireless devices build support
DEPPATH += --dep-path wireless
diff --git a/nuttx/drivers/wireless/cc3000/cc3000_common.c b/nuttx/drivers/wireless/cc3000/cc3000_common.c
index dae74d4c4..75a6ded4b 100644
--- a/nuttx/drivers/wireless/cc3000/cc3000_common.c
+++ b/nuttx/drivers/wireless/cc3000/cc3000_common.c
@@ -43,10 +43,10 @@
* Include files
*
*****************************************************************************/
-#include <nuttx/cc3000/cc3000_common.h>
-#include <nuttx/cc3000/socket.h>
-#include <nuttx/cc3000/wlan.h>
-#include <nuttx/cc3000/evnt_handler.h>
+#include <nuttx/wireless/cc3000/cc3000_common.h>
+#include <nuttx/wireless/cc3000/socket.h>
+#include <nuttx/wireless/cc3000/wlan.h>
+#include <nuttx/wireless/cc3000/evnt_handler.h>
//*****************************************************************************
//
diff --git a/nuttx/drivers/wireless/cc3000/evnt_handler.c b/nuttx/drivers/wireless/cc3000/evnt_handler.c
index f430c820e..ffc3ae6cd 100644
--- a/nuttx/drivers/wireless/cc3000/evnt_handler.c
+++ b/nuttx/drivers/wireless/cc3000/evnt_handler.c
@@ -44,13 +44,13 @@
//******************************************************************************
#include <string.h>
-#include <nuttx/cc3000/cc3000_common.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/evnt_handler.h>
-#include <nuttx/cc3000/wlan.h>
-#include <nuttx/cc3000/socket.h>
-#include <nuttx/cc3000/netapp.h>
-#include <nuttx/cc3000/spi.h>
+#include <nuttx/wireless/cc3000/cc3000_common.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/evnt_handler.h>
+#include <nuttx/wireless/cc3000/wlan.h>
+#include <nuttx/wireless/cc3000/socket.h>
+#include <nuttx/wireless/cc3000/netapp.h>
+#include <nuttx/wireless/cc3000/spi.h>
diff --git a/nuttx/drivers/wireless/cc3000/hci.c b/nuttx/drivers/wireless/cc3000/hci.c
index c238b2772..033f1e7cd 100644
--- a/nuttx/drivers/wireless/cc3000/hci.c
+++ b/nuttx/drivers/wireless/cc3000/hci.c
@@ -41,11 +41,11 @@
//*****************************************************************************
#include <string.h>
-#include <nuttx/cc3000/cc3000_common.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/spi.h>
-#include <nuttx/cc3000/evnt_handler.h>
-#include <nuttx/cc3000/wlan.h>
+#include <nuttx/wireless/cc3000/cc3000_common.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/spi.h>
+#include <nuttx/wireless/cc3000/evnt_handler.h>
+#include <nuttx/wireless/cc3000/wlan.h>
#define SL_PATCH_PORTION_SIZE (1000)
diff --git a/nuttx/drivers/wireless/cc3000/netapp.c b/nuttx/drivers/wireless/cc3000/netapp.c
index fe00a7254..4bdd205db 100644
--- a/nuttx/drivers/wireless/cc3000/netapp.c
+++ b/nuttx/drivers/wireless/cc3000/netapp.c
@@ -33,11 +33,11 @@
*
*****************************************************************************/
#include <string.h>
-#include <nuttx/cc3000/netapp.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/socket.h>
-#include <nuttx/cc3000/evnt_handler.h>
-#include <nuttx/cc3000/nvmem.h>
+#include <nuttx/wireless/cc3000/netapp.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/socket.h>
+#include <nuttx/wireless/cc3000/evnt_handler.h>
+#include <nuttx/wireless/cc3000/nvmem.h>
#define MIN_TIMER_VAL_SECONDS 20
#define MIN_TIMER_SET(t) if ((0 != t) && (t < MIN_TIMER_VAL_SECONDS)) \
diff --git a/nuttx/drivers/wireless/cc3000/nvmem.c b/nuttx/drivers/wireless/cc3000/nvmem.c
index 66c9cb850..779d4304e 100644
--- a/nuttx/drivers/wireless/cc3000/nvmem.c
+++ b/nuttx/drivers/wireless/cc3000/nvmem.c
@@ -42,10 +42,10 @@
#include <stdio.h>
#include <string.h>
-#include <nuttx/cc3000/nvmem.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/socket.h>
-#include <nuttx/cc3000/evnt_handler.h>
+#include <nuttx/wireless/cc3000/nvmem.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/socket.h>
+#include <nuttx/wireless/cc3000/evnt_handler.h>
//*****************************************************************************
//
diff --git a/nuttx/drivers/wireless/cc3000/security.c b/nuttx/drivers/wireless/cc3000/security.c
index c364c68d7..e37d9a0de 100644
--- a/nuttx/drivers/wireless/cc3000/security.c
+++ b/nuttx/drivers/wireless/cc3000/security.c
@@ -40,7 +40,7 @@
//
//*****************************************************************************
-#include <nuttx/cc3000/security.h>
+#include <nuttx/wireless/cc3000/security.h>
#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
// foreward sbox
diff --git a/nuttx/drivers/wireless/cc3000/socket.c b/nuttx/drivers/wireless/cc3000/socket.c
index 5b810f231..8e6c873ff 100644
--- a/nuttx/drivers/wireless/cc3000/socket.c
+++ b/nuttx/drivers/wireless/cc3000/socket.c
@@ -43,10 +43,10 @@
#include <stdio.h>
#include <string.h>
#include <stdlib.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/socket.h>
-#include <nuttx/cc3000/evnt_handler.h>
-#include <nuttx/cc3000/netapp.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/socket.h>
+#include <nuttx/wireless/cc3000/evnt_handler.h>
+#include <nuttx/wireless/cc3000/netapp.h>
diff --git a/nuttx/drivers/wireless/cc3000/spi.c b/nuttx/drivers/wireless/cc3000/spi.c
index 47e809bba..78582cc62 100644
--- a/nuttx/drivers/wireless/cc3000/spi.c
+++ b/nuttx/drivers/wireless/cc3000/spi.c
@@ -5,9 +5,9 @@
* This code uses the Arduino hardware SPI library (or a bit-banged
* SPI for the Teensy 3.0) to send & receive data between the library
* API calls and the CC3000 hardware. Every
-*
+*
* Version 1.0.1b
-*
+*
* Copyright (C) 2013 Chris Magagna - cmagagna@yahoo.com
*
* Redistribution and use in source and binary forms, with or without
@@ -25,9 +25,9 @@
#include <nuttx/config.h>
#include <nuttx/spi/spi.h>
#include <arch/board/kl_wifi.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/spi.h>
-//#include <nuttx/cc3000/ArduinoCC3000Core.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/spi.h>
+//#include <nuttx/wireless/cc3000/ArduinoCC3000Core.h>
// This flag lets the interrupt handler know if it should respond to
// the WL_SPI_IRQ pin going low or not
@@ -42,17 +42,17 @@ int16_t SPIInterruptsEnabled=0;
#define HEADERS_SIZE_EVNT (SPI_HEADER_SIZE + 5)
-#define SPI_HEADER_SIZE (5)
+#define SPI_HEADER_SIZE (5)
-#define eSPI_STATE_POWERUP (0)
-#define eSPI_STATE_INITIALIZED (1)
-#define eSPI_STATE_IDLE (2)
-#define eSPI_STATE_WRITE_IRQ (3)
-#define eSPI_STATE_WRITE_FIRST_PORTION (4)
-#define eSPI_STATE_WRITE_EOT (5)
-#define eSPI_STATE_READ_IRQ (6)
-#define eSPI_STATE_READ_FIRST_PORTION (7)
-#define eSPI_STATE_READ_EOT (8)
+#define eSPI_STATE_POWERUP (0)
+#define eSPI_STATE_INITIALIZED (1)
+#define eSPI_STATE_IDLE (2)
+#define eSPI_STATE_WRITE_IRQ (3)
+#define eSPI_STATE_WRITE_FIRST_PORTION (4)
+#define eSPI_STATE_WRITE_EOT (5)
+#define eSPI_STATE_READ_IRQ (6)
+#define eSPI_STATE_READ_FIRST_PORTION (7)
+#define eSPI_STATE_READ_EOT (8)
/* !!!HACK!!!*/
#define KL_PORTA_ISFR 0x400490a0
@@ -60,7 +60,6 @@ int16_t SPIInterruptsEnabled=0;
#define getreg32(a) (*(volatile uint32_t *)(a))
#define putreg32(v,a) (*(volatile uint32_t *)(a) = (v))
-
#undef SPI_DEBUG /* Define to enable debug */
#undef SPI_VERBOSE /* Define to enable verbose debug */
@@ -77,7 +76,6 @@ int16_t SPIInterruptsEnabled=0;
# define spivdbg(x...)
#endif
-
#ifdef CONFIG_KL_SPI0
void kl_spi0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
bool selected)
@@ -96,7 +94,6 @@ void kl_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
}
#endif
-
#ifdef CONFIG_KL_SPI0
uint8_t kl_spi0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
@@ -111,20 +108,17 @@ uint8_t kl_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
}
#endif
-
-
typedef struct
{
- gcSpiHandleRx SPIRxHandler;
+ gcSpiHandleRx SPIRxHandler;
- uint16_t usTxPacketLength;
- uint16_t usRxPacketLength;
- unsigned long ulSpiState;
- uint8_t *pTxPacket;
- uint8_t *pRxPacket;
-
-}tSpiInformation;
+ uint16_t usTxPacketLength;
+ uint16_t usRxPacketLength;
+ unsigned long ulSpiState;
+ uint8_t *pTxPacket;
+ uint8_t *pRxPacket;
+} tSpiInformation;
tSpiInformation sSpiInformation;
@@ -133,9 +127,8 @@ tSpiInformation sSpiInformation;
//
uint8_t tSpiReadHeader[] = {READ, 0, 0, 0, 0};
-
// The magic number that resides at the end of the TX/RX buffer (1 byte after the allocated size)
-// for the purpose of detection of the overrun. The location of the memory where the magic number
+// for the purpose of detection of the overrun. The location of the memory where the magic number
// resides shall never be written. In case it is written - the overrun occured and either recevie function
// or send function will stuck forever.
#define CC3000_BUFFER_MAGIC_NUMBER (0xDE)
@@ -147,23 +140,23 @@ struct spi_dev_s *spi = NULL;
unsigned int SPIPump(uint8_t data)
{
- uint8_t rx;
+ uint8_t rx;
- printf("SPIPump tx = 0x%X ", data);
+ printf("SPIPump tx = 0x%X ", data);
- if(!spi){
- spi = up_spiinitialize(1);
- SPI_SETBITS(spi, 8);
- SPI_SETMODE(spi, SPIDEV_MODE1);
- }
+ if (!spi)
+ {
+ spi = up_spiinitialize(1);
+ SPI_SETBITS(spi, 8);
+ SPI_SETMODE(spi, SPIDEV_MODE1);
+ }
- SPI_EXCHANGE(spi, &data, &rx, 1);
+ SPI_EXCHANGE(spi, &data, &rx, 1);
- printf(" rx = 0x%X\n", rx);
-
- return rx;
-}
+ printf(" rx = 0x%X\n", rx);
+ return rx;
+}
//*****************************************************************************
//
@@ -173,16 +166,15 @@ unsigned int SPIPump(uint8_t data)
//!
//! \return none
//!
-//! \brief The function triggers a user provided callback for
+//! \brief The function triggers a user provided callback for
//
//*****************************************************************************
void SpiPauseSpi(void)
{
- SPIInterruptsEnabled = 0;
+ SPIInterruptsEnabled = 0;
}
-
//*****************************************************************************
//
//! This function enter point for write flow
@@ -191,16 +183,15 @@ void SpiPauseSpi(void)
//!
//! \return none
//!
-//! \brief The function triggers a user provided callback for
+//! \brief The function triggers a user provided callback for
//
//*****************************************************************************
void SpiResumeSpi(void)
{
- SPIInterruptsEnabled = 1;
+ SPIInterruptsEnabled = 1;
}
-
//*****************************************************************************
//
//! This function enter point for write flow
@@ -209,30 +200,30 @@ void SpiResumeSpi(void)
//!
//! \return none
//!
-//! \brief The function triggers a user provided callback for
+//! \brief The function triggers a user provided callback for
//
//*****************************************************************************
void SpiTriggerRxProcessing(void)
{
- //
- // Trigger Rx processing
- //
- SpiPauseSpi();
- DeassertWlanCS();
-
- // The magic number that resides at the end of the TX/RX buffer (1 byte after the allocated size)
- // for the purpose of detection of the overrun. If the magic number is overriten - buffer overrun
- // occurred - and we will stuck here forever!
- if (sSpiInformation.pRxPacket[CC3000_RX_BUFFER_SIZE - 1] != CC3000_BUFFER_MAGIC_NUMBER)
- {
- while (1)
- ;
- }
-
- sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
- sSpiInformation.SPIRxHandler(sSpiInformation.pRxPacket + SPI_HEADER_SIZE);
-}
+ //
+ // Trigger Rx processing
+ //
+ SpiPauseSpi();
+ DeassertWlanCS();
+
+ // The magic number that resides at the end of the TX/RX buffer (1 byte after the allocated size)
+ // for the purpose of detection of the overrun. If the magic number is overriten - buffer overrun
+ // occurred - and we will stuck here forever!
+ if (sSpiInformation.pRxPacket[CC3000_RX_BUFFER_SIZE - 1] != CC3000_BUFFER_MAGIC_NUMBER)
+ {
+ while (1)
+ ;
+ }
+
+ sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
+ sSpiInformation.SPIRxHandler(sSpiInformation.pRxPacket + SPI_HEADER_SIZE);
+}
//*****************************************************************************
//
@@ -245,16 +236,17 @@ void SpiTriggerRxProcessing(void)
//! \brief ...
//
//*****************************************************************************
+
void SpiReadDataSynchronous(uint8_t *data, uint16_t size)
{
- long i = 0;
+ long i = 0;
uint8_t *data_to_send = tSpiReadHeader;
-
- for (i = 0; i < size; i ++) {
- data[i] = SPIPump(data_to_send[0]);
- }
-}
+ for (i = 0; i < size; i ++)
+ {
+ data[i] = SPIPump(data_to_send[0]);
+ }
+}
//*****************************************************************************
//
@@ -267,18 +259,17 @@ void SpiReadDataSynchronous(uint8_t *data, uint16_t size)
//! \brief ...
//
//*****************************************************************************
+
void SpiWriteDataSynchronous(uint8_t *data, uint16_t size)
{
-
- while (size)
- {
- SPIPump(*data);
- size --;
- data++;
- }
+ while (size)
+ {
+ SPIPump(*data);
+ size --;
+ data++;
+ }
}
-
//*****************************************************************************
//
//! This function enter point for write flow
@@ -292,30 +283,30 @@ void SpiWriteDataSynchronous(uint8_t *data, uint16_t size)
//*****************************************************************************
long SpiFirstWrite(uint8_t *ucBuf, uint16_t usLength)
{
- //
- // workaround for first transaction
- //
- int i = 0, j = 1;
- AssertWlanCS();
-
- usleep(70);
-
- // SPI writes first 4 bytes of data
- SpiWriteDataSynchronous(ucBuf, 4);
-
- usleep(70);
-
- SpiWriteDataSynchronous(ucBuf + 4, usLength - 4);
-
- sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
-
- DeassertWlanCS();
-
- //printf("Executed SpiFirstWrite!\n");
-
- return(0);
-}
+ //
+ // workaround for first transaction
+ //
+
+ AssertWlanCS();
+
+ usleep(70);
+
+ // SPI writes first 4 bytes of data
+ SpiWriteDataSynchronous(ucBuf, 4);
+
+ usleep(70);
+
+ SpiWriteDataSynchronous(ucBuf + 4, usLength - 4);
+
+ sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
+
+ DeassertWlanCS();
+
+ //printf("Executed SpiFirstWrite!\n");
+
+ return(0);
+}
//*****************************************************************************
//
@@ -328,109 +319,114 @@ long SpiFirstWrite(uint8_t *ucBuf, uint16_t usLength)
//! \brief ...
//
//*****************************************************************************
+
long SpiWrite(uint8_t *pUserBuffer, uint16_t usLength)
{
- uint8_t ucPad = 0;
-
- //
- // Figure out the total length of the packet in order to figure out if there is padding or not
- //
- if(!(usLength & 0x0001))
+ uint8_t ucPad = 0;
+
+ //
+ // Figure out the total length of the packet in order to figure out if there is padding or not
+ //
+
+ if(!(usLength & 0x0001))
{
- ucPad++;
+ ucPad++;
}
+ pUserBuffer[0] = WRITE;
+ pUserBuffer[1] = HI(usLength + ucPad);
+ pUserBuffer[2] = LO(usLength + ucPad);
+ pUserBuffer[3] = 0;
+ pUserBuffer[4] = 0;
- pUserBuffer[0] = WRITE;
- pUserBuffer[1] = HI(usLength + ucPad);
- pUserBuffer[2] = LO(usLength + ucPad);
- pUserBuffer[3] = 0;
- pUserBuffer[4] = 0;
-
- usLength += (SPI_HEADER_SIZE + ucPad);
-
- // The magic number that resides at the end of the TX/RX buffer (1 byte after the allocated size)
- // for the purpose of overrun detection. If the magic number is overwritten - buffer overrun
- // occurred - and we will be stuck here forever!
- if (wlan_tx_buffer[CC3000_TX_BUFFER_SIZE - 1] != CC3000_BUFFER_MAGIC_NUMBER)
- {
- while (1)
- ;
- }
-
- if (sSpiInformation.ulSpiState == eSPI_STATE_POWERUP)
- {
- while (sSpiInformation.ulSpiState != eSPI_STATE_INITIALIZED) {
- }
- ;
- }
-
- if (sSpiInformation.ulSpiState == eSPI_STATE_INITIALIZED)
- {
- //
- // This is time for first TX/RX transactions over SPI:
- // the IRQ is down - so need to send read buffer size command
- //
- SpiFirstWrite(pUserBuffer, usLength);
- }
- else
- {
- //
- // We need to prevent here race that can occur in case two back to back packets are sent to the
- // device, so the state will move to IDLE and once again to not IDLE due to IRQ
- //
- tSLInformation.WlanInterruptDisable();
-
- while (sSpiInformation.ulSpiState != eSPI_STATE_IDLE)
- {
- ;
- }
-
-
- sSpiInformation.ulSpiState = eSPI_STATE_WRITE_IRQ;
- sSpiInformation.pTxPacket = pUserBuffer;
- sSpiInformation.usTxPacketLength = usLength;
-
- //
- // Assert the CS line and wait till SSI IRQ line is active and then initialize write operation
- //
- AssertWlanCS();
-
- //
- // Re-enable IRQ - if it was not disabled - this is not a problem...
- //
- tSLInformation.WlanInterruptEnable();
-
- //
- // check for a missing interrupt between the CS assertion and enabling back the interrupts
- //
- if (tSLInformation.ReadWlanInterruptPin() == 0)
- {
- SpiWriteDataSynchronous(sSpiInformation.pTxPacket, sSpiInformation.usTxPacketLength);
-
- sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
-
- DeassertWlanCS();
- }
- }
-
-
- //
- // Due to the fact that we are currently implementing a blocking situation
- // here we will wait till end of transaction
- //
-
- while (eSPI_STATE_IDLE != sSpiInformation.ulSpiState)
- ;
-
- return(0);
-}
+ usLength += (SPI_HEADER_SIZE + ucPad);
+
+ // The magic number that resides at the end of the TX/RX buffer (1 byte after the allocated size)
+ // for the purpose of overrun detection. If the magic number is overwritten - buffer overrun
+ // occurred - and we will be stuck here forever!
+
+ if (wlan_tx_buffer[CC3000_TX_BUFFER_SIZE - 1] != CC3000_BUFFER_MAGIC_NUMBER)
+ {
+ while (1)
+ ;
+ }
+
+ if (sSpiInformation.ulSpiState == eSPI_STATE_POWERUP)
+ {
+ while (sSpiInformation.ulSpiState != eSPI_STATE_INITIALIZED)
+ {
+ }
+ }
+
+ if (sSpiInformation.ulSpiState == eSPI_STATE_INITIALIZED)
+ {
+ //
+ // This is time for first TX/RX transactions over SPI:
+ // the IRQ is down - so need to send read buffer size command
+ //
+
+ SpiFirstWrite(pUserBuffer, usLength);
+ }
+ else
+ {
+ //
+ // We need to prevent here race that can occur in case two back to back packets are sent to the
+ // device, so the state will move to IDLE and once again to not IDLE due to IRQ
+ //
+
+ tSLInformation.WlanInterruptDisable();
+ while (sSpiInformation.ulSpiState != eSPI_STATE_IDLE)
+ {
+ ;
+ }
+
+ sSpiInformation.ulSpiState = eSPI_STATE_WRITE_IRQ;
+ sSpiInformation.pTxPacket = pUserBuffer;
+ sSpiInformation.usTxPacketLength = usLength;
+
+ //
+ // Assert the CS line and wait till SSI IRQ line is active and then initialize write operation
+ //
+
+ AssertWlanCS();
+
+ //
+ // Re-enable IRQ - if it was not disabled - this is not a problem...
+ //
+
+ tSLInformation.WlanInterruptEnable();
+
+ //
+ // check for a missing interrupt between the CS assertion and enabling back the interrupts
+ //
+
+ if (tSLInformation.ReadWlanInterruptPin() == 0)
+ {
+ SpiWriteDataSynchronous(sSpiInformation.pTxPacket, sSpiInformation.usTxPacketLength);
+
+ sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
+
+ DeassertWlanCS();
+ }
+ }
+
+
+ //
+ // Due to the fact that we are currently implementing a blocking situation
+ // here we will wait till end of transaction
+ //
+
+ while (eSPI_STATE_IDLE != sSpiInformation.ulSpiState)
+ ;
+
+ return(0);
+}
//*****************************************************************************
//
-//! This function processes received SPI Header and in accordance with it - continues reading
-//! the packet
+//! This function processes received SPI Header and in accordance with it - continues reading
+//! the packet
//!
//! \param None
//!
@@ -439,69 +435,74 @@ long SpiWrite(uint8_t *pUserBuffer, uint16_t usLength)
//! \brief ...
//
//*****************************************************************************
+
long SpiReadDataCont(void)
{
- long data_to_recv;
- uint8_t *evnt_buff, type;
-
-
- //
- //determine what type of packet we have
- //
- evnt_buff = sSpiInformation.pRxPacket;
- data_to_recv = 0;
- STREAM_TO_UINT8((char *)(evnt_buff + SPI_HEADER_SIZE), HCI_PACKET_TYPE_OFFSET, type);
-
- switch(type)
+ long data_to_recv;
+ uint8_t *evnt_buff, type;
+
+ //
+ //determine what type of packet we have
+ //
+
+ evnt_buff = sSpiInformation.pRxPacket;
+ data_to_recv = 0;
+ STREAM_TO_UINT8((char *)(evnt_buff + SPI_HEADER_SIZE), HCI_PACKET_TYPE_OFFSET, type);
+
+ switch(type)
{
- case HCI_TYPE_DATA:
+ case HCI_TYPE_DATA:
{
- //
- // We need to read the rest of data..
- //
- STREAM_TO_UINT16((char *)(evnt_buff + SPI_HEADER_SIZE), HCI_DATA_LENGTH_OFFSET, data_to_recv);
- if (!((HEADERS_SIZE_EVNT + data_to_recv) & 1))
- {
- data_to_recv++;
- }
-
- if (data_to_recv)
- {
- SpiReadDataSynchronous(evnt_buff + 10, data_to_recv);
- }
- break;
+ //
+ // We need to read the rest of data..
+ //
+
+ STREAM_TO_UINT16((char *)(evnt_buff + SPI_HEADER_SIZE), HCI_DATA_LENGTH_OFFSET, data_to_recv);
+
+ if (!((HEADERS_SIZE_EVNT + data_to_recv) & 1))
+ {
+ data_to_recv++;
+ }
+
+ if (data_to_recv)
+ {
+ SpiReadDataSynchronous(evnt_buff + 10, data_to_recv);
+ }
+ break;
}
- case HCI_TYPE_EVNT:
+
+ case HCI_TYPE_EVNT:
{
- //
- // Calculate the rest length of the data
- //
- STREAM_TO_UINT8((char *)(evnt_buff + SPI_HEADER_SIZE), HCI_EVENT_LENGTH_OFFSET, data_to_recv);
- data_to_recv -= 1;
-
- //
- // Add padding byte if needed
- //
- if ((HEADERS_SIZE_EVNT + data_to_recv) & 1)
- {
-
- data_to_recv++;
- }
-
- if (data_to_recv)
- {
- SpiReadDataSynchronous(evnt_buff + 10, data_to_recv);
- }
-
- sSpiInformation.ulSpiState = eSPI_STATE_READ_EOT;
- break;
+ //
+ // Calculate the rest length of the data
+ //
+
+ STREAM_TO_UINT8((char *)(evnt_buff + SPI_HEADER_SIZE), HCI_EVENT_LENGTH_OFFSET, data_to_recv);
+
+ data_to_recv -= 1;
+
+ //
+ // Add padding byte if needed
+ //
+
+ if ((HEADERS_SIZE_EVNT + data_to_recv) & 1)
+ {
+ data_to_recv++;
+ }
+
+ if (data_to_recv)
+ {
+ SpiReadDataSynchronous(evnt_buff + 10, data_to_recv);
+ }
+
+ sSpiInformation.ulSpiState = eSPI_STATE_READ_EOT;
+ break;
}
}
-
+
return (0);
}
-
//*****************************************************************************
//
//! This function enter point for write flow
@@ -510,32 +511,30 @@ long SpiReadDataCont(void)
//!
//! \return none
//!
-//! \brief The function triggers a user provided callback for
+//! \brief The function triggers a user provided callback for
//
//*****************************************************************************
void SSIContReadOperation(void)
{
- //
- // The header was read - continue with the payload read
- //
- if (!SpiReadDataCont())
- {
-
-
- //
- // All the data was read - finalize handling by switching to teh task
- // and calling from task Event Handler
- //
- SpiTriggerRxProcessing();
- }
-}
+ //
+ // The header was read - continue with the payload read
+ //
+ if (!SpiReadDataCont())
+ {
+ //
+ // All the data was read - finalize handling by switching to teh task
+ // and calling from task Event Handler
+ //
+ SpiTriggerRxProcessing();
+ }
+}
//*****************************************************************************
//
//! This function enter point for read flow: first we read minimal 5 SPI header bytes and 5 Event
-//! Data bytes
+//! Data bytes
//!
//! \param buffer
//!
@@ -546,82 +545,84 @@ void SSIContReadOperation(void)
//*****************************************************************************
void SpiReadHeader(void)
{
- SpiReadDataSynchronous(sSpiInformation.pRxPacket, 10);
+ SpiReadDataSynchronous(sSpiInformation.pRxPacket, 10);
}
-
//*****************************************************************************
-//
+//
//! The IntSpiGPIOHandler interrupt handler
-//!
+//!
//! \param none
-//!
+//!
//! \return none
-//!
+//!
//! \brief GPIO A interrupt handler. When the external SSI WLAN device is
//! ready to interact with Host CPU it generates an interrupt signal.
//! After that Host CPU has registrated this interrupt request
//! it set the corresponding /CS in active state.
-//
+//
//*****************************************************************************
//#pragma vector=PORT2_VECTOR
//__interrupt void IntSpiGPIOHandler(void)
int CC3000InterruptHandler(int irq, void *context)
{
+ uint32_t regval = 0;
- uint32_t regval = 0;
+ regval = getreg32(KL_PORTA_ISFR);
+ if (regval & (1 << PIN16))
+ {
+ //printf("\nAn interrupt was issued!\n");
- regval = getreg32(KL_PORTA_ISFR);
- if (regval & (1 << PIN16))
+ if (!SPIInterruptsEnabled)
{
- //printf("\nAn interrupt was issued!\n");
-
- if (!SPIInterruptsEnabled) {
- goto out;
- }
-
- //printf("\nSPIInterrupt was enabled!\n");
-
- if (sSpiInformation.ulSpiState == eSPI_STATE_POWERUP)
- {
- /* This means IRQ line was low call a callback of HCI Layer to inform on event */
- sSpiInformation.ulSpiState = eSPI_STATE_INITIALIZED;
- }
- else if (sSpiInformation.ulSpiState == eSPI_STATE_IDLE)
- {
- sSpiInformation.ulSpiState = eSPI_STATE_READ_IRQ;
-
- /* IRQ line goes down - start reception */
- AssertWlanCS();
-
- //
- // Wait for TX/RX Complete which will come as DMA interrupt
- //
- SpiReadHeader();
-
- sSpiInformation.ulSpiState = eSPI_STATE_READ_EOT;
-
- SSIContReadOperation();
- }
- else if (sSpiInformation.ulSpiState == eSPI_STATE_WRITE_IRQ)
- {
-
- SpiWriteDataSynchronous(sSpiInformation.pTxPacket, sSpiInformation.usTxPacketLength);
-
- sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
-
- DeassertWlanCS();
- }
- else {
- }
-
-out:
- regval = (1 << PIN16);
- putreg32(regval, KL_PORTA_ISFR);
+ goto out;
}
- return 0;
-}
+ //printf("\nSPIInterrupt was enabled!\n");
+
+ if (sSpiInformation.ulSpiState == eSPI_STATE_POWERUP)
+ {
+ /* This means IRQ line was low call a callback of HCI Layer to inform on event */
+
+ sSpiInformation.ulSpiState = eSPI_STATE_INITIALIZED;
+ }
+ else if (sSpiInformation.ulSpiState == eSPI_STATE_IDLE)
+ {
+ sSpiInformation.ulSpiState = eSPI_STATE_READ_IRQ;
+
+ /* IRQ line goes down - start reception */
+
+ AssertWlanCS();
+
+ //
+ // Wait for TX/RX Complete which will come as DMA interrupt
+ //
+
+ SpiReadHeader();
+
+ sSpiInformation.ulSpiState = eSPI_STATE_READ_EOT;
+
+ SSIContReadOperation();
+ }
+ else if (sSpiInformation.ulSpiState == eSPI_STATE_WRITE_IRQ)
+ {
+ SpiWriteDataSynchronous(sSpiInformation.pTxPacket, sSpiInformation.usTxPacketLength);
+
+ sSpiInformation.ulSpiState = eSPI_STATE_IDLE;
+
+ DeassertWlanCS();
+ }
+ else
+ {
+ }
+
+out:
+ regval = (1 << PIN16);
+ putreg32(regval, KL_PORTA_ISFR);
+ }
+
+ return 0;
+}
//*****************************************************************************
//
@@ -634,29 +635,28 @@ out:
//! \brief Cofigure the SSI
//
//*****************************************************************************
+
void SpiOpen(gcSpiHandleRx pfRxHandler)
{
- sSpiInformation.ulSpiState = eSPI_STATE_POWERUP;
-
- memset(spi_buffer, 0, sizeof(spi_buffer));
- memset(wlan_tx_buffer, 0, sizeof(spi_buffer));
-
- sSpiInformation.SPIRxHandler = pfRxHandler;
- sSpiInformation.usTxPacketLength = 0;
- sSpiInformation.pTxPacket = NULL;
- sSpiInformation.pRxPacket = (uint8_t *)spi_buffer;
- sSpiInformation.usRxPacketLength = 0;
- spi_buffer[CC3000_RX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER;
- wlan_tx_buffer[CC3000_TX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER;
-
- //
- // Enable interrupt on the GPIO pin of WLAN IRQ
- //
- tSLInformation.WlanInterruptEnable();
-
+ sSpiInformation.ulSpiState = eSPI_STATE_POWERUP;
+
+ memset(spi_buffer, 0, sizeof(spi_buffer));
+ memset(wlan_tx_buffer, 0, sizeof(spi_buffer));
+
+ sSpiInformation.SPIRxHandler = pfRxHandler;
+ sSpiInformation.usTxPacketLength = 0;
+ sSpiInformation.pTxPacket = NULL;
+ sSpiInformation.pRxPacket = (uint8_t *)spi_buffer;
+ sSpiInformation.usRxPacketLength = 0;
+ spi_buffer[CC3000_RX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER;
+ wlan_tx_buffer[CC3000_TX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER;
+
+ //
+ // Enable interrupt on the GPIO pin of WLAN IRQ
+ //
+ tSLInformation.WlanInterruptEnable();
}
-
//*****************************************************************************
//
//! SpiClose
@@ -668,16 +668,17 @@ void SpiOpen(gcSpiHandleRx pfRxHandler)
//! \brief Cofigure the SSI
//
//*****************************************************************************
+
void SpiClose(void)
{
- if (sSpiInformation.pRxPacket)
- {
- sSpiInformation.pRxPacket = 0;
- }
-
- //
- // Disable Interrupt in GPIOA module...
- //
- tSLInformation.WlanInterruptDisable();
-}
+ if (sSpiInformation.pRxPacket)
+ {
+ sSpiInformation.pRxPacket = 0;
+ }
+ //
+ // Disable Interrupt in GPIOA module...
+ //
+
+ tSLInformation.WlanInterruptDisable();
+}
diff --git a/nuttx/drivers/wireless/cc3000/wlan.c b/nuttx/drivers/wireless/cc3000/wlan.c
index 48735947b..38f8f2b70 100644
--- a/nuttx/drivers/wireless/cc3000/wlan.c
+++ b/nuttx/drivers/wireless/cc3000/wlan.c
@@ -40,13 +40,13 @@
//
//*****************************************************************************
#include <string.h>
-#include <nuttx/cc3000/wlan.h>
-#include <nuttx/cc3000/hci.h>
-#include <nuttx/cc3000/spi.h>
-#include <nuttx/cc3000/socket.h>
-#include <nuttx/cc3000/nvmem.h>
-#include <nuttx/cc3000/security.h>
-#include <nuttx/cc3000/evnt_handler.h>
+#include <nuttx/wireless/cc3000/wlan.h>
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/spi.h>
+#include <nuttx/wireless/cc3000/socket.h>
+#include <nuttx/wireless/cc3000/nvmem.h>
+#include <nuttx/wireless/cc3000/security.h>
+#include <nuttx/wireless/cc3000/evnt_handler.h>
volatile sSimplLinkInformation tSLInformation;
diff --git a/nuttx/include/nuttx/cc3000/cc3000_common.h b/nuttx/include/nuttx/wireless/cc3000/cc3000_common.h
index e4dfe2d9f..e4dfe2d9f 100644
--- a/nuttx/include/nuttx/cc3000/cc3000_common.h
+++ b/nuttx/include/nuttx/wireless/cc3000/cc3000_common.h
diff --git a/nuttx/include/nuttx/cc3000/evnt_handler.h b/nuttx/include/nuttx/wireless/cc3000/evnt_handler.h
index 00e709642..6496392ea 100644
--- a/nuttx/include/nuttx/cc3000/evnt_handler.h
+++ b/nuttx/include/nuttx/wireless/cc3000/evnt_handler.h
@@ -34,8 +34,9 @@
*****************************************************************************/
#ifndef __EVENT_HANDLER_H__
#define __EVENT_HANDLER_H__
-#include "hci.h"
-#include "socket.h"
+
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/socket.h>
//*****************************************************************************
//
diff --git a/nuttx/include/nuttx/cc3000/hci.h b/nuttx/include/nuttx/wireless/cc3000/hci.h
index 2894221b2..b3e361f12 100644
--- a/nuttx/include/nuttx/cc3000/hci.h
+++ b/nuttx/include/nuttx/wireless/cc3000/hci.h
@@ -35,7 +35,7 @@
#ifndef __HCI_H__
#define __HCI_H__
-#include "cc3000_common.h"
+#include <nuttx/wireless/cc3000/cc3000_common.h>
//*****************************************************************************
//
diff --git a/nuttx/include/nuttx/cc3000/host_driver_version.h b/nuttx/include/nuttx/wireless/cc3000/host_driver_version.h
index 8742818d7..8742818d7 100644
--- a/nuttx/include/nuttx/cc3000/host_driver_version.h
+++ b/nuttx/include/nuttx/wireless/cc3000/host_driver_version.h
diff --git a/nuttx/include/nuttx/cc3000/netapp.h b/nuttx/include/nuttx/wireless/cc3000/netapp.h
index fd38884b2..fd38884b2 100644
--- a/nuttx/include/nuttx/cc3000/netapp.h
+++ b/nuttx/include/nuttx/wireless/cc3000/netapp.h
diff --git a/nuttx/include/nuttx/cc3000/nvmem.h b/nuttx/include/nuttx/wireless/cc3000/nvmem.h
index 3f59d09d6..180344348 100644
--- a/nuttx/include/nuttx/cc3000/nvmem.h
+++ b/nuttx/include/nuttx/wireless/cc3000/nvmem.h
@@ -35,7 +35,7 @@
#ifndef __NVRAM_H__
#define __NVRAM_H__
-#include "cc3000_common.h"
+#include <nuttx/wireless/cc3000/cc3000_common.h>
//*****************************************************************************
diff --git a/nuttx/include/nuttx/cc3000/security.h b/nuttx/include/nuttx/wireless/cc3000/security.h
index a53b05616..2b81b536f 100644
--- a/nuttx/include/nuttx/cc3000/security.h
+++ b/nuttx/include/nuttx/wireless/cc3000/security.h
@@ -35,7 +35,7 @@
#ifndef __SECURITY__
#define __SECURITY__
-#include "nvmem.h"
+#include <nuttx/wireless/cc3000/nvmem.h>
//*****************************************************************************
//
diff --git a/nuttx/include/nuttx/cc3000/socket.h b/nuttx/include/nuttx/wireless/cc3000/socket.h
index 8933a0c5b..8933a0c5b 100644
--- a/nuttx/include/nuttx/cc3000/socket.h
+++ b/nuttx/include/nuttx/wireless/cc3000/socket.h
diff --git a/nuttx/include/nuttx/cc3000/spi.h b/nuttx/include/nuttx/wireless/cc3000/spi.h
index bf68b3eb1..bf68b3eb1 100644
--- a/nuttx/include/nuttx/cc3000/spi.h
+++ b/nuttx/include/nuttx/wireless/cc3000/spi.h
diff --git a/nuttx/include/nuttx/cc3000/spi_version.h b/nuttx/include/nuttx/wireless/cc3000/spi_version.h
index 44ff64397..44ff64397 100644
--- a/nuttx/include/nuttx/cc3000/spi_version.h
+++ b/nuttx/include/nuttx/wireless/cc3000/spi_version.h
diff --git a/nuttx/include/nuttx/cc3000/wlan.h b/nuttx/include/nuttx/wireless/cc3000/wlan.h
index f9e649f12..d910c4e9f 100644
--- a/nuttx/include/nuttx/cc3000/wlan.h
+++ b/nuttx/include/nuttx/wireless/cc3000/wlan.h
@@ -35,7 +35,7 @@
#ifndef __WLAN_H__
#define __WLAN_H__
-#include "cc3000_common.h"
+#include <nuttx/wireless/cc3000/cc3000_common.h>
//*****************************************************************************
//