summaryrefslogtreecommitdiff
path: root/nuttx/include/nuttx/wireless
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/include/nuttx/wireless')
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/cc3000_common.h359
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/evnt_handler.h167
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/hci.h328
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/host_driver_version.h55
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/netapp.h342
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/nvmem.h248
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/security.h126
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/socket.h664
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/spi.h45
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/spi_version.h53
-rw-r--r--nuttx/include/nuttx/wireless/cc3000/wlan.h517
11 files changed, 2904 insertions, 0 deletions
diff --git a/nuttx/include/nuttx/wireless/cc3000/cc3000_common.h b/nuttx/include/nuttx/wireless/cc3000/cc3000_common.h
new file mode 100644
index 000000000..e4dfe2d9f
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/cc3000_common.h
@@ -0,0 +1,359 @@
+/*****************************************************************************
+*
+* cc3000_common.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __COMMON_H__
+#define __COMMON_H__
+
+//******************************************************************************
+// Include files
+//******************************************************************************
+#include <sys/time.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <stdint.h>
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+//*****************************************************************************
+// ERROR CODES
+//*****************************************************************************
+#define ESUCCESS 0
+#define EFAIL -1
+#define EERROR EFAIL
+
+//*****************************************************************************
+// COMMON DEFINES
+//*****************************************************************************
+#define ERROR_SOCKET_INACTIVE -57
+
+#define WLAN_ENABLE (1)
+#define WLAN_DISABLE (0)
+
+#define MAC_ADDR_LEN (6)
+
+#define SP_PORTION_SIZE (32)
+
+/*Defines for minimal and maximal RX buffer size. This size includes the spi
+ header and hci header.
+ The maximal buffer size derives from:
+ MTU + HCI header + SPI header + sendto() agrs size
+ The minimum buffer size derives from:
+ HCI header + SPI header + max args size
+
+ This buffer is used for receiving events and data.
+ The packet can not be longer than MTU size and CC3000 does not support
+ fragmentation. Note that the same buffer is used for reception of the data
+ and events from CC3000. That is why the minimum is defined.
+ The calculation for the actual size of buffer for reception is:
+ Given the maximal data size MAX_DATA that is expected to be received by
+ application, the required buffer is:
+ Using recv() or recvfrom():
+
+ max(CC3000_MINIMAL_RX_SIZE, MAX_DATA + HEADERS_SIZE_DATA + fromlen
+ + ucArgsize + 1)
+
+ Using gethostbyname() with minimal buffer size will limit the host name
+ returned to 99 bytes only.
+ The 1 is used for the overrun detection
+
+ Buffer size increased to 130 following the add_profile() with WEP security
+ which requires TX buffer size of 130 bytes:
+ HEADERS_SIZE_EVNT + WLAN_ADD_PROFILE_WEP_PARAM_LEN + MAX SSID LEN + 4 * MAX KEY LEN = 130
+ MAX SSID LEN = 32
+ MAX SSID LEN = 13 (with add_profile only ascii key setting is supported,
+ therfore maximum key size is 13)
+*/
+
+#define CC3000_MINIMAL_RX_SIZE (130 + 1)
+#define CC3000_MAXIMAL_RX_SIZE (1519 + 1)
+
+/*Defines for minimal and maximal TX buffer size.
+ This buffer is used for sending events and data.
+ The packet can not be longer than MTU size and CC3000 does not support
+ fragmentation. Note that the same buffer is used for transmission of the data
+ and commands. That is why the minimum is defined.
+ The calculation for the actual size of buffer for transmission is:
+ Given the maximal data size MAX_DATA, the required buffer is:
+ Using Sendto():
+
+ max(CC3000_MINIMAL_TX_SIZE, MAX_DATA + SPI_HEADER_SIZE
+ + SOCKET_SENDTO_PARAMS_LEN + SIMPLE_LINK_HCI_DATA_HEADER_SIZE + 1)
+
+ Using Send():
+
+ max(CC3000_MINIMAL_TX_SIZE, MAX_DATA + SPI_HEADER_SIZE
+ + HCI_CMND_SEND_ARG_LENGTH + SIMPLE_LINK_HCI_DATA_HEADER_SIZE + 1)
+
+ The 1 is used for the overrun detection */
+
+#define CC3000_MINIMAL_TX_SIZE (130 + 1)
+#define CC3000_MAXIMAL_TX_SIZE (1519 + 1)
+
+//TX and RX buffer sizes, allow to receive and transmit maximum data at length 8.
+#ifdef CC3000_TINY_DRIVER
+#define TINY_CC3000_MAXIMAL_RX_SIZE 44
+#define TINY_CC3000_MAXIMAL_TX_SIZE 59
+#endif
+
+/*In order to determine your preferred buffer size,
+ change CC3000_MAXIMAL_RX_SIZE and CC3000_MAXIMAL_TX_SIZE to a value between
+ the minimal and maximal specified above.
+ Note that the buffers are allocated by SPI.
+ In case you change the size of those buffers, you might need also to change
+ the linker file, since for example on MSP430 FRAM devices the buffers are
+ allocated in the FRAM section that is allocated manually and not by IDE.
+*/
+
+#ifndef CC3000_TINY_DRIVER
+
+ #define CC3000_RX_BUFFER_SIZE (CC3000_MINIMAL_RX_SIZE)
+ #define CC3000_TX_BUFFER_SIZE (CC3000_MINIMAL_TX_SIZE)
+
+//if defined TINY DRIVER we use smaller RX and TX buffer in order to minimize RAM consumption
+#else
+ #define CC3000_RX_BUFFER_SIZE (TINY_CC3000_MAXIMAL_RX_SIZE)
+ #define CC3000_TX_BUFFER_SIZE (TINY_CC3000_MAXIMAL_TX_SIZE)
+
+#endif
+
+//*****************************************************************************
+// Compound Types
+//*****************************************************************************
+//acassis: comment to use system definition
+//typedef long time_t;
+//typedef unsigned long clock_t;
+//typedef long suseconds_t;
+
+//typedef struct timeval timeval;
+
+//struct timeval
+//{
+// time_t tv_sec; /* seconds */
+// suseconds_t tv_usec; /* microseconds */
+//};
+
+typedef char *(*tFWPatches)(unsigned long *usLength);
+
+typedef char *(*tDriverPatches)(unsigned long *usLength);
+
+typedef char *(*tBootLoaderPatches)(unsigned long *usLength);
+
+typedef void (*tWlanCB)(long event_type, char * data, uint8_t length );
+
+typedef long (*tWlanReadInteruptPin)(void);
+
+typedef void (*tWlanInterruptEnable)(void);
+
+typedef void (*tWlanInterruptDisable)(void);
+
+typedef void (*tWriteWlanPin)(uint8_t val);
+
+typedef struct
+{
+ uint16_t usRxEventOpcode;
+ uint16_t usEventOrDataReceived;
+ uint8_t *pucReceivedData;
+ uint8_t *pucTxCommandBuffer;
+
+ tFWPatches sFWPatches;
+ tDriverPatches sDriverPatches;
+ tBootLoaderPatches sBootLoaderPatches;
+ tWlanCB sWlanCB;
+ tWlanReadInteruptPin ReadWlanInterruptPin;
+ tWlanInterruptEnable WlanInterruptEnable;
+ tWlanInterruptDisable WlanInterruptDisable;
+ tWriteWlanPin WriteWlanPin;
+
+ signed long slTransmitDataError;
+ uint16_t usNumberOfFreeBuffers;
+ uint16_t usSlBufferLength;
+ uint16_t usBufferSize;
+ uint16_t usRxDataPending;
+
+ unsigned long NumberOfSentPackets;
+ unsigned long NumberOfReleasedPackets;
+
+ uint8_t InformHostOnTxComplete;
+}sSimplLinkInformation;
+
+extern volatile sSimplLinkInformation tSLInformation;
+
+
+//*****************************************************************************
+// Prototypes for the APIs.
+//*****************************************************************************
+
+
+
+//*****************************************************************************
+//
+//! SimpleLinkWaitEvent
+//!
+//! @param usOpcode command operation code
+//! @param pRetParams command return parameters
+//!
+//! @return none
+//!
+//! @brief Wait for event, pass it to the hci_event_handler and
+//! update the event opcode in a global variable.
+//
+//*****************************************************************************
+
+extern void SimpleLinkWaitEvent(uint16_t usOpcode, void *pRetParams);
+
+//*****************************************************************************
+//
+//! SimpleLinkWaitData
+//!
+//! @param pBuf data buffer
+//! @param from from information
+//! @param fromlen from information length
+//!
+//! @return none
+//!
+//! @brief Wait for data, pass it to the hci_event_handler
+//! and update in a global variable that there is
+//! data to read.
+//
+//*****************************************************************************
+
+extern void SimpleLinkWaitData(uint8_t *pBuf, uint8_t *from, uint8_t *fromlen);
+
+//*****************************************************************************
+//
+//! UINT32_TO_STREAM_f
+//!
+//! \param p pointer to the new stream
+//! \param u32 pointer to the 32 bit
+//!
+//! \return pointer to the new stream
+//!
+//! \brief This function is used for copying 32 bit to stream
+//! while converting to little endian format.
+//
+//*****************************************************************************
+
+extern uint8_t* UINT32_TO_STREAM_f (uint8_t *p, unsigned long u32);
+
+//*****************************************************************************
+//
+//! UINT16_TO_STREAM_f
+//!
+//! \param p pointer to the new stream
+//! \param u32 pointer to the 16 bit
+//!
+//! \return pointer to the new stream
+//!
+//! \brief This function is used for copying 16 bit to stream
+//! while converting to little endian format.
+//
+//*****************************************************************************
+
+extern uint8_t* UINT16_TO_STREAM_f (uint8_t *p, uint16_t u16);
+
+//*****************************************************************************
+//
+//! STREAM_TO_UINT16_f
+//!
+//! \param p pointer to the stream
+//! \param offset offset in the stream
+//!
+//! \return pointer to the new 16 bit
+//!
+//! \brief This function is used for copying received stream to
+//! 16 bit in little endian format.
+//
+//*****************************************************************************
+
+extern uint16_t STREAM_TO_UINT16_f(char* p, uint16_t offset);
+
+//*****************************************************************************
+//
+//! STREAM_TO_UINT32_f
+//!
+//! \param p pointer to the stream
+//! \param offset offset in the stream
+//!
+//! \return pointer to the new 32 bit
+//!
+//! \brief This function is used for copying received stream to
+//! 32 bit in little endian format.
+//
+//*****************************************************************************
+
+extern unsigned long STREAM_TO_UINT32_f(char* p, uint16_t offset);
+
+
+//*****************************************************************************
+// COMMON MACROs
+//*****************************************************************************
+
+
+//This macro is used for copying 8 bit to stream while converting to little endian format.
+#define UINT8_TO_STREAM(_p, _val) {*(_p)++ = (_val);}
+//This macro is used for copying 16 bit to stream while converting to little endian format.
+#define UINT16_TO_STREAM(_p, _u16) (UINT16_TO_STREAM_f(_p, _u16))
+//This macro is used for copying 32 bit to stream while converting to little endian format.
+#define UINT32_TO_STREAM(_p, _u32) (UINT32_TO_STREAM_f(_p, _u32))
+//This macro is used for copying a specified value length bits (l) to stream while converting to little endian format.
+#define ARRAY_TO_STREAM(p, a, l) {register int16_t _i; for (_i = 0; _i < l; _i++) *(p)++ = ((uint8_t *) a)[_i];}
+//This macro is used for copying received stream to 8 bit in little endian format.
+#define STREAM_TO_UINT8(_p, _offset, _u8) {_u8 = (uint8_t)(*(_p + _offset));}
+//This macro is used for copying received stream to 16 bit in little endian format.
+#define STREAM_TO_UINT16(_p, _offset, _u16) {_u16 = STREAM_TO_UINT16_f(_p, _offset);}
+//This macro is used for copying received stream to 32 bit in little endian format.
+#define STREAM_TO_UINT32(_p, _offset, _u32) {_u32 = STREAM_TO_UINT32_f(_p, _offset);}
+#define STREAM_TO_STREAM(p, a, l) {register int16_t _i; for (_i = 0; _i < l; _i++) *(a)++= ((uint8_t *) p)[_i];}
+
+
+
+
+//*****************************************************************************
+//
+// Mark the end of the C bindings section for C++ compilers.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif // __COMMON_H__
diff --git a/nuttx/include/nuttx/wireless/cc3000/evnt_handler.h b/nuttx/include/nuttx/wireless/cc3000/evnt_handler.h
new file mode 100644
index 000000000..6496392ea
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/evnt_handler.h
@@ -0,0 +1,167 @@
+/*****************************************************************************
+*
+* evnt_handler.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __EVENT_HANDLER_H__
+#define __EVENT_HANDLER_H__
+
+#include <nuttx/wireless/cc3000/hci.h>
+#include <nuttx/wireless/cc3000/socket.h>
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+//*****************************************************************************
+//
+// Prototypes for the APIs.
+//
+//*****************************************************************************
+
+//*****************************************************************************
+//
+//! hci_event_handler
+//!
+//! @param pRetParams incoming data buffer
+//! @param from from information (in case of data received)
+//! @param fromlen from information length (in case of data received)
+//!
+//! @return none
+//!
+//! @brief Parse the incoming events packets and issues corresponding
+//! event handler from global array of handlers pointers
+//
+//*****************************************************************************
+extern uint8_t *hci_event_handler(void *pRetParams, uint8_t *from, uint8_t *fromlen);
+
+//*****************************************************************************
+//
+//! hci_unsol_event_handler
+//!
+//! @param event_hdr event header
+//!
+//! @return 1 if event supported and handled
+//! 0 if event is not supported
+//!
+//! @brief Handle unsolicited events
+//
+//*****************************************************************************
+extern long hci_unsol_event_handler(char *event_hdr);
+
+//*****************************************************************************
+//
+//! hci_unsolicited_event_handler
+//!
+//! @param None
+//!
+//! @return ESUCCESS if successful, EFAIL if an error occurred
+//!
+//! @brief Parse the incoming unsolicited event packets and issues
+//! corresponding event handler.
+//
+//*****************************************************************************
+extern long hci_unsolicited_event_handler(void);
+
+#define M_BSD_RESP_PARAMS_OFFSET(hci_event_hdr)((char *)(hci_event_hdr) + HCI_EVENT_HEADER_SIZE)
+
+#define SOCKET_STATUS_ACTIVE 0
+#define SOCKET_STATUS_INACTIVE 1
+/* Init socket_active_status = 'all ones': init all sockets with SOCKET_STATUS_INACTIVE.
+ Will be changed by 'set_socket_active_status' upon 'connect' and 'accept' calls */
+#define SOCKET_STATUS_INIT_VAL 0xFFFF
+#define M_IS_VALID_SD(sd) ((0 <= (sd)) && ((sd) <= 7))
+#define M_IS_VALID_STATUS(status) (((status) == SOCKET_STATUS_ACTIVE)||((status) == SOCKET_STATUS_INACTIVE))
+
+extern unsigned long socket_active_status;
+
+extern void set_socket_active_status(long Sd, long Status);
+extern long get_socket_active_status(long Sd);
+
+typedef struct _bsd_accept_return_t
+{
+ long iSocketDescriptor;
+ long iStatus;
+ sockaddr tSocketAddress;
+
+} tBsdReturnParams;
+
+
+typedef struct _bsd_read_return_t
+{
+ long iSocketDescriptor;
+ long iNumberOfBytes;
+ unsigned long uiFlags;
+} tBsdReadReturnParams;
+
+#define BSD_RECV_FROM_FROMLEN_OFFSET (4)
+#define BSD_RECV_FROM_FROM_OFFSET (16)
+
+
+typedef struct _bsd_select_return_t
+{
+ long iStatus;
+ unsigned long uiRdfd;
+ unsigned long uiWrfd;
+ unsigned long uiExfd;
+} tBsdSelectRecvParams;
+
+
+typedef struct _bsd_getsockopt_return_t
+{
+ uint8_t ucOptValue[4];
+ char iStatus;
+} tBsdGetSockOptReturnParams;
+
+typedef struct _bsd_gethostbyname_return_t
+{
+ long retVal;
+ long outputAddress;
+} tBsdGethostbynameParams;
+
+//*****************************************************************************
+//
+// Mark the end of the C bindings section for C++ compilers.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif // __EVENT_HANDLER_H__
+
diff --git a/nuttx/include/nuttx/wireless/cc3000/hci.h b/nuttx/include/nuttx/wireless/cc3000/hci.h
new file mode 100644
index 000000000..b3e361f12
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/hci.h
@@ -0,0 +1,328 @@
+/*****************************************************************************
+*
+* hci.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __HCI_H__
+#define __HCI_H__
+
+#include <nuttx/wireless/cc3000/cc3000_common.h>
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#define SPI_HEADER_SIZE (5)
+#define SIMPLE_LINK_HCI_CMND_HEADER_SIZE (4)
+#define HEADERS_SIZE_CMD (SPI_HEADER_SIZE + SIMPLE_LINK_HCI_CMND_HEADER_SIZE)
+#define SIMPLE_LINK_HCI_DATA_CMND_HEADER_SIZE (5)
+#define SIMPLE_LINK_HCI_DATA_HEADER_SIZE (5)
+#define SIMPLE_LINK_HCI_PATCH_HEADER_SIZE (2)
+
+
+//*****************************************************************************
+//
+// Values that can be used as HCI Commands and HCI Packet header defines
+//
+//*****************************************************************************
+#define HCI_TYPE_CMND 0x1
+#define HCI_TYPE_DATA 0x2
+#define HCI_TYPE_PATCH 0x3
+#define HCI_TYPE_EVNT 0x4
+
+
+#define HCI_EVENT_PATCHES_DRV_REQ (1)
+#define HCI_EVENT_PATCHES_FW_REQ (2)
+#define HCI_EVENT_PATCHES_BOOTLOAD_REQ (3)
+
+
+#define HCI_CMND_WLAN_BASE (0x0000)
+#define HCI_CMND_WLAN_CONNECT 0x0001
+#define HCI_CMND_WLAN_DISCONNECT 0x0002
+#define HCI_CMND_WLAN_IOCTL_SET_SCANPARAM 0x0003
+#define HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY 0x0004
+#define HCI_CMND_WLAN_IOCTL_ADD_PROFILE 0x0005
+#define HCI_CMND_WLAN_IOCTL_DEL_PROFILE 0x0006
+#define HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS 0x0007
+#define HCI_CMND_EVENT_MASK 0x0008
+#define HCI_CMND_WLAN_IOCTL_STATUSGET 0x0009
+#define HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START 0x000A
+#define HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP 0x000B
+#define HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX 0x000C
+#define HCI_CMND_WLAN_CONFIGURE_PATCH 0x000D
+
+
+#define HCI_CMND_SOCKET_BASE 0x1000
+#define HCI_CMND_SOCKET 0x1001
+#define HCI_CMND_BIND 0x1002
+#define HCI_CMND_RECV 0x1004
+#define HCI_CMND_ACCEPT 0x1005
+#define HCI_CMND_LISTEN 0x1006
+#define HCI_CMND_CONNECT 0x1007
+#define HCI_CMND_BSD_SELECT 0x1008
+#define HCI_CMND_SETSOCKOPT 0x1009
+#define HCI_CMND_GETSOCKOPT 0x100A
+#define HCI_CMND_CLOSE_SOCKET 0x100B
+#define HCI_CMND_RECVFROM 0x100D
+#define HCI_CMND_GETHOSTNAME 0x1010
+#define HCI_CMND_MDNS_ADVERTISE 0x1011
+
+
+#define HCI_DATA_BASE 0x80
+
+#define HCI_CMND_SEND (0x01 + HCI_DATA_BASE)
+#define HCI_CMND_SENDTO (0x03 + HCI_DATA_BASE)
+#define HCI_DATA_BSD_RECVFROM (0x04 + HCI_DATA_BASE)
+#define HCI_DATA_BSD_RECV (0x05 + HCI_DATA_BASE)
+
+
+#define HCI_CMND_NVMEM_CBASE (0x0200)
+
+
+#define HCI_CMND_NVMEM_CREATE_ENTRY (0x0203)
+#define HCI_CMND_NVMEM_SWAP_ENTRY (0x0205)
+#define HCI_CMND_NVMEM_READ (0x0201)
+#define HCI_CMND_NVMEM_WRITE (0x0090)
+#define HCI_CMND_NVMEM_WRITE_PATCH (0x0204)
+#define HCI_CMND_READ_SP_VERSION (0x0207)
+
+#define HCI_CMND_READ_BUFFER_SIZE 0x400B
+#define HCI_CMND_SIMPLE_LINK_START 0x4000
+
+#define HCI_CMND_NETAPP_BASE 0x2000
+
+#define HCI_NETAPP_DHCP (0x0001 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_PING_SEND (0x0002 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_PING_REPORT (0x0003 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_PING_STOP (0x0004 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_IPCONFIG (0x0005 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_ARP_FLUSH (0x0006 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_SET_DEBUG_LEVEL (0x0008 + HCI_CMND_NETAPP_BASE)
+#define HCI_NETAPP_SET_TIMERS (0x0009 + HCI_CMND_NETAPP_BASE)
+
+
+
+
+
+
+//*****************************************************************************
+//
+// Values that can be used as HCI Events defines
+//
+//*****************************************************************************
+#define HCI_EVNT_WLAN_BASE 0x0000
+#define HCI_EVNT_WLAN_CONNECT 0x0001
+#define HCI_EVNT_WLAN_DISCONNECT \
+ 0x0002
+#define HCI_EVNT_WLAN_IOCTL_ADD_PROFILE \
+ 0x0005
+
+
+#define HCI_EVNT_SOCKET HCI_CMND_SOCKET
+#define HCI_EVNT_BIND HCI_CMND_BIND
+#define HCI_EVNT_RECV HCI_CMND_RECV
+#define HCI_EVNT_ACCEPT HCI_CMND_ACCEPT
+#define HCI_EVNT_LISTEN HCI_CMND_LISTEN
+#define HCI_EVNT_CONNECT HCI_CMND_CONNECT
+#define HCI_EVNT_SELECT HCI_CMND_BSD_SELECT
+#define HCI_EVNT_CLOSE_SOCKET HCI_CMND_CLOSE_SOCKET
+#define HCI_EVNT_RECVFROM HCI_CMND_RECVFROM
+#define HCI_EVNT_SETSOCKOPT HCI_CMND_SETSOCKOPT
+#define HCI_EVNT_GETSOCKOPT HCI_CMND_GETSOCKOPT
+#define HCI_EVNT_BSD_GETHOSTBYNAME HCI_CMND_GETHOSTNAME
+#define HCI_EVNT_MDNS_ADVERTISE HCI_CMND_MDNS_ADVERTISE
+
+#define HCI_EVNT_SEND 0x1003
+#define HCI_EVNT_WRITE 0x100E
+#define HCI_EVNT_SENDTO 0x100F
+
+#define HCI_EVNT_PATCHES_REQ 0x1000
+
+#define HCI_EVNT_UNSOL_BASE 0x4000
+
+#define HCI_EVNT_WLAN_UNSOL_BASE (0x8000)
+
+#define HCI_EVNT_WLAN_UNSOL_CONNECT (0x0001 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_UNSOL_DISCONNECT (0x0002 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_UNSOL_INIT (0x0004 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_TX_COMPLETE (0x0008 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_UNSOL_DHCP (0x0010 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_ASYNC_PING_REPORT (0x0040 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE (0x0080 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_WLAN_KEEPALIVE (0x0200 + HCI_EVNT_WLAN_UNSOL_BASE)
+#define HCI_EVNT_BSD_TCP_CLOSE_WAIT (0x0800 + HCI_EVNT_WLAN_UNSOL_BASE)
+
+#define HCI_EVNT_DATA_UNSOL_FREE_BUFF \
+ 0x4100
+
+#define HCI_EVNT_NVMEM_CREATE_ENTRY \
+ HCI_CMND_NVMEM_CREATE_ENTRY
+#define HCI_EVNT_NVMEM_SWAP_ENTRY HCI_CMND_NVMEM_SWAP_ENTRY
+
+#define HCI_EVNT_NVMEM_READ HCI_CMND_NVMEM_READ
+#define HCI_EVNT_NVMEM_WRITE (0x0202)
+
+#define HCI_EVNT_READ_SP_VERSION \
+ HCI_CMND_READ_SP_VERSION
+
+#define HCI_EVNT_INPROGRESS 0xFFFF
+
+
+#define HCI_DATA_RECVFROM 0x84
+#define HCI_DATA_RECV 0x85
+#define HCI_DATA_NVMEM 0x91
+
+#define HCI_EVENT_CC3000_CAN_SHUT_DOWN 0x99
+
+//*****************************************************************************
+//
+// Prototypes for the structures for APIs.
+//
+//*****************************************************************************
+
+#define HCI_DATA_HEADER_SIZE (5)
+#define HCI_EVENT_HEADER_SIZE (5)
+#define HCI_DATA_CMD_HEADER_SIZE (5)
+#define HCI_PATCH_HEADER_SIZE (6)
+
+#define HCI_PACKET_TYPE_OFFSET (0)
+#define HCI_PACKET_ARGSIZE_OFFSET (2)
+#define HCI_PACKET_LENGTH_OFFSET (3)
+
+
+#define HCI_EVENT_OPCODE_OFFSET (1)
+#define HCI_EVENT_LENGTH_OFFSET (3)
+#define HCI_EVENT_STATUS_OFFSET (4)
+#define HCI_DATA_LENGTH_OFFSET (3)
+
+
+
+
+//*****************************************************************************
+//
+// Prototypes for the APIs.
+//
+//*****************************************************************************
+
+//*****************************************************************************
+//
+//! hci_command_send
+//!
+//! @param usOpcode command operation code
+//! @param pucBuff pointer to the command's arguments buffer
+//! @param ucArgsLength length of the arguments
+//!
+//! @return none
+//!
+//! @brief Initiate an HCI command.
+//
+//*****************************************************************************
+extern uint16_t hci_command_send(uint16_t usOpcode,
+ uint8_t *ucArgs,
+ uint8_t ucArgsLength);
+
+
+//*****************************************************************************
+//
+//! hci_data_send
+//!
+//! @param usOpcode command operation code
+//! @param ucArgs pointer to the command's arguments buffer
+//! @param usArgsLength length of the arguments
+//! @param ucTail pointer to the data buffer
+//! @param usTailLength buffer length
+//!
+//! @return none
+//!
+//! @brief Initiate an HCI data write operation
+//
+//*****************************************************************************
+extern long hci_data_send(uint8_t ucOpcode,
+ uint8_t *ucArgs,
+ uint16_t usArgsLength,
+ uint16_t usDataLength,
+ const uint8_t *ucTail,
+ uint16_t usTailLength);
+
+
+//*****************************************************************************
+//
+//! hci_data_command_send
+//!
+//! @param usOpcode command operation code
+//! @param pucBuff pointer to the data buffer
+//! @param ucArgsLength arguments length
+//! @param ucDataLength data length
+//!
+//! @return none
+//!
+//! @brief Prepare HCI header and initiate an HCI data write operation
+//
+//*****************************************************************************
+extern void hci_data_command_send(uint16_t usOpcode, uint8_t *pucBuff,
+ uint8_t ucArgsLength, uint16_t ucDataLength);
+
+//*****************************************************************************
+//
+//! hci_patch_send
+//!
+//! @param usOpcode command operation code
+//! @param pucBuff pointer to the command's arguments buffer
+//! @param patch pointer to patch content buffer
+//! @param usDataLength data length
+//!
+//! @return none
+//!
+//! @brief Prepare HCI header and initiate an HCI patch write operation
+//
+//*****************************************************************************
+extern void hci_patch_send(uint8_t ucOpcode, uint8_t *pucBuff, char *patch, uint16_t usDataLength);
+
+
+
+//*****************************************************************************
+//
+// Mark the end of the C bindings section for C++ compilers.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif // __HCI_H__
diff --git a/nuttx/include/nuttx/wireless/cc3000/host_driver_version.h b/nuttx/include/nuttx/wireless/cc3000/host_driver_version.h
new file mode 100644
index 000000000..8742818d7
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/host_driver_version.h
@@ -0,0 +1,55 @@
+/*****************************************************************************
+*
+* host_driver_version.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __HOST_DRIVER_VERSION_H__
+#define __HOST_DRIVER_VERSION_H__
+
+#define DRIVER_VERSION_NUMBER 13
+
+
+
+#endif // __VERSION_H__
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/nuttx/include/nuttx/wireless/cc3000/netapp.h b/nuttx/include/nuttx/wireless/cc3000/netapp.h
new file mode 100644
index 000000000..fd38884b2
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/netapp.h
@@ -0,0 +1,342 @@
+/*****************************************************************************
+*
+* netapp.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __NETAPP_H__
+#define __NETAPP_H__
+
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+//*****************************************************************************
+//
+//! \addtogroup netapp_api
+//! @{
+//
+//*****************************************************************************
+
+typedef struct _netapp_dhcp_ret_args_t
+{
+ uint8_t aucIP[4];
+ uint8_t aucSubnetMask[4];
+ uint8_t aucDefaultGateway[4];
+ uint8_t aucDHCPServer[4];
+ uint8_t aucDNSServer[4];
+}tNetappDhcpParams;
+
+typedef struct _netapp_ipconfig_ret_args_t
+{
+ uint8_t aucIP[4];
+ uint8_t aucSubnetMask[4];
+ uint8_t aucDefaultGateway[4];
+ uint8_t aucDHCPServer[4];
+ uint8_t aucDNSServer[4];
+ uint8_t uaMacAddr[6];
+ uint8_t uaSSID[32];
+}tNetappIpconfigRetArgs;
+
+
+/*Ping send report parameters*/
+typedef struct _netapp_pingreport_args
+{
+ unsigned long packets_sent;
+ unsigned long packets_received;
+ unsigned long min_round_time;
+ unsigned long max_round_time;
+ unsigned long avg_round_time;
+} netapp_pingreport_args_t;
+
+
+//*****************************************************************************
+//
+//! netapp_config_mac_adrress
+//!
+//! @param mac device mac address, 6 bytes. Saved: yes
+//!
+//! @return return on success 0, otherwise error.
+//!
+//! @brief Configure device MAC address and store it in NVMEM.
+//! The value of the MAC address configured through the API will
+//! be stored in CC3000 non volatile memory, thus preserved
+//! over resets.
+//
+//*****************************************************************************
+extern long netapp_config_mac_adrress( uint8_t *mac );
+
+//*****************************************************************************
+//
+//! netapp_dhcp
+//!
+//! @param aucIP device mac address, 6 bytes. Saved: yes
+//! @param aucSubnetMask device mac address, 6 bytes. Saved: yes
+//! @param aucDefaultGateway device mac address, 6 bytes. Saved: yes
+//! @param aucDNSServer device mac address, 6 bytes. Saved: yes
+//!
+//! @return return on success 0, otherwise error.
+//!
+//! @brief netapp_dhcp is used to configure the network interface,
+//! static or dynamic (DHCP).\n In order to activate DHCP mode,
+//! aucIP, aucSubnetMask, aucDefaultGateway must be 0.
+//! The default mode of CC3000 is DHCP mode.
+//! Note that the configuration is saved in non volatile memory
+//! and thus preserved over resets.
+//!
+//! @note If the mode is altered a reset of CC3000 device is required
+//! in order to apply changes.\nAlso note that asynchronous event
+//! of DHCP_EVENT, which is generated when an IP address is
+//! allocated either by the DHCP server or due to static
+//! allocation is generated only upon a connection to the
+//! AP was established.
+//!
+//*****************************************************************************
+extern long netapp_dhcp(unsigned long *aucIP, unsigned long *aucSubnetMask,unsigned long *aucDefaultGateway, unsigned long *aucDNSServer);
+
+
+
+//*****************************************************************************
+//
+//! netapp_timeout_values
+//!
+//! @param aucDHCP DHCP lease time request, also impact
+//! the DHCP renew timeout. Range: [0-0xffffffff] seconds,
+//! 0 or 0xffffffff == infinity lease timeout.
+//! Resolution:10 seconds. Influence: only after
+//! reconnecting to the AP.
+//! Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 seconds.
+//! The parameter is saved into the CC3000 NVMEM.
+//! The default value on CC3000 is 14400 seconds.
+//!
+//! @param aucARP ARP refresh timeout, if ARP entry is not updated by
+//! incoming packet, the ARP entry will be deleted by
+//! the end of the timeout.
+//! Range: [0-0xffffffff] seconds, 0 == infinity ARP timeout
+//! Resolution: 10 seconds. Influence: on runtime.
+//! Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 seconds
+//! The parameter is saved into the CC3000 NVMEM.
+//! The default value on CC3000 is 3600 seconds.
+//!
+//! @param aucKeepalive Keepalive event sent by the end of keepalive timeout
+//! Range: [0-0xffffffff] seconds, 0 == infinity timeout
+//! Resolution: 10 seconds.
+//! Influence: on runtime.
+//! Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 sec
+//! The parameter is saved into the CC3000 NVMEM.
+//! The default value on CC3000 is 10 seconds.
+//!
+//! @param aucInactivity Socket inactivity timeout, socket timeout is
+//! refreshed by incoming or outgoing packet, by the
+//! end of the socket timeout the socket will be closed
+//! Range: [0-0xffffffff] sec, 0 == infinity timeout.
+//! Resolution: 10 seconds. Influence: on runtime.
+//! Minimal bound value: MIN_TIMER_VAL_SECONDS - 20 sec
+//! The parameter is saved into the CC3000 NVMEM.
+//! The default value on CC3000 is 60 seconds.
+//!
+//! @return return on success 0, otherwise error.
+//!
+//! @brief Set new timeout values. Function set new timeout values for:
+//! DHCP lease timeout, ARP refresh timeout, keepalive event
+//! timeout and socket inactivity timeout
+//!
+//! @note If a parameter set to non zero value which is less than 20s,
+//! it will be set automatically to 20s.
+//!
+//*****************************************************************************
+ #ifndef CC3000_TINY_DRIVER
+extern long netapp_timeout_values(unsigned long *aucDHCP, unsigned long *aucARP,unsigned long *aucKeepalive, unsigned long *aucInactivity);
+#endif
+
+//*****************************************************************************
+//
+//! netapp_ping_send
+//!
+//! @param ip destination IP address
+//! @param pingAttempts number of echo requests to send
+//! @param pingSize send buffer size which may be up to 1400 bytes
+//! @param pingTimeout Time to wait for a response,in milliseconds.
+//!
+//! @return return on success 0, otherwise error.
+//!
+//! @brief send ICMP ECHO_REQUEST to network hosts
+//!
+//! @note If an operation finished successfully asynchronous ping report
+//! event will be generated. The report structure is as defined
+//! by structure netapp_pingreport_args_t.
+//!
+//! @warning Calling this function while a previous Ping Requests are in
+//! progress will stop the previous ping request.
+//*****************************************************************************
+
+ #ifndef CC3000_TINY_DRIVER
+extern long netapp_ping_send(unsigned long *ip, unsigned long ulPingAttempts, unsigned long ulPingSize, unsigned long ulPingTimeout);
+#endif
+
+//*****************************************************************************
+//
+//! netapp_ping_stop
+//!
+//! @param none
+//!
+//! @return On success, zero is returned. On error, -1 is returned.
+//!
+//! @brief Stop any ping request.
+//!
+//!
+//*****************************************************************************
+
+#ifndef CC3000_TINY_DRIVER
+extern long netapp_ping_stop();
+#endif
+//*****************************************************************************
+//
+//! netapp_ping_report
+//!
+//! @param none
+//!
+//! @return none
+//!
+//! @brief Request for ping status. This API triggers the CC3000 to send
+//! asynchronous events: HCI_EVNT_WLAN_ASYNC_PING_REPORT.
+//! This event will carry the report structure:
+//! netapp_pingreport_args_t. This structure is filled in with ping
+//! results up till point of triggering API.
+//! netapp_pingreport_args_t:\n packets_sent - echo sent,
+//! packets_received - echo reply, min_round_time - minimum
+//! round time, max_round_time - max round time,
+//! avg_round_time - average round time
+//!
+//! @note When a ping operation is not active, the returned structure
+//! fields are 0.
+//!
+//*****************************************************************************
+#ifndef CC3000_TINY_DRIVER
+extern void netapp_ping_report();
+#endif
+
+
+//*****************************************************************************
+//
+//! netapp_ipconfig
+//!
+//! @param[out] ipconfig This argument is a pointer to a
+//! tNetappIpconfigRetArgs structure. This structure is
+//! filled in with the network interface configuration.
+//! tNetappIpconfigRetArgs:\n aucIP - ip address,
+//! aucSubnetMask - mask, aucDefaultGateway - default
+//! gateway address, aucDHCPServer - dhcp server address
+//! aucDNSServer - dns server address, uaMacAddr - mac
+//! address, uaSSID - connected AP ssid
+//!
+//! @return none
+//!
+//! @brief Obtain the CC3000 Network interface information.
+//! Note that the information is available only after the WLAN
+//! connection was established. Calling this function before
+//! associated, will cause non-defined values to be returned.
+//!
+//! @note The function is useful for figuring out the IP Configuration of
+//! the device when DHCP is used and for figuring out the SSID of
+//! the Wireless network the device is associated with.
+//!
+//*****************************************************************************
+
+extern void netapp_ipconfig( tNetappIpconfigRetArgs * ipconfig );
+
+
+//*****************************************************************************
+//
+//! netapp_arp_flush
+//!
+//! @param none
+//!
+//! @return none
+//!
+//! @brief Flushes ARP table
+//!
+//*****************************************************************************
+
+#ifndef CC3000_TINY_DRIVER
+extern long netapp_arp_flush();
+#endif
+
+
+//*****************************************************************************
+//
+//! netapp_set_debug_level
+//!
+//! @param[in] level debug level. Bitwise [0-8],
+//! 0(disable)or 1(enable).\n Bitwise map: 0 - Critical
+//! message, 1 information message, 2 - core messages, 3 -
+//! HCI messages, 4 - Network stack messages, 5 - wlan
+//! messages, 6 - wlan driver messages, 7 - epprom messages,
+//! 8 - general messages. Default: 0x13f. Saved: no
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief Debug messages sent via the UART debug channel, this function
+//! enable/disable the debug level
+//!
+//*****************************************************************************
+
+
+#ifndef CC3000_TINY_DRIVER
+long netapp_set_debug_level(unsigned long ulLevel);
+#endif
+//*****************************************************************************
+//
+// Close the Doxygen group.
+//! @}
+//
+//*****************************************************************************
+
+
+
+//*****************************************************************************
+//
+// Mark the end of the C bindings section for C++ compilers.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif // __NETAPP_H__
+
diff --git a/nuttx/include/nuttx/wireless/cc3000/nvmem.h b/nuttx/include/nuttx/wireless/cc3000/nvmem.h
new file mode 100644
index 000000000..180344348
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/nvmem.h
@@ -0,0 +1,248 @@
+/*****************************************************************************
+*
+* nvmem.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __NVRAM_H__
+#define __NVRAM_H__
+
+#include <nuttx/wireless/cc3000/cc3000_common.h>
+
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+//*****************************************************************************
+//
+//! \addtogroup nvmem_api
+//! @{
+//
+//*****************************************************************************
+
+/****************************************************************************
+**
+** Definitions for File IDs
+**
+****************************************************************************/
+/* NVMEM file ID - system files*/
+#define NVMEM_NVS_FILEID (0)
+#define NVMEM_NVS_SHADOW_FILEID (1)
+#define NVMEM_WLAN_CONFIG_FILEID (2)
+#define NVMEM_WLAN_CONFIG_SHADOW_FILEID (3)
+#define NVMEM_WLAN_DRIVER_SP_FILEID (4)
+#define NVMEM_WLAN_FW_SP_FILEID (5)
+#define NVMEM_MAC_FILEID (6)
+#define NVMEM_FRONTEND_VARS_FILEID (7)
+#define NVMEM_IP_CONFIG_FILEID (8)
+#define NVMEM_IP_CONFIG_SHADOW_FILEID (9)
+#define NVMEM_BOOTLOADER_SP_FILEID (10)
+#define NVMEM_RM_FILEID (11)
+
+/* NVMEM file ID - user files*/
+#define NVMEM_AES128_KEY_FILEID (12)
+#define NVMEM_SHARED_MEM_FILEID (13)
+
+/* max entry in order to invalid nvmem */
+#define NVMEM_MAX_ENTRY (16)
+
+
+//*****************************************************************************
+//
+//! nvmem_read
+//!
+//! @param ulFileId nvmem file id:\n
+//! NVMEM_NVS_FILEID, NVMEM_NVS_SHADOW_FILEID,
+//! NVMEM_WLAN_CONFIG_FILEID, NVMEM_WLAN_CONFIG_SHADOW_FILEID,
+//! NVMEM_WLAN_DRIVER_SP_FILEID, NVMEM_WLAN_FW_SP_FILEID,
+//! NVMEM_MAC_FILEID, NVMEM_FRONTEND_VARS_FILEID,
+//! NVMEM_IP_CONFIG_FILEID, NVMEM_IP_CONFIG_SHADOW_FILEID,
+//! NVMEM_BOOTLOADER_SP_FILEID, NVMEM_RM_FILEID,
+//! and user files 12-15.
+//! @param ulLength number of bytes to read
+//! @param ulOffset ulOffset in file from where to read
+//! @param buff output buffer pointer
+//!
+//! @return number of bytes read, otherwise error.
+//!
+//! @brief Reads data from the file referred by the ulFileId parameter.
+//! Reads data from file ulOffset till length. Err if the file can't
+//! be used, is invalid, or if the read is out of bounds.
+//!
+//*****************************************************************************
+
+extern signed long nvmem_read(unsigned long file_id, unsigned long length, unsigned long offset, uint8_t *buff);
+
+//*****************************************************************************
+//
+//! nvmem_write
+//!
+//! @param ulFileId nvmem file id:\n
+//! NVMEM_WLAN_DRIVER_SP_FILEID, NVMEM_WLAN_FW_SP_FILEID,
+//! NVMEM_MAC_FILEID, NVMEM_BOOTLOADER_SP_FILEID,
+//! and user files 12-15.
+//! @param ulLength number of bytes to write
+//! @param ulEntryOffset offset in file to start write operation from
+//! @param buff data to write
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief Write data to nvmem.
+//! writes data to file referred by the ulFileId parameter.
+//! Writes data to file ulOffset till ulLength.The file id will be
+//! marked invalid till the write is done. The file entry doesn't
+//! need to be valid - only allocated.
+//!
+//*****************************************************************************
+
+extern signed long nvmem_write(unsigned long ulFileId, unsigned long ulLength, unsigned long ulEntryOffset, uint8_t *buff);
+
+
+//*****************************************************************************
+//
+//! nvmem_set_mac_address
+//!
+//! @param mac mac address to be set
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief Write MAC address to EEPROM.
+//! mac address as appears over the air (OUI first)
+//!
+//*****************************************************************************
+extern uint8_t nvmem_set_mac_address(uint8_t *mac);
+
+
+//*****************************************************************************
+//
+//! nvmem_get_mac_address
+//!
+//! @param[out] mac mac address
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief Read MAC address from EEPROM.
+//! mac address as appears over the air (OUI first)
+//!
+//*****************************************************************************
+extern uint8_t nvmem_get_mac_address(uint8_t *mac);
+
+
+//*****************************************************************************
+//
+//! nvmem_write_patch
+//!
+//! @param ulFileId nvmem file id:\n
+//! NVMEM_WLAN_DRIVER_SP_FILEID, NVMEM_WLAN_FW_SP_FILEID,
+//! @param spLength number of bytes to write
+//! @param spData SP data to write
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief program a patch to a specific file ID.
+//! The SP data is assumed to be organized in 2-dimensional.
+//! Each line is SP_PORTION_SIZE bytes long. Actual programming is
+//! applied in SP_PORTION_SIZE bytes portions.
+//!
+//*****************************************************************************
+extern uint8_t nvmem_write_patch(unsigned long ulFileId, unsigned long spLength, const uint8_t *spData);
+
+
+//*****************************************************************************
+//
+//! nvmem_read_sp_version
+//!
+//! @param[out] patchVer first number indicates package ID and the second
+//! number indicates package build number
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief Read patch version. read package version (WiFi FW patch,
+//! driver-supplicant-NS patch, bootloader patch)
+//!
+//*****************************************************************************
+#ifndef CC3000_TINY_DRIVER
+extern uint8_t nvmem_read_sp_version(uint8_t* patchVer);
+#endif
+
+//*****************************************************************************
+//
+//! nvmem_create_entry
+//!
+//! @param ulFileId nvmem file Id:\n
+//! * NVMEM_AES128_KEY_FILEID: 12
+//! * NVMEM_SHARED_MEM_FILEID: 13
+//! * and fileIDs 14 and 15
+//! @param ulNewLen entry ulLength
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief Create new file entry and allocate space on the NVMEM.
+//! Applies only to user files.
+//! Modify the size of file.
+//! If the entry is unallocated - allocate it to size
+//! ulNewLen (marked invalid).
+//! If it is allocated then deallocate it first.
+//! To just mark the file as invalid without resizing -
+//! set ulNewLen=0.
+//!
+//*****************************************************************************
+extern signed long nvmem_create_entry(unsigned long file_id, unsigned long newlen);
+
+
+//*****************************************************************************
+//
+// Mark the end of the C bindings section for C++ compilers.
+//
+//*****************************************************************************
+
+
+//*****************************************************************************
+//
+// Close the Doxygen group.
+//! @}
+//
+//*****************************************************************************
+
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif // __NVRAM_H__
diff --git a/nuttx/include/nuttx/wireless/cc3000/security.h b/nuttx/include/nuttx/wireless/cc3000/security.h
new file mode 100644
index 000000000..2b81b536f
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/security.h
@@ -0,0 +1,126 @@
+/*****************************************************************************
+*
+* security.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __SECURITY__
+#define __SECURITY__
+
+#include <nuttx/wireless/cc3000/nvmem.h>
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+#define AES128_KEY_SIZE 16
+
+#ifndef CC3000_UNENCRYPTED_SMART_CONFIG
+
+
+//*****************************************************************************
+//
+//! aes_encrypt
+//!
+//! @param[in] key AES128 key of size 16 bytes
+//! @param[in\out] state 16 bytes of plain text and cipher text
+//!
+//! @return none
+//!
+//! @brief AES128 encryption:
+//! Given AES128 key and 16 bytes plain text, cipher text of 16 bytes
+//! is computed. The AES implementation is in mode ECB (Electronic
+//! Code Book).
+//!
+//!
+//*****************************************************************************
+extern void aes_encrypt(uint8_t *state, uint8_t *key);
+
+//*****************************************************************************
+//
+//! aes_decrypt
+//!
+//! @param[in] key AES128 key of size 16 bytes
+//! @param[in\out] state 16 bytes of cipher text and plain text
+//!
+//! @return none
+//!
+//! @brief AES128 decryption:
+//! Given AES128 key and 16 bytes cipher text, plain text of 16 bytes
+//! is computed The AES implementation is in mode ECB
+//! (Electronic Code Book).
+//!
+//!
+//*****************************************************************************
+extern void aes_decrypt(uint8_t *state, uint8_t *key);
+
+
+//*****************************************************************************
+//
+//! aes_read_key
+//!
+//! @param[out] key AES128 key of size 16 bytes
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief Reads AES128 key from EEPROM
+//! Reads the AES128 key from fileID #12 in EEPROM
+//! returns an error if the key does not exist.
+//!
+//!
+//*****************************************************************************
+extern signed long aes_read_key(uint8_t *key);
+
+//*****************************************************************************
+//
+//! aes_write_key
+//!
+//! @param[out] key AES128 key of size 16 bytes
+//!
+//! @return on success 0, error otherwise.
+//!
+//! @brief writes AES128 key from EEPROM
+//! Writes the AES128 key to fileID #12 in EEPROM
+//!
+//!
+//*****************************************************************************
+extern signed long aes_write_key(uint8_t *key);
+
+#endif //CC3000_UNENCRYPTED_SMART_CONFIG
+
+#endif
diff --git a/nuttx/include/nuttx/wireless/cc3000/socket.h b/nuttx/include/nuttx/wireless/cc3000/socket.h
new file mode 100644
index 000000000..8933a0c5b
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/socket.h
@@ -0,0 +1,664 @@
+/*****************************************************************************
+*
+* socket.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __SOCKET_H__
+#define __SOCKET_H__
+
+
+//*****************************************************************************
+//
+//! \addtogroup socket_api
+//! @{
+//
+//*****************************************************************************
+
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define HOSTNAME_MAX_LENGTH (230) // 230 bytes + header shouldn't exceed 8 bit value
+
+//--------- Address Families --------
+
+#define AF_INET 2
+#define AF_INET6 23
+
+//------------ Socket Types ------------
+
+#define SOCK_STREAM 1
+#define SOCK_DGRAM 2
+#define SOCK_RAW 3 // Raw sockets allow new IPv4 protocols to be implemented in user space. A raw socket receives or sends the raw datagram not including link level headers
+#define SOCK_RDM 4
+#define SOCK_SEQPACKET 5
+
+//----------- Socket Protocol ----------
+
+#define IPPROTO_IP 0 // dummy for IP
+#define IPPROTO_ICMP 1 // control message protocol
+#define IPPROTO_IPV4 IPPROTO_IP // IP inside IP
+#define IPPROTO_TCP 6 // tcp
+#define IPPROTO_UDP 17 // user datagram protocol
+#define IPPROTO_IPV6 41 // IPv6 in IPv6
+#define IPPROTO_NONE 59 // No next header
+#define IPPROTO_RAW 255 // raw IP packet
+#define IPPROTO_MAX 256
+
+//----------- Socket retunr codes -----------
+
+#define SOC_ERROR (-1) // error
+#define SOC_IN_PROGRESS (-2) // socket in progress
+
+//----------- Socket Options -----------
+#define SOL_SOCKET 0xffff // socket level
+#define SOCKOPT_RECV_NONBLOCK 0 // recv non block mode, set SOCK_ON or SOCK_OFF (default block mode)
+#define SOCKOPT_RECV_TIMEOUT 1 // optname to configure recv and recvfromtimeout
+#define SOCKOPT_ACCEPT_NONBLOCK 2 // accept non block mode, set SOCK_ON or SOCK_OFF (default block mode)
+#define SOCK_ON 0 // socket non-blocking mode is enabled
+#define SOCK_OFF 1 // socket blocking mode is enabled
+
+#define TCP_NODELAY 0x0001
+#define TCP_BSDURGENT 0x7000
+
+#define MAX_PACKET_SIZE 1500
+#define MAX_LISTEN_QUEUE 4
+
+#define IOCTL_SOCKET_EVENTMASK
+
+#define ENOBUFS 55 // No buffer space available
+
+#define __FD_SETSIZE 32
+
+#define ASIC_ADDR_LEN 8
+
+#define NO_QUERY_RECIVED -3
+
+
+typedef struct _in_addr_t
+{
+ unsigned long s_addr; // load with inet_aton()
+} in_addr;
+
+typedef struct _sockaddr_t
+{
+ uint16_t sa_family;
+ uint8_t sa_data[14];
+} sockaddr;
+
+typedef struct _sockaddr_in_t
+{
+ int16_t sin_family; // e.g. AF_INET
+ uint16_t sin_port; // e.g. htons(3490)
+ in_addr sin_addr; // see struct in_addr, below
+ char sin_zero[8]; // zero this if you want to
+} sockaddr_in;
+
+//typedef unsigned long socklen_t; //acassis: conflict with previous declaration on nuttx
+
+// The fd_set member is required to be an array of longs.
+typedef long int __fd_mask;
+
+// It's easier to assume 8-bit bytes than to get CHAR_BIT.
+#define __NFDBITS (8 * sizeof (__fd_mask))
+#define __FDELT(d) ((d) / __NFDBITS)
+#define __FDMASK(d) ((__fd_mask) 1 << ((d) % __NFDBITS))
+
+// fd_set for select and pselect.
+typedef struct
+{
+ __fd_mask fds_bits[__FD_SETSIZE / __NFDBITS];
+#define __FDS_BITS(set) ((set)->fds_bits)
+} TICC3000fd_set;
+
+// We don't use `memset' because this would require a prototype and
+// the array isn't too big.
+#define __FD_ZERO(set) \
+ do { \
+ unsigned int __i; \
+ TICC3000fd_set *__arr = (set); \
+ for (__i = 0; __i < sizeof (TICC3000fd_set) / sizeof (__fd_mask); ++__i) \
+ __FDS_BITS (__arr)[__i] = 0; \
+ } while (0)
+#define __FD_SET(d, set) (__FDS_BITS (set)[__FDELT (d)] |= __FDMASK (d))
+#define __FD_CLR(d, set) (__FDS_BITS (set)[__FDELT (d)] &= ~__FDMASK (d))
+#define __FD_ISSET(d, set) (__FDS_BITS (set)[__FDELT (d)] & __FDMASK (d))
+
+// Access macros for 'TICC3000fd_set'.
+#define FD_SET(fd, fdsetp) __FD_SET (fd, fdsetp)
+#define FD_CLR(fd, fdsetp) __FD_CLR (fd, fdsetp)
+#define FD_ISSET(fd, fdsetp) __FD_ISSET (fd, fdsetp)
+#define FD_ZERO(fdsetp) __FD_ZERO (fdsetp)
+
+//Use in case of Big Endian only
+
+#define htonl(A) ((((unsigned long)(A) & 0xff000000) >> 24) | \
+ (((unsigned long)(A) & 0x00ff0000) >> 8) | \
+ (((unsigned long)(A) & 0x0000ff00) << 8) | \
+ (((unsigned long)(A) & 0x000000ff) << 24))
+
+#define ntohl htonl
+
+//Use in case of Big Endian only
+#define htons(A) ((((unsigned long)(A) & 0xff00) >> 8) | \
+ (((unsigned long)(A) & 0x00ff) << 8))
+
+
+#define ntohs htons
+
+// mDNS port - 5353 mDNS multicast address - 224.0.0.251
+#define SET_mDNS_ADD(sockaddr) sockaddr.sa_data[0] = 0x14; \
+ sockaddr.sa_data[1] = 0xe9; \
+ sockaddr.sa_data[2] = 0xe0; \
+ sockaddr.sa_data[3] = 0x0; \
+ sockaddr.sa_data[4] = 0x0; \
+ sockaddr.sa_data[5] = 0xfb;
+
+
+//*****************************************************************************
+//
+// Prototypes for the APIs.
+//
+//*****************************************************************************
+
+//*****************************************************************************
+//
+//! socket
+//!
+//! @param domain selects the protocol family which will be used for
+//! communication. On this version only AF_INET is supported
+//! @param type specifies the communication semantics. On this version
+//! only SOCK_STREAM, SOCK_DGRAM, SOCK_RAW are supported
+//! @param protocol specifies a particular protocol to be used with the
+//! socket IPPROTO_TCP, IPPROTO_UDP or IPPROTO_RAW are
+//! supported.
+//!
+//! @return On success, socket handle that is used for consequent socket
+//! operations. On error, -1 is returned.
+//!
+//! @brief create an endpoint for communication
+//! The socket function creates a socket that is bound to a specific
+//! transport service provider. This function is called by the
+//! application layer to obtain a socket handle.
+//
+//*****************************************************************************
+extern int socket(long domain, long type, long protocol);
+
+//*****************************************************************************
+//
+//! closesocket
+//!
+//! @param sd socket handle.
+//!
+//! @return On success, zero is returned. On error, -1 is returned.
+//!
+//! @brief The socket function closes a created socket.
+//
+//*****************************************************************************
+extern long closesocket(long sd);
+
+//*****************************************************************************
+//
+//! accept
+//!
+//! @param[in] sd socket descriptor (handle)
+//! @param[out] addr the argument addr is a pointer to a sockaddr structure
+//! This structure is filled in with the address of the
+//! peer socket, as known to the communications layer.
+//! determined. The exact format of the address returned
+//! addr is by the socket's address sockaddr.
+//! On this version only AF_INET is supported.
+//! This argument returns in network order.
+//! @param[out] addrlen the addrlen argument is a value-result argument:
+//! it should initially contain the size of the structure
+//! pointed to by addr.
+//!
+//! @return For socket in blocking mode:
+//! On success, socket handle. on failure negative
+//! For socket in non-blocking mode:
+//! - On connection establishment, socket handle
+//! - On connection pending, SOC_IN_PROGRESS (-2)
+//! - On failure, SOC_ERROR (-1)
+//!
+//! @brief accept a connection on a socket:
+//! This function is used with connection-based socket types
+//! (SOCK_STREAM). It extracts the first connection request on the
+//! queue of pending connections, creates a new connected socket, and
+//! returns a new file descriptor referring to that socket.
+//! The newly created socket is not in the listening state.
+//! The original socket sd is unaffected by this call.
+//! The argument sd is a socket that has been created with socket(),
+//! bound to a local address with bind(), and is listening for
+//! connections after a listen(). The argument addr is a pointer
+//! to a sockaddr structure. This structure is filled in with the
+//! address of the peer socket, as known to the communications layer.
+//! The exact format of the address returned addr is determined by the
+//! socket's address family. The addrlen argument is a value-result
+//! argument: it should initially contain the size of the structure
+//! pointed to by addr, on return it will contain the actual
+//! length (in bytes) of the address returned.
+//!
+//! @sa socket ; bind ; listen
+//
+//*****************************************************************************
+extern long accept(long sd, sockaddr *addr, socklen_t *addrlen);
+
+//*****************************************************************************
+//
+//! bind
+//!
+//! @param[in] sd socket descriptor (handle)
+//! @param[out] addr specifies the destination address. On this version
+//! only AF_INET is supported.
+//! @param[out] addrlen contains the size of the structure pointed to by addr.
+//!
+//! @return On success, zero is returned. On error, -1 is returned.
+//!
+//! @brief assign a name to a socket
+//! This function gives the socket the local address addr.
+//! addr is addrlen bytes long. Traditionally, this is called when a
+//! socket is created with socket, it exists in a name space (address
+//! family) but has no name assigned.
+//! It is necessary to assign a local address before a SOCK_STREAM
+//! socket may receive connections.
+//!
+//! @sa socket ; accept ; listen
+//
+//*****************************************************************************
+extern long bind(long sd, const sockaddr *addr, long addrlen);
+
+//*****************************************************************************
+//
+//! listen
+//!
+//! @param[in] sd socket descriptor (handle)
+//! @param[in] backlog specifies the listen queue depth. On this version
+//! backlog is not supported.
+//! @return On success, zero is returned. On error, -1 is returned.
+//!
+//! @brief listen for connections on a socket
+//! The willingness to accept incoming connections and a queue
+//! limit for incoming connections are specified with listen(),
+//! and then the connections are accepted with accept.
+//! The listen() call applies only to sockets of type SOCK_STREAM
+//! The backlog parameter defines the maximum length the queue of
+//! pending connections may grow to.
+//!
+//! @sa socket ; accept ; bind
+//!
+//! @note On this version, backlog is not supported
+//
+//*****************************************************************************
+extern long listen(long sd, long backlog);
+
+//*****************************************************************************
+//
+//! gethostbyname
+//!
+//! @param[in] hostname host name
+//! @param[in] usNameLen name length
+//! @param[out] out_ip_addr This parameter is filled in with host IP address.
+//! In case that host name is not resolved,
+//! out_ip_addr is zero.
+//! @return On success, positive is returned. On error, negative is returned
+//!
+//! @brief Get host IP by name. Obtain the IP Address of machine on network,
+//! by its name.
+//!
+//! @note On this version, only blocking mode is supported. Also note that
+//! the function requires DNS server to be configured prior to its usage.
+//
+//*****************************************************************************
+#ifndef CC3000_TINY_DRIVER
+extern int gethostbyname(char * hostname, uint16_t usNameLen, unsigned long* out_ip_addr);
+#endif
+
+
+//*****************************************************************************
+//
+//! connect
+//!
+//! @param[in] sd socket descriptor (handle)
+//! @param[in] addr specifies the destination addr. On this version
+//! only AF_INET is supported.
+//! @param[out] addrlen contains the size of the structure pointed to by addr
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief initiate a connection on a socket
+//! Function connects the socket referred to by the socket descriptor
+//! sd, to the address specified by addr. The addrlen argument
+//! specifies the size of addr. The format of the address in addr is
+//! determined by the address space of the socket. If it is of type
+//! SOCK_DGRAM, this call specifies the peer with which the socket is
+//! to be associated; this address is that to which datagrams are to be
+//! sent, and the only address from which datagrams are to be received.
+//! If the socket is of type SOCK_STREAM, this call attempts to make a
+//! connection to another socket. The other socket is specified by
+//! address, which is an address in the communications space of the
+//! socket. Note that the function implements only blocking behavior
+//! thus the caller will be waiting either for the connection
+//! establishment or for the connection establishment failure.
+//!
+//! @sa socket
+//
+//*****************************************************************************
+extern long connect(long sd, const sockaddr *addr, long addrlen);
+
+//*****************************************************************************
+//
+//! select
+//!
+//! @param[in] nfds the highest-numbered file descriptor in any of the
+//! three sets, plus 1.
+//! @param[out] writesds socket descriptors list for write monitoring
+//! @param[out] readsds socket descriptors list for read monitoring
+//! @param[out] exceptsds socket descriptors list for exception monitoring
+//! @param[in] timeout is an upper bound on the amount of time elapsed
+//! before select() returns. Null means infinity
+//! timeout. The minimum timeout is 5 milliseconds,
+//! less than 5 milliseconds will be set
+//! automatically to 5 milliseconds.
+//! @return On success, select() returns the number of file descriptors
+//! contained in the three returned descriptor sets (that is, the
+//! total number of bits that are set in readfds, writefds,
+//! exceptfds) which may be zero if the timeout expires before
+//! anything interesting happens.
+//! On error, -1 is returned.
+//! *readsds - return the sockets on which Read request will
+//! return without delay with valid data.
+//! *writesds - return the sockets on which Write request
+//! will return without delay.
+//! *exceptsds - return the sockets which closed recently.
+//!
+//! @brief Monitor socket activity
+//! Select allow a program to monitor multiple file descriptors,
+//! waiting until one or more of the file descriptors become
+//! "ready" for some class of I/O operation
+//!
+//! @Note If the timeout value set to less than 5ms it will automatically set
+//! to 5ms to prevent overload of the system
+//!
+//! @sa socket
+//
+//*****************************************************************************
+extern int select(long nfds, TICC3000fd_set *readsds, TICC3000fd_set *writesds,
+ TICC3000fd_set *exceptsds, struct timeval *timeout);
+
+//*****************************************************************************
+//
+//! setsockopt
+//!
+//! @param[in] sd socket handle
+//! @param[in] level defines the protocol level for this option
+//! @param[in] optname defines the option name to Interrogate
+//! @param[in] optval specifies a value for the option
+//! @param[in] optlen specifies the length of the option value
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief set socket options
+//! This function manipulate the options associated with a socket.
+//! Options may exist at multiple protocol levels; they are always
+//! present at the uppermost socket level.
+//! When manipulating socket options the level at which the option
+//! resides and the name of the option must be specified.
+//! To manipulate options at the socket level, level is specified as
+//! SOL_SOCKET. To manipulate options at any other level the protocol
+//! number of the appropriate protocol controlling the option is
+//! supplied. For example, to indicate that an option is to be
+//! interpreted by the TCP protocol, level should be set to the
+//! protocol number of TCP;
+//! The parameters optval and optlen are used to access optval -
+//! use for setsockopt(). For getsockopt() they identify a buffer
+//! in which the value for the requested option(s) are to
+//! be returned. For getsockopt(), optlen is a value-result
+//! parameter, initially containing the size of the buffer
+//! pointed to by option_value, and modified on return to
+//! indicate the actual size of the value returned. If no option
+//! value is to be supplied or returned, option_value may be NULL.
+//!
+//! @Note On this version the following two socket options are enabled:
+//! The only protocol level supported in this version
+//! is SOL_SOCKET (level).
+//! 1. SOCKOPT_RECV_TIMEOUT (optname)
+//! SOCKOPT_RECV_TIMEOUT configures recv and recvfrom timeout
+//! in milliseconds.
+//! In that case optval should be pointer to unsigned long.
+//! 2. SOCKOPT_NONBLOCK (optname). sets the socket non-blocking mode on
+//! or off.
+//! In that case optval should be SOCK_ON or SOCK_OFF (optval).
+//!
+//! @sa getsockopt
+//
+//*****************************************************************************
+#ifndef CC3000_TINY_DRIVER
+extern int setsockopt(long sd, long level, long optname, const void *optval,
+ socklen_t optlen);
+#endif
+//*****************************************************************************
+//
+//! getsockopt
+//!
+//! @param[in] sd socket handle
+//! @param[in] level defines the protocol level for this option
+//! @param[in] optname defines the option name to Interrogate
+//! @param[out] optval specifies a value for the option
+//! @param[out] optlen specifies the length of the option value
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief set socket options
+//! This function manipulate the options associated with a socket.
+//! Options may exist at multiple protocol levels; they are always
+//! present at the uppermost socket level.
+//! When manipulating socket options the level at which the option
+//! resides and the name of the option must be specified.
+//! To manipulate options at the socket level, level is specified as
+//! SOL_SOCKET. To manipulate options at any other level the protocol
+//! number of the appropriate protocol controlling the option is
+//! supplied. For example, to indicate that an option is to be
+//! interpreted by the TCP protocol, level should be set to the
+//! protocol number of TCP;
+//! The parameters optval and optlen are used to access optval -
+//! use for setsockopt(). For getsockopt() they identify a buffer
+//! in which the value for the requested option(s) are to
+//! be returned. For getsockopt(), optlen is a value-result
+//! parameter, initially containing the size of the buffer
+//! pointed to by option_value, and modified on return to
+//! indicate the actual size of the value returned. If no option
+//! value is to be supplied or returned, option_value may be NULL.
+//!
+//! @Note On this version the following two socket options are enabled:
+//! The only protocol level supported in this version
+//! is SOL_SOCKET (level).
+//! 1. SOCKOPT_RECV_TIMEOUT (optname)
+//! SOCKOPT_RECV_TIMEOUT configures recv and recvfrom timeout
+//! in milliseconds.
+//! In that case optval should be pointer to unsigned long.
+//! 2. SOCKOPT_NONBLOCK (optname). sets the socket non-blocking mode on
+//! or off.
+//! In that case optval should be SOCK_ON or SOCK_OFF (optval).
+//!
+//! @sa setsockopt
+//
+//*****************************************************************************
+extern int getsockopt(long sd, long level, long optname, void *optval,
+ socklen_t *optlen);
+
+//*****************************************************************************
+//
+//! recv
+//!
+//! @param[in] sd socket handle
+//! @param[out] buf Points to the buffer where the message should be stored
+//! @param[in] len Specifies the length in bytes of the buffer pointed to
+//! by the buffer argument.
+//! @param[in] flags Specifies the type of message reception.
+//! On this version, this parameter is not supported.
+//!
+//! @return Return the number of bytes received, or -1 if an error
+//! occurred
+//!
+//! @brief function receives a message from a connection-mode socket
+//!
+//! @sa recvfrom
+//!
+//! @Note On this version, only blocking mode is supported.
+//
+//*****************************************************************************
+extern int recv(long sd, void *buf, long len, long flags);
+
+//*****************************************************************************
+//
+//! recvfrom
+//!
+//! @param[in] sd socket handle
+//! @param[out] buf Points to the buffer where the message should be stored
+//! @param[in] len Specifies the length in bytes of the buffer pointed to
+//! by the buffer argument.
+//! @param[in] flags Specifies the type of message reception.
+//! On this version, this parameter is not supported.
+//! @param[in] from pointer to an address structure indicating the source
+//! address: sockaddr. On this version only AF_INET is
+//! supported.
+//! @param[in] fromlen source address structure size
+//!
+//! @return Return the number of bytes received, or -1 if an error
+//! occurred
+//!
+//! @brief read data from socket
+//! function receives a message from a connection-mode or
+//! connectionless-mode socket. Note that raw sockets are not
+//! supported.
+//!
+//! @sa recv
+//!
+//! @Note On this version, only blocking mode is supported.
+//
+//*****************************************************************************
+extern int recvfrom(long sd, void *buf, long len, long flags, sockaddr *from,
+ socklen_t *fromlen);
+
+//*****************************************************************************
+//
+//! send
+//!
+//! @param sd socket handle
+//! @param buf Points to a buffer containing the message to be sent
+//! @param len message size in bytes
+//! @param flags On this version, this parameter is not supported
+//!
+//! @return Return the number of bytes transmitted, or -1 if an
+//! error occurred
+//!
+//! @brief Write data to TCP socket
+//! This function is used to transmit a message to another
+//! socket.
+//!
+//! @Note On this version, only blocking mode is supported.
+//!
+//! @sa sendto
+//
+//*****************************************************************************
+
+extern int send(long sd, const void *buf, long len, long flags);
+
+//*****************************************************************************
+//
+//! sendto
+//!
+//! @param sd socket handle
+//! @param buf Points to a buffer containing the message to be sent
+//! @param len message size in bytes
+//! @param flags On this version, this parameter is not supported
+//! @param to pointer to an address structure indicating the destination
+//! address: sockaddr. On this version only AF_INET is
+//! supported.
+//! @param tolen destination address structure size
+//!
+//! @return Return the number of bytes transmitted, or -1 if an
+//! error occurred
+//!
+//! @brief Write data to TCP socket
+//! This function is used to transmit a message to another
+//! socket.
+//!
+//! @Note On this version, only blocking mode is supported.
+//!
+//! @sa send
+//
+//*****************************************************************************
+
+extern int sendto(long sd, const void *buf, long len, long flags,
+ const sockaddr *to, socklen_t tolen);
+
+//*****************************************************************************
+//
+//! mdnsAdvertiser
+//!
+//! @param[in] mdnsEnabled flag to enable/disable the mDNS feature
+//! @param[in] deviceServiceName Service name as part of the published
+//! canonical domain name
+//! @param[in] deviceServiceNameLength Length of the service name
+//!
+//!
+//! @return On success, zero is returned, return SOC_ERROR if socket was not
+//! opened successfully, or if an error occurred.
+//!
+//! @brief Set CC3000 in mDNS advertiser mode in order to advertise itself.
+//
+//*****************************************************************************
+extern int mdnsAdvertiser(uint16_t mdnsEnabled, char * deviceServiceName, uint16_t deviceServiceNameLength);
+
+//*****************************************************************************
+//
+// Close the Doxygen group.
+//! @}
+//
+//*****************************************************************************
+
+
+//*****************************************************************************
+//
+// Mark the end of the C bindings section for C++ compilers.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif // __SOCKET_H__
diff --git a/nuttx/include/nuttx/wireless/cc3000/spi.h b/nuttx/include/nuttx/wireless/cc3000/spi.h
new file mode 100644
index 000000000..bf68b3eb1
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/spi.h
@@ -0,0 +1,45 @@
+/**************************************************************************
+*
+* ArduinoCC3000SPI.h - SPI functions to connect an Arduidno to the TI
+* CC3000
+*
+* 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
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Don't sue me if my code blows up your board and burns down your house
+*
+****************************************************************************/
+
+
+
+
+typedef void (*gcSpiHandleRx)(void *p);
+
+//*****************************************************************************
+//
+// Prototypes for the APIs.
+//
+//*****************************************************************************
+
+void SpiOpen(gcSpiHandleRx pfRxHandler);
+
+void SpiClose(void);
+
+long SpiWrite(uint8_t *pUserBuffer, uint16_t usLength);
+
+void SpiResumeSpi(void);
+
+int CC3000InterruptHandler(int irq, void *context);
+
+int16_t SPIInterruptsEnabled;
+
+uint8_t wlan_tx_buffer[];
diff --git a/nuttx/include/nuttx/wireless/cc3000/spi_version.h b/nuttx/include/nuttx/wireless/cc3000/spi_version.h
new file mode 100644
index 000000000..44ff64397
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/spi_version.h
@@ -0,0 +1,53 @@
+/*****************************************************************************
+*
+* spi_version.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __SPI_VERSION_H__
+#define __SPI_VERSION_H__
+
+#define SPI_VERSION_NUMBER 7
+
+#endif // __VERSION_H__
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/nuttx/include/nuttx/wireless/cc3000/wlan.h b/nuttx/include/nuttx/wireless/cc3000/wlan.h
new file mode 100644
index 000000000..d910c4e9f
--- /dev/null
+++ b/nuttx/include/nuttx/wireless/cc3000/wlan.h
@@ -0,0 +1,517 @@
+/*****************************************************************************
+*
+* wlan.h - CC3000 Host Driver Implementation.
+* Copyright (C) 2011 Texas Instruments Incorporated - http://www.ti.com/
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+*
+* Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+*
+* 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.
+*
+* Neither the name of Texas Instruments Incorporated 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.
+*
+*****************************************************************************/
+#ifndef __WLAN_H__
+#define __WLAN_H__
+
+#include <nuttx/wireless/cc3000/cc3000_common.h>
+
+//*****************************************************************************
+//
+// If building with a C++ compiler, make all of the definitions in this header
+// have a C binding.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#define WLAN_SEC_UNSEC (0)
+#define WLAN_SEC_WEP (1)
+#define WLAN_SEC_WPA (2)
+#define WLAN_SEC_WPA2 (3)
+//*****************************************************************************
+//
+//! \addtogroup wlan_api
+//! @{
+//
+//*****************************************************************************
+
+
+//*****************************************************************************
+//
+//! wlan_init
+//!
+//! @param sWlanCB Asynchronous events callback.
+//! 0 no event call back.
+//! -call back parameters:
+//! 1) event_type: HCI_EVNT_WLAN_UNSOL_CONNECT connect event,
+//! HCI_EVNT_WLAN_UNSOL_DISCONNECT disconnect event,
+//! HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE config done,
+//! HCI_EVNT_WLAN_UNSOL_DHCP dhcp report,
+//! HCI_EVNT_WLAN_ASYNC_PING_REPORT ping report OR
+//! HCI_EVNT_WLAN_KEEPALIVE keepalive.
+//! 2) data: pointer to extra data that received by the event
+//! (NULL no data).
+//! 3) length: data length.
+//! -Events with extra data:
+//! HCI_EVNT_WLAN_UNSOL_DHCP: 4 bytes IP, 4 bytes Mask,
+//! 4 bytes default gateway, 4 bytes DHCP server and 4 bytes
+//! for DNS server.
+//! HCI_EVNT_WLAN_ASYNC_PING_REPORT: 4 bytes Packets sent,
+//! 4 bytes Packets received, 4 bytes Min round time,
+//! 4 bytes Max round time and 4 bytes for Avg round time.
+//!
+//! @param sFWPatches 0 no patch or pointer to FW patches
+//! @param sDriverPatches 0 no patch or pointer to driver patches
+//! @param sBootLoaderPatches 0 no patch or pointer to bootloader patches
+//! @param sReadWlanInterruptPin init callback. the callback read wlan
+//! interrupt status.
+//! @param sWlanInterruptEnable init callback. the callback enable wlan
+//! interrupt.
+//! @param sWlanInterruptDisable init callback. the callback disable wlan
+//! interrupt.
+//! @param sWriteWlanPin init callback. the callback write value
+//! to device pin.
+//!
+//! @return none
+//!
+//! @sa wlan_set_event_mask , wlan_start , wlan_stop
+//!
+//! @brief Initialize wlan driver
+//!
+//! @warning This function must be called before ANY other wlan driver function
+//
+//*****************************************************************************
+extern void wlan_init( tWlanCB sWlanCB,
+ tFWPatches sFWPatches,
+ tDriverPatches sDriverPatches,
+ tBootLoaderPatches sBootLoaderPatches,
+ tWlanReadInteruptPin sReadWlanInterruptPin,
+ tWlanInterruptEnable sWlanInterruptEnable,
+ tWlanInterruptDisable sWlanInterruptDisable,
+ tWriteWlanPin sWriteWlanPin);
+
+
+
+//*****************************************************************************
+//
+//! wlan_start
+//!
+//! @param usPatchesAvailableAtHost - flag to indicate if patches available
+//! from host or from EEPROM. Due to the
+//! fact the patches are burn to the EEPROM
+//! using the patch programmer utility, the
+//! patches will be available from the EEPROM
+//! and not from the host.
+//!
+//! @return none
+//!
+//! @brief Start WLAN device. This function asserts the enable pin of
+//! the device (WLAN_EN), starting the HW initialization process.
+//! The function blocked until device Initialization is completed.
+//! Function also configure patches (FW, driver or bootloader)
+//! and calls appropriate device callbacks.
+//!
+//! @Note Prior calling the function wlan_init shall be called.
+//! @Warning This function must be called after wlan_init and before any
+//! other wlan API
+//! @sa wlan_init , wlan_stop
+//!
+//
+//*****************************************************************************
+extern void wlan_start(uint16_t usPatchesAvailableAtHost);
+
+//*****************************************************************************
+//
+//! wlan_stop
+//!
+//! @param none
+//!
+//! @return none
+//!
+//! @brief Stop WLAN device by putting it into reset state.
+//!
+//! @sa wlan_start
+//
+//*****************************************************************************
+extern void wlan_stop(void);
+
+//*****************************************************************************
+//
+//! wlan_connect
+//!
+//! @param sec_type security options:
+//! WLAN_SEC_UNSEC,
+//! WLAN_SEC_WEP (ASCII support only),
+//! WLAN_SEC_WPA or WLAN_SEC_WPA2
+//! @param ssid up to 32 bytes and is ASCII SSID of the AP
+//! @param ssid_len length of the SSID
+//! @param bssid 6 bytes specified the AP bssid
+//! @param key up to 16 bytes specified the AP security key
+//! @param key_len key length
+//!
+//! @return On success, zero is returned. On error, negative is returned.
+//! Note that even though a zero is returned on success to trigger
+//! connection operation, it does not mean that CCC3000 is already
+//! connected. An asynchronous "Connected" event is generated when
+//! actual association process finishes and CC3000 is connected to
+//! the AP. If DHCP is set, An asynchronous "DHCP" event is
+//! generated when DHCP process is finish.
+//!
+//!
+//! @brief Connect to AP
+//! @warning Please Note that when connection to AP configured with security
+//! type WEP, please confirm that the key is set as ASCII and not
+//! as HEX.
+//! @sa wlan_disconnect
+//
+//*****************************************************************************
+#ifndef CC3000_TINY_DRIVER
+extern long wlan_connect(unsigned long ulSecType, char *ssid, long ssid_len,
+ uint8_t *bssid, uint8_t *key, long key_len);
+#else
+extern long wlan_connect(char *ssid, long ssid_len);
+
+#endif
+
+//*****************************************************************************
+//
+//! wlan_disconnect
+//!
+//! @return 0 disconnected done, other CC3000 already disconnected
+//!
+//! @brief Disconnect connection from AP.
+//!
+//! @sa wlan_connect
+//
+//*****************************************************************************
+
+extern long wlan_disconnect(void);
+
+//*****************************************************************************
+//
+//! wlan_add_profile
+//!
+//! @param ulSecType WLAN_SEC_UNSEC,WLAN_SEC_WEP,WLAN_SEC_WPA,WLAN_SEC_WPA2
+//! @param ucSsid ssid SSID up to 32 bytes
+//! @param ulSsidLen ssid length
+//! @param ucBssid bssid 6 bytes
+//! @param ulPriority ulPriority profile priority. Lowest priority:0.
+//! @param ulPairwiseCipher_Or_TxKeyLen key length for WEP security
+//! @param ulGroupCipher_TxKeyIndex key index
+//! @param ulKeyMgmt KEY management
+//! @param ucPf_OrKey security key
+//! @param ulPassPhraseLen security key length for WPA\WPA2
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief When auto start is enabled, the device connects to
+//! station from the profiles table. Up to 7 profiles are supported.
+//! If several profiles configured the device choose the highest
+//! priority profile, within each priority group, device will choose
+//! profile based on security policy, signal strength, etc
+//! parameters. All the profiles are stored in CC3000 NVMEM.
+//!
+//! @sa wlan_ioctl_del_profile
+//
+//*****************************************************************************
+
+extern long wlan_add_profile(unsigned long ulSecType, uint8_t* ucSsid,
+ unsigned long ulSsidLen,
+ uint8_t *ucBssid,
+ unsigned long ulPriority,
+ unsigned long ulPairwiseCipher_Or_Key,
+ unsigned long ulGroupCipher_TxKeyLen,
+ unsigned long ulKeyMgmt,
+ uint8_t* ucPf_OrKey,
+ unsigned long ulPassPhraseLen);
+
+
+
+//*****************************************************************************
+//
+//! wlan_ioctl_del_profile
+//!
+//! @param index number of profile to delete
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief Delete WLAN profile
+//!
+//! @Note In order to delete all stored profile, set index to 255.
+//!
+//! @sa wlan_add_profile
+//
+//*****************************************************************************
+extern long wlan_ioctl_del_profile(unsigned long ulIndex);
+
+//*****************************************************************************
+//
+//! wlan_set_event_mask
+//!
+//! @param mask mask option:
+//! HCI_EVNT_WLAN_UNSOL_CONNECT connect event
+//! HCI_EVNT_WLAN_UNSOL_DISCONNECT disconnect event
+//! HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE smart config done
+//! HCI_EVNT_WLAN_UNSOL_INIT init done
+//! HCI_EVNT_WLAN_UNSOL_DHCP dhcp event report
+//! HCI_EVNT_WLAN_ASYNC_PING_REPORT ping report
+//! HCI_EVNT_WLAN_KEEPALIVE keepalive
+//! HCI_EVNT_WLAN_TX_COMPLETE - disable information on end of transmission
+//! Saved: no.
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief Mask event according to bit mask. In case that event is
+//! masked (1), the device will not send the masked event to host.
+//
+//*****************************************************************************
+extern long wlan_set_event_mask(unsigned long ulMask);
+
+//*****************************************************************************
+//
+//! wlan_ioctl_statusget
+//!
+//! @param none
+//!
+//! @return WLAN_STATUS_DISCONNECTED, WLAN_STATUS_SCANING,
+//! STATUS_CONNECTING or WLAN_STATUS_CONNECTED
+//!
+//! @brief get wlan status: disconnected, scanning, connecting or connected
+//
+//*****************************************************************************
+extern long wlan_ioctl_statusget(void);
+
+
+//*****************************************************************************
+//
+//! wlan_ioctl_set_connection_policy
+//!
+//! @param should_connect_to_open_ap enable(1), disable(0) connect to any
+//! available AP. This parameter corresponds to the configuration of
+//! item # 3 in the brief description.
+//! @param should_use_fast_connect enable(1), disable(0). if enabled, tries
+//! to connect to the last connected AP. This parameter corresponds
+//! to the configuration of item # 1 in the brief description.
+//! @param auto_start enable(1), disable(0) auto connect
+//! after reset and periodically reconnect if needed. This
+//! configuration configures option 2 in the above description.
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief When auto is enabled, the device tries to connect according
+//! the following policy:
+//! 1) If fast connect is enabled and last connection is valid,
+//! the device will try to connect to it without the scanning
+//! procedure (fast). The last connection will be marked as
+//! invalid, due to adding/removing profile.
+//! 2) If profile exists, the device will try to connect it
+//! (Up to seven profiles).
+//! 3) If fast and profiles are not found, and open mode is
+//! enabled, the device will try to connect to any AP.
+//! * Note that the policy settings are stored in the CC3000 NVMEM.
+//!
+//! @sa wlan_add_profile , wlan_ioctl_del_profile
+//
+//*****************************************************************************
+extern long wlan_ioctl_set_connection_policy(
+ unsigned long should_connect_to_open_ap,
+ unsigned long should_use_fast_connect,
+ unsigned long ulUseProfiles);
+
+//*****************************************************************************
+//
+//! wlan_ioctl_get_scan_results
+//!
+//! @param[in] scan_timeout parameter not supported
+//! @param[out] ucResults scan result (_wlan_full_scan_results_args_t)
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief Gets entry from scan result table.
+//! The scan results are returned one by one, and each entry
+//! represents a single AP found in the area. The following is a
+//! format of the scan result:
+//! - 4 Bytes: number of networks found
+//! - 4 Bytes: The status of the scan: 0 - aged results,
+//! 1 - results valid, 2 - no results
+//! - 42 bytes: Result entry, where the bytes are arranged as follows:
+//!
+//! - 1 bit isValid - is result valid or not
+//! - 7 bits rssi - RSSI value;
+//! - 2 bits: securityMode - security mode of the AP:
+//! 0 - Open, 1 - WEP, 2 WPA, 3 WPA2
+//! - 6 bits: SSID name length
+//! - 2 bytes: the time at which the entry has entered into
+//! scans result table
+//! - 32 bytes: SSID name
+//! - 6 bytes: BSSID
+//!
+//! @Note scan_timeout, is not supported on this version.
+//!
+//! @sa wlan_ioctl_set_scan_params
+//
+//*****************************************************************************
+
+
+extern long wlan_ioctl_get_scan_results(unsigned long ulScanTimeout,
+ uint8_t *ucResults);
+
+//*****************************************************************************
+//
+//! wlan_ioctl_set_scan_params
+//!
+//! @param uiEnable - start/stop application scan:
+//! 1 = start scan with default interval value of 10 min.
+//! in order to set a different scan interval value apply the value
+//! in milliseconds. minimum 1 second. 0=stop). Wlan reset
+//! (wlan_stop() wlan_start()) is needed when changing scan interval
+//! value. Saved: No
+//! @param uiMinDwellTime minimum dwell time value to be used for each
+//! channel, in milliseconds. Saved: yes
+//! Recommended Value: 100 (Default: 20)
+//! @param uiMaxDwellTime maximum dwell time value to be used for each
+//! channel, in milliseconds. Saved: yes
+//! Recommended Value: 100 (Default: 30)
+//! @param uiNumOfProbeRequests max probe request between dwell time.
+//! Saved: yes. Recommended Value: 5 (Default:2)
+//! @param uiChannelMask bitwise, up to 13 channels (0x1fff).
+//! Saved: yes. Default: 0x7ff
+//! @param uiRSSIThreshold RSSI threshold. Saved: yes (Default: -80)
+//! @param uiSNRThreshold NSR threshold. Saved: yes (Default: 0)
+//! @param uiDefaultTxPower probe Tx power. Saved: yes (Default: 205)
+//! @param aiIntervalList pointer to array with 16 entries (16 channels)
+//! each entry (unsigned long) holds timeout between periodic scan
+//! (connection scan) - in milliseconds. Saved: yes. Default 2000ms.
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief start and stop scan procedure. Set scan parameters.
+//!
+//! @Note uiDefaultTxPower, is not supported on this version.
+//!
+//! @sa wlan_ioctl_get_scan_results
+//
+//*****************************************************************************
+extern long wlan_ioctl_set_scan_params(unsigned long uiEnable, unsigned long
+ uiMinDwellTime,unsigned long uiMaxDwellTime,
+ unsigned long uiNumOfProbeRequests,
+ unsigned long uiChannelMask,
+ long iRSSIThreshold,unsigned long uiSNRThreshold,
+ unsigned long uiDefaultTxPower,
+ unsigned long *aiIntervalList);
+
+
+//*****************************************************************************
+//
+//! wlan_smart_config_start
+//!
+//! @param algoEncryptedFlag indicates whether the information is encrypted
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief Start to acquire device profile. The device acquire its own
+//! profile, if profile message is found. The acquired AP information
+//! is stored in CC3000 EEPROM only in case AES128 encryption is used.
+//! In case AES128 encryption is not used, a profile is created by
+//! CC3000 internally.
+//!
+//! @Note An asynchronous event - Smart Config Done will be generated as soon
+//! as the process finishes successfully.
+//!
+//! @sa wlan_smart_config_set_prefix , wlan_smart_config_stop
+//
+//*****************************************************************************
+extern long wlan_smart_config_start(unsigned long algoEncryptedFlag);
+
+
+//*****************************************************************************
+//
+//! wlan_smart_config_stop
+//!
+//! @param algoEncryptedFlag indicates whether the information is encrypted
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief Stop the acquire profile procedure
+//!
+//! @sa wlan_smart_config_start , wlan_smart_config_set_prefix
+//
+//*****************************************************************************
+extern long wlan_smart_config_stop(void);
+
+//*****************************************************************************
+//
+//! wlan_smart_config_set_prefix
+//!
+//! @param newPrefix 3 bytes identify the SSID prefix for the Smart Config.
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief Configure station ssid prefix. The prefix is used internally
+//! in CC3000. It should always be TTT.
+//!
+//! @Note The prefix is stored in CC3000 NVMEM
+//!
+//! @sa wlan_smart_config_start , wlan_smart_config_stop
+//
+//*****************************************************************************
+extern long wlan_smart_config_set_prefix(char* cNewPrefix);
+
+//*****************************************************************************
+//
+//! wlan_smart_config_process
+//!
+//! @param none
+//!
+//! @return On success, zero is returned. On error, -1 is returned
+//!
+//! @brief process the acquired data and store it as a profile. The acquired
+//! AP information is stored in CC3000 EEPROM encrypted.
+//! The encrypted data is decrypted and stored as a profile.
+//! behavior is as defined by connection policy.
+//
+//*****************************************************************************
+extern long wlan_smart_config_process(void);
+
+//*****************************************************************************
+//
+// Close the Doxygen group.
+//! @}
+//
+//*****************************************************************************
+
+
+
+//*****************************************************************************
+//
+// Mark the end of the C bindings section for C++ compilers.
+//
+//*****************************************************************************
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+
+#endif // __WLAN_H__