From a2ffe6b068f3975e7574feabff0d20b368bd2f49 Mon Sep 17 00:00:00 2001 From: Gregory Nutt Date: Wed, 4 Sep 2013 09:45:59 -0600 Subject: CC3000 driver updates from Alan Carvalho de Assis --- apps/examples/cc3000/board.c | 10 +- apps/examples/cc3000/board.h | 15 +- apps/examples/cc3000/cc3000basic.c | 33 +- nuttx/drivers/wireless/cc3000/cc3000_common.c | 328 ++-- nuttx/drivers/wireless/cc3000/evnt_handler.c | 1687 +++++++++-------- nuttx/drivers/wireless/cc3000/hci.c | 460 ++--- nuttx/drivers/wireless/cc3000/netapp.c | 918 ++++----- nuttx/drivers/wireless/cc3000/nvmem.c | 680 +++---- nuttx/drivers/wireless/cc3000/security.c | 1066 +++++------ nuttx/drivers/wireless/cc3000/socket.c | 2338 +++++++++++------------ nuttx/drivers/wireless/cc3000/spi.c | 32 +- nuttx/drivers/wireless/cc3000/wlan.c | 2505 ++++++++++++------------- nuttx/include/nuttx/cc3000/cc3000_common.h | 718 +++---- nuttx/include/nuttx/cc3000/evnt_handler.h | 332 ++-- nuttx/include/nuttx/cc3000/hci.h | 656 +++---- nuttx/include/nuttx/cc3000/netapp.h | 684 +++---- nuttx/include/nuttx/cc3000/nvmem.h | 496 ++--- nuttx/include/nuttx/cc3000/security.h | 252 +-- nuttx/include/nuttx/cc3000/socket.h | 1328 ++++++------- nuttx/include/nuttx/cc3000/spi.h | 6 +- nuttx/include/nuttx/cc3000/wlan.h | 1034 +++++----- 21 files changed, 7786 insertions(+), 7792 deletions(-) diff --git a/apps/examples/cc3000/board.c b/apps/examples/cc3000/board.c index feba5bbe4..1868b061d 100644 --- a/apps/examples/cc3000/board.c +++ b/apps/examples/cc3000/board.c @@ -38,7 +38,7 @@ volatile unsigned long ulSmartConfigFinished, OkToDoShutDown, ulCC3000DHCP_configured; -volatile unsigned char ucStopSmartConfig; +volatile uint8_t ucStopSmartConfig; @@ -47,7 +47,7 @@ volatile unsigned char ucStopSmartConfig; #define CC3000_RX_BUFFER_OVERHEAD_SIZE (20) /* -unsigned char pucCC3000_Rx_Buffer[CC3000_APP_BUFFER_SIZE + CC3000_RX_BUFFER_OVERHEAD_SIZE]; +uint8_t pucCC3000_Rx_Buffer[CC3000_APP_BUFFER_SIZE + CC3000_RX_BUFFER_OVERHEAD_SIZE]; */ @@ -60,9 +60,9 @@ unsigned char pucCC3000_Rx_Buffer[CC3000_APP_BUFFER_SIZE + CC3000_RX_BUFFER_OVER So now we just set a flag and write to a string, and the master loop can deal with it when it wants. */ -unsigned char asyncNotificationWaiting = false; +uint8_t asyncNotificationWaiting = false; long lastAsyncEvent; -unsigned char dhcpIPAddress[4]; +uint8_t dhcpIPAddress[4]; /*------------------------------------------------------------------- @@ -78,7 +78,7 @@ unsigned char dhcpIPAddress[4]; ---------------------------------------------------------------------*/ -void CC3000_AsyncCallback(long lEventType, char * data, unsigned char length) +void CC3000_AsyncCallback(long lEventType, char * data, uint8_t length) { lastAsyncEvent = lEventType; diff --git a/apps/examples/cc3000/board.h b/apps/examples/cc3000/board.h index 2d659fabe..61976b346 100644 --- a/apps/examples/cc3000/board.h +++ b/apps/examples/cc3000/board.h @@ -18,16 +18,13 @@ * ****************************************************************************/ - - - - - /* Some things are different for the Teensy 3.0, so set a flag if we're using that hardware. */ +#include + #if defined(__arm__) && defined(CORE_TEENSY) && defined(__MK20DX128__) #define TEENSY3 1 #endif @@ -165,7 +162,7 @@ #define ENABLE (1) //AES key "smartconfigAES16" -//const unsigned char smartconfigkey[] = {0x73,0x6d,0x61,0x72,0x74,0x63,0x6f,0x6e,0x66,0x69,0x67,0x41,0x45,0x53,0x31,0x36}; +//const uint8_t smartconfigkey[] = {0x73,0x6d,0x61,0x72,0x74,0x63,0x6f,0x6e,0x66,0x69,0x67,0x41,0x45,0x53,0x31,0x36}; @@ -202,9 +199,9 @@ -extern unsigned char asyncNotificationWaiting; +extern uint8_t asyncNotificationWaiting; extern long lastAsyncEvent; -extern unsigned char dhcpIPAddress[]; +extern uint8_t dhcpIPAddress[]; @@ -217,4 +214,4 @@ extern volatile unsigned long ulSmartConfigFinished, OkToDoShutDown, ulCC3000DHCP_configured; -extern volatile unsigned char ucStopSmartConfig; +extern volatile uint8_t ucStopSmartConfig; diff --git a/apps/examples/cc3000/cc3000basic.c b/apps/examples/cc3000/cc3000basic.c index ae60abc6a..39f8f7c8f 100644 --- a/apps/examples/cc3000/cc3000basic.c +++ b/apps/examples/cc3000/cc3000basic.c @@ -90,6 +90,7 @@ Arduino pin -----> 560 Ohm --+--> 1K Ohm -----> GND #include "board.h" #include #include +#include #include #include #include @@ -111,7 +112,7 @@ void ManualConnect(void); void ManualConnect(void); void ManualAddProfile(void); void ListAccessPoints(void); -void PrintIPBytes(unsigned char *ipBytes); +void PrintIPBytes(uint8_t *ipBytes); void ShowInformation(void); // When operations that take a long time (like Smart Config) are running, the @@ -223,7 +224,7 @@ void execute(int cmd) void Initialize(void) { - unsigned char fancyBuffer[MAC_ADDR_LEN], i = 0; + uint8_t fancyBuffer[MAC_ADDR_LEN], i = 0; if (isInitialized) { printf("CC3000 already initialized. Shutting down and restarting...\n"); @@ -417,9 +418,9 @@ void StartSmartConfig(void) { void ManualConnect(void) { - char ssidName[] = "OpenNET"; - char AP_KEY[] = "gargame1"; - unsigned char rval; + char ssidName[] = "YourAP"; + char AP_KEY[] = "yourpass"; + uint8_t rval; if (!isInitialized) { @@ -452,7 +453,7 @@ void ManualConnect(void) { ssidName, strlen(ssidName), NULL, - (unsigned char *)AP_KEY, + (uint8_t *)AP_KEY, strlen(AP_KEY)); if (rval==0) { @@ -484,7 +485,7 @@ void ManualConnect(void) { void ManualAddProfile(void) { char ssidName[] = "YourAP"; char AP_KEY[] = "yourpass"; - unsigned char rval; + uint8_t rval; if (!isInitialized) { @@ -500,14 +501,14 @@ void ManualAddProfile(void) { printf(" Adding profile...\n"); rval = wlan_add_profile ( WLAN_SEC_WPA2, // WLAN_SEC_UNSEC, WLAN_SEC_WEP, WLAN_SEC_WPA or WLAN_SEC_WPA2 - (unsigned char *)ssidName, + (uint8_t *)ssidName, strlen(ssidName), NULL, // BSSID, TI always uses NULL 0, // profile priority 0x18, // key length for WEP security, undocumented why this needs to be 0x18 0x1e, // key index, undocumented why this needs to be 0x1e 0x2, // key management, undocumented why this needs to be 2 - (unsigned char *)AP_KEY, // WPA security key + (uint8_t *)AP_KEY, // WPA security key strlen(AP_KEY) // WPA security key length ); @@ -587,16 +588,16 @@ typedef struct scanResults { unsigned rssi:7; unsigned securityMode:2; unsigned ssidLength:6; - unsigned short frameTime; - unsigned char ssid_name[32]; - unsigned char bssid[6]; + uint16_t frameTime; + uint8_t ssid_name[32]; + uint8_t bssid[6]; } scanResults; #define NUM_CHANNELS 16 void ListAccessPoints(void) { unsigned long aiIntervalList[NUM_CHANNELS]; - unsigned char rval; + uint8_t rval; scanResults sr; int apCounter, i; char localB[33]; @@ -639,7 +640,7 @@ void ListAccessPoints(void) { // actual # of APs currently seen. Get that # then loop through and print // out what's found. - if ((rval=wlan_ioctl_get_scan_results(2000, (unsigned char *)&sr))!=0) { + if ((rval=wlan_ioctl_get_scan_results(2000, (uint8_t *)&sr))!=0) { printf(" Got back unusual result from wlan_ioctl_get scan results, can't continue: %d\n", rval); return; } @@ -672,7 +673,7 @@ void ListAccessPoints(void) { } if (--apCounter>0) { - if ((rval=wlan_ioctl_get_scan_results(2000, (unsigned char *)&sr))!=0) { + if ((rval=wlan_ioctl_get_scan_results(2000, (uint8_t *)&sr))!=0) { printf(" Got back unusual result from wlan_ioctl_get scan, can't continue: %d\n", rval); return; } @@ -684,7 +685,7 @@ void ListAccessPoints(void) { -void PrintIPBytes(unsigned char *ipBytes) { +void PrintIPBytes(uint8_t *ipBytes) { printf("%d.%d.%d.%d\n", ipBytes[3], ipBytes[2], ipBytes[1], ipBytes[0]); } diff --git a/nuttx/drivers/wireless/cc3000/cc3000_common.c b/nuttx/drivers/wireless/cc3000/cc3000_common.c index 01fcd0a69..dae74d4c4 100644 --- a/nuttx/drivers/wireless/cc3000/cc3000_common.c +++ b/nuttx/drivers/wireless/cc3000/cc3000_common.c @@ -1,164 +1,164 @@ -/***************************************************************************** -* -* cc3000_common.c.c - 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. -* -*****************************************************************************/ -//***************************************************************************** -// -//! \addtogroup common_api -//! @{ -// -//***************************************************************************** -/****************************************************************************** - * - * Include files - * - *****************************************************************************/ -#include -#include -#include -#include - -//***************************************************************************** -// -//! __error__ -//! -//! @param pcFilename - file name, where error occurred -//! @param ulLine - line number, where error occurred -//! -//! @return none -//! -//! @brief stub function for ASSERT macro -// -//***************************************************************************** -void -__error__(char *pcFilename, unsigned long ulLine) -{ - //TODO full up function -} - - - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -unsigned char* UINT32_TO_STREAM_f (unsigned char *p, unsigned long u32) -{ - *(p)++ = (unsigned char)(u32); - *(p)++ = (unsigned char)((u32) >> 8); - *(p)++ = (unsigned char)((u32) >> 16); - *(p)++ = (unsigned char)((u32) >> 24); - return p; -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -unsigned char* UINT16_TO_STREAM_f (unsigned char *p, unsigned short u16) -{ - *(p)++ = (unsigned char)(u16); - *(p)++ = (unsigned char)((u16) >> 8); - return p; -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -unsigned short STREAM_TO_UINT16_f(char* p, unsigned short offset) -{ - return (unsigned short)((unsigned short)((unsigned short) - (*(p + offset + 1)) << 8) + (unsigned short)(*(p + 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. -// -//***************************************************************************** - -unsigned long STREAM_TO_UINT32_f(char* p, unsigned short offset) -{ - return (unsigned long)((unsigned long)((unsigned long) - (*(p + offset + 3)) << 24) + (unsigned long)((unsigned long) - (*(p + offset + 2)) << 16) + (unsigned long)((unsigned long) - (*(p + offset + 1)) << 8) + (unsigned long)(*(p + offset))); -} - - - -//***************************************************************************** -// -// Close the Doxygen group. -//! @} -// -//***************************************************************************** +/***************************************************************************** +* +* cc3000_common.c.c - 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. +* +*****************************************************************************/ +//***************************************************************************** +// +//! \addtogroup common_api +//! @{ +// +//***************************************************************************** +/****************************************************************************** + * + * Include files + * + *****************************************************************************/ +#include +#include +#include +#include + +//***************************************************************************** +// +//! __error__ +//! +//! @param pcFilename - file name, where error occurred +//! @param ulLine - line number, where error occurred +//! +//! @return none +//! +//! @brief stub function for ASSERT macro +// +//***************************************************************************** +void +__error__(char *pcFilename, unsigned long ulLine) +{ + //TODO full up function +} + + + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +uint8_t* UINT32_TO_STREAM_f (uint8_t *p, unsigned long u32) +{ + *(p)++ = (uint8_t)(u32); + *(p)++ = (uint8_t)((u32) >> 8); + *(p)++ = (uint8_t)((u32) >> 16); + *(p)++ = (uint8_t)((u32) >> 24); + return p; +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +uint8_t* UINT16_TO_STREAM_f (uint8_t *p, uint16_t u16) +{ + *(p)++ = (uint8_t)(u16); + *(p)++ = (uint8_t)((u16) >> 8); + return p; +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +uint16_t STREAM_TO_UINT16_f(char* p, uint16_t offset) +{ + return (uint16_t)((uint16_t)((uint16_t) + (*(p + offset + 1)) << 8) + (uint16_t)(*(p + 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. +// +//***************************************************************************** + +unsigned long STREAM_TO_UINT32_f(char* p, uint16_t offset) +{ + return (unsigned long)((unsigned long)((unsigned long) + (*(p + offset + 3)) << 24) + (unsigned long)((unsigned long) + (*(p + offset + 2)) << 16) + (unsigned long)((unsigned long) + (*(p + offset + 1)) << 8) + (unsigned long)(*(p + offset))); +} + + + +//***************************************************************************** +// +// Close the Doxygen group. +//! @} +// +//***************************************************************************** diff --git a/nuttx/drivers/wireless/cc3000/evnt_handler.c b/nuttx/drivers/wireless/cc3000/evnt_handler.c index c4a362e0b..f430c820e 100644 --- a/nuttx/drivers/wireless/cc3000/evnt_handler.c +++ b/nuttx/drivers/wireless/cc3000/evnt_handler.c @@ -1,844 +1,843 @@ -/***************************************************************************** -* -* evnt_handler.c - 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. -* -*****************************************************************************/ -//***************************************************************************** -// -//! \addtogroup evnt_handler_api -//! @{ -// -//****************************************************************************** - -//****************************************************************************** -// INCLUDE FILES -//****************************************************************************** - -#include -#include -#include -#include -#include -#include -#include -#include - - - -//***************************************************************************** -// COMMON DEFINES -//***************************************************************************** - -#define FLOW_CONTROL_EVENT_HANDLE_OFFSET (0) -#define FLOW_CONTROL_EVENT_BLOCK_MODE_OFFSET (1) -#define FLOW_CONTROL_EVENT_FREE_BUFFS_OFFSET (2) -#define FLOW_CONTROL_EVENT_SIZE (4) - -#define BSD_RSP_PARAMS_SOCKET_OFFSET (0) -#define BSD_RSP_PARAMS_STATUS_OFFSET (4) - -#define GET_HOST_BY_NAME_RETVAL_OFFSET (0) -#define GET_HOST_BY_NAME_ADDR_OFFSET (4) - -#define ACCEPT_SD_OFFSET (0) -#define ACCEPT_RETURN_STATUS_OFFSET (4) -#define ACCEPT_ADDRESS__OFFSET (8) - -#define SL_RECEIVE_SD_OFFSET (0) -#define SL_RECEIVE_NUM_BYTES_OFFSET (4) -#define SL_RECEIVE__FLAGS__OFFSET (8) - - -#define SELECT_STATUS_OFFSET (0) -#define SELECT_READFD_OFFSET (4) -#define SELECT_WRITEFD_OFFSET (8) -#define SELECT_EXFD_OFFSET (12) - - -#define NETAPP_IPCONFIG_IP_OFFSET (0) -#define NETAPP_IPCONFIG_SUBNET_OFFSET (4) -#define NETAPP_IPCONFIG_GW_OFFSET (8) -#define NETAPP_IPCONFIG_DHCP_OFFSET (12) -#define NETAPP_IPCONFIG_DNS_OFFSET (16) -#define NETAPP_IPCONFIG_MAC_OFFSET (20) -#define NETAPP_IPCONFIG_SSID_OFFSET (26) - -#define NETAPP_IPCONFIG_IP_LENGTH (4) -#define NETAPP_IPCONFIG_MAC_LENGTH (6) -#define NETAPP_IPCONFIG_SSID_LENGTH (32) - - -#define NETAPP_PING_PACKETS_SENT_OFFSET (0) -#define NETAPP_PING_PACKETS_RCVD_OFFSET (4) -#define NETAPP_PING_MIN_RTT_OFFSET (8) -#define NETAPP_PING_MAX_RTT_OFFSET (12) -#define NETAPP_PING_AVG_RTT_OFFSET (16) - -#define GET_SCAN_RESULTS_TABlE_COUNT_OFFSET (0) -#define GET_SCAN_RESULTS_SCANRESULT_STATUS_OFFSET (4) -#define GET_SCAN_RESULTS_ISVALID_TO_SSIDLEN_OFFSET (8) -#define GET_SCAN_RESULTS_FRAME_TIME_OFFSET (10) -#define GET_SCAN_RESULTS_SSID_MAC_LENGTH (38) - - - -//***************************************************************************** -// GLOBAL VARAIABLES -//***************************************************************************** - -unsigned long socket_active_status = SOCKET_STATUS_INIT_VAL; - - -//***************************************************************************** -// Prototypes for the static functions -//***************************************************************************** - -static long hci_event_unsol_flowcontrol_handler(char *pEvent); - -static void update_socket_active_status(char *resp_params); - - -//***************************************************************************** -// -//! hci_unsol_handle_patch_request -//! -//! @param event_hdr event header -//! -//! @return none -//! -//! @brief Handle unsolicited event from type patch request -// -//***************************************************************************** -void hci_unsol_handle_patch_request(char *event_hdr) -{ - char *params = (char *)(event_hdr) + HCI_EVENT_HEADER_SIZE; - unsigned long ucLength = 0; - char *patch; - - switch (*params) - { - case HCI_EVENT_PATCHES_DRV_REQ: - - if (tSLInformation.sDriverPatches) - { - patch = tSLInformation.sDriverPatches(&ucLength); - - if (patch) - { - hci_patch_send(HCI_EVENT_PATCHES_DRV_REQ, - tSLInformation.pucTxCommandBuffer, patch, ucLength); - return; - } - } - - // Send 0 length Patches response event - hci_patch_send(HCI_EVENT_PATCHES_DRV_REQ, - tSLInformation.pucTxCommandBuffer, 0, 0); - break; - - case HCI_EVENT_PATCHES_FW_REQ: - - if (tSLInformation.sFWPatches) - { - patch = tSLInformation.sFWPatches(&ucLength); - - // Build and send a patch - if (patch) - { - hci_patch_send(HCI_EVENT_PATCHES_FW_REQ, - tSLInformation.pucTxCommandBuffer, patch, ucLength); - return; - } - } - - // Send 0 length Patches response event - hci_patch_send(HCI_EVENT_PATCHES_FW_REQ, - tSLInformation.pucTxCommandBuffer, 0, 0); - break; - - case HCI_EVENT_PATCHES_BOOTLOAD_REQ: - - if (tSLInformation.sBootLoaderPatches) - { - patch = tSLInformation.sBootLoaderPatches(&ucLength); - - if (patch) - { - hci_patch_send(HCI_EVENT_PATCHES_BOOTLOAD_REQ, - tSLInformation.pucTxCommandBuffer, patch, ucLength); - return; - } - } - - // Send 0 length Patches response event - hci_patch_send(HCI_EVENT_PATCHES_BOOTLOAD_REQ, - tSLInformation.pucTxCommandBuffer, 0, 0); - break; - } -} - - - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - - -unsigned char * -hci_event_handler(void *pRetParams, unsigned char *from, unsigned char *fromlen) -{ - unsigned char *pucReceivedData, ucArgsize; - unsigned short usLength; - unsigned char *pucReceivedParams; - unsigned short usReceivedEventOpcode = 0; - unsigned long retValue32; - unsigned char * RecvParams; - unsigned char *RetParams; - - - while (1) - { - if (tSLInformation.usEventOrDataReceived != 0) - { - pucReceivedData = (tSLInformation.pucReceivedData); - - if (*pucReceivedData == HCI_TYPE_EVNT) - { - // Event Received - STREAM_TO_UINT16((char *)pucReceivedData, HCI_EVENT_OPCODE_OFFSET, - usReceivedEventOpcode); - pucReceivedParams = pucReceivedData + HCI_EVENT_HEADER_SIZE; - RecvParams = pucReceivedParams; - RetParams = (unsigned char *)pRetParams; - - // In case unsolicited event received - here the handling finished - if (hci_unsol_event_handler((char *)pucReceivedData) == 0) - { - STREAM_TO_UINT8(pucReceivedData, HCI_DATA_LENGTH_OFFSET, usLength); - - switch(usReceivedEventOpcode) - { - case HCI_CMND_READ_BUFFER_SIZE: - { - STREAM_TO_UINT8((char *)pucReceivedParams, 0, - tSLInformation.usNumberOfFreeBuffers); - STREAM_TO_UINT16((char *)pucReceivedParams, 1, - tSLInformation.usSlBufferLength); - } - break; - - case HCI_CMND_WLAN_CONFIGURE_PATCH: - case HCI_NETAPP_DHCP: - case HCI_NETAPP_PING_SEND: - case HCI_NETAPP_PING_STOP: - case HCI_NETAPP_ARP_FLUSH: - case HCI_NETAPP_SET_DEBUG_LEVEL: - case HCI_NETAPP_SET_TIMERS: - case HCI_EVNT_NVMEM_READ: - case HCI_EVNT_NVMEM_CREATE_ENTRY: - case HCI_CMND_NVMEM_WRITE_PATCH: - case HCI_NETAPP_PING_REPORT: - case HCI_EVNT_MDNS_ADVERTISE: - - STREAM_TO_UINT8(pucReceivedData, HCI_EVENT_STATUS_OFFSET - ,*(unsigned char *)pRetParams); - break; - - case HCI_CMND_SETSOCKOPT: - case HCI_CMND_WLAN_CONNECT: - case HCI_CMND_WLAN_IOCTL_STATUSGET: - case HCI_EVNT_WLAN_IOCTL_ADD_PROFILE: - case HCI_CMND_WLAN_IOCTL_DEL_PROFILE: - case HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY: - case HCI_CMND_WLAN_IOCTL_SET_SCANPARAM: - case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START: - case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP: - case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX: - case HCI_CMND_EVENT_MASK: - case HCI_EVNT_WLAN_DISCONNECT: - case HCI_EVNT_SOCKET: - case HCI_EVNT_BIND: - case HCI_CMND_LISTEN: - case HCI_EVNT_CLOSE_SOCKET: - case HCI_EVNT_CONNECT: - case HCI_EVNT_NVMEM_WRITE: - - STREAM_TO_UINT32((char *)pucReceivedParams,0 - ,*(unsigned long *)pRetParams); - break; - - case HCI_EVNT_READ_SP_VERSION: - - STREAM_TO_UINT8(pucReceivedData, HCI_EVENT_STATUS_OFFSET - ,*(unsigned char *)pRetParams); - pRetParams = ((char *)pRetParams) + 1; - STREAM_TO_UINT32((char *)pucReceivedParams, 0, retValue32); - UINT32_TO_STREAM((unsigned char *)pRetParams, retValue32); - break; - - case HCI_EVNT_BSD_GETHOSTBYNAME: - - STREAM_TO_UINT32((char *)pucReceivedParams - ,GET_HOST_BY_NAME_RETVAL_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams - ,GET_HOST_BY_NAME_ADDR_OFFSET,*(unsigned long *)pRetParams); - break; - - case HCI_EVNT_ACCEPT: - { - STREAM_TO_UINT32((char *)pucReceivedParams,ACCEPT_SD_OFFSET - ,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams - ,ACCEPT_RETURN_STATUS_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - - //This argument returns in network order - memcpy((unsigned char *)pRetParams, - pucReceivedParams + ACCEPT_ADDRESS__OFFSET, sizeof(sockaddr)); - break; - } - - case HCI_EVNT_RECV: - case HCI_EVNT_RECVFROM: - { - STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_SD_OFFSET ,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_NUM_BYTES_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE__FLAGS__OFFSET,*(unsigned long *)pRetParams); - - if(((tBsdReadReturnParams *)pRetParams)->iNumberOfBytes == ERROR_SOCKET_INACTIVE) - { - set_socket_active_status(((tBsdReadReturnParams *)pRetParams)->iSocketDescriptor,SOCKET_STATUS_INACTIVE); - } - break; - } - - case HCI_EVNT_SEND: - case HCI_EVNT_SENDTO: - { - STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_SD_OFFSET ,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_NUM_BYTES_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - - break; - } - - case HCI_EVNT_SELECT: - { - STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_STATUS_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_READFD_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_WRITEFD_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_EXFD_OFFSET,*(unsigned long *)pRetParams); - break; - } - - case HCI_CMND_GETSOCKOPT: - - STREAM_TO_UINT8(pucReceivedData, HCI_EVENT_STATUS_OFFSET,((tBsdGetSockOptReturnParams *)pRetParams)->iStatus); - //This argument returns in network order - memcpy((unsigned char *)pRetParams, pucReceivedParams, 4); - break; - - case HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS: - - STREAM_TO_UINT32((char *)pucReceivedParams,GET_SCAN_RESULTS_TABlE_COUNT_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT32((char *)pucReceivedParams,GET_SCAN_RESULTS_SCANRESULT_STATUS_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 4; - STREAM_TO_UINT16((char *)pucReceivedParams,GET_SCAN_RESULTS_ISVALID_TO_SSIDLEN_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 2; - STREAM_TO_UINT16((char *)pucReceivedParams,GET_SCAN_RESULTS_FRAME_TIME_OFFSET,*(unsigned long *)pRetParams); - pRetParams = ((char *)pRetParams) + 2; - memcpy((unsigned char *)pRetParams, - (char *)(pucReceivedParams + GET_SCAN_RESULTS_FRAME_TIME_OFFSET + 2), - GET_SCAN_RESULTS_SSID_MAC_LENGTH); - break; - - case HCI_CMND_SIMPLE_LINK_START: - break; - - case HCI_NETAPP_IPCONFIG: - - //Read IP address - STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); - RecvParams += 4; - - //Read subnet - STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); - RecvParams += 4; - - //Read default GW - STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); - RecvParams += 4; - - //Read DHCP server - STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); - RecvParams += 4; - - //Read DNS server - STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); - RecvParams += 4; - - //Read Mac address - STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_MAC_LENGTH); - RecvParams += 6; - - //Read SSID - STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_SSID_LENGTH); - - } - } - - if (usReceivedEventOpcode == tSLInformation.usRxEventOpcode) - { - tSLInformation.usRxEventOpcode = 0; - } - } - else - { - pucReceivedParams = pucReceivedData; - STREAM_TO_UINT8((char *)pucReceivedData, HCI_PACKET_ARGSIZE_OFFSET, ucArgsize); - - STREAM_TO_UINT16((char *)pucReceivedData, HCI_PACKET_LENGTH_OFFSET, usLength); - - // Data received: note that the only case where from and from length - // are not null is in recv from, so fill the args accordingly - if (from) - { - STREAM_TO_UINT32((char *)(pucReceivedData + HCI_DATA_HEADER_SIZE), BSD_RECV_FROM_FROMLEN_OFFSET, *(unsigned long *)fromlen); - memcpy(from, (pucReceivedData + HCI_DATA_HEADER_SIZE + BSD_RECV_FROM_FROM_OFFSET) ,*fromlen); - } - - memcpy(pRetParams, pucReceivedParams + HCI_DATA_HEADER_SIZE + ucArgsize, - usLength - ucArgsize); - - tSLInformation.usRxDataPending = 0; - } - - tSLInformation.usEventOrDataReceived = 0; - - SpiResumeSpi(); - - // Since we are going to TX - we need to handle this event after the - // ResumeSPi since we need interrupts - if ((*pucReceivedData == HCI_TYPE_EVNT) && - (usReceivedEventOpcode == HCI_EVNT_PATCHES_REQ)) - { - hci_unsol_handle_patch_request((char *)pucReceivedData); - } - - if ((tSLInformation.usRxEventOpcode == 0) && (tSLInformation.usRxDataPending == 0)) - { - return NULL; - } - } - } - -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** -long -hci_unsol_event_handler(char *event_hdr) -{ - char * data = NULL; - long event_type; - unsigned long NumberOfReleasedPackets; - unsigned long NumberOfSentPackets; - - STREAM_TO_UINT16(event_hdr, HCI_EVENT_OPCODE_OFFSET,event_type); - - if (event_type & HCI_EVNT_UNSOL_BASE) - { - switch(event_type) - { - - case HCI_EVNT_DATA_UNSOL_FREE_BUFF: - { - hci_event_unsol_flowcontrol_handler(event_hdr); - - NumberOfReleasedPackets = tSLInformation.NumberOfReleasedPackets; - NumberOfSentPackets = tSLInformation.NumberOfSentPackets; - - if (NumberOfReleasedPackets == NumberOfSentPackets) - { - if (tSLInformation.InformHostOnTxComplete) - { - tSLInformation.sWlanCB(HCI_EVENT_CC3000_CAN_SHUT_DOWN, NULL, 0); - } - } - return 1; - - } - } - } - - if(event_type & HCI_EVNT_WLAN_UNSOL_BASE) - { - switch(event_type) - { - case HCI_EVNT_WLAN_KEEPALIVE: - case HCI_EVNT_WLAN_UNSOL_CONNECT: - case HCI_EVNT_WLAN_UNSOL_DISCONNECT: - case HCI_EVNT_WLAN_UNSOL_INIT: - case HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE: - - if( tSLInformation.sWlanCB ) - { - tSLInformation.sWlanCB(event_type, 0, 0); - } - break; - - case HCI_EVNT_WLAN_UNSOL_DHCP: - { - unsigned char params[NETAPP_IPCONFIG_MAC_OFFSET + 1]; // extra byte is for the status - unsigned char *recParams = params; - - data = (char*)(event_hdr) + HCI_EVENT_HEADER_SIZE; - - //Read IP address - STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); - data += 4; - //Read subnet - STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); - data += 4; - //Read default GW - STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); - data += 4; - //Read DHCP server - STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); - data += 4; - //Read DNS server - STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); - // read the status - STREAM_TO_UINT8(event_hdr, HCI_EVENT_STATUS_OFFSET, *recParams); - - - if( tSLInformation.sWlanCB ) - { - tSLInformation.sWlanCB(event_type, (char *)params, sizeof(params)); - } - } - break; - - case HCI_EVNT_WLAN_ASYNC_PING_REPORT: - { - netapp_pingreport_args_t params; - data = (char*)(event_hdr) + HCI_EVENT_HEADER_SIZE; - STREAM_TO_UINT32(data, NETAPP_PING_PACKETS_SENT_OFFSET, params.packets_sent); - STREAM_TO_UINT32(data, NETAPP_PING_PACKETS_RCVD_OFFSET, params.packets_received); - STREAM_TO_UINT32(data, NETAPP_PING_MIN_RTT_OFFSET, params.min_round_time); - STREAM_TO_UINT32(data, NETAPP_PING_MAX_RTT_OFFSET, params.max_round_time); - STREAM_TO_UINT32(data, NETAPP_PING_AVG_RTT_OFFSET, params.avg_round_time); - - if( tSLInformation.sWlanCB ) - { - tSLInformation.sWlanCB(event_type, (char *)¶ms, sizeof(params)); - } - } - break; - case HCI_EVNT_BSD_TCP_CLOSE_WAIT: - { - if( tSLInformation.sWlanCB ) - { - tSLInformation.sWlanCB(event_type, NULL, 0); - } - } - break; - - //'default' case which means "event not supported" - default: - return (0); - } - return(1); - } - - if ((event_type == HCI_EVNT_SEND) || (event_type == HCI_EVNT_SENDTO) - || (event_type == HCI_EVNT_WRITE)) - { - char *pArg; - long status; - - pArg = M_BSD_RESP_PARAMS_OFFSET(event_hdr); - STREAM_TO_UINT32(pArg, BSD_RSP_PARAMS_STATUS_OFFSET,status); - - if (ERROR_SOCKET_INACTIVE == status) - { - // The only synchronous event that can come from SL device in form of - // command complete is "Command Complete" on data sent, in case SL device - // was unable to transmit - STREAM_TO_UINT8(event_hdr, HCI_EVENT_STATUS_OFFSET, tSLInformation.slTransmitDataError); - update_socket_active_status(M_BSD_RESP_PARAMS_OFFSET(event_hdr)); - - return (1); - } - else - return (0); - } - - return(0); -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** -long -hci_unsolicited_event_handler(void) -{ - unsigned long res = 0; - unsigned char *pucReceivedData; - - if (tSLInformation.usEventOrDataReceived != 0) - { - pucReceivedData = (tSLInformation.pucReceivedData); - - if (*pucReceivedData == HCI_TYPE_EVNT) - { - - // In case unsolicited event received - here the handling finished - if (hci_unsol_event_handler((char *)pucReceivedData) == 1) - { - - // There was an unsolicited event received - we can release the buffer - // and clean the event received - tSLInformation.usEventOrDataReceived = 0; - - res = 1; - SpiResumeSpi(); - } - } - } - - return res; -} - -//***************************************************************************** -// -//! set_socket_active_status -//! -//! @param Sd -//! @param Status -//! @return none -//! -//! @brief Check if the socket ID and status are valid and set -//! accordingly the global socket status -// -//***************************************************************************** -void set_socket_active_status(long Sd, long Status) -{ - if(M_IS_VALID_SD(Sd) && M_IS_VALID_STATUS(Status)) - { - socket_active_status &= ~(1 << Sd); /* clean socket's mask */ - socket_active_status |= (Status << Sd); /* set new socket's mask */ - } -} - - -//***************************************************************************** -// -//! hci_event_unsol_flowcontrol_handler -//! -//! @param pEvent pointer to the string contains parameters for IPERF -//! @return ESUCCESS if successful, EFAIL if an error occurred -//! -//! @brief Called in case unsolicited event from type -//! HCI_EVNT_DATA_UNSOL_FREE_BUFF has received. -//! Keep track on the number of packets transmitted and update the -//! number of free buffer in the SL device. -// -//***************************************************************************** -long -hci_event_unsol_flowcontrol_handler(char *pEvent) -{ - - long temp, value; - unsigned short i; - unsigned short pusNumberOfHandles=0; - char *pReadPayload; - - STREAM_TO_UINT16((char *)pEvent,HCI_EVENT_HEADER_SIZE,pusNumberOfHandles); - pReadPayload = ((char *)pEvent + - HCI_EVENT_HEADER_SIZE + sizeof(pusNumberOfHandles)); - temp = 0; - - for(i = 0; i < pusNumberOfHandles ; i++) - { - STREAM_TO_UINT16(pReadPayload, FLOW_CONTROL_EVENT_FREE_BUFFS_OFFSET, value); - temp += value; - pReadPayload += FLOW_CONTROL_EVENT_SIZE; - } - - tSLInformation.usNumberOfFreeBuffers += temp; - tSLInformation.NumberOfReleasedPackets += temp; - - return(ESUCCESS); -} - -//***************************************************************************** -// -//! get_socket_active_status -//! -//! @param Sd Socket IS -//! @return Current status of the socket. -//! -//! @brief Retrieve socket status -// -//***************************************************************************** - -long -get_socket_active_status(long Sd) -{ - if(M_IS_VALID_SD(Sd)) - { - return (socket_active_status & (1 << Sd)) ? SOCKET_STATUS_INACTIVE : SOCKET_STATUS_ACTIVE; - } - return SOCKET_STATUS_INACTIVE; -} - -//***************************************************************************** -// -//! update_socket_active_status -//! -//! @param resp_params Socket IS -//! @return Current status of the socket. -//! -//! @brief Retrieve socket status -// -//***************************************************************************** -void -update_socket_active_status(char *resp_params) -{ - long status, sd; - - STREAM_TO_UINT32(resp_params, BSD_RSP_PARAMS_SOCKET_OFFSET,sd); - STREAM_TO_UINT32(resp_params, BSD_RSP_PARAMS_STATUS_OFFSET,status); - - if(ERROR_SOCKET_INACTIVE == status) - { - set_socket_active_status(sd, SOCKET_STATUS_INACTIVE); - } -} - - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -void -SimpleLinkWaitEvent(unsigned short usOpcode, void *pRetParams) -{ - // In the blocking implementation the control to caller will be returned only - // after the end of current transaction - tSLInformation.usRxEventOpcode = usOpcode; - printf("Going to call hci_event_handler...\n"); - hci_event_handler(pRetParams, 0, 0); -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -void -SimpleLinkWaitData(unsigned char *pBuf, unsigned char *from, - unsigned char *fromlen) -{ - // In the blocking implementation the control to caller will be returned only - // after the end of current transaction, i.e. only after data will be received - tSLInformation.usRxDataPending = 1; - hci_event_handler(pBuf, from, fromlen); -} - -//***************************************************************************** -// -// Close the Doxygen group. -//! @} -// -//***************************************************************************** +/***************************************************************************** +* +* evnt_handler.c - 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. +* +*****************************************************************************/ +//***************************************************************************** +// +//! \addtogroup evnt_handler_api +//! @{ +// +//****************************************************************************** + +//****************************************************************************** +// INCLUDE FILES +//****************************************************************************** + +#include +#include +#include +#include +#include +#include +#include +#include + + + +//***************************************************************************** +// COMMON DEFINES +//***************************************************************************** + +#define FLOW_CONTROL_EVENT_HANDLE_OFFSET (0) +#define FLOW_CONTROL_EVENT_BLOCK_MODE_OFFSET (1) +#define FLOW_CONTROL_EVENT_FREE_BUFFS_OFFSET (2) +#define FLOW_CONTROL_EVENT_SIZE (4) + +#define BSD_RSP_PARAMS_SOCKET_OFFSET (0) +#define BSD_RSP_PARAMS_STATUS_OFFSET (4) + +#define GET_HOST_BY_NAME_RETVAL_OFFSET (0) +#define GET_HOST_BY_NAME_ADDR_OFFSET (4) + +#define ACCEPT_SD_OFFSET (0) +#define ACCEPT_RETURN_STATUS_OFFSET (4) +#define ACCEPT_ADDRESS__OFFSET (8) + +#define SL_RECEIVE_SD_OFFSET (0) +#define SL_RECEIVE_NUM_BYTES_OFFSET (4) +#define SL_RECEIVE__FLAGS__OFFSET (8) + + +#define SELECT_STATUS_OFFSET (0) +#define SELECT_READFD_OFFSET (4) +#define SELECT_WRITEFD_OFFSET (8) +#define SELECT_EXFD_OFFSET (12) + + +#define NETAPP_IPCONFIG_IP_OFFSET (0) +#define NETAPP_IPCONFIG_SUBNET_OFFSET (4) +#define NETAPP_IPCONFIG_GW_OFFSET (8) +#define NETAPP_IPCONFIG_DHCP_OFFSET (12) +#define NETAPP_IPCONFIG_DNS_OFFSET (16) +#define NETAPP_IPCONFIG_MAC_OFFSET (20) +#define NETAPP_IPCONFIG_SSID_OFFSET (26) + +#define NETAPP_IPCONFIG_IP_LENGTH (4) +#define NETAPP_IPCONFIG_MAC_LENGTH (6) +#define NETAPP_IPCONFIG_SSID_LENGTH (32) + + +#define NETAPP_PING_PACKETS_SENT_OFFSET (0) +#define NETAPP_PING_PACKETS_RCVD_OFFSET (4) +#define NETAPP_PING_MIN_RTT_OFFSET (8) +#define NETAPP_PING_MAX_RTT_OFFSET (12) +#define NETAPP_PING_AVG_RTT_OFFSET (16) + +#define GET_SCAN_RESULTS_TABlE_COUNT_OFFSET (0) +#define GET_SCAN_RESULTS_SCANRESULT_STATUS_OFFSET (4) +#define GET_SCAN_RESULTS_ISVALID_TO_SSIDLEN_OFFSET (8) +#define GET_SCAN_RESULTS_FRAME_TIME_OFFSET (10) +#define GET_SCAN_RESULTS_SSID_MAC_LENGTH (38) + + + +//***************************************************************************** +// GLOBAL VARAIABLES +//***************************************************************************** + +unsigned long socket_active_status = SOCKET_STATUS_INIT_VAL; + + +//***************************************************************************** +// Prototypes for the static functions +//***************************************************************************** + +static long hci_event_unsol_flowcontrol_handler(char *pEvent); + +static void update_socket_active_status(char *resp_params); + + +//***************************************************************************** +// +//! hci_unsol_handle_patch_request +//! +//! @param event_hdr event header +//! +//! @return none +//! +//! @brief Handle unsolicited event from type patch request +// +//***************************************************************************** +void hci_unsol_handle_patch_request(char *event_hdr) +{ + char *params = (char *)(event_hdr) + HCI_EVENT_HEADER_SIZE; + unsigned long ucLength = 0; + char *patch; + + switch (*params) + { + case HCI_EVENT_PATCHES_DRV_REQ: + + if (tSLInformation.sDriverPatches) + { + patch = tSLInformation.sDriverPatches(&ucLength); + + if (patch) + { + hci_patch_send(HCI_EVENT_PATCHES_DRV_REQ, + tSLInformation.pucTxCommandBuffer, patch, ucLength); + return; + } + } + + // Send 0 length Patches response event + hci_patch_send(HCI_EVENT_PATCHES_DRV_REQ, + tSLInformation.pucTxCommandBuffer, 0, 0); + break; + + case HCI_EVENT_PATCHES_FW_REQ: + + if (tSLInformation.sFWPatches) + { + patch = tSLInformation.sFWPatches(&ucLength); + + // Build and send a patch + if (patch) + { + hci_patch_send(HCI_EVENT_PATCHES_FW_REQ, + tSLInformation.pucTxCommandBuffer, patch, ucLength); + return; + } + } + + // Send 0 length Patches response event + hci_patch_send(HCI_EVENT_PATCHES_FW_REQ, + tSLInformation.pucTxCommandBuffer, 0, 0); + break; + + case HCI_EVENT_PATCHES_BOOTLOAD_REQ: + + if (tSLInformation.sBootLoaderPatches) + { + patch = tSLInformation.sBootLoaderPatches(&ucLength); + + if (patch) + { + hci_patch_send(HCI_EVENT_PATCHES_BOOTLOAD_REQ, + tSLInformation.pucTxCommandBuffer, patch, ucLength); + return; + } + } + + // Send 0 length Patches response event + hci_patch_send(HCI_EVENT_PATCHES_BOOTLOAD_REQ, + tSLInformation.pucTxCommandBuffer, 0, 0); + break; + } +} + + + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + + +uint8_t * +hci_event_handler(void *pRetParams, uint8_t *from, uint8_t *fromlen) +{ + uint8_t *pucReceivedData, ucArgsize; + uint16_t usLength; + uint8_t *pucReceivedParams; + uint16_t usReceivedEventOpcode = 0; + unsigned long retValue32; + uint8_t * RecvParams; + uint8_t *RetParams; + + + while (1) + { + if (tSLInformation.usEventOrDataReceived != 0) + { + pucReceivedData = (tSLInformation.pucReceivedData); + + if (*pucReceivedData == HCI_TYPE_EVNT) + { + // Event Received + STREAM_TO_UINT16((char *)pucReceivedData, HCI_EVENT_OPCODE_OFFSET, + usReceivedEventOpcode); + pucReceivedParams = pucReceivedData + HCI_EVENT_HEADER_SIZE; + RecvParams = pucReceivedParams; + RetParams = (uint8_t *)pRetParams; + + // In case unsolicited event received - here the handling finished + if (hci_unsol_event_handler((char *)pucReceivedData) == 0) + { + STREAM_TO_UINT8(pucReceivedData, HCI_DATA_LENGTH_OFFSET, usLength); + + switch(usReceivedEventOpcode) + { + case HCI_CMND_READ_BUFFER_SIZE: + { + STREAM_TO_UINT8((char *)pucReceivedParams, 0, + tSLInformation.usNumberOfFreeBuffers); + STREAM_TO_UINT16((char *)pucReceivedParams, 1, + tSLInformation.usSlBufferLength); + } + break; + + case HCI_CMND_WLAN_CONFIGURE_PATCH: + case HCI_NETAPP_DHCP: + case HCI_NETAPP_PING_SEND: + case HCI_NETAPP_PING_STOP: + case HCI_NETAPP_ARP_FLUSH: + case HCI_NETAPP_SET_DEBUG_LEVEL: + case HCI_NETAPP_SET_TIMERS: + case HCI_EVNT_NVMEM_READ: + case HCI_EVNT_NVMEM_CREATE_ENTRY: + case HCI_CMND_NVMEM_WRITE_PATCH: + case HCI_NETAPP_PING_REPORT: + case HCI_EVNT_MDNS_ADVERTISE: + + STREAM_TO_UINT8(pucReceivedData, HCI_EVENT_STATUS_OFFSET + ,*(uint8_t *)pRetParams); + break; + + case HCI_CMND_SETSOCKOPT: + case HCI_CMND_WLAN_CONNECT: + case HCI_CMND_WLAN_IOCTL_STATUSGET: + case HCI_EVNT_WLAN_IOCTL_ADD_PROFILE: + case HCI_CMND_WLAN_IOCTL_DEL_PROFILE: + case HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY: + case HCI_CMND_WLAN_IOCTL_SET_SCANPARAM: + case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START: + case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP: + case HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX: + case HCI_CMND_EVENT_MASK: + case HCI_EVNT_WLAN_DISCONNECT: + case HCI_EVNT_SOCKET: + case HCI_EVNT_BIND: + case HCI_CMND_LISTEN: + case HCI_EVNT_CLOSE_SOCKET: + case HCI_EVNT_CONNECT: + case HCI_EVNT_NVMEM_WRITE: + + STREAM_TO_UINT32((char *)pucReceivedParams,0 + ,*(unsigned long *)pRetParams); + break; + + case HCI_EVNT_READ_SP_VERSION: + + STREAM_TO_UINT8(pucReceivedData, HCI_EVENT_STATUS_OFFSET + ,*(uint8_t *)pRetParams); + pRetParams = ((char *)pRetParams) + 1; + STREAM_TO_UINT32((char *)pucReceivedParams, 0, retValue32); + UINT32_TO_STREAM((uint8_t *)pRetParams, retValue32); + break; + + case HCI_EVNT_BSD_GETHOSTBYNAME: + + STREAM_TO_UINT32((char *)pucReceivedParams + ,GET_HOST_BY_NAME_RETVAL_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams + ,GET_HOST_BY_NAME_ADDR_OFFSET,*(unsigned long *)pRetParams); + break; + + case HCI_EVNT_ACCEPT: + { + STREAM_TO_UINT32((char *)pucReceivedParams,ACCEPT_SD_OFFSET + ,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams + ,ACCEPT_RETURN_STATUS_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + + //This argument returns in network order + memcpy((uint8_t *)pRetParams, + pucReceivedParams + ACCEPT_ADDRESS__OFFSET, sizeof(sockaddr)); + break; + } + + case HCI_EVNT_RECV: + case HCI_EVNT_RECVFROM: + { + STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_SD_OFFSET ,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_NUM_BYTES_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE__FLAGS__OFFSET,*(unsigned long *)pRetParams); + + if(((tBsdReadReturnParams *)pRetParams)->iNumberOfBytes == ERROR_SOCKET_INACTIVE) + { + set_socket_active_status(((tBsdReadReturnParams *)pRetParams)->iSocketDescriptor,SOCKET_STATUS_INACTIVE); + } + break; + } + + case HCI_EVNT_SEND: + case HCI_EVNT_SENDTO: + { + STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_SD_OFFSET ,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams,SL_RECEIVE_NUM_BYTES_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + + break; + } + + case HCI_EVNT_SELECT: + { + STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_STATUS_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_READFD_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_WRITEFD_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams,SELECT_EXFD_OFFSET,*(unsigned long *)pRetParams); + break; + } + + case HCI_CMND_GETSOCKOPT: + + STREAM_TO_UINT8(pucReceivedData, HCI_EVENT_STATUS_OFFSET,((tBsdGetSockOptReturnParams *)pRetParams)->iStatus); + //This argument returns in network order + memcpy((uint8_t *)pRetParams, pucReceivedParams, 4); + break; + + case HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS: + + STREAM_TO_UINT32((char *)pucReceivedParams,GET_SCAN_RESULTS_TABlE_COUNT_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT32((char *)pucReceivedParams,GET_SCAN_RESULTS_SCANRESULT_STATUS_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 4; + STREAM_TO_UINT16((char *)pucReceivedParams,GET_SCAN_RESULTS_ISVALID_TO_SSIDLEN_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 2; + STREAM_TO_UINT16((char *)pucReceivedParams,GET_SCAN_RESULTS_FRAME_TIME_OFFSET,*(unsigned long *)pRetParams); + pRetParams = ((char *)pRetParams) + 2; + memcpy((uint8_t *)pRetParams, + (char *)(pucReceivedParams + GET_SCAN_RESULTS_FRAME_TIME_OFFSET + 2), + GET_SCAN_RESULTS_SSID_MAC_LENGTH); + break; + + case HCI_CMND_SIMPLE_LINK_START: + break; + + case HCI_NETAPP_IPCONFIG: + + //Read IP address + STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); + RecvParams += 4; + + //Read subnet + STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); + RecvParams += 4; + + //Read default GW + STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); + RecvParams += 4; + + //Read DHCP server + STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); + RecvParams += 4; + + //Read DNS server + STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_IP_LENGTH); + RecvParams += 4; + + //Read Mac address + STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_MAC_LENGTH); + RecvParams += 6; + + //Read SSID + STREAM_TO_STREAM(RecvParams,RetParams,NETAPP_IPCONFIG_SSID_LENGTH); + + } + } + + if (usReceivedEventOpcode == tSLInformation.usRxEventOpcode) + { + tSLInformation.usRxEventOpcode = 0; + } + } + else + { + pucReceivedParams = pucReceivedData; + STREAM_TO_UINT8((char *)pucReceivedData, HCI_PACKET_ARGSIZE_OFFSET, ucArgsize); + + STREAM_TO_UINT16((char *)pucReceivedData, HCI_PACKET_LENGTH_OFFSET, usLength); + + // Data received: note that the only case where from and from length + // are not null is in recv from, so fill the args accordingly + if (from) + { + STREAM_TO_UINT32((char *)(pucReceivedData + HCI_DATA_HEADER_SIZE), BSD_RECV_FROM_FROMLEN_OFFSET, *(unsigned long *)fromlen); + memcpy(from, (pucReceivedData + HCI_DATA_HEADER_SIZE + BSD_RECV_FROM_FROM_OFFSET) ,*fromlen); + } + + memcpy(pRetParams, pucReceivedParams + HCI_DATA_HEADER_SIZE + ucArgsize, + usLength - ucArgsize); + + tSLInformation.usRxDataPending = 0; + } + + tSLInformation.usEventOrDataReceived = 0; + + SpiResumeSpi(); + + // Since we are going to TX - we need to handle this event after the + // ResumeSPi since we need interrupts + if ((*pucReceivedData == HCI_TYPE_EVNT) && + (usReceivedEventOpcode == HCI_EVNT_PATCHES_REQ)) + { + hci_unsol_handle_patch_request((char *)pucReceivedData); + } + + if ((tSLInformation.usRxEventOpcode == 0) && (tSLInformation.usRxDataPending == 0)) + { + return NULL; + } + } + } + +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** +long +hci_unsol_event_handler(char *event_hdr) +{ + char * data = NULL; + long event_type; + unsigned long NumberOfReleasedPackets; + unsigned long NumberOfSentPackets; + + STREAM_TO_UINT16(event_hdr, HCI_EVENT_OPCODE_OFFSET,event_type); + + if (event_type & HCI_EVNT_UNSOL_BASE) + { + switch(event_type) + { + + case HCI_EVNT_DATA_UNSOL_FREE_BUFF: + { + hci_event_unsol_flowcontrol_handler(event_hdr); + + NumberOfReleasedPackets = tSLInformation.NumberOfReleasedPackets; + NumberOfSentPackets = tSLInformation.NumberOfSentPackets; + + if (NumberOfReleasedPackets == NumberOfSentPackets) + { + if (tSLInformation.InformHostOnTxComplete) + { + tSLInformation.sWlanCB(HCI_EVENT_CC3000_CAN_SHUT_DOWN, NULL, 0); + } + } + return 1; + + } + } + } + + if(event_type & HCI_EVNT_WLAN_UNSOL_BASE) + { + switch(event_type) + { + case HCI_EVNT_WLAN_KEEPALIVE: + case HCI_EVNT_WLAN_UNSOL_CONNECT: + case HCI_EVNT_WLAN_UNSOL_DISCONNECT: + case HCI_EVNT_WLAN_UNSOL_INIT: + case HCI_EVNT_WLAN_ASYNC_SIMPLE_CONFIG_DONE: + + if( tSLInformation.sWlanCB ) + { + tSLInformation.sWlanCB(event_type, 0, 0); + } + break; + + case HCI_EVNT_WLAN_UNSOL_DHCP: + { + uint8_t params[NETAPP_IPCONFIG_MAC_OFFSET + 1]; // extra byte is for the status + uint8_t *recParams = params; + + data = (char*)(event_hdr) + HCI_EVENT_HEADER_SIZE; + + //Read IP address + STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); + data += 4; + //Read subnet + STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); + data += 4; + //Read default GW + STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); + data += 4; + //Read DHCP server + STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); + data += 4; + //Read DNS server + STREAM_TO_STREAM(data,recParams,NETAPP_IPCONFIG_IP_LENGTH); + // read the status + STREAM_TO_UINT8(event_hdr, HCI_EVENT_STATUS_OFFSET, *recParams); + + + if( tSLInformation.sWlanCB ) + { + tSLInformation.sWlanCB(event_type, (char *)params, sizeof(params)); + } + } + break; + + case HCI_EVNT_WLAN_ASYNC_PING_REPORT: + { + netapp_pingreport_args_t params; + data = (char*)(event_hdr) + HCI_EVENT_HEADER_SIZE; + STREAM_TO_UINT32(data, NETAPP_PING_PACKETS_SENT_OFFSET, params.packets_sent); + STREAM_TO_UINT32(data, NETAPP_PING_PACKETS_RCVD_OFFSET, params.packets_received); + STREAM_TO_UINT32(data, NETAPP_PING_MIN_RTT_OFFSET, params.min_round_time); + STREAM_TO_UINT32(data, NETAPP_PING_MAX_RTT_OFFSET, params.max_round_time); + STREAM_TO_UINT32(data, NETAPP_PING_AVG_RTT_OFFSET, params.avg_round_time); + + if( tSLInformation.sWlanCB ) + { + tSLInformation.sWlanCB(event_type, (char *)¶ms, sizeof(params)); + } + } + break; + case HCI_EVNT_BSD_TCP_CLOSE_WAIT: + { + if( tSLInformation.sWlanCB ) + { + tSLInformation.sWlanCB(event_type, NULL, 0); + } + } + break; + + //'default' case which means "event not supported" + default: + return (0); + } + return(1); + } + + if ((event_type == HCI_EVNT_SEND) || (event_type == HCI_EVNT_SENDTO) + || (event_type == HCI_EVNT_WRITE)) + { + char *pArg; + long status; + + pArg = M_BSD_RESP_PARAMS_OFFSET(event_hdr); + STREAM_TO_UINT32(pArg, BSD_RSP_PARAMS_STATUS_OFFSET,status); + + if (ERROR_SOCKET_INACTIVE == status) + { + // The only synchronous event that can come from SL device in form of + // command complete is "Command Complete" on data sent, in case SL device + // was unable to transmit + STREAM_TO_UINT8(event_hdr, HCI_EVENT_STATUS_OFFSET, tSLInformation.slTransmitDataError); + update_socket_active_status(M_BSD_RESP_PARAMS_OFFSET(event_hdr)); + + return (1); + } + else + return (0); + } + + return(0); +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** +long +hci_unsolicited_event_handler(void) +{ + unsigned long res = 0; + uint8_t *pucReceivedData; + + if (tSLInformation.usEventOrDataReceived != 0) + { + pucReceivedData = (tSLInformation.pucReceivedData); + + if (*pucReceivedData == HCI_TYPE_EVNT) + { + + // In case unsolicited event received - here the handling finished + if (hci_unsol_event_handler((char *)pucReceivedData) == 1) + { + + // There was an unsolicited event received - we can release the buffer + // and clean the event received + tSLInformation.usEventOrDataReceived = 0; + + res = 1; + SpiResumeSpi(); + } + } + } + + return res; +} + +//***************************************************************************** +// +//! set_socket_active_status +//! +//! @param Sd +//! @param Status +//! @return none +//! +//! @brief Check if the socket ID and status are valid and set +//! accordingly the global socket status +// +//***************************************************************************** +void set_socket_active_status(long Sd, long Status) +{ + if(M_IS_VALID_SD(Sd) && M_IS_VALID_STATUS(Status)) + { + socket_active_status &= ~(1 << Sd); /* clean socket's mask */ + socket_active_status |= (Status << Sd); /* set new socket's mask */ + } +} + + +//***************************************************************************** +// +//! hci_event_unsol_flowcontrol_handler +//! +//! @param pEvent pointer to the string contains parameters for IPERF +//! @return ESUCCESS if successful, EFAIL if an error occurred +//! +//! @brief Called in case unsolicited event from type +//! HCI_EVNT_DATA_UNSOL_FREE_BUFF has received. +//! Keep track on the number of packets transmitted and update the +//! number of free buffer in the SL device. +// +//***************************************************************************** +long +hci_event_unsol_flowcontrol_handler(char *pEvent) +{ + + long temp, value; + uint16_t i; + uint16_t pusNumberOfHandles=0; + char *pReadPayload; + + STREAM_TO_UINT16((char *)pEvent,HCI_EVENT_HEADER_SIZE,pusNumberOfHandles); + pReadPayload = ((char *)pEvent + + HCI_EVENT_HEADER_SIZE + sizeof(pusNumberOfHandles)); + temp = 0; + + for(i = 0; i < pusNumberOfHandles ; i++) + { + STREAM_TO_UINT16(pReadPayload, FLOW_CONTROL_EVENT_FREE_BUFFS_OFFSET, value); + temp += value; + pReadPayload += FLOW_CONTROL_EVENT_SIZE; + } + + tSLInformation.usNumberOfFreeBuffers += temp; + tSLInformation.NumberOfReleasedPackets += temp; + + return(ESUCCESS); +} + +//***************************************************************************** +// +//! get_socket_active_status +//! +//! @param Sd Socket IS +//! @return Current status of the socket. +//! +//! @brief Retrieve socket status +// +//***************************************************************************** + +long +get_socket_active_status(long Sd) +{ + if(M_IS_VALID_SD(Sd)) + { + return (socket_active_status & (1 << Sd)) ? SOCKET_STATUS_INACTIVE : SOCKET_STATUS_ACTIVE; + } + return SOCKET_STATUS_INACTIVE; +} + +//***************************************************************************** +// +//! update_socket_active_status +//! +//! @param resp_params Socket IS +//! @return Current status of the socket. +//! +//! @brief Retrieve socket status +// +//***************************************************************************** +void +update_socket_active_status(char *resp_params) +{ + long status, sd; + + STREAM_TO_UINT32(resp_params, BSD_RSP_PARAMS_SOCKET_OFFSET,sd); + STREAM_TO_UINT32(resp_params, BSD_RSP_PARAMS_STATUS_OFFSET,status); + + if(ERROR_SOCKET_INACTIVE == status) + { + set_socket_active_status(sd, SOCKET_STATUS_INACTIVE); + } +} + + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +void +SimpleLinkWaitEvent(uint16_t usOpcode, void *pRetParams) +{ + // In the blocking implementation the control to caller will be returned only + // after the end of current transaction + tSLInformation.usRxEventOpcode = usOpcode; + hci_event_handler(pRetParams, 0, 0); +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +void +SimpleLinkWaitData(uint8_t *pBuf, uint8_t *from, + uint8_t *fromlen) +{ + // In the blocking implementation the control to caller will be returned only + // after the end of current transaction, i.e. only after data will be received + tSLInformation.usRxDataPending = 1; + hci_event_handler(pBuf, from, fromlen); +} + +//***************************************************************************** +// +// Close the Doxygen group. +//! @} +// +//***************************************************************************** diff --git a/nuttx/drivers/wireless/cc3000/hci.c b/nuttx/drivers/wireless/cc3000/hci.c index 38e126f3c..c238b2772 100644 --- a/nuttx/drivers/wireless/cc3000/hci.c +++ b/nuttx/drivers/wireless/cc3000/hci.c @@ -1,230 +1,230 @@ -/***************************************************************************** -* -* hci.c - 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. -* -*****************************************************************************/ - -//***************************************************************************** -// -//! \addtogroup hci_app -//! @{ -// -//***************************************************************************** - -#include -#include -#include -#include -#include -#include - -#define SL_PATCH_PORTION_SIZE (1000) - - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** -unsigned short -hci_command_send(unsigned short usOpcode, unsigned char *pucBuff, - unsigned char ucArgsLength) -{ - unsigned char *stream; - - stream = (pucBuff + SPI_HEADER_SIZE); - - UINT8_TO_STREAM(stream, HCI_TYPE_CMND); - stream = UINT16_TO_STREAM(stream, usOpcode); - UINT8_TO_STREAM(stream, ucArgsLength); - - //Update the opcode of the event we will be waiting for - SpiWrite(pucBuff, ucArgsLength + SIMPLE_LINK_HCI_CMND_HEADER_SIZE); - - return(0); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** -long -hci_data_send(unsigned char ucOpcode, - unsigned char *ucArgs, - unsigned short usArgsLength, - unsigned short usDataLength, - const unsigned char *ucTail, - unsigned short usTailLength) -{ - unsigned char *stream; - - stream = ((ucArgs) + SPI_HEADER_SIZE); - - UINT8_TO_STREAM(stream, HCI_TYPE_DATA); - UINT8_TO_STREAM(stream, ucOpcode); - UINT8_TO_STREAM(stream, usArgsLength); - stream = UINT16_TO_STREAM(stream, usArgsLength + usDataLength + usTailLength); - - // Send the packet over the SPI - SpiWrite(ucArgs, SIMPLE_LINK_HCI_DATA_HEADER_SIZE + usArgsLength + usDataLength + usTailLength); - - return(ESUCCESS); -} - - -//***************************************************************************** -// -//! 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 Prepeare HCI header and initiate an HCI data write operation -// -//***************************************************************************** -void hci_data_command_send(unsigned short usOpcode, unsigned char *pucBuff, - unsigned char ucArgsLength,unsigned short ucDataLength) -{ - unsigned char *stream = (pucBuff + SPI_HEADER_SIZE); - - UINT8_TO_STREAM(stream, HCI_TYPE_DATA); - UINT8_TO_STREAM(stream, usOpcode); - UINT8_TO_STREAM(stream, ucArgsLength); - stream = UINT16_TO_STREAM(stream, ucArgsLength + ucDataLength); - - // Send the command over SPI on data channel - SpiWrite(pucBuff, ucArgsLength + ucDataLength + SIMPLE_LINK_HCI_DATA_CMND_HEADER_SIZE); - - return; -} - -//***************************************************************************** -// -//! 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 Prepeare HCI header and initiate an HCI patch write operation -// -//***************************************************************************** -void -hci_patch_send(unsigned char ucOpcode, unsigned char *pucBuff, char *patch, unsigned short usDataLength) -{ - unsigned char *data_ptr = (pucBuff + SPI_HEADER_SIZE); - unsigned short usTransLength; - unsigned char *stream = (pucBuff + SPI_HEADER_SIZE); - - UINT8_TO_STREAM(stream, HCI_TYPE_PATCH); - UINT8_TO_STREAM(stream, ucOpcode); - stream = UINT16_TO_STREAM(stream, usDataLength + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE); - - if (usDataLength <= SL_PATCH_PORTION_SIZE) - { - UINT16_TO_STREAM(stream, usDataLength); - stream = UINT16_TO_STREAM(stream, usDataLength); - memcpy((pucBuff + SPI_HEADER_SIZE) + HCI_PATCH_HEADER_SIZE, patch, usDataLength); - - // Update the opcode of the event we will be waiting for - SpiWrite(pucBuff, usDataLength + HCI_PATCH_HEADER_SIZE); - } - else - { - - usTransLength = (usDataLength/SL_PATCH_PORTION_SIZE); - UINT16_TO_STREAM(stream, usDataLength + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE + usTransLength*SIMPLE_LINK_HCI_PATCH_HEADER_SIZE); - stream = UINT16_TO_STREAM(stream, SL_PATCH_PORTION_SIZE); - memcpy(pucBuff + SPI_HEADER_SIZE + HCI_PATCH_HEADER_SIZE, patch, SL_PATCH_PORTION_SIZE); - usDataLength -= SL_PATCH_PORTION_SIZE; - patch += SL_PATCH_PORTION_SIZE; - - // Update the opcode of the event we will be waiting for - SpiWrite(pucBuff, SL_PATCH_PORTION_SIZE + HCI_PATCH_HEADER_SIZE); - - while (usDataLength) - { - if (usDataLength <= SL_PATCH_PORTION_SIZE) - { - usTransLength = usDataLength; - usDataLength = 0; - - } - else - { - usTransLength = SL_PATCH_PORTION_SIZE; - usDataLength -= usTransLength; - } - - *(unsigned short *)data_ptr = usTransLength; - memcpy(data_ptr + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE, patch, usTransLength); - patch += usTransLength; - - // Update the opcode of the event we will be waiting for - SpiWrite((unsigned char *)data_ptr, usTransLength + sizeof(usTransLength)); - } - } -} - -//***************************************************************************** -// -// Close the Doxygen group. -//! @} -// -// -//***************************************************************************** +/***************************************************************************** +* +* hci.c - 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. +* +*****************************************************************************/ + +//***************************************************************************** +// +//! \addtogroup hci_app +//! @{ +// +//***************************************************************************** + +#include +#include +#include +#include +#include +#include + +#define SL_PATCH_PORTION_SIZE (1000) + + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** +uint16_t +hci_command_send(uint16_t usOpcode, uint8_t *pucBuff, + uint8_t ucArgsLength) +{ + uint8_t *stream; + + stream = (pucBuff + SPI_HEADER_SIZE); + + UINT8_TO_STREAM(stream, HCI_TYPE_CMND); + stream = UINT16_TO_STREAM(stream, usOpcode); + UINT8_TO_STREAM(stream, ucArgsLength); + + //Update the opcode of the event we will be waiting for + SpiWrite(pucBuff, ucArgsLength + SIMPLE_LINK_HCI_CMND_HEADER_SIZE); + + return(0); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** +long +hci_data_send(uint8_t ucOpcode, + uint8_t *ucArgs, + uint16_t usArgsLength, + uint16_t usDataLength, + const uint8_t *ucTail, + uint16_t usTailLength) +{ + uint8_t *stream; + + stream = ((ucArgs) + SPI_HEADER_SIZE); + + UINT8_TO_STREAM(stream, HCI_TYPE_DATA); + UINT8_TO_STREAM(stream, ucOpcode); + UINT8_TO_STREAM(stream, usArgsLength); + stream = UINT16_TO_STREAM(stream, usArgsLength + usDataLength + usTailLength); + + // Send the packet over the SPI + SpiWrite(ucArgs, SIMPLE_LINK_HCI_DATA_HEADER_SIZE + usArgsLength + usDataLength + usTailLength); + + return(ESUCCESS); +} + + +//***************************************************************************** +// +//! 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 Prepeare HCI header and initiate an HCI data write operation +// +//***************************************************************************** +void hci_data_command_send(uint16_t usOpcode, uint8_t *pucBuff, + uint8_t ucArgsLength,uint16_t ucDataLength) +{ + uint8_t *stream = (pucBuff + SPI_HEADER_SIZE); + + UINT8_TO_STREAM(stream, HCI_TYPE_DATA); + UINT8_TO_STREAM(stream, usOpcode); + UINT8_TO_STREAM(stream, ucArgsLength); + stream = UINT16_TO_STREAM(stream, ucArgsLength + ucDataLength); + + // Send the command over SPI on data channel + SpiWrite(pucBuff, ucArgsLength + ucDataLength + SIMPLE_LINK_HCI_DATA_CMND_HEADER_SIZE); + + return; +} + +//***************************************************************************** +// +//! 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 Prepeare HCI header and initiate an HCI patch write operation +// +//***************************************************************************** +void +hci_patch_send(uint8_t ucOpcode, uint8_t *pucBuff, char *patch, uint16_t usDataLength) +{ + uint8_t *data_ptr = (pucBuff + SPI_HEADER_SIZE); + uint16_t usTransLength; + uint8_t *stream = (pucBuff + SPI_HEADER_SIZE); + + UINT8_TO_STREAM(stream, HCI_TYPE_PATCH); + UINT8_TO_STREAM(stream, ucOpcode); + stream = UINT16_TO_STREAM(stream, usDataLength + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE); + + if (usDataLength <= SL_PATCH_PORTION_SIZE) + { + UINT16_TO_STREAM(stream, usDataLength); + stream = UINT16_TO_STREAM(stream, usDataLength); + memcpy((pucBuff + SPI_HEADER_SIZE) + HCI_PATCH_HEADER_SIZE, patch, usDataLength); + + // Update the opcode of the event we will be waiting for + SpiWrite(pucBuff, usDataLength + HCI_PATCH_HEADER_SIZE); + } + else + { + + usTransLength = (usDataLength/SL_PATCH_PORTION_SIZE); + UINT16_TO_STREAM(stream, usDataLength + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE + usTransLength*SIMPLE_LINK_HCI_PATCH_HEADER_SIZE); + stream = UINT16_TO_STREAM(stream, SL_PATCH_PORTION_SIZE); + memcpy(pucBuff + SPI_HEADER_SIZE + HCI_PATCH_HEADER_SIZE, patch, SL_PATCH_PORTION_SIZE); + usDataLength -= SL_PATCH_PORTION_SIZE; + patch += SL_PATCH_PORTION_SIZE; + + // Update the opcode of the event we will be waiting for + SpiWrite(pucBuff, SL_PATCH_PORTION_SIZE + HCI_PATCH_HEADER_SIZE); + + while (usDataLength) + { + if (usDataLength <= SL_PATCH_PORTION_SIZE) + { + usTransLength = usDataLength; + usDataLength = 0; + + } + else + { + usTransLength = SL_PATCH_PORTION_SIZE; + usDataLength -= usTransLength; + } + + *(uint16_t *)data_ptr = usTransLength; + memcpy(data_ptr + SIMPLE_LINK_HCI_PATCH_HEADER_SIZE, patch, usTransLength); + patch += usTransLength; + + // Update the opcode of the event we will be waiting for + SpiWrite((uint8_t *)data_ptr, usTransLength + sizeof(usTransLength)); + } + } +} + +//***************************************************************************** +// +// Close the Doxygen group. +//! @} +// +// +//***************************************************************************** diff --git a/nuttx/drivers/wireless/cc3000/netapp.c b/nuttx/drivers/wireless/cc3000/netapp.c index 561e499c3..fe00a7254 100644 --- a/nuttx/drivers/wireless/cc3000/netapp.c +++ b/nuttx/drivers/wireless/cc3000/netapp.c @@ -1,459 +1,459 @@ -/***************************************************************************** -* -* netapp.c - 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. -* -*****************************************************************************/ -#include -#include -#include -#include -#include -#include - -#define MIN_TIMER_VAL_SECONDS 20 -#define MIN_TIMER_SET(t) if ((0 != t) && (t < MIN_TIMER_VAL_SECONDS)) \ - { \ - t = MIN_TIMER_VAL_SECONDS; \ - } - - -#define NETAPP_DHCP_PARAMS_LEN (20) -#define NETAPP_SET_TIMER_PARAMS_LEN (20) -#define NETAPP_SET_DEBUG_LEVEL_PARAMS_LEN (4) -#define NETAPP_PING_SEND_PARAMS_LEN (16) - - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** -long netapp_config_mac_adrress(unsigned char * mac) -{ - return nvmem_set_mac_address(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. -//! -//***************************************************************************** -long netapp_dhcp(unsigned long *aucIP, unsigned long *aucSubnetMask,unsigned long *aucDefaultGateway, unsigned long *aucDNSServer) -{ - signed char scRet; - unsigned char *ptr; - unsigned char *args; - - scRet = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - ARRAY_TO_STREAM(args,aucIP,4); - ARRAY_TO_STREAM(args,aucSubnetMask,4); - ARRAY_TO_STREAM(args,aucDefaultGateway,4); - args = UINT32_TO_STREAM(args, 0); - ARRAY_TO_STREAM(args,aucDNSServer,4); - - // Initiate a HCI command - hci_command_send(HCI_NETAPP_DHCP, ptr, NETAPP_DHCP_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_NETAPP_DHCP, &scRet); - - return(scRet); -} - - -//***************************************************************************** -// -//! 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 -long -netapp_timeout_values(unsigned long *aucDHCP, unsigned long *aucARP,unsigned long *aucKeepalive, unsigned long *aucInactivity) -{ - signed char scRet; - unsigned char *ptr; - unsigned char *args; - - scRet = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Set minimal values of timers - MIN_TIMER_SET(*aucDHCP) - MIN_TIMER_SET(*aucARP) - MIN_TIMER_SET(*aucKeepalive) - MIN_TIMER_SET(*aucInactivity) - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, *aucDHCP); - args = UINT32_TO_STREAM(args, *aucARP); - args = UINT32_TO_STREAM(args, *aucKeepalive); - args = UINT32_TO_STREAM(args, *aucInactivity); - - // Initiate a HCI command - hci_command_send(HCI_NETAPP_SET_TIMERS, ptr, NETAPP_SET_TIMER_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_NETAPP_SET_TIMERS, &scRet); - - return(scRet); -} -#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 -long -netapp_ping_send(unsigned long *ip, unsigned long ulPingAttempts, unsigned long ulPingSize, unsigned long ulPingTimeout) -{ - signed char scRet; - unsigned char *ptr, *args; - - scRet = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, *ip); - args = UINT32_TO_STREAM(args, ulPingAttempts); - args = UINT32_TO_STREAM(args, ulPingSize); - args = UINT32_TO_STREAM(args, ulPingTimeout); - - // Initiate a HCI command - hci_command_send(HCI_NETAPP_PING_SEND, ptr, NETAPP_PING_SEND_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_NETAPP_PING_SEND, &scRet); - - return(scRet); -} -#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 -void netapp_ping_report(void) -{ - unsigned char *ptr; - ptr = tSLInformation.pucTxCommandBuffer; - signed char scRet; - - scRet = EFAIL; - - // Initiate a HCI command - hci_command_send(HCI_NETAPP_PING_REPORT, ptr, 0); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_NETAPP_PING_REPORT, &scRet); -} -#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 -long netapp_ping_stop(void) -{ - signed char scRet; - unsigned char *ptr; - - scRet = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - - // Initiate a HCI command - hci_command_send(HCI_NETAPP_PING_STOP, ptr, 0); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_NETAPP_PING_STOP, &scRet); - - return(scRet); -} -#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. -//! -//***************************************************************************** - -#ifndef CC3000_TINY_DRIVER -void netapp_ipconfig( tNetappIpconfigRetArgs * ipconfig ) -{ - unsigned char *ptr; - - ptr = tSLInformation.pucTxCommandBuffer; - - // Initiate a HCI command - hci_command_send(HCI_NETAPP_IPCONFIG, ptr, 0); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_NETAPP_IPCONFIG, ipconfig ); - -} -#else -void netapp_ipconfig( tNetappIpconfigRetArgs * ipconfig ) -{ - -} -#endif - -//***************************************************************************** -// -//! netapp_arp_flush -//! -//! @param none -//! -//! @return none -//! -//! @brief Flushes ARP table -//! -//***************************************************************************** - -#ifndef CC3000_TINY_DRIVER -long netapp_arp_flush(void) -{ - signed char scRet; - unsigned char *ptr; - - scRet = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - - // Initiate a HCI command - hci_command_send(HCI_NETAPP_ARP_FLUSH, ptr, 0); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_NETAPP_ARP_FLUSH, &scRet); - - return(scRet); -} -#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) -{ - signed char scRet; - unsigned char *ptr, *args; - - scRet = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // - // Fill in temporary command buffer - // - args = UINT32_TO_STREAM(args, ulLevel); - - - // - // Initiate a HCI command - // - hci_command_send(HCI_NETAPP_SET_DEBUG_LEVEL, ptr, NETAPP_SET_DEBUG_LEVEL_PARAMS_LEN); - - // - // Wait for command complete event - // - SimpleLinkWaitEvent(HCI_NETAPP_SET_DEBUG_LEVEL, &scRet); - - return(scRet); - -} -#endif +/***************************************************************************** +* +* netapp.c - 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. +* +*****************************************************************************/ +#include +#include +#include +#include +#include +#include + +#define MIN_TIMER_VAL_SECONDS 20 +#define MIN_TIMER_SET(t) if ((0 != t) && (t < MIN_TIMER_VAL_SECONDS)) \ + { \ + t = MIN_TIMER_VAL_SECONDS; \ + } + + +#define NETAPP_DHCP_PARAMS_LEN (20) +#define NETAPP_SET_TIMER_PARAMS_LEN (20) +#define NETAPP_SET_DEBUG_LEVEL_PARAMS_LEN (4) +#define NETAPP_PING_SEND_PARAMS_LEN (16) + + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** +long netapp_config_mac_adrress(uint8_t * mac) +{ + return nvmem_set_mac_address(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. +//! +//***************************************************************************** +long netapp_dhcp(unsigned long *aucIP, unsigned long *aucSubnetMask,unsigned long *aucDefaultGateway, unsigned long *aucDNSServer) +{ + int8_t scRet; + uint8_t *ptr; + uint8_t *args; + + scRet = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + ARRAY_TO_STREAM(args,aucIP,4); + ARRAY_TO_STREAM(args,aucSubnetMask,4); + ARRAY_TO_STREAM(args,aucDefaultGateway,4); + args = UINT32_TO_STREAM(args, 0); + ARRAY_TO_STREAM(args,aucDNSServer,4); + + // Initiate a HCI command + hci_command_send(HCI_NETAPP_DHCP, ptr, NETAPP_DHCP_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_NETAPP_DHCP, &scRet); + + return(scRet); +} + + +//***************************************************************************** +// +//! 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 +long +netapp_timeout_values(unsigned long *aucDHCP, unsigned long *aucARP,unsigned long *aucKeepalive, unsigned long *aucInactivity) +{ + int8_t scRet; + uint8_t *ptr; + uint8_t *args; + + scRet = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Set minimal values of timers + MIN_TIMER_SET(*aucDHCP) + MIN_TIMER_SET(*aucARP) + MIN_TIMER_SET(*aucKeepalive) + MIN_TIMER_SET(*aucInactivity) + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, *aucDHCP); + args = UINT32_TO_STREAM(args, *aucARP); + args = UINT32_TO_STREAM(args, *aucKeepalive); + args = UINT32_TO_STREAM(args, *aucInactivity); + + // Initiate a HCI command + hci_command_send(HCI_NETAPP_SET_TIMERS, ptr, NETAPP_SET_TIMER_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_NETAPP_SET_TIMERS, &scRet); + + return(scRet); +} +#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 +long +netapp_ping_send(unsigned long *ip, unsigned long ulPingAttempts, unsigned long ulPingSize, unsigned long ulPingTimeout) +{ + int8_t scRet; + uint8_t *ptr, *args; + + scRet = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, *ip); + args = UINT32_TO_STREAM(args, ulPingAttempts); + args = UINT32_TO_STREAM(args, ulPingSize); + args = UINT32_TO_STREAM(args, ulPingTimeout); + + // Initiate a HCI command + hci_command_send(HCI_NETAPP_PING_SEND, ptr, NETAPP_PING_SEND_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_NETAPP_PING_SEND, &scRet); + + return(scRet); +} +#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 +void netapp_ping_report(void) +{ + uint8_t *ptr; + ptr = tSLInformation.pucTxCommandBuffer; + int8_t scRet; + + scRet = EFAIL; + + // Initiate a HCI command + hci_command_send(HCI_NETAPP_PING_REPORT, ptr, 0); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_NETAPP_PING_REPORT, &scRet); +} +#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 +long netapp_ping_stop(void) +{ + int8_t scRet; + uint8_t *ptr; + + scRet = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + + // Initiate a HCI command + hci_command_send(HCI_NETAPP_PING_STOP, ptr, 0); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_NETAPP_PING_STOP, &scRet); + + return(scRet); +} +#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. +//! +//***************************************************************************** + +#ifndef CC3000_TINY_DRIVER +void netapp_ipconfig( tNetappIpconfigRetArgs * ipconfig ) +{ + uint8_t *ptr; + + ptr = tSLInformation.pucTxCommandBuffer; + + // Initiate a HCI command + hci_command_send(HCI_NETAPP_IPCONFIG, ptr, 0); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_NETAPP_IPCONFIG, ipconfig ); + +} +#else +void netapp_ipconfig( tNetappIpconfigRetArgs * ipconfig ) +{ + +} +#endif + +//***************************************************************************** +// +//! netapp_arp_flush +//! +//! @param none +//! +//! @return none +//! +//! @brief Flushes ARP table +//! +//***************************************************************************** + +#ifndef CC3000_TINY_DRIVER +long netapp_arp_flush(void) +{ + int8_t scRet; + uint8_t *ptr; + + scRet = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + + // Initiate a HCI command + hci_command_send(HCI_NETAPP_ARP_FLUSH, ptr, 0); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_NETAPP_ARP_FLUSH, &scRet); + + return(scRet); +} +#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) +{ + int8_t scRet; + uint8_t *ptr, *args; + + scRet = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // + // Fill in temporary command buffer + // + args = UINT32_TO_STREAM(args, ulLevel); + + + // + // Initiate a HCI command + // + hci_command_send(HCI_NETAPP_SET_DEBUG_LEVEL, ptr, NETAPP_SET_DEBUG_LEVEL_PARAMS_LEN); + + // + // Wait for command complete event + // + SimpleLinkWaitEvent(HCI_NETAPP_SET_DEBUG_LEVEL, &scRet); + + return(scRet); + +} +#endif diff --git a/nuttx/drivers/wireless/cc3000/nvmem.c b/nuttx/drivers/wireless/cc3000/nvmem.c index 3d0054591..66c9cb850 100644 --- a/nuttx/drivers/wireless/cc3000/nvmem.c +++ b/nuttx/drivers/wireless/cc3000/nvmem.c @@ -1,340 +1,340 @@ -/***************************************************************************** -* -* nvmem.c - 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. -* -*****************************************************************************/ - -//***************************************************************************** -// -//! \addtogroup nvmem_api -//! @{ -// -//***************************************************************************** - -#include -#include -#include -#include -#include -#include - -//***************************************************************************** -// -// Prototypes for the structures for APIs. -// -//***************************************************************************** - -#define NVMEM_READ_PARAMS_LEN (12) -#define NVMEM_CREATE_PARAMS_LEN (8) -#define NVMEM_WRITE_PARAMS_LEN (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. -//! -//***************************************************************************** - -signed long -nvmem_read(unsigned long ulFileId, unsigned long ulLength, unsigned long ulOffset, unsigned char *buff) -{ - unsigned char ucStatus = 0xFF; - unsigned char *ptr; - unsigned char *args; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, ulFileId); - args = UINT32_TO_STREAM(args, ulLength); - args = UINT32_TO_STREAM(args, ulOffset); - - // Initiate a HCI command - hci_command_send(HCI_CMND_NVMEM_READ, ptr, NVMEM_READ_PARAMS_LEN); - SimpleLinkWaitEvent(HCI_CMND_NVMEM_READ, &ucStatus); - - // In case there is data - read it - even if an error code is returned - // Note: It is the user responsibility to ignore the data in case of an error code - - // Wait for the data in a synchronous way. Here we assume that the buffer is - // big enough to store also parameters of nvmem - - SimpleLinkWaitData(buff, 0, 0); - - return(ucStatus); -} - -//***************************************************************************** -// -//! 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. -//! -//***************************************************************************** - -signed long -nvmem_write(unsigned long ulFileId, unsigned long ulLength, unsigned long - ulEntryOffset, unsigned char *buff) -{ - long iRes; - unsigned char *ptr; - unsigned char *args; - - iRes = EFAIL; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + SPI_HEADER_SIZE + HCI_DATA_CMD_HEADER_SIZE); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, ulFileId); - args = UINT32_TO_STREAM(args, 12); - args = UINT32_TO_STREAM(args, ulLength); - args = UINT32_TO_STREAM(args, ulEntryOffset); - - memcpy((ptr + SPI_HEADER_SIZE + HCI_DATA_CMD_HEADER_SIZE + - NVMEM_WRITE_PARAMS_LEN),buff,ulLength); - - // Initiate a HCI command but it will come on data channel - hci_data_command_send(HCI_CMND_NVMEM_WRITE, ptr, NVMEM_WRITE_PARAMS_LEN, - ulLength); - - SimpleLinkWaitEvent(HCI_EVNT_NVMEM_WRITE, &iRes); - - return(iRes); -} - - -//***************************************************************************** -// -//! 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) -//! -//***************************************************************************** - -unsigned char nvmem_set_mac_address(unsigned char *mac) -{ - return nvmem_write(NVMEM_MAC_FILEID, MAC_ADDR_LEN, 0, 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) -//! -//***************************************************************************** - -unsigned char nvmem_get_mac_address(unsigned char *mac) -{ - return nvmem_read(NVMEM_MAC_FILEID, MAC_ADDR_LEN, 0, 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. -//! -//***************************************************************************** - -unsigned char nvmem_write_patch(unsigned long ulFileId, unsigned long spLength, const unsigned char *spData) -{ - unsigned char status = 0; - unsigned short offset = 0; - unsigned char* spDataPtr = (unsigned char*)spData; - - while ((status == 0) && (spLength >= SP_PORTION_SIZE)) - { - status = nvmem_write(ulFileId, SP_PORTION_SIZE, offset, spDataPtr); - offset += SP_PORTION_SIZE; - spLength -= SP_PORTION_SIZE; - spDataPtr += SP_PORTION_SIZE; - } - - if (status !=0) - { - // NVMEM error occurred - return status; - } - - if (spLength != 0) - { - // if reached here, a reminder is left - status = nvmem_write(ulFileId, spLength, offset, spDataPtr); - } - - return status; -} - -//***************************************************************************** -// -//! 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 -unsigned char nvmem_read_sp_version(unsigned char* patchVer) -{ - unsigned char *ptr; - // 1st byte is the status and the rest is the SP version - unsigned char retBuf[5]; - - ptr = tSLInformation.pucTxCommandBuffer; - - // Initiate a HCI command, no args are required - hci_command_send(HCI_CMND_READ_SP_VERSION, ptr, 0); - SimpleLinkWaitEvent(HCI_CMND_READ_SP_VERSION, retBuf); - - // package ID - *patchVer = retBuf[3]; - // package build number - *(patchVer+1) = retBuf[4]; - - return(retBuf[0]); -} -#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. -//! -//***************************************************************************** - -signed long -nvmem_create_entry(unsigned long ulFileId, unsigned long ulNewLen) -{ - unsigned char *ptr; - unsigned char *args; - unsigned short retval; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, ulFileId); - args = UINT32_TO_STREAM(args, ulNewLen); - - // Initiate a HCI command - hci_command_send(HCI_CMND_NVMEM_CREATE_ENTRY,ptr, NVMEM_CREATE_PARAMS_LEN); - - SimpleLinkWaitEvent(HCI_CMND_NVMEM_CREATE_ENTRY, &retval); - - return(retval); -} - - - -//***************************************************************************** -// -// Close the Doxygen group. -//! @} -// -//***************************************************************************** - +/***************************************************************************** +* +* nvmem.c - 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. +* +*****************************************************************************/ + +//***************************************************************************** +// +//! \addtogroup nvmem_api +//! @{ +// +//***************************************************************************** + +#include +#include +#include +#include +#include +#include + +//***************************************************************************** +// +// Prototypes for the structures for APIs. +// +//***************************************************************************** + +#define NVMEM_READ_PARAMS_LEN (12) +#define NVMEM_CREATE_PARAMS_LEN (8) +#define NVMEM_WRITE_PARAMS_LEN (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. +//! +//***************************************************************************** + +signed long +nvmem_read(unsigned long ulFileId, unsigned long ulLength, unsigned long ulOffset, uint8_t *buff) +{ + uint8_t ucStatus = 0xFF; + uint8_t *ptr; + uint8_t *args; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, ulFileId); + args = UINT32_TO_STREAM(args, ulLength); + args = UINT32_TO_STREAM(args, ulOffset); + + // Initiate a HCI command + hci_command_send(HCI_CMND_NVMEM_READ, ptr, NVMEM_READ_PARAMS_LEN); + SimpleLinkWaitEvent(HCI_CMND_NVMEM_READ, &ucStatus); + + // In case there is data - read it - even if an error code is returned + // Note: It is the user responsibility to ignore the data in case of an error code + + // Wait for the data in a synchronous way. Here we assume that the buffer is + // big enough to store also parameters of nvmem + + SimpleLinkWaitData(buff, 0, 0); + + return(ucStatus); +} + +//***************************************************************************** +// +//! 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. +//! +//***************************************************************************** + +signed long +nvmem_write(unsigned long ulFileId, unsigned long ulLength, unsigned long + ulEntryOffset, uint8_t *buff) +{ + long iRes; + uint8_t *ptr; + uint8_t *args; + + iRes = EFAIL; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + SPI_HEADER_SIZE + HCI_DATA_CMD_HEADER_SIZE); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, ulFileId); + args = UINT32_TO_STREAM(args, 12); + args = UINT32_TO_STREAM(args, ulLength); + args = UINT32_TO_STREAM(args, ulEntryOffset); + + memcpy((ptr + SPI_HEADER_SIZE + HCI_DATA_CMD_HEADER_SIZE + + NVMEM_WRITE_PARAMS_LEN),buff,ulLength); + + // Initiate a HCI command but it will come on data channel + hci_data_command_send(HCI_CMND_NVMEM_WRITE, ptr, NVMEM_WRITE_PARAMS_LEN, + ulLength); + + SimpleLinkWaitEvent(HCI_EVNT_NVMEM_WRITE, &iRes); + + return(iRes); +} + + +//***************************************************************************** +// +//! 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) +//! +//***************************************************************************** + +uint8_t nvmem_set_mac_address(uint8_t *mac) +{ + return nvmem_write(NVMEM_MAC_FILEID, MAC_ADDR_LEN, 0, 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) +//! +//***************************************************************************** + +uint8_t nvmem_get_mac_address(uint8_t *mac) +{ + return nvmem_read(NVMEM_MAC_FILEID, MAC_ADDR_LEN, 0, 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. +//! +//***************************************************************************** + +uint8_t nvmem_write_patch(unsigned long ulFileId, unsigned long spLength, const uint8_t *spData) +{ + uint8_t status = 0; + uint16_t offset = 0; + uint8_t* spDataPtr = (uint8_t*)spData; + + while ((status == 0) && (spLength >= SP_PORTION_SIZE)) + { + status = nvmem_write(ulFileId, SP_PORTION_SIZE, offset, spDataPtr); + offset += SP_PORTION_SIZE; + spLength -= SP_PORTION_SIZE; + spDataPtr += SP_PORTION_SIZE; + } + + if (status !=0) + { + // NVMEM error occurred + return status; + } + + if (spLength != 0) + { + // if reached here, a reminder is left + status = nvmem_write(ulFileId, spLength, offset, spDataPtr); + } + + return status; +} + +//***************************************************************************** +// +//! 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 +uint8_t nvmem_read_sp_version(uint8_t* patchVer) +{ + uint8_t *ptr; + // 1st byte is the status and the rest is the SP version + uint8_t retBuf[5]; + + ptr = tSLInformation.pucTxCommandBuffer; + + // Initiate a HCI command, no args are required + hci_command_send(HCI_CMND_READ_SP_VERSION, ptr, 0); + SimpleLinkWaitEvent(HCI_CMND_READ_SP_VERSION, retBuf); + + // package ID + *patchVer = retBuf[3]; + // package build number + *(patchVer+1) = retBuf[4]; + + return(retBuf[0]); +} +#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. +//! +//***************************************************************************** + +signed long +nvmem_create_entry(unsigned long ulFileId, unsigned long ulNewLen) +{ + uint8_t *ptr; + uint8_t *args; + uint16_t retval; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, ulFileId); + args = UINT32_TO_STREAM(args, ulNewLen); + + // Initiate a HCI command + hci_command_send(HCI_CMND_NVMEM_CREATE_ENTRY,ptr, NVMEM_CREATE_PARAMS_LEN); + + SimpleLinkWaitEvent(HCI_CMND_NVMEM_CREATE_ENTRY, &retval); + + return(retval); +} + + + +//***************************************************************************** +// +// Close the Doxygen group. +//! @} +// +//***************************************************************************** + diff --git a/nuttx/drivers/wireless/cc3000/security.c b/nuttx/drivers/wireless/cc3000/security.c index 699bbb6d7..c364c68d7 100644 --- a/nuttx/drivers/wireless/cc3000/security.c +++ b/nuttx/drivers/wireless/cc3000/security.c @@ -1,533 +1,533 @@ -/***************************************************************************** -* -* security.c - 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. -* -*****************************************************************************/ - -//***************************************************************************** -// -//! \addtogroup security_api -//! @{ -// -//***************************************************************************** - -#include - -#ifndef CC3000_UNENCRYPTED_SMART_CONFIG -// foreward sbox -const unsigned char sbox[256] = { -//0 1 2 3 4 5 6 7 8 9 A B C D E F -0x63, 0x7c, 0x77, 0x7b, 0xf2, 0x6b, 0x6f, 0xc5, 0x30, 0x01, 0x67, 0x2b, 0xfe, 0xd7, 0xab, 0x76, //0 -0xca, 0x82, 0xc9, 0x7d, 0xfa, 0x59, 0x47, 0xf0, 0xad, 0xd4, 0xa2, 0xaf, 0x9c, 0xa4, 0x72, 0xc0, //1 -0xb7, 0xfd, 0x93, 0x26, 0x36, 0x3f, 0xf7, 0xcc, 0x34, 0xa5, 0xe5, 0xf1, 0x71, 0xd8, 0x31, 0x15, //2 -0x04, 0xc7, 0x23, 0xc3, 0x18, 0x96, 0x05, 0x9a, 0x07, 0x12, 0x80, 0xe2, 0xeb, 0x27, 0xb2, 0x75, //3 -0x09, 0x83, 0x2c, 0x1a, 0x1b, 0x6e, 0x5a, 0xa0, 0x52, 0x3b, 0xd6, 0xb3, 0x29, 0xe3, 0x2f, 0x84, //4 -0x53, 0xd1, 0x00, 0xed, 0x20, 0xfc, 0xb1, 0x5b, 0x6a, 0xcb, 0xbe, 0x39, 0x4a, 0x4c, 0x58, 0xcf, //5 -0xd0, 0xef, 0xaa, 0xfb, 0x43, 0x4d, 0x33, 0x85, 0x45, 0xf9, 0x02, 0x7f, 0x50, 0x3c, 0x9f, 0xa8, //6 -0x51, 0xa3, 0x40, 0x8f, 0x92, 0x9d, 0x38, 0xf5, 0xbc, 0xb6, 0xda, 0x21, 0x10, 0xff, 0xf3, 0xd2, //7 -0xcd, 0x0c, 0x13, 0xec, 0x5f, 0x97, 0x44, 0x17, 0xc4, 0xa7, 0x7e, 0x3d, 0x64, 0x5d, 0x19, 0x73, //8 -0x60, 0x81, 0x4f, 0xdc, 0x22, 0x2a, 0x90, 0x88, 0x46, 0xee, 0xb8, 0x14, 0xde, 0x5e, 0x0b, 0xdb, //9 -0xe0, 0x32, 0x3a, 0x0a, 0x49, 0x06, 0x24, 0x5c, 0xc2, 0xd3, 0xac, 0x62, 0x91, 0x95, 0xe4, 0x79, //A -0xe7, 0xc8, 0x37, 0x6d, 0x8d, 0xd5, 0x4e, 0xa9, 0x6c, 0x56, 0xf4, 0xea, 0x65, 0x7a, 0xae, 0x08, //B -0xba, 0x78, 0x25, 0x2e, 0x1c, 0xa6, 0xb4, 0xc6, 0xe8, 0xdd, 0x74, 0x1f, 0x4b, 0xbd, 0x8b, 0x8a, //C -0x70, 0x3e, 0xb5, 0x66, 0x48, 0x03, 0xf6, 0x0e, 0x61, 0x35, 0x57, 0xb9, 0x86, 0xc1, 0x1d, 0x9e, //D -0xe1, 0xf8, 0x98, 0x11, 0x69, 0xd9, 0x8e, 0x94, 0x9b, 0x1e, 0x87, 0xe9, 0xce, 0x55, 0x28, 0xdf, //E -0x8c, 0xa1, 0x89, 0x0d, 0xbf, 0xe6, 0x42, 0x68, 0x41, 0x99, 0x2d, 0x0f, 0xb0, 0x54, 0xbb, 0x16 }; //F -// inverse sbox -const unsigned char rsbox[256] = -{ 0x52, 0x09, 0x6a, 0xd5, 0x30, 0x36, 0xa5, 0x38, 0xbf, 0x40, 0xa3, 0x9e, 0x81, 0xf3, 0xd7, 0xfb -, 0x7c, 0xe3, 0x39, 0x82, 0x9b, 0x2f, 0xff, 0x87, 0x34, 0x8e, 0x43, 0x44, 0xc4, 0xde, 0xe9, 0xcb -, 0x54, 0x7b, 0x94, 0x32, 0xa6, 0xc2, 0x23, 0x3d, 0xee, 0x4c, 0x95, 0x0b, 0x42, 0xfa, 0xc3, 0x4e -, 0x08, 0x2e, 0xa1, 0x66, 0x28, 0xd9, 0x24, 0xb2, 0x76, 0x5b, 0xa2, 0x49, 0x6d, 0x8b, 0xd1, 0x25 -, 0x72, 0xf8, 0xf6, 0x64, 0x86, 0x68, 0x98, 0x16, 0xd4, 0xa4, 0x5c, 0xcc, 0x5d, 0x65, 0xb6, 0x92 -, 0x6c, 0x70, 0x48, 0x50, 0xfd, 0xed, 0xb9, 0xda, 0x5e, 0x15, 0x46, 0x57, 0xa7, 0x8d, 0x9d, 0x84 -, 0x90, 0xd8, 0xab, 0x00, 0x8c, 0xbc, 0xd3, 0x0a, 0xf7, 0xe4, 0x58, 0x05, 0xb8, 0xb3, 0x45, 0x06 -, 0xd0, 0x2c, 0x1e, 0x8f, 0xca, 0x3f, 0x0f, 0x02, 0xc1, 0xaf, 0xbd, 0x03, 0x01, 0x13, 0x8a, 0x6b -, 0x3a, 0x91, 0x11, 0x41, 0x4f, 0x67, 0xdc, 0xea, 0x97, 0xf2, 0xcf, 0xce, 0xf0, 0xb4, 0xe6, 0x73 -, 0x96, 0xac, 0x74, 0x22, 0xe7, 0xad, 0x35, 0x85, 0xe2, 0xf9, 0x37, 0xe8, 0x1c, 0x75, 0xdf, 0x6e -, 0x47, 0xf1, 0x1a, 0x71, 0x1d, 0x29, 0xc5, 0x89, 0x6f, 0xb7, 0x62, 0x0e, 0xaa, 0x18, 0xbe, 0x1b -, 0xfc, 0x56, 0x3e, 0x4b, 0xc6, 0xd2, 0x79, 0x20, 0x9a, 0xdb, 0xc0, 0xfe, 0x78, 0xcd, 0x5a, 0xf4 -, 0x1f, 0xdd, 0xa8, 0x33, 0x88, 0x07, 0xc7, 0x31, 0xb1, 0x12, 0x10, 0x59, 0x27, 0x80, 0xec, 0x5f -, 0x60, 0x51, 0x7f, 0xa9, 0x19, 0xb5, 0x4a, 0x0d, 0x2d, 0xe5, 0x7a, 0x9f, 0x93, 0xc9, 0x9c, 0xef -, 0xa0, 0xe0, 0x3b, 0x4d, 0xae, 0x2a, 0xf5, 0xb0, 0xc8, 0xeb, 0xbb, 0x3c, 0x83, 0x53, 0x99, 0x61 -, 0x17, 0x2b, 0x04, 0x7e, 0xba, 0x77, 0xd6, 0x26, 0xe1, 0x69, 0x14, 0x63, 0x55, 0x21, 0x0c, 0x7d }; -// round constant -const unsigned char Rcon[11] = { - 0x8d, 0x01, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x80, 0x1b, 0x36}; - - -unsigned char aexpandedKey[176]; - -//***************************************************************************** -// -//! expandKey -//! -//! @param key AES128 key - 16 bytes -//! @param expandedKey expanded AES128 key -//! -//! @return none -//! -//! @brief expend a 16 bytes key for AES128 implementation -//! -//***************************************************************************** - -void expandKey(unsigned char *expandedKey, - unsigned char *key) -{ - unsigned short ii, buf1; - for (ii=0;ii<16;ii++) - expandedKey[ii] = key[ii]; - for (ii=1;ii<11;ii++){ - buf1 = expandedKey[ii*16 - 4]; - expandedKey[ii*16 + 0] = sbox[expandedKey[ii*16 - 3]]^expandedKey[(ii-1)*16 + 0]^Rcon[ii]; - expandedKey[ii*16 + 1] = sbox[expandedKey[ii*16 - 2]]^expandedKey[(ii-1)*16 + 1]; - expandedKey[ii*16 + 2] = sbox[expandedKey[ii*16 - 1]]^expandedKey[(ii-1)*16 + 2]; - expandedKey[ii*16 + 3] = sbox[buf1 ]^expandedKey[(ii-1)*16 + 3]; - expandedKey[ii*16 + 4] = expandedKey[(ii-1)*16 + 4]^expandedKey[ii*16 + 0]; - expandedKey[ii*16 + 5] = expandedKey[(ii-1)*16 + 5]^expandedKey[ii*16 + 1]; - expandedKey[ii*16 + 6] = expandedKey[(ii-1)*16 + 6]^expandedKey[ii*16 + 2]; - expandedKey[ii*16 + 7] = expandedKey[(ii-1)*16 + 7]^expandedKey[ii*16 + 3]; - expandedKey[ii*16 + 8] = expandedKey[(ii-1)*16 + 8]^expandedKey[ii*16 + 4]; - expandedKey[ii*16 + 9] = expandedKey[(ii-1)*16 + 9]^expandedKey[ii*16 + 5]; - expandedKey[ii*16 +10] = expandedKey[(ii-1)*16 +10]^expandedKey[ii*16 + 6]; - expandedKey[ii*16 +11] = expandedKey[(ii-1)*16 +11]^expandedKey[ii*16 + 7]; - expandedKey[ii*16 +12] = expandedKey[(ii-1)*16 +12]^expandedKey[ii*16 + 8]; - expandedKey[ii*16 +13] = expandedKey[(ii-1)*16 +13]^expandedKey[ii*16 + 9]; - expandedKey[ii*16 +14] = expandedKey[(ii-1)*16 +14]^expandedKey[ii*16 +10]; - expandedKey[ii*16 +15] = expandedKey[(ii-1)*16 +15]^expandedKey[ii*16 +11]; - } - -} - -//***************************************************************************** -// -//! galois_mul2 -//! -//! @param value argument to multiply -//! -//! @return multiplied argument -//! -//! @brief multiply by 2 in the galois field -//! -//***************************************************************************** - -unsigned char galois_mul2(unsigned char value) -{ - if (value>>7) - { - value = value << 1; - return (value^0x1b); - } else - return value<<1; -} - -//***************************************************************************** -// -//! aes_encr -//! -//! @param[in] expandedKey expanded AES128 key -//! @param[in/out] state 16 bytes of plain text and cipher text -//! -//! @return none -//! -//! @brief internal implementation of AES128 encryption. -//! straight forward aes encryption implementation -//! first the group of operations -//! - addRoundKey -//! - subbytes -//! - shiftrows -//! - mixcolums -//! is executed 9 times, after this addroundkey to finish the 9th -//! round, after that the 10th round without mixcolums -//! no further subfunctions to save cycles for function calls -//! no structuring with "for (....)" to save cycles. -//! -//! -//***************************************************************************** - -void aes_encr(unsigned char *state, unsigned char *expandedKey) -{ - unsigned char buf1, buf2, buf3, round; - - for (round = 0; round < 9; round ++){ - // addroundkey, sbox and shiftrows - // row 0 - state[ 0] = sbox[(state[ 0] ^ expandedKey[(round*16) ])]; - state[ 4] = sbox[(state[ 4] ^ expandedKey[(round*16) + 4])]; - state[ 8] = sbox[(state[ 8] ^ expandedKey[(round*16) + 8])]; - state[12] = sbox[(state[12] ^ expandedKey[(round*16) + 12])]; - // row 1 - buf1 = state[1] ^ expandedKey[(round*16) + 1]; - state[ 1] = sbox[(state[ 5] ^ expandedKey[(round*16) + 5])]; - state[ 5] = sbox[(state[ 9] ^ expandedKey[(round*16) + 9])]; - state[ 9] = sbox[(state[13] ^ expandedKey[(round*16) + 13])]; - state[13] = sbox[buf1]; - // row 2 - buf1 = state[2] ^ expandedKey[(round*16) + 2]; - buf2 = state[6] ^ expandedKey[(round*16) + 6]; - state[ 2] = sbox[(state[10] ^ expandedKey[(round*16) + 10])]; - state[ 6] = sbox[(state[14] ^ expandedKey[(round*16) + 14])]; - state[10] = sbox[buf1]; - state[14] = sbox[buf2]; - // row 3 - buf1 = state[15] ^ expandedKey[(round*16) + 15]; - state[15] = sbox[(state[11] ^ expandedKey[(round*16) + 11])]; - state[11] = sbox[(state[ 7] ^ expandedKey[(round*16) + 7])]; - state[ 7] = sbox[(state[ 3] ^ expandedKey[(round*16) + 3])]; - state[ 3] = sbox[buf1]; - - // mixcolums ////////// - // col1 - buf1 = state[0] ^ state[1] ^ state[2] ^ state[3]; - buf2 = state[0]; - buf3 = state[0]^state[1]; buf3=galois_mul2(buf3); state[0] = state[0] ^ buf3 ^ buf1; - buf3 = state[1]^state[2]; buf3=galois_mul2(buf3); state[1] = state[1] ^ buf3 ^ buf1; - buf3 = state[2]^state[3]; buf3=galois_mul2(buf3); state[2] = state[2] ^ buf3 ^ buf1; - buf3 = state[3]^buf2; buf3=galois_mul2(buf3); state[3] = state[3] ^ buf3 ^ buf1; - // col2 - buf1 = state[4] ^ state[5] ^ state[6] ^ state[7]; - buf2 = state[4]; - buf3 = state[4]^state[5]; buf3=galois_mul2(buf3); state[4] = state[4] ^ buf3 ^ buf1; - buf3 = state[5]^state[6]; buf3=galois_mul2(buf3); state[5] = state[5] ^ buf3 ^ buf1; - buf3 = state[6]^state[7]; buf3=galois_mul2(buf3); state[6] = state[6] ^ buf3 ^ buf1; - buf3 = state[7]^buf2; buf3=galois_mul2(buf3); state[7] = state[7] ^ buf3 ^ buf1; - // col3 - buf1 = state[8] ^ state[9] ^ state[10] ^ state[11]; - buf2 = state[8]; - buf3 = state[8]^state[9]; buf3=galois_mul2(buf3); state[8] = state[8] ^ buf3 ^ buf1; - buf3 = state[9]^state[10]; buf3=galois_mul2(buf3); state[9] = state[9] ^ buf3 ^ buf1; - buf3 = state[10]^state[11]; buf3=galois_mul2(buf3); state[10] = state[10] ^ buf3 ^ buf1; - buf3 = state[11]^buf2; buf3=galois_mul2(buf3); state[11] = state[11] ^ buf3 ^ buf1; - // col4 - buf1 = state[12] ^ state[13] ^ state[14] ^ state[15]; - buf2 = state[12]; - buf3 = state[12]^state[13]; buf3=galois_mul2(buf3); state[12] = state[12] ^ buf3 ^ buf1; - buf3 = state[13]^state[14]; buf3=galois_mul2(buf3); state[13] = state[13] ^ buf3 ^ buf1; - buf3 = state[14]^state[15]; buf3=galois_mul2(buf3); state[14] = state[14] ^ buf3 ^ buf1; - buf3 = state[15]^buf2; buf3=galois_mul2(buf3); state[15] = state[15] ^ buf3 ^ buf1; - - } - // 10th round without mixcols - state[ 0] = sbox[(state[ 0] ^ expandedKey[(round*16) ])]; - state[ 4] = sbox[(state[ 4] ^ expandedKey[(round*16) + 4])]; - state[ 8] = sbox[(state[ 8] ^ expandedKey[(round*16) + 8])]; - state[12] = sbox[(state[12] ^ expandedKey[(round*16) + 12])]; - // row 1 - buf1 = state[1] ^ expandedKey[(round*16) + 1]; - state[ 1] = sbox[(state[ 5] ^ expandedKey[(round*16) + 5])]; - state[ 5] = sbox[(state[ 9] ^ expandedKey[(round*16) + 9])]; - state[ 9] = sbox[(state[13] ^ expandedKey[(round*16) + 13])]; - state[13] = sbox[buf1]; - // row 2 - buf1 = state[2] ^ expandedKey[(round*16) + 2]; - buf2 = state[6] ^ expandedKey[(round*16) + 6]; - state[ 2] = sbox[(state[10] ^ expandedKey[(round*16) + 10])]; - state[ 6] = sbox[(state[14] ^ expandedKey[(round*16) + 14])]; - state[10] = sbox[buf1]; - state[14] = sbox[buf2]; - // row 3 - buf1 = state[15] ^ expandedKey[(round*16) + 15]; - state[15] = sbox[(state[11] ^ expandedKey[(round*16) + 11])]; - state[11] = sbox[(state[ 7] ^ expandedKey[(round*16) + 7])]; - state[ 7] = sbox[(state[ 3] ^ expandedKey[(round*16) + 3])]; - state[ 3] = sbox[buf1]; - // last addroundkey - state[ 0]^=expandedKey[160]; - state[ 1]^=expandedKey[161]; - state[ 2]^=expandedKey[162]; - state[ 3]^=expandedKey[163]; - state[ 4]^=expandedKey[164]; - state[ 5]^=expandedKey[165]; - state[ 6]^=expandedKey[166]; - state[ 7]^=expandedKey[167]; - state[ 8]^=expandedKey[168]; - state[ 9]^=expandedKey[169]; - state[10]^=expandedKey[170]; - state[11]^=expandedKey[171]; - state[12]^=expandedKey[172]; - state[13]^=expandedKey[173]; - state[14]^=expandedKey[174]; - state[15]^=expandedKey[175]; -} - -//***************************************************************************** -// -//! aes_decr -//! -//! @param[in] expandedKey expanded AES128 key -//! @param[in\out] state 16 bytes of cipher text and plain text -//! -//! @return none -//! -//! @brief internal implementation of AES128 decryption. -//! straight forward aes decryption implementation -//! the order of substeps is the exact reverse of decryption -//! inverse functions: -//! - addRoundKey is its own inverse -//! - rsbox is inverse of sbox -//! - rightshift instead of leftshift -//! - invMixColumns = barreto + mixColumns -//! no further subfunctions to save cycles for function calls -//! no structuring with "for (....)" to save cycles -//! -//***************************************************************************** - -void aes_decr(unsigned char *state, unsigned char *expandedKey) -{ - unsigned char buf1, buf2, buf3; - signed char round; - round = 9; - - // initial addroundkey - state[ 0]^=expandedKey[160]; - state[ 1]^=expandedKey[161]; - state[ 2]^=expandedKey[162]; - state[ 3]^=expandedKey[163]; - state[ 4]^=expandedKey[164]; - state[ 5]^=expandedKey[165]; - state[ 6]^=expandedKey[166]; - state[ 7]^=expandedKey[167]; - state[ 8]^=expandedKey[168]; - state[ 9]^=expandedKey[169]; - state[10]^=expandedKey[170]; - state[11]^=expandedKey[171]; - state[12]^=expandedKey[172]; - state[13]^=expandedKey[173]; - state[14]^=expandedKey[174]; - state[15]^=expandedKey[175]; - - // 10th round without mixcols - state[ 0] = rsbox[state[ 0]] ^ expandedKey[(round*16) ]; - state[ 4] = rsbox[state[ 4]] ^ expandedKey[(round*16) + 4]; - state[ 8] = rsbox[state[ 8]] ^ expandedKey[(round*16) + 8]; - state[12] = rsbox[state[12]] ^ expandedKey[(round*16) + 12]; - // row 1 - buf1 = rsbox[state[13]] ^ expandedKey[(round*16) + 1]; - state[13] = rsbox[state[ 9]] ^ expandedKey[(round*16) + 13]; - state[ 9] = rsbox[state[ 5]] ^ expandedKey[(round*16) + 9]; - state[ 5] = rsbox[state[ 1]] ^ expandedKey[(round*16) + 5]; - state[ 1] = buf1; - // row 2 - buf1 = rsbox[state[ 2]] ^ expandedKey[(round*16) + 10]; - buf2 = rsbox[state[ 6]] ^ expandedKey[(round*16) + 14]; - state[ 2] = rsbox[state[10]] ^ expandedKey[(round*16) + 2]; - state[ 6] = rsbox[state[14]] ^ expandedKey[(round*16) + 6]; - state[10] = buf1; - state[14] = buf2; - // row 3 - buf1 = rsbox[state[ 3]] ^ expandedKey[(round*16) + 15]; - state[ 3] = rsbox[state[ 7]] ^ expandedKey[(round*16) + 3]; - state[ 7] = rsbox[state[11]] ^ expandedKey[(round*16) + 7]; - state[11] = rsbox[state[15]] ^ expandedKey[(round*16) + 11]; - state[15] = buf1; - - for (round = 8; round >= 0; round--){ - // barreto - //col1 - buf1 = galois_mul2(galois_mul2(state[0]^state[2])); - buf2 = galois_mul2(galois_mul2(state[1]^state[3])); - state[0] ^= buf1; state[1] ^= buf2; state[2] ^= buf1; state[3] ^= buf2; - //col2 - buf1 = galois_mul2(galois_mul2(state[4]^state[6])); - buf2 = galois_mul2(galois_mul2(state[5]^state[7])); - state[4] ^= buf1; state[5] ^= buf2; state[6] ^= buf1; state[7] ^= buf2; - //col3 - buf1 = galois_mul2(galois_mul2(state[8]^state[10])); - buf2 = galois_mul2(galois_mul2(state[9]^state[11])); - state[8] ^= buf1; state[9] ^= buf2; state[10] ^= buf1; state[11] ^= buf2; - //col4 - buf1 = galois_mul2(galois_mul2(state[12]^state[14])); - buf2 = galois_mul2(galois_mul2(state[13]^state[15])); - state[12] ^= buf1; state[13] ^= buf2; state[14] ^= buf1; state[15] ^= buf2; - // mixcolums ////////// - // col1 - buf1 = state[0] ^ state[1] ^ state[2] ^ state[3]; - buf2 = state[0]; - buf3 = state[0]^state[1]; buf3=galois_mul2(buf3); state[0] = state[0] ^ buf3 ^ buf1; - buf3 = state[1]^state[2]; buf3=galois_mul2(buf3); state[1] = state[1] ^ buf3 ^ buf1; - buf3 = state[2]^state[3]; buf3=galois_mul2(buf3); state[2] = state[2] ^ buf3 ^ buf1; - buf3 = state[3]^buf2; buf3=galois_mul2(buf3); state[3] = state[3] ^ buf3 ^ buf1; - // col2 - buf1 = state[4] ^ state[5] ^ state[6] ^ state[7]; - buf2 = state[4]; - buf3 = state[4]^state[5]; buf3=galois_mul2(buf3); state[4] = state[4] ^ buf3 ^ buf1; - buf3 = state[5]^state[6]; buf3=galois_mul2(buf3); state[5] = state[5] ^ buf3 ^ buf1; - buf3 = state[6]^state[7]; buf3=galois_mul2(buf3); state[6] = state[6] ^ buf3 ^ buf1; - buf3 = state[7]^buf2; buf3=galois_mul2(buf3); state[7] = state[7] ^ buf3 ^ buf1; - // col3 - buf1 = state[8] ^ state[9] ^ state[10] ^ state[11]; - buf2 = state[8]; - buf3 = state[8]^state[9]; buf3=galois_mul2(buf3); state[8] = state[8] ^ buf3 ^ buf1; - buf3 = state[9]^state[10]; buf3=galois_mul2(buf3); state[9] = state[9] ^ buf3 ^ buf1; - buf3 = state[10]^state[11]; buf3=galois_mul2(buf3); state[10] = state[10] ^ buf3 ^ buf1; - buf3 = state[11]^buf2; buf3=galois_mul2(buf3); state[11] = state[11] ^ buf3 ^ buf1; - // col4 - buf1 = state[12] ^ state[13] ^ state[14] ^ state[15]; - buf2 = state[12]; - buf3 = state[12]^state[13]; buf3=galois_mul2(buf3); state[12] = state[12] ^ buf3 ^ buf1; - buf3 = state[13]^state[14]; buf3=galois_mul2(buf3); state[13] = state[13] ^ buf3 ^ buf1; - buf3 = state[14]^state[15]; buf3=galois_mul2(buf3); state[14] = state[14] ^ buf3 ^ buf1; - buf3 = state[15]^buf2; buf3=galois_mul2(buf3); state[15] = state[15] ^ buf3 ^ buf1; - - // addroundkey, rsbox and shiftrows - // row 0 - state[ 0] = rsbox[state[ 0]] ^ expandedKey[(round*16) ]; - state[ 4] = rsbox[state[ 4]] ^ expandedKey[(round*16) + 4]; - state[ 8] = rsbox[state[ 8]] ^ expandedKey[(round*16) + 8]; - state[12] = rsbox[state[12]] ^ expandedKey[(round*16) + 12]; - // row 1 - buf1 = rsbox[state[13]] ^ expandedKey[(round*16) + 1]; - state[13] = rsbox[state[ 9]] ^ expandedKey[(round*16) + 13]; - state[ 9] = rsbox[state[ 5]] ^ expandedKey[(round*16) + 9]; - state[ 5] = rsbox[state[ 1]] ^ expandedKey[(round*16) + 5]; - state[ 1] = buf1; - // row 2 - buf1 = rsbox[state[ 2]] ^ expandedKey[(round*16) + 10]; - buf2 = rsbox[state[ 6]] ^ expandedKey[(round*16) + 14]; - state[ 2] = rsbox[state[10]] ^ expandedKey[(round*16) + 2]; - state[ 6] = rsbox[state[14]] ^ expandedKey[(round*16) + 6]; - state[10] = buf1; - state[14] = buf2; - // row 3 - buf1 = rsbox[state[ 3]] ^ expandedKey[(round*16) + 15]; - state[ 3] = rsbox[state[ 7]] ^ expandedKey[(round*16) + 3]; - state[ 7] = rsbox[state[11]] ^ expandedKey[(round*16) + 7]; - state[11] = rsbox[state[15]] ^ expandedKey[(round*16) + 11]; - state[15] = buf1; - } - -} - -//***************************************************************************** -// -//! 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). -//! -//! -//***************************************************************************** - -void aes_encrypt(unsigned char *state, - unsigned char *key) -{ - // expand the key into 176 bytes - expandKey(aexpandedKey, key); - aes_encr(state, aexpandedKey); -} - -//***************************************************************************** -// -//! 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). -//! -//! -//***************************************************************************** - -void aes_decrypt(unsigned char *state, - unsigned char *key) -{ - expandKey(aexpandedKey, key); // expand the key into 176 bytes - aes_decr(state, aexpandedKey); -} - -//***************************************************************************** -// -//! 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. -//! -//! -//***************************************************************************** - -signed long aes_read_key(unsigned char *key) -{ - signed long returnValue; - - returnValue = nvmem_read(NVMEM_AES128_KEY_FILEID, AES128_KEY_SIZE, 0, key); - - return returnValue; -} - -//***************************************************************************** -// -//! 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 -//! -//! -//***************************************************************************** - -signed long aes_write_key(unsigned char *key) -{ - signed long returnValue; - - returnValue = nvmem_write(NVMEM_AES128_KEY_FILEID, AES128_KEY_SIZE, 0, key); - - return returnValue; -} - -#endif //CC3000_UNENCRYPTED_SMART_CONFIG - -//***************************************************************************** -// -// Close the Doxygen group. -//! @} -// -//***************************************************************************** +/***************************************************************************** +* +* security.c - 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. +* +*****************************************************************************/ + +//***************************************************************************** +// +//! \addtogroup security_api +//! @{ +// +//***************************************************************************** + +#include + +#ifndef CC3000_UNENCRYPTED_SMART_CONFIG +// foreward sbox +const uint8_t sbox[256] = { +//0 1 2 3 4 5 6 7 8 9 A B C D E F +0x63, 0x7c, 0x77, 0x7b, 0xf2, 0x6b, 0x6f, 0xc5, 0x30, 0x01, 0x67, 0x2b, 0xfe, 0xd7, 0xab, 0x76, //0 +0xca, 0x82, 0xc9, 0x7d, 0xfa, 0x59, 0x47, 0xf0, 0xad, 0xd4, 0xa2, 0xaf, 0x9c, 0xa4, 0x72, 0xc0, //1 +0xb7, 0xfd, 0x93, 0x26, 0x36, 0x3f, 0xf7, 0xcc, 0x34, 0xa5, 0xe5, 0xf1, 0x71, 0xd8, 0x31, 0x15, //2 +0x04, 0xc7, 0x23, 0xc3, 0x18, 0x96, 0x05, 0x9a, 0x07, 0x12, 0x80, 0xe2, 0xeb, 0x27, 0xb2, 0x75, //3 +0x09, 0x83, 0x2c, 0x1a, 0x1b, 0x6e, 0x5a, 0xa0, 0x52, 0x3b, 0xd6, 0xb3, 0x29, 0xe3, 0x2f, 0x84, //4 +0x53, 0xd1, 0x00, 0xed, 0x20, 0xfc, 0xb1, 0x5b, 0x6a, 0xcb, 0xbe, 0x39, 0x4a, 0x4c, 0x58, 0xcf, //5 +0xd0, 0xef, 0xaa, 0xfb, 0x43, 0x4d, 0x33, 0x85, 0x45, 0xf9, 0x02, 0x7f, 0x50, 0x3c, 0x9f, 0xa8, //6 +0x51, 0xa3, 0x40, 0x8f, 0x92, 0x9d, 0x38, 0xf5, 0xbc, 0xb6, 0xda, 0x21, 0x10, 0xff, 0xf3, 0xd2, //7 +0xcd, 0x0c, 0x13, 0xec, 0x5f, 0x97, 0x44, 0x17, 0xc4, 0xa7, 0x7e, 0x3d, 0x64, 0x5d, 0x19, 0x73, //8 +0x60, 0x81, 0x4f, 0xdc, 0x22, 0x2a, 0x90, 0x88, 0x46, 0xee, 0xb8, 0x14, 0xde, 0x5e, 0x0b, 0xdb, //9 +0xe0, 0x32, 0x3a, 0x0a, 0x49, 0x06, 0x24, 0x5c, 0xc2, 0xd3, 0xac, 0x62, 0x91, 0x95, 0xe4, 0x79, //A +0xe7, 0xc8, 0x37, 0x6d, 0x8d, 0xd5, 0x4e, 0xa9, 0x6c, 0x56, 0xf4, 0xea, 0x65, 0x7a, 0xae, 0x08, //B +0xba, 0x78, 0x25, 0x2e, 0x1c, 0xa6, 0xb4, 0xc6, 0xe8, 0xdd, 0x74, 0x1f, 0x4b, 0xbd, 0x8b, 0x8a, //C +0x70, 0x3e, 0xb5, 0x66, 0x48, 0x03, 0xf6, 0x0e, 0x61, 0x35, 0x57, 0xb9, 0x86, 0xc1, 0x1d, 0x9e, //D +0xe1, 0xf8, 0x98, 0x11, 0x69, 0xd9, 0x8e, 0x94, 0x9b, 0x1e, 0x87, 0xe9, 0xce, 0x55, 0x28, 0xdf, //E +0x8c, 0xa1, 0x89, 0x0d, 0xbf, 0xe6, 0x42, 0x68, 0x41, 0x99, 0x2d, 0x0f, 0xb0, 0x54, 0xbb, 0x16 }; //F +// inverse sbox +const uint8_t rsbox[256] = +{ 0x52, 0x09, 0x6a, 0xd5, 0x30, 0x36, 0xa5, 0x38, 0xbf, 0x40, 0xa3, 0x9e, 0x81, 0xf3, 0xd7, 0xfb +, 0x7c, 0xe3, 0x39, 0x82, 0x9b, 0x2f, 0xff, 0x87, 0x34, 0x8e, 0x43, 0x44, 0xc4, 0xde, 0xe9, 0xcb +, 0x54, 0x7b, 0x94, 0x32, 0xa6, 0xc2, 0x23, 0x3d, 0xee, 0x4c, 0x95, 0x0b, 0x42, 0xfa, 0xc3, 0x4e +, 0x08, 0x2e, 0xa1, 0x66, 0x28, 0xd9, 0x24, 0xb2, 0x76, 0x5b, 0xa2, 0x49, 0x6d, 0x8b, 0xd1, 0x25 +, 0x72, 0xf8, 0xf6, 0x64, 0x86, 0x68, 0x98, 0x16, 0xd4, 0xa4, 0x5c, 0xcc, 0x5d, 0x65, 0xb6, 0x92 +, 0x6c, 0x70, 0x48, 0x50, 0xfd, 0xed, 0xb9, 0xda, 0x5e, 0x15, 0x46, 0x57, 0xa7, 0x8d, 0x9d, 0x84 +, 0x90, 0xd8, 0xab, 0x00, 0x8c, 0xbc, 0xd3, 0x0a, 0xf7, 0xe4, 0x58, 0x05, 0xb8, 0xb3, 0x45, 0x06 +, 0xd0, 0x2c, 0x1e, 0x8f, 0xca, 0x3f, 0x0f, 0x02, 0xc1, 0xaf, 0xbd, 0x03, 0x01, 0x13, 0x8a, 0x6b +, 0x3a, 0x91, 0x11, 0x41, 0x4f, 0x67, 0xdc, 0xea, 0x97, 0xf2, 0xcf, 0xce, 0xf0, 0xb4, 0xe6, 0x73 +, 0x96, 0xac, 0x74, 0x22, 0xe7, 0xad, 0x35, 0x85, 0xe2, 0xf9, 0x37, 0xe8, 0x1c, 0x75, 0xdf, 0x6e +, 0x47, 0xf1, 0x1a, 0x71, 0x1d, 0x29, 0xc5, 0x89, 0x6f, 0xb7, 0x62, 0x0e, 0xaa, 0x18, 0xbe, 0x1b +, 0xfc, 0x56, 0x3e, 0x4b, 0xc6, 0xd2, 0x79, 0x20, 0x9a, 0xdb, 0xc0, 0xfe, 0x78, 0xcd, 0x5a, 0xf4 +, 0x1f, 0xdd, 0xa8, 0x33, 0x88, 0x07, 0xc7, 0x31, 0xb1, 0x12, 0x10, 0x59, 0x27, 0x80, 0xec, 0x5f +, 0x60, 0x51, 0x7f, 0xa9, 0x19, 0xb5, 0x4a, 0x0d, 0x2d, 0xe5, 0x7a, 0x9f, 0x93, 0xc9, 0x9c, 0xef +, 0xa0, 0xe0, 0x3b, 0x4d, 0xae, 0x2a, 0xf5, 0xb0, 0xc8, 0xeb, 0xbb, 0x3c, 0x83, 0x53, 0x99, 0x61 +, 0x17, 0x2b, 0x04, 0x7e, 0xba, 0x77, 0xd6, 0x26, 0xe1, 0x69, 0x14, 0x63, 0x55, 0x21, 0x0c, 0x7d }; +// round constant +const uint8_t Rcon[11] = { + 0x8d, 0x01, 0x02, 0x04, 0x08, 0x10, 0x20, 0x40, 0x80, 0x1b, 0x36}; + + +uint8_t aexpandedKey[176]; + +//***************************************************************************** +// +//! expandKey +//! +//! @param key AES128 key - 16 bytes +//! @param expandedKey expanded AES128 key +//! +//! @return none +//! +//! @brief expend a 16 bytes key for AES128 implementation +//! +//***************************************************************************** + +void expandKey(uint8_t *expandedKey, + uint8_t *key) +{ + uint16_t ii, buf1; + for (ii=0;ii<16;ii++) + expandedKey[ii] = key[ii]; + for (ii=1;ii<11;ii++){ + buf1 = expandedKey[ii*16 - 4]; + expandedKey[ii*16 + 0] = sbox[expandedKey[ii*16 - 3]]^expandedKey[(ii-1)*16 + 0]^Rcon[ii]; + expandedKey[ii*16 + 1] = sbox[expandedKey[ii*16 - 2]]^expandedKey[(ii-1)*16 + 1]; + expandedKey[ii*16 + 2] = sbox[expandedKey[ii*16 - 1]]^expandedKey[(ii-1)*16 + 2]; + expandedKey[ii*16 + 3] = sbox[buf1 ]^expandedKey[(ii-1)*16 + 3]; + expandedKey[ii*16 + 4] = expandedKey[(ii-1)*16 + 4]^expandedKey[ii*16 + 0]; + expandedKey[ii*16 + 5] = expandedKey[(ii-1)*16 + 5]^expandedKey[ii*16 + 1]; + expandedKey[ii*16 + 6] = expandedKey[(ii-1)*16 + 6]^expandedKey[ii*16 + 2]; + expandedKey[ii*16 + 7] = expandedKey[(ii-1)*16 + 7]^expandedKey[ii*16 + 3]; + expandedKey[ii*16 + 8] = expandedKey[(ii-1)*16 + 8]^expandedKey[ii*16 + 4]; + expandedKey[ii*16 + 9] = expandedKey[(ii-1)*16 + 9]^expandedKey[ii*16 + 5]; + expandedKey[ii*16 +10] = expandedKey[(ii-1)*16 +10]^expandedKey[ii*16 + 6]; + expandedKey[ii*16 +11] = expandedKey[(ii-1)*16 +11]^expandedKey[ii*16 + 7]; + expandedKey[ii*16 +12] = expandedKey[(ii-1)*16 +12]^expandedKey[ii*16 + 8]; + expandedKey[ii*16 +13] = expandedKey[(ii-1)*16 +13]^expandedKey[ii*16 + 9]; + expandedKey[ii*16 +14] = expandedKey[(ii-1)*16 +14]^expandedKey[ii*16 +10]; + expandedKey[ii*16 +15] = expandedKey[(ii-1)*16 +15]^expandedKey[ii*16 +11]; + } + +} + +//***************************************************************************** +// +//! galois_mul2 +//! +//! @param value argument to multiply +//! +//! @return multiplied argument +//! +//! @brief multiply by 2 in the galois field +//! +//***************************************************************************** + +uint8_t galois_mul2(uint8_t value) +{ + if (value>>7) + { + value = value << 1; + return (value^0x1b); + } else + return value<<1; +} + +//***************************************************************************** +// +//! aes_encr +//! +//! @param[in] expandedKey expanded AES128 key +//! @param[in/out] state 16 bytes of plain text and cipher text +//! +//! @return none +//! +//! @brief internal implementation of AES128 encryption. +//! straight forward aes encryption implementation +//! first the group of operations +//! - addRoundKey +//! - subbytes +//! - shiftrows +//! - mixcolums +//! is executed 9 times, after this addroundkey to finish the 9th +//! round, after that the 10th round without mixcolums +//! no further subfunctions to save cycles for function calls +//! no structuring with "for (....)" to save cycles. +//! +//! +//***************************************************************************** + +void aes_encr(uint8_t *state, uint8_t *expandedKey) +{ + uint8_t buf1, buf2, buf3, round; + + for (round = 0; round < 9; round ++){ + // addroundkey, sbox and shiftrows + // row 0 + state[ 0] = sbox[(state[ 0] ^ expandedKey[(round*16) ])]; + state[ 4] = sbox[(state[ 4] ^ expandedKey[(round*16) + 4])]; + state[ 8] = sbox[(state[ 8] ^ expandedKey[(round*16) + 8])]; + state[12] = sbox[(state[12] ^ expandedKey[(round*16) + 12])]; + // row 1 + buf1 = state[1] ^ expandedKey[(round*16) + 1]; + state[ 1] = sbox[(state[ 5] ^ expandedKey[(round*16) + 5])]; + state[ 5] = sbox[(state[ 9] ^ expandedKey[(round*16) + 9])]; + state[ 9] = sbox[(state[13] ^ expandedKey[(round*16) + 13])]; + state[13] = sbox[buf1]; + // row 2 + buf1 = state[2] ^ expandedKey[(round*16) + 2]; + buf2 = state[6] ^ expandedKey[(round*16) + 6]; + state[ 2] = sbox[(state[10] ^ expandedKey[(round*16) + 10])]; + state[ 6] = sbox[(state[14] ^ expandedKey[(round*16) + 14])]; + state[10] = sbox[buf1]; + state[14] = sbox[buf2]; + // row 3 + buf1 = state[15] ^ expandedKey[(round*16) + 15]; + state[15] = sbox[(state[11] ^ expandedKey[(round*16) + 11])]; + state[11] = sbox[(state[ 7] ^ expandedKey[(round*16) + 7])]; + state[ 7] = sbox[(state[ 3] ^ expandedKey[(round*16) + 3])]; + state[ 3] = sbox[buf1]; + + // mixcolums ////////// + // col1 + buf1 = state[0] ^ state[1] ^ state[2] ^ state[3]; + buf2 = state[0]; + buf3 = state[0]^state[1]; buf3=galois_mul2(buf3); state[0] = state[0] ^ buf3 ^ buf1; + buf3 = state[1]^state[2]; buf3=galois_mul2(buf3); state[1] = state[1] ^ buf3 ^ buf1; + buf3 = state[2]^state[3]; buf3=galois_mul2(buf3); state[2] = state[2] ^ buf3 ^ buf1; + buf3 = state[3]^buf2; buf3=galois_mul2(buf3); state[3] = state[3] ^ buf3 ^ buf1; + // col2 + buf1 = state[4] ^ state[5] ^ state[6] ^ state[7]; + buf2 = state[4]; + buf3 = state[4]^state[5]; buf3=galois_mul2(buf3); state[4] = state[4] ^ buf3 ^ buf1; + buf3 = state[5]^state[6]; buf3=galois_mul2(buf3); state[5] = state[5] ^ buf3 ^ buf1; + buf3 = state[6]^state[7]; buf3=galois_mul2(buf3); state[6] = state[6] ^ buf3 ^ buf1; + buf3 = state[7]^buf2; buf3=galois_mul2(buf3); state[7] = state[7] ^ buf3 ^ buf1; + // col3 + buf1 = state[8] ^ state[9] ^ state[10] ^ state[11]; + buf2 = state[8]; + buf3 = state[8]^state[9]; buf3=galois_mul2(buf3); state[8] = state[8] ^ buf3 ^ buf1; + buf3 = state[9]^state[10]; buf3=galois_mul2(buf3); state[9] = state[9] ^ buf3 ^ buf1; + buf3 = state[10]^state[11]; buf3=galois_mul2(buf3); state[10] = state[10] ^ buf3 ^ buf1; + buf3 = state[11]^buf2; buf3=galois_mul2(buf3); state[11] = state[11] ^ buf3 ^ buf1; + // col4 + buf1 = state[12] ^ state[13] ^ state[14] ^ state[15]; + buf2 = state[12]; + buf3 = state[12]^state[13]; buf3=galois_mul2(buf3); state[12] = state[12] ^ buf3 ^ buf1; + buf3 = state[13]^state[14]; buf3=galois_mul2(buf3); state[13] = state[13] ^ buf3 ^ buf1; + buf3 = state[14]^state[15]; buf3=galois_mul2(buf3); state[14] = state[14] ^ buf3 ^ buf1; + buf3 = state[15]^buf2; buf3=galois_mul2(buf3); state[15] = state[15] ^ buf3 ^ buf1; + + } + // 10th round without mixcols + state[ 0] = sbox[(state[ 0] ^ expandedKey[(round*16) ])]; + state[ 4] = sbox[(state[ 4] ^ expandedKey[(round*16) + 4])]; + state[ 8] = sbox[(state[ 8] ^ expandedKey[(round*16) + 8])]; + state[12] = sbox[(state[12] ^ expandedKey[(round*16) + 12])]; + // row 1 + buf1 = state[1] ^ expandedKey[(round*16) + 1]; + state[ 1] = sbox[(state[ 5] ^ expandedKey[(round*16) + 5])]; + state[ 5] = sbox[(state[ 9] ^ expandedKey[(round*16) + 9])]; + state[ 9] = sbox[(state[13] ^ expandedKey[(round*16) + 13])]; + state[13] = sbox[buf1]; + // row 2 + buf1 = state[2] ^ expandedKey[(round*16) + 2]; + buf2 = state[6] ^ expandedKey[(round*16) + 6]; + state[ 2] = sbox[(state[10] ^ expandedKey[(round*16) + 10])]; + state[ 6] = sbox[(state[14] ^ expandedKey[(round*16) + 14])]; + state[10] = sbox[buf1]; + state[14] = sbox[buf2]; + // row 3 + buf1 = state[15] ^ expandedKey[(round*16) + 15]; + state[15] = sbox[(state[11] ^ expandedKey[(round*16) + 11])]; + state[11] = sbox[(state[ 7] ^ expandedKey[(round*16) + 7])]; + state[ 7] = sbox[(state[ 3] ^ expandedKey[(round*16) + 3])]; + state[ 3] = sbox[buf1]; + // last addroundkey + state[ 0]^=expandedKey[160]; + state[ 1]^=expandedKey[161]; + state[ 2]^=expandedKey[162]; + state[ 3]^=expandedKey[163]; + state[ 4]^=expandedKey[164]; + state[ 5]^=expandedKey[165]; + state[ 6]^=expandedKey[166]; + state[ 7]^=expandedKey[167]; + state[ 8]^=expandedKey[168]; + state[ 9]^=expandedKey[169]; + state[10]^=expandedKey[170]; + state[11]^=expandedKey[171]; + state[12]^=expandedKey[172]; + state[13]^=expandedKey[173]; + state[14]^=expandedKey[174]; + state[15]^=expandedKey[175]; +} + +//***************************************************************************** +// +//! aes_decr +//! +//! @param[in] expandedKey expanded AES128 key +//! @param[in\out] state 16 bytes of cipher text and plain text +//! +//! @return none +//! +//! @brief internal implementation of AES128 decryption. +//! straight forward aes decryption implementation +//! the order of substeps is the exact reverse of decryption +//! inverse functions: +//! - addRoundKey is its own inverse +//! - rsbox is inverse of sbox +//! - rightshift instead of leftshift +//! - invMixColumns = barreto + mixColumns +//! no further subfunctions to save cycles for function calls +//! no structuring with "for (....)" to save cycles +//! +//***************************************************************************** + +void aes_decr(uint8_t *state, uint8_t *expandedKey) +{ + uint8_t buf1, buf2, buf3; + int8_t round; + round = 9; + + // initial addroundkey + state[ 0]^=expandedKey[160]; + state[ 1]^=expandedKey[161]; + state[ 2]^=expandedKey[162]; + state[ 3]^=expandedKey[163]; + state[ 4]^=expandedKey[164]; + state[ 5]^=expandedKey[165]; + state[ 6]^=expandedKey[166]; + state[ 7]^=expandedKey[167]; + state[ 8]^=expandedKey[168]; + state[ 9]^=expandedKey[169]; + state[10]^=expandedKey[170]; + state[11]^=expandedKey[171]; + state[12]^=expandedKey[172]; + state[13]^=expandedKey[173]; + state[14]^=expandedKey[174]; + state[15]^=expandedKey[175]; + + // 10th round without mixcols + state[ 0] = rsbox[state[ 0]] ^ expandedKey[(round*16) ]; + state[ 4] = rsbox[state[ 4]] ^ expandedKey[(round*16) + 4]; + state[ 8] = rsbox[state[ 8]] ^ expandedKey[(round*16) + 8]; + state[12] = rsbox[state[12]] ^ expandedKey[(round*16) + 12]; + // row 1 + buf1 = rsbox[state[13]] ^ expandedKey[(round*16) + 1]; + state[13] = rsbox[state[ 9]] ^ expandedKey[(round*16) + 13]; + state[ 9] = rsbox[state[ 5]] ^ expandedKey[(round*16) + 9]; + state[ 5] = rsbox[state[ 1]] ^ expandedKey[(round*16) + 5]; + state[ 1] = buf1; + // row 2 + buf1 = rsbox[state[ 2]] ^ expandedKey[(round*16) + 10]; + buf2 = rsbox[state[ 6]] ^ expandedKey[(round*16) + 14]; + state[ 2] = rsbox[state[10]] ^ expandedKey[(round*16) + 2]; + state[ 6] = rsbox[state[14]] ^ expandedKey[(round*16) + 6]; + state[10] = buf1; + state[14] = buf2; + // row 3 + buf1 = rsbox[state[ 3]] ^ expandedKey[(round*16) + 15]; + state[ 3] = rsbox[state[ 7]] ^ expandedKey[(round*16) + 3]; + state[ 7] = rsbox[state[11]] ^ expandedKey[(round*16) + 7]; + state[11] = rsbox[state[15]] ^ expandedKey[(round*16) + 11]; + state[15] = buf1; + + for (round = 8; round >= 0; round--){ + // barreto + //col1 + buf1 = galois_mul2(galois_mul2(state[0]^state[2])); + buf2 = galois_mul2(galois_mul2(state[1]^state[3])); + state[0] ^= buf1; state[1] ^= buf2; state[2] ^= buf1; state[3] ^= buf2; + //col2 + buf1 = galois_mul2(galois_mul2(state[4]^state[6])); + buf2 = galois_mul2(galois_mul2(state[5]^state[7])); + state[4] ^= buf1; state[5] ^= buf2; state[6] ^= buf1; state[7] ^= buf2; + //col3 + buf1 = galois_mul2(galois_mul2(state[8]^state[10])); + buf2 = galois_mul2(galois_mul2(state[9]^state[11])); + state[8] ^= buf1; state[9] ^= buf2; state[10] ^= buf1; state[11] ^= buf2; + //col4 + buf1 = galois_mul2(galois_mul2(state[12]^state[14])); + buf2 = galois_mul2(galois_mul2(state[13]^state[15])); + state[12] ^= buf1; state[13] ^= buf2; state[14] ^= buf1; state[15] ^= buf2; + // mixcolums ////////// + // col1 + buf1 = state[0] ^ state[1] ^ state[2] ^ state[3]; + buf2 = state[0]; + buf3 = state[0]^state[1]; buf3=galois_mul2(buf3); state[0] = state[0] ^ buf3 ^ buf1; + buf3 = state[1]^state[2]; buf3=galois_mul2(buf3); state[1] = state[1] ^ buf3 ^ buf1; + buf3 = state[2]^state[3]; buf3=galois_mul2(buf3); state[2] = state[2] ^ buf3 ^ buf1; + buf3 = state[3]^buf2; buf3=galois_mul2(buf3); state[3] = state[3] ^ buf3 ^ buf1; + // col2 + buf1 = state[4] ^ state[5] ^ state[6] ^ state[7]; + buf2 = state[4]; + buf3 = state[4]^state[5]; buf3=galois_mul2(buf3); state[4] = state[4] ^ buf3 ^ buf1; + buf3 = state[5]^state[6]; buf3=galois_mul2(buf3); state[5] = state[5] ^ buf3 ^ buf1; + buf3 = state[6]^state[7]; buf3=galois_mul2(buf3); state[6] = state[6] ^ buf3 ^ buf1; + buf3 = state[7]^buf2; buf3=galois_mul2(buf3); state[7] = state[7] ^ buf3 ^ buf1; + // col3 + buf1 = state[8] ^ state[9] ^ state[10] ^ state[11]; + buf2 = state[8]; + buf3 = state[8]^state[9]; buf3=galois_mul2(buf3); state[8] = state[8] ^ buf3 ^ buf1; + buf3 = state[9]^state[10]; buf3=galois_mul2(buf3); state[9] = state[9] ^ buf3 ^ buf1; + buf3 = state[10]^state[11]; buf3=galois_mul2(buf3); state[10] = state[10] ^ buf3 ^ buf1; + buf3 = state[11]^buf2; buf3=galois_mul2(buf3); state[11] = state[11] ^ buf3 ^ buf1; + // col4 + buf1 = state[12] ^ state[13] ^ state[14] ^ state[15]; + buf2 = state[12]; + buf3 = state[12]^state[13]; buf3=galois_mul2(buf3); state[12] = state[12] ^ buf3 ^ buf1; + buf3 = state[13]^state[14]; buf3=galois_mul2(buf3); state[13] = state[13] ^ buf3 ^ buf1; + buf3 = state[14]^state[15]; buf3=galois_mul2(buf3); state[14] = state[14] ^ buf3 ^ buf1; + buf3 = state[15]^buf2; buf3=galois_mul2(buf3); state[15] = state[15] ^ buf3 ^ buf1; + + // addroundkey, rsbox and shiftrows + // row 0 + state[ 0] = rsbox[state[ 0]] ^ expandedKey[(round*16) ]; + state[ 4] = rsbox[state[ 4]] ^ expandedKey[(round*16) + 4]; + state[ 8] = rsbox[state[ 8]] ^ expandedKey[(round*16) + 8]; + state[12] = rsbox[state[12]] ^ expandedKey[(round*16) + 12]; + // row 1 + buf1 = rsbox[state[13]] ^ expandedKey[(round*16) + 1]; + state[13] = rsbox[state[ 9]] ^ expandedKey[(round*16) + 13]; + state[ 9] = rsbox[state[ 5]] ^ expandedKey[(round*16) + 9]; + state[ 5] = rsbox[state[ 1]] ^ expandedKey[(round*16) + 5]; + state[ 1] = buf1; + // row 2 + buf1 = rsbox[state[ 2]] ^ expandedKey[(round*16) + 10]; + buf2 = rsbox[state[ 6]] ^ expandedKey[(round*16) + 14]; + state[ 2] = rsbox[state[10]] ^ expandedKey[(round*16) + 2]; + state[ 6] = rsbox[state[14]] ^ expandedKey[(round*16) + 6]; + state[10] = buf1; + state[14] = buf2; + // row 3 + buf1 = rsbox[state[ 3]] ^ expandedKey[(round*16) + 15]; + state[ 3] = rsbox[state[ 7]] ^ expandedKey[(round*16) + 3]; + state[ 7] = rsbox[state[11]] ^ expandedKey[(round*16) + 7]; + state[11] = rsbox[state[15]] ^ expandedKey[(round*16) + 11]; + state[15] = buf1; + } + +} + +//***************************************************************************** +// +//! 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). +//! +//! +//***************************************************************************** + +void aes_encrypt(uint8_t *state, + uint8_t *key) +{ + // expand the key into 176 bytes + expandKey(aexpandedKey, key); + aes_encr(state, aexpandedKey); +} + +//***************************************************************************** +// +//! 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). +//! +//! +//***************************************************************************** + +void aes_decrypt(uint8_t *state, + uint8_t *key) +{ + expandKey(aexpandedKey, key); // expand the key into 176 bytes + aes_decr(state, aexpandedKey); +} + +//***************************************************************************** +// +//! 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. +//! +//! +//***************************************************************************** + +signed long aes_read_key(uint8_t *key) +{ + signed long returnValue; + + returnValue = nvmem_read(NVMEM_AES128_KEY_FILEID, AES128_KEY_SIZE, 0, key); + + return returnValue; +} + +//***************************************************************************** +// +//! 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 +//! +//! +//***************************************************************************** + +signed long aes_write_key(uint8_t *key) +{ + signed long returnValue; + + returnValue = nvmem_write(NVMEM_AES128_KEY_FILEID, AES128_KEY_SIZE, 0, key); + + return returnValue; +} + +#endif //CC3000_UNENCRYPTED_SMART_CONFIG + +//***************************************************************************** +// +// Close the Doxygen group. +//! @} +// +//***************************************************************************** diff --git a/nuttx/drivers/wireless/cc3000/socket.c b/nuttx/drivers/wireless/cc3000/socket.c index 20bbd5017..5b810f231 100644 --- a/nuttx/drivers/wireless/cc3000/socket.c +++ b/nuttx/drivers/wireless/cc3000/socket.c @@ -1,1169 +1,1169 @@ -/***************************************************************************** -* -* socket.c - 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. -* -*****************************************************************************/ - -//***************************************************************************** -// -//! \addtogroup socket_api -//! @{ -// -//***************************************************************************** - -#include -#include -#include -#include -#include -#include -#include - - - -//Enable this flag if and only if you must comply with BSD socket -//close() function -#ifdef _API_USE_BSD_CLOSE - #define close(sd) closesocket(sd) -#endif - -//Enable this flag if and only if you must comply with BSD socket read() and -//write() functions -#ifdef _API_USE_BSD_READ_WRITE - #define read(sd, buf, len, flags) recv(sd, buf, len, flags) - #define write(sd, buf, len, flags) send(sd, buf, len, flags) -#endif - -#define SOCKET_OPEN_PARAMS_LEN (12) -#define SOCKET_CLOSE_PARAMS_LEN (4) -#define SOCKET_ACCEPT_PARAMS_LEN (4) -#define SOCKET_BIND_PARAMS_LEN (20) -#define SOCKET_LISTEN_PARAMS_LEN (8) -#define SOCKET_GET_HOST_BY_NAME_PARAMS_LEN (9) -#define SOCKET_CONNECT_PARAMS_LEN (20) -#define SOCKET_SELECT_PARAMS_LEN (44) -#define SOCKET_SET_SOCK_OPT_PARAMS_LEN (20) -#define SOCKET_GET_SOCK_OPT_PARAMS_LEN (12) -#define SOCKET_RECV_FROM_PARAMS_LEN (12) -#define SOCKET_SENDTO_PARAMS_LEN (24) -#define SOCKET_MDNS_ADVERTISE_PARAMS_LEN (12) - - -// The legnth of arguments for the SEND command: sd + buff_offset + len + flags, -// while size of each parameter is 32 bit - so the total length is 16 bytes; - -#define HCI_CMND_SEND_ARG_LENGTH (16) - - -#define SELECT_TIMEOUT_MIN_MICRO_SECONDS 5000 - -#define HEADERS_SIZE_DATA (SPI_HEADER_SIZE + 5) - -#define SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE (SPI_HEADER_SIZE + SIMPLE_LINK_HCI_CMND_HEADER_SIZE) - -#define MDNS_DEVICE_SERVICE_MAX_LENGTH (32) - - -//***************************************************************************** -// -//! HostFlowControlConsumeBuff -//! -//! @param sd socket descriptor -//! -//! @return 0 in case there are buffers available, -//! -1 in case of bad socket -//! -2 if there are no free buffers present (only when -//! SEND_NON_BLOCKING is enabled) -//! -//! @brief if SEND_NON_BLOCKING not define - block until have free buffer -//! becomes available, else return immediately with correct status -//! regarding the buffers available. -// -//***************************************************************************** -int -HostFlowControlConsumeBuff(int sd) -{ -#ifndef SEND_NON_BLOCKING - /* wait in busy loop */ - do - { - // In case last transmission failed then we will return the last failure - // reason here. - // Note that the buffer will not be allocated in this case - if (tSLInformation.slTransmitDataError != 0) - { - errno = tSLInformation.slTransmitDataError; - tSLInformation.slTransmitDataError = 0; - return errno; - } - - if(SOCKET_STATUS_ACTIVE != get_socket_active_status(sd)) - return -1; - } while(0 == tSLInformation.usNumberOfFreeBuffers); - - tSLInformation.usNumberOfFreeBuffers--; - - return 0; -#else - - // In case last transmission failed then we will return the last failure - // reason here. - // Note that the buffer will not be allocated in this case - if (tSLInformation.slTransmitDataError != 0) - { - errno = tSLInformation.slTransmitDataError; - tSLInformation.slTransmitDataError = 0; - return errno; - } - if(SOCKET_STATUS_ACTIVE != get_socket_active_status(sd)) - return -1; - - //If there are no available buffers, return -2. It is recommended to use - // select or receive to see if there is any buffer occupied with received data - // If so, call receive() to release the buffer. - if(0 == tSLInformation.usNumberOfFreeBuffers) - { - return -2; - } - else - { - tSLInformation.usNumberOfFreeBuffers--; - return 0; - } -#endif -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -int -socket(long domain, long type, long protocol) -{ - long ret; - unsigned char *ptr, *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, domain); - args = UINT32_TO_STREAM(args, type); - args = UINT32_TO_STREAM(args, protocol); - - // Initiate a HCI command - hci_command_send(HCI_CMND_SOCKET, ptr, SOCKET_OPEN_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_SOCKET, &ret); - - // Process the event - errno = ret; - - set_socket_active_status(ret, SOCKET_STATUS_ACTIVE); - - return(ret); -} - -//***************************************************************************** -// -//! closesocket -//! -//! @param sd socket handle. -//! -//! @return On success, zero is returned. On error, -1 is returned. -//! -//! @brief The socket function closes a created socket. -// -//***************************************************************************** - -long -closesocket(long sd) -{ - long ret; - unsigned char *ptr, *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, sd); - - // Initiate a HCI command - hci_command_send(HCI_CMND_CLOSE_SOCKET, - ptr, SOCKET_CLOSE_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_CLOSE_SOCKET, &ret); - errno = ret; - - // since 'close' call may result in either OK (and then it closed) or error - // mark this socket as invalid - set_socket_active_status(sd, SOCKET_STATUS_INACTIVE); - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -accept(long sd, sockaddr *addr, socklen_t *addrlen) -{ - long ret; - unsigned char *ptr, *args; - tBsdReturnParams tAcceptReturnArguments; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, sd); - - // Initiate a HCI command - hci_command_send(HCI_CMND_ACCEPT, - ptr, SOCKET_ACCEPT_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_ACCEPT, &tAcceptReturnArguments); - - - // need specify return parameters!!! - memcpy(addr, &tAcceptReturnArguments.tSocketAddress, ASIC_ADDR_LEN); - *addrlen = ASIC_ADDR_LEN; - errno = tAcceptReturnArguments.iStatus; - ret = errno; - - // if succeeded, iStatus = new socket descriptor. otherwise - error number - if(M_IS_VALID_SD(ret)) - { - set_socket_active_status(ret, SOCKET_STATUS_ACTIVE); - } - else - { - set_socket_active_status(sd, SOCKET_STATUS_INACTIVE); - } - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -bind(long sd, const sockaddr *addr, long addrlen) -{ - long ret; - unsigned char *ptr, *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - addrlen = ASIC_ADDR_LEN; - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, sd); - args = UINT32_TO_STREAM(args, 0x00000008); - args = UINT32_TO_STREAM(args, addrlen); - ARRAY_TO_STREAM(args, ((unsigned char *)addr), addrlen); - - // Initiate a HCI command - hci_command_send(HCI_CMND_BIND, - ptr, SOCKET_BIND_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_BIND, &ret); - - errno = ret; - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -listen(long sd, long backlog) -{ - long ret; - unsigned char *ptr, *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, sd); - args = UINT32_TO_STREAM(args, backlog); - - // Initiate a HCI command - hci_command_send(HCI_CMND_LISTEN, - ptr, SOCKET_LISTEN_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_LISTEN, &ret); - errno = ret; - - return(ret); -} - -//***************************************************************************** -// -//! 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 -int -gethostbyname(char * hostname, unsigned short usNameLen, - unsigned long* out_ip_addr) -{ - tBsdGethostbynameParams ret; - unsigned char *ptr, *args; - - errno = EFAIL; - - if (usNameLen > HOSTNAME_MAX_LENGTH) - { - return errno; - } - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, 8); - args = UINT32_TO_STREAM(args, usNameLen); - ARRAY_TO_STREAM(args, hostname, usNameLen); - - // Initiate a HCI command - hci_command_send(HCI_CMND_GETHOSTNAME, ptr, SOCKET_GET_HOST_BY_NAME_PARAMS_LEN - + usNameLen - 1); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_EVNT_BSD_GETHOSTBYNAME, &ret); - - errno = ret.retVal; - - (*((long*)out_ip_addr)) = ret.outputAddress; - - return (errno); - -} -#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 -// -//***************************************************************************** - -long -connect(long sd, const sockaddr *addr, long addrlen) -{ - long int ret; - unsigned char *ptr, *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE); - addrlen = 8; - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, sd); - args = UINT32_TO_STREAM(args, 0x00000008); - args = UINT32_TO_STREAM(args, addrlen); - ARRAY_TO_STREAM(args, ((unsigned char *)addr), addrlen); - - // Initiate a HCI command - hci_command_send(HCI_CMND_CONNECT, - ptr, SOCKET_CONNECT_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_CONNECT, &ret); - - errno = ret; - - return((long)ret); -} - - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -int -select(long nfds, TICC3000fd_set *readsds, TICC3000fd_set *writesds, TICC3000fd_set *exceptsds, - struct timeval *timeout) -{ - unsigned char *ptr, *args; - tBsdSelectRecvParams tParams; - unsigned long is_blocking; - - if( timeout == NULL) - { - is_blocking = 1; /* blocking , infinity timeout */ - } - else - { - is_blocking = 0; /* no blocking, timeout */ - } - - // Fill in HCI packet structure - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, nfds); - args = UINT32_TO_STREAM(args, 0x00000014); - args = UINT32_TO_STREAM(args, 0x00000014); - args = UINT32_TO_STREAM(args, 0x00000014); - args = UINT32_TO_STREAM(args, 0x00000014); - args = UINT32_TO_STREAM(args, is_blocking); - args = UINT32_TO_STREAM(args, ((readsds) ? *(unsigned long*)readsds : 0)); - args = UINT32_TO_STREAM(args, ((writesds) ? *(unsigned long*)writesds : 0)); - args = UINT32_TO_STREAM(args, ((exceptsds) ? *(unsigned long*)exceptsds : 0)); - - if (timeout) - { - if ( 0 == timeout->tv_sec && timeout->tv_usec < - SELECT_TIMEOUT_MIN_MICRO_SECONDS) - { - timeout->tv_usec = SELECT_TIMEOUT_MIN_MICRO_SECONDS; - } - args = UINT32_TO_STREAM(args, timeout->tv_sec); - args = UINT32_TO_STREAM(args, timeout->tv_usec); - } - - // Initiate a HCI command - hci_command_send(HCI_CMND_BSD_SELECT, ptr, SOCKET_SELECT_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_EVNT_SELECT, &tParams); - - // Update actually read FD - if (tParams.iStatus >= 0) - { - if (readsds) - { - memcpy(readsds, &tParams.uiRdfd, sizeof(tParams.uiRdfd)); - } - - if (writesds) - { - memcpy(writesds, &tParams.uiWrfd, sizeof(tParams.uiWrfd)); - } - - if (exceptsds) - { - memcpy(exceptsds, &tParams.uiExfd, sizeof(tParams.uiExfd)); - } - - return(tParams.iStatus); - - } - else - { - errno = tParams.iStatus; - return(-1); - } -} - -//***************************************************************************** -// -//! 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 -int -setsockopt(long sd, long level, long optname, const void *optval, - socklen_t optlen) -{ - int ret; - unsigned char *ptr, *args; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, sd); - args = UINT32_TO_STREAM(args, level); - args = UINT32_TO_STREAM(args, optname); - args = UINT32_TO_STREAM(args, 0x00000008); - args = UINT32_TO_STREAM(args, optlen); - ARRAY_TO_STREAM(args, ((unsigned char *)optval), optlen); - - // Initiate a HCI command - hci_command_send(HCI_CMND_SETSOCKOPT, - ptr, SOCKET_SET_SOCK_OPT_PARAMS_LEN + optlen); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_SETSOCKOPT, &ret); - - if (ret >= 0) - { - return (0); - } - else - { - errno = ret; - return ret; - } -} -#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 -// -//***************************************************************************** - -int -getsockopt (long sd, long level, long optname, void *optval, socklen_t *optlen) -{ - unsigned char *ptr, *args; - tBsdGetSockOptReturnParams tRetParams; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, sd); - args = UINT32_TO_STREAM(args, level); - args = UINT32_TO_STREAM(args, optname); - - // Initiate a HCI command - hci_command_send(HCI_CMND_GETSOCKOPT, - ptr, SOCKET_GET_SOCK_OPT_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_CMND_GETSOCKOPT, &tRetParams); - - if (((signed char)tRetParams.iStatus) >= 0) - { - *optlen = 4; - memcpy(optval, tRetParams.ucOptValue, 4); - return (0); - } - else - { - errno = tRetParams.iStatus; - return errno; - } -} - -//***************************************************************************** -// -//! simple_link_recv -//! -//! @param sd socket handle -//! @param buf read buffer -//! @param len buffer length -//! @param flags indicates blocking or non-blocking operation -//! @param from pointer to an address structure indicating source address -//! @param fromlen source address structure size -//! -//! @return Return the number of bytes received, or -1 if an error -//! occurred -//! -//! @brief Read data from socket -//! Return the length of the message on successful completion. -//! If a message is too long to fit in the supplied buffer, -//! excess bytes may be discarded depending on the type of -//! socket the message is received from -// -//***************************************************************************** -int -simple_link_recv(long sd, void *buf, long len, long flags, sockaddr *from, - socklen_t *fromlen, long opcode) -{ - unsigned char *ptr, *args; - tBsdReadReturnParams tSocketReadEvent; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, sd); - args = UINT32_TO_STREAM(args, len); - args = UINT32_TO_STREAM(args, flags); - - // Generate the read command, and wait for the - hci_command_send(opcode, ptr, SOCKET_RECV_FROM_PARAMS_LEN); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(opcode, &tSocketReadEvent); - - // In case the number of bytes is more then zero - read data - if (tSocketReadEvent.iNumberOfBytes > 0) - { - // Wait for the data in a synchronous way. Here we assume that the bug is - // big enough to store also parameters of receive from too.... - SimpleLinkWaitData((unsigned char *)buf, (unsigned char *)from, (unsigned char *)fromlen); - } - - errno = tSocketReadEvent.iNumberOfBytes; - - return(tSocketReadEvent.iNumberOfBytes); -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -int -recv(long sd, void *buf, long len, long flags) -{ - return(simple_link_recv(sd, buf, len, flags, NULL, NULL, HCI_CMND_RECV)); -} - -//***************************************************************************** -// -//! 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 tructure 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. -// -//***************************************************************************** -int -recvfrom(long sd, void *buf, long len, long flags, sockaddr *from, - socklen_t *fromlen) -{ - return(simple_link_recv(sd, buf, len, flags, from, fromlen, - HCI_CMND_RECVFROM)); -} - -//***************************************************************************** -// -//! simple_link_send -//! -//! @param sd socket handle -//! @param buf write buffer -//! @param len buffer length -//! @param flags On this version, this parameter is not supported -//! @param to pointer to an address structure indicating destination -//! address -//! @param tolen destination address structure size -//! -//! @return Return the number of bytes transmitted, or -1 if an error -//! occurred, or -2 in case there are no free buffers available -//! (only when SEND_NON_BLOCKING is enabled) -//! -//! @brief This function is used to transmit a message to another -//! socket -// -//***************************************************************************** -int -simple_link_send(long sd, const void *buf, long len, long flags, - const sockaddr *to, long tolen, long opcode) -{ - unsigned char uArgSize = 0, addrlen; - unsigned char *ptr, *pDataPtr = NULL, *args; - unsigned long addr_offset = 0; - int res; - tBsdReadReturnParams tSocketSendEvent; - - // Check the bsd_arguments - if (0 != (res = HostFlowControlConsumeBuff(sd))) - { - return res; - } - - //Update the number of sent packets - tSLInformation.NumberOfSentPackets++; - - // Allocate a buffer and construct a packet and send it over spi - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_DATA); - - // Update the offset of data and parameters according to the command - switch(opcode) - { - case HCI_CMND_SENDTO: - { - addr_offset = len + sizeof(len) + sizeof(len); - addrlen = 8; - uArgSize = SOCKET_SENDTO_PARAMS_LEN; - pDataPtr = ptr + HEADERS_SIZE_DATA + SOCKET_SENDTO_PARAMS_LEN; - break; - } - - case HCI_CMND_SEND: - { - tolen = 0; - to = NULL; - uArgSize = HCI_CMND_SEND_ARG_LENGTH; - pDataPtr = ptr + HEADERS_SIZE_DATA + HCI_CMND_SEND_ARG_LENGTH; - break; - } - - default: - { - break; - } - } - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, sd); - args = UINT32_TO_STREAM(args, uArgSize - sizeof(sd)); - args = UINT32_TO_STREAM(args, len); - args = UINT32_TO_STREAM(args, flags); - - if (opcode == HCI_CMND_SENDTO) - { - args = UINT32_TO_STREAM(args, addr_offset); - args = UINT32_TO_STREAM(args, addrlen); - } - - // Copy the data received from user into the TX Buffer - ARRAY_TO_STREAM(pDataPtr, ((unsigned char *)buf), len); - - // In case we are using SendTo, copy the to parameters - if (opcode == HCI_CMND_SENDTO) - { - ARRAY_TO_STREAM(pDataPtr, ((unsigned char *)to), tolen); - } - - // Initiate a HCI command - hci_data_send(opcode, ptr, uArgSize, len,(unsigned char*)to, tolen); - - if (opcode == HCI_CMND_SENDTO) - SimpleLinkWaitEvent(HCI_EVNT_SENDTO, &tSocketSendEvent); - else - SimpleLinkWaitEvent(HCI_EVNT_SEND, &tSocketSendEvent); - - return (len); -} - - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -int -send(long sd, const void *buf, long len, long flags) -{ - return(simple_link_send(sd, buf, len, flags, NULL, 0, HCI_CMND_SEND)); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -int -sendto(long sd, const void *buf, long len, long flags, const sockaddr *to, - socklen_t tolen) -{ - return(simple_link_send(sd, buf, len, flags, to, tolen, HCI_CMND_SENDTO)); -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -int -mdnsAdvertiser(unsigned short mdnsEnabled, char * deviceServiceName, unsigned short deviceServiceNameLength) -{ - int ret; - unsigned char *pTxBuffer, *pArgs; - - if (deviceServiceNameLength > MDNS_DEVICE_SERVICE_MAX_LENGTH) - { - return EFAIL; - } - - pTxBuffer = tSLInformation.pucTxCommandBuffer; - pArgs = (pTxBuffer + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE); - - // Fill in HCI packet structure - pArgs = UINT32_TO_STREAM(pArgs, mdnsEnabled); - pArgs = UINT32_TO_STREAM(pArgs, 8); - pArgs = UINT32_TO_STREAM(pArgs, deviceServiceNameLength); - ARRAY_TO_STREAM(pArgs, deviceServiceName, deviceServiceNameLength); - - // Initiate a HCI command - hci_command_send(HCI_CMND_MDNS_ADVERTISE, pTxBuffer, SOCKET_MDNS_ADVERTISE_PARAMS_LEN + deviceServiceNameLength); - - // Since we are in blocking state - wait for event complete - SimpleLinkWaitEvent(HCI_EVNT_MDNS_ADVERTISE, &ret); - - return ret; - -} +/***************************************************************************** +* +* socket.c - 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. +* +*****************************************************************************/ + +//***************************************************************************** +// +//! \addtogroup socket_api +//! @{ +// +//***************************************************************************** + +#include +#include +#include +#include +#include +#include +#include + + + +//Enable this flag if and only if you must comply with BSD socket +//close() function +#ifdef _API_USE_BSD_CLOSE + #define close(sd) closesocket(sd) +#endif + +//Enable this flag if and only if you must comply with BSD socket read() and +//write() functions +#ifdef _API_USE_BSD_READ_WRITE + #define read(sd, buf, len, flags) recv(sd, buf, len, flags) + #define write(sd, buf, len, flags) send(sd, buf, len, flags) +#endif + +#define SOCKET_OPEN_PARAMS_LEN (12) +#define SOCKET_CLOSE_PARAMS_LEN (4) +#define SOCKET_ACCEPT_PARAMS_LEN (4) +#define SOCKET_BIND_PARAMS_LEN (20) +#define SOCKET_LISTEN_PARAMS_LEN (8) +#define SOCKET_GET_HOST_BY_NAME_PARAMS_LEN (9) +#define SOCKET_CONNECT_PARAMS_LEN (20) +#define SOCKET_SELECT_PARAMS_LEN (44) +#define SOCKET_SET_SOCK_OPT_PARAMS_LEN (20) +#define SOCKET_GET_SOCK_OPT_PARAMS_LEN (12) +#define SOCKET_RECV_FROM_PARAMS_LEN (12) +#define SOCKET_SENDTO_PARAMS_LEN (24) +#define SOCKET_MDNS_ADVERTISE_PARAMS_LEN (12) + + +// The legnth of arguments for the SEND command: sd + buff_offset + len + flags, +// while size of each parameter is 32 bit - so the total length is 16 bytes; + +#define HCI_CMND_SEND_ARG_LENGTH (16) + + +#define SELECT_TIMEOUT_MIN_MICRO_SECONDS 5000 + +#define HEADERS_SIZE_DATA (SPI_HEADER_SIZE + 5) + +#define SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE (SPI_HEADER_SIZE + SIMPLE_LINK_HCI_CMND_HEADER_SIZE) + +#define MDNS_DEVICE_SERVICE_MAX_LENGTH (32) + + +//***************************************************************************** +// +//! HostFlowControlConsumeBuff +//! +//! @param sd socket descriptor +//! +//! @return 0 in case there are buffers available, +//! -1 in case of bad socket +//! -2 if there are no free buffers present (only when +//! SEND_NON_BLOCKING is enabled) +//! +//! @brief if SEND_NON_BLOCKING not define - block until have free buffer +//! becomes available, else return immediately with correct status +//! regarding the buffers available. +// +//***************************************************************************** +int +HostFlowControlConsumeBuff(int sd) +{ +#ifndef SEND_NON_BLOCKING + /* wait in busy loop */ + do + { + // In case last transmission failed then we will return the last failure + // reason here. + // Note that the buffer will not be allocated in this case + if (tSLInformation.slTransmitDataError != 0) + { + errno = tSLInformation.slTransmitDataError; + tSLInformation.slTransmitDataError = 0; + return errno; + } + + if(SOCKET_STATUS_ACTIVE != get_socket_active_status(sd)) + return -1; + } while(0 == tSLInformation.usNumberOfFreeBuffers); + + tSLInformation.usNumberOfFreeBuffers--; + + return 0; +#else + + // In case last transmission failed then we will return the last failure + // reason here. + // Note that the buffer will not be allocated in this case + if (tSLInformation.slTransmitDataError != 0) + { + errno = tSLInformation.slTransmitDataError; + tSLInformation.slTransmitDataError = 0; + return errno; + } + if(SOCKET_STATUS_ACTIVE != get_socket_active_status(sd)) + return -1; + + //If there are no available buffers, return -2. It is recommended to use + // select or receive to see if there is any buffer occupied with received data + // If so, call receive() to release the buffer. + if(0 == tSLInformation.usNumberOfFreeBuffers) + { + return -2; + } + else + { + tSLInformation.usNumberOfFreeBuffers--; + return 0; + } +#endif +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +int +socket(long domain, long type, long protocol) +{ + long ret; + uint8_t *ptr, *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, domain); + args = UINT32_TO_STREAM(args, type); + args = UINT32_TO_STREAM(args, protocol); + + // Initiate a HCI command + hci_command_send(HCI_CMND_SOCKET, ptr, SOCKET_OPEN_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_SOCKET, &ret); + + // Process the event + errno = ret; + + set_socket_active_status(ret, SOCKET_STATUS_ACTIVE); + + return(ret); +} + +//***************************************************************************** +// +//! closesocket +//! +//! @param sd socket handle. +//! +//! @return On success, zero is returned. On error, -1 is returned. +//! +//! @brief The socket function closes a created socket. +// +//***************************************************************************** + +long +closesocket(long sd) +{ + long ret; + uint8_t *ptr, *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, sd); + + // Initiate a HCI command + hci_command_send(HCI_CMND_CLOSE_SOCKET, + ptr, SOCKET_CLOSE_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_CLOSE_SOCKET, &ret); + errno = ret; + + // since 'close' call may result in either OK (and then it closed) or error + // mark this socket as invalid + set_socket_active_status(sd, SOCKET_STATUS_INACTIVE); + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +accept(long sd, sockaddr *addr, socklen_t *addrlen) +{ + long ret; + uint8_t *ptr, *args; + tBsdReturnParams tAcceptReturnArguments; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, sd); + + // Initiate a HCI command + hci_command_send(HCI_CMND_ACCEPT, + ptr, SOCKET_ACCEPT_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_ACCEPT, &tAcceptReturnArguments); + + + // need specify return parameters!!! + memcpy(addr, &tAcceptReturnArguments.tSocketAddress, ASIC_ADDR_LEN); + *addrlen = ASIC_ADDR_LEN; + errno = tAcceptReturnArguments.iStatus; + ret = errno; + + // if succeeded, iStatus = new socket descriptor. otherwise - error number + if(M_IS_VALID_SD(ret)) + { + set_socket_active_status(ret, SOCKET_STATUS_ACTIVE); + } + else + { + set_socket_active_status(sd, SOCKET_STATUS_INACTIVE); + } + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +bind(long sd, const sockaddr *addr, long addrlen) +{ + long ret; + uint8_t *ptr, *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + addrlen = ASIC_ADDR_LEN; + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, sd); + args = UINT32_TO_STREAM(args, 0x00000008); + args = UINT32_TO_STREAM(args, addrlen); + ARRAY_TO_STREAM(args, ((uint8_t *)addr), addrlen); + + // Initiate a HCI command + hci_command_send(HCI_CMND_BIND, + ptr, SOCKET_BIND_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_BIND, &ret); + + errno = ret; + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +listen(long sd, long backlog) +{ + long ret; + uint8_t *ptr, *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, sd); + args = UINT32_TO_STREAM(args, backlog); + + // Initiate a HCI command + hci_command_send(HCI_CMND_LISTEN, + ptr, SOCKET_LISTEN_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_LISTEN, &ret); + errno = ret; + + return(ret); +} + +//***************************************************************************** +// +//! 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 +int +gethostbyname(char * hostname, uint16_t usNameLen, + unsigned long* out_ip_addr) +{ + tBsdGethostbynameParams ret; + uint8_t *ptr, *args; + + errno = EFAIL; + + if (usNameLen > HOSTNAME_MAX_LENGTH) + { + return errno; + } + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, 8); + args = UINT32_TO_STREAM(args, usNameLen); + ARRAY_TO_STREAM(args, hostname, usNameLen); + + // Initiate a HCI command + hci_command_send(HCI_CMND_GETHOSTNAME, ptr, SOCKET_GET_HOST_BY_NAME_PARAMS_LEN + + usNameLen - 1); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_EVNT_BSD_GETHOSTBYNAME, &ret); + + errno = ret.retVal; + + (*((long*)out_ip_addr)) = ret.outputAddress; + + return (errno); + +} +#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 +// +//***************************************************************************** + +long +connect(long sd, const sockaddr *addr, long addrlen) +{ + long int ret; + uint8_t *ptr, *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE); + addrlen = 8; + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, sd); + args = UINT32_TO_STREAM(args, 0x00000008); + args = UINT32_TO_STREAM(args, addrlen); + ARRAY_TO_STREAM(args, ((uint8_t *)addr), addrlen); + + // Initiate a HCI command + hci_command_send(HCI_CMND_CONNECT, + ptr, SOCKET_CONNECT_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_CONNECT, &ret); + + errno = ret; + + return((long)ret); +} + + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +int +select(long nfds, TICC3000fd_set *readsds, TICC3000fd_set *writesds, TICC3000fd_set *exceptsds, + struct timeval *timeout) +{ + uint8_t *ptr, *args; + tBsdSelectRecvParams tParams; + unsigned long is_blocking; + + if( timeout == NULL) + { + is_blocking = 1; /* blocking , infinity timeout */ + } + else + { + is_blocking = 0; /* no blocking, timeout */ + } + + // Fill in HCI packet structure + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, nfds); + args = UINT32_TO_STREAM(args, 0x00000014); + args = UINT32_TO_STREAM(args, 0x00000014); + args = UINT32_TO_STREAM(args, 0x00000014); + args = UINT32_TO_STREAM(args, 0x00000014); + args = UINT32_TO_STREAM(args, is_blocking); + args = UINT32_TO_STREAM(args, ((readsds) ? *(unsigned long*)readsds : 0)); + args = UINT32_TO_STREAM(args, ((writesds) ? *(unsigned long*)writesds : 0)); + args = UINT32_TO_STREAM(args, ((exceptsds) ? *(unsigned long*)exceptsds : 0)); + + if (timeout) + { + if ( 0 == timeout->tv_sec && timeout->tv_usec < + SELECT_TIMEOUT_MIN_MICRO_SECONDS) + { + timeout->tv_usec = SELECT_TIMEOUT_MIN_MICRO_SECONDS; + } + args = UINT32_TO_STREAM(args, timeout->tv_sec); + args = UINT32_TO_STREAM(args, timeout->tv_usec); + } + + // Initiate a HCI command + hci_command_send(HCI_CMND_BSD_SELECT, ptr, SOCKET_SELECT_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_EVNT_SELECT, &tParams); + + // Update actually read FD + if (tParams.iStatus >= 0) + { + if (readsds) + { + memcpy(readsds, &tParams.uiRdfd, sizeof(tParams.uiRdfd)); + } + + if (writesds) + { + memcpy(writesds, &tParams.uiWrfd, sizeof(tParams.uiWrfd)); + } + + if (exceptsds) + { + memcpy(exceptsds, &tParams.uiExfd, sizeof(tParams.uiExfd)); + } + + return(tParams.iStatus); + + } + else + { + errno = tParams.iStatus; + return(-1); + } +} + +//***************************************************************************** +// +//! 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 +int +setsockopt(long sd, long level, long optname, const void *optval, + socklen_t optlen) +{ + int ret; + uint8_t *ptr, *args; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, sd); + args = UINT32_TO_STREAM(args, level); + args = UINT32_TO_STREAM(args, optname); + args = UINT32_TO_STREAM(args, 0x00000008); + args = UINT32_TO_STREAM(args, optlen); + ARRAY_TO_STREAM(args, ((uint8_t *)optval), optlen); + + // Initiate a HCI command + hci_command_send(HCI_CMND_SETSOCKOPT, + ptr, SOCKET_SET_SOCK_OPT_PARAMS_LEN + optlen); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_SETSOCKOPT, &ret); + + if (ret >= 0) + { + return (0); + } + else + { + errno = ret; + return ret; + } +} +#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 +// +//***************************************************************************** + +int +getsockopt (long sd, long level, long optname, void *optval, socklen_t *optlen) +{ + uint8_t *ptr, *args; + tBsdGetSockOptReturnParams tRetParams; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, sd); + args = UINT32_TO_STREAM(args, level); + args = UINT32_TO_STREAM(args, optname); + + // Initiate a HCI command + hci_command_send(HCI_CMND_GETSOCKOPT, + ptr, SOCKET_GET_SOCK_OPT_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_CMND_GETSOCKOPT, &tRetParams); + + if (((int8_t)tRetParams.iStatus) >= 0) + { + *optlen = 4; + memcpy(optval, tRetParams.ucOptValue, 4); + return (0); + } + else + { + errno = tRetParams.iStatus; + return errno; + } +} + +//***************************************************************************** +// +//! simple_link_recv +//! +//! @param sd socket handle +//! @param buf read buffer +//! @param len buffer length +//! @param flags indicates blocking or non-blocking operation +//! @param from pointer to an address structure indicating source address +//! @param fromlen source address structure size +//! +//! @return Return the number of bytes received, or -1 if an error +//! occurred +//! +//! @brief Read data from socket +//! Return the length of the message on successful completion. +//! If a message is too long to fit in the supplied buffer, +//! excess bytes may be discarded depending on the type of +//! socket the message is received from +// +//***************************************************************************** +int +simple_link_recv(long sd, void *buf, long len, long flags, sockaddr *from, + socklen_t *fromlen, long opcode) +{ + uint8_t *ptr, *args; + tBsdReadReturnParams tSocketReadEvent; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, sd); + args = UINT32_TO_STREAM(args, len); + args = UINT32_TO_STREAM(args, flags); + + // Generate the read command, and wait for the + hci_command_send(opcode, ptr, SOCKET_RECV_FROM_PARAMS_LEN); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(opcode, &tSocketReadEvent); + + // In case the number of bytes is more then zero - read data + if (tSocketReadEvent.iNumberOfBytes > 0) + { + // Wait for the data in a synchronous way. Here we assume that the bug is + // big enough to store also parameters of receive from too.... + SimpleLinkWaitData((uint8_t *)buf, (uint8_t *)from, (uint8_t *)fromlen); + } + + errno = tSocketReadEvent.iNumberOfBytes; + + return(tSocketReadEvent.iNumberOfBytes); +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +int +recv(long sd, void *buf, long len, long flags) +{ + return(simple_link_recv(sd, buf, len, flags, NULL, NULL, HCI_CMND_RECV)); +} + +//***************************************************************************** +// +//! 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 tructure 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. +// +//***************************************************************************** +int +recvfrom(long sd, void *buf, long len, long flags, sockaddr *from, + socklen_t *fromlen) +{ + return(simple_link_recv(sd, buf, len, flags, from, fromlen, + HCI_CMND_RECVFROM)); +} + +//***************************************************************************** +// +//! simple_link_send +//! +//! @param sd socket handle +//! @param buf write buffer +//! @param len buffer length +//! @param flags On this version, this parameter is not supported +//! @param to pointer to an address structure indicating destination +//! address +//! @param tolen destination address structure size +//! +//! @return Return the number of bytes transmitted, or -1 if an error +//! occurred, or -2 in case there are no free buffers available +//! (only when SEND_NON_BLOCKING is enabled) +//! +//! @brief This function is used to transmit a message to another +//! socket +// +//***************************************************************************** +int +simple_link_send(long sd, const void *buf, long len, long flags, + const sockaddr *to, long tolen, long opcode) +{ + uint8_t uArgSize = 0, addrlen; + uint8_t *ptr, *pDataPtr = NULL, *args; + unsigned long addr_offset = 0; + int res; + tBsdReadReturnParams tSocketSendEvent; + + // Check the bsd_arguments + if (0 != (res = HostFlowControlConsumeBuff(sd))) + { + return res; + } + + //Update the number of sent packets + tSLInformation.NumberOfSentPackets++; + + // Allocate a buffer and construct a packet and send it over spi + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_DATA); + + // Update the offset of data and parameters according to the command + switch(opcode) + { + case HCI_CMND_SENDTO: + { + addr_offset = len + sizeof(len) + sizeof(len); + addrlen = 8; + uArgSize = SOCKET_SENDTO_PARAMS_LEN; + pDataPtr = ptr + HEADERS_SIZE_DATA + SOCKET_SENDTO_PARAMS_LEN; + break; + } + + case HCI_CMND_SEND: + { + tolen = 0; + to = NULL; + uArgSize = HCI_CMND_SEND_ARG_LENGTH; + pDataPtr = ptr + HEADERS_SIZE_DATA + HCI_CMND_SEND_ARG_LENGTH; + break; + } + + default: + { + break; + } + } + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, sd); + args = UINT32_TO_STREAM(args, uArgSize - sizeof(sd)); + args = UINT32_TO_STREAM(args, len); + args = UINT32_TO_STREAM(args, flags); + + if (opcode == HCI_CMND_SENDTO) + { + args = UINT32_TO_STREAM(args, addr_offset); + args = UINT32_TO_STREAM(args, addrlen); + } + + // Copy the data received from user into the TX Buffer + ARRAY_TO_STREAM(pDataPtr, ((uint8_t *)buf), len); + + // In case we are using SendTo, copy the to parameters + if (opcode == HCI_CMND_SENDTO) + { + ARRAY_TO_STREAM(pDataPtr, ((uint8_t *)to), tolen); + } + + // Initiate a HCI command + hci_data_send(opcode, ptr, uArgSize, len,(uint8_t*)to, tolen); + + if (opcode == HCI_CMND_SENDTO) + SimpleLinkWaitEvent(HCI_EVNT_SENDTO, &tSocketSendEvent); + else + SimpleLinkWaitEvent(HCI_EVNT_SEND, &tSocketSendEvent); + + return (len); +} + + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +int +send(long sd, const void *buf, long len, long flags) +{ + return(simple_link_send(sd, buf, len, flags, NULL, 0, HCI_CMND_SEND)); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +int +sendto(long sd, const void *buf, long len, long flags, const sockaddr *to, + socklen_t tolen) +{ + return(simple_link_send(sd, buf, len, flags, to, tolen, HCI_CMND_SENDTO)); +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +int +mdnsAdvertiser(uint16_t mdnsEnabled, char * deviceServiceName, uint16_t deviceServiceNameLength) +{ + int ret; + uint8_t *pTxBuffer, *pArgs; + + if (deviceServiceNameLength > MDNS_DEVICE_SERVICE_MAX_LENGTH) + { + return EFAIL; + } + + pTxBuffer = tSLInformation.pucTxCommandBuffer; + pArgs = (pTxBuffer + SIMPLE_LINK_HCI_CMND_TRANSPORT_HEADER_SIZE); + + // Fill in HCI packet structure + pArgs = UINT32_TO_STREAM(pArgs, mdnsEnabled); + pArgs = UINT32_TO_STREAM(pArgs, 8); + pArgs = UINT32_TO_STREAM(pArgs, deviceServiceNameLength); + ARRAY_TO_STREAM(pArgs, deviceServiceName, deviceServiceNameLength); + + // Initiate a HCI command + hci_command_send(HCI_CMND_MDNS_ADVERTISE, pTxBuffer, SOCKET_MDNS_ADVERTISE_PARAMS_LEN + deviceServiceNameLength); + + // Since we are in blocking state - wait for event complete + SimpleLinkWaitEvent(HCI_EVNT_MDNS_ADVERTISE, &ret); + + return ret; + +} diff --git a/nuttx/drivers/wireless/cc3000/spi.c b/nuttx/drivers/wireless/cc3000/spi.c index b7e31ff3b..47e809bba 100644 --- a/nuttx/drivers/wireless/cc3000/spi.c +++ b/nuttx/drivers/wireless/cc3000/spi.c @@ -31,7 +31,7 @@ // This flag lets the interrupt handler know if it should respond to // the WL_SPI_IRQ pin going low or not -short SPIInterruptsEnabled=0; +int16_t SPIInterruptsEnabled=0; #define READ 3 @@ -117,11 +117,11 @@ typedef struct { gcSpiHandleRx SPIRxHandler; - unsigned short usTxPacketLength; - unsigned short usRxPacketLength; + uint16_t usTxPacketLength; + uint16_t usRxPacketLength; unsigned long ulSpiState; - unsigned char *pTxPacket; - unsigned char *pRxPacket; + uint8_t *pTxPacket; + uint8_t *pRxPacket; }tSpiInformation; @@ -131,7 +131,7 @@ tSpiInformation sSpiInformation; // // Static buffer for 5 bytes of SPI HEADER // -unsigned char tSpiReadHeader[] = {READ, 0, 0, 0, 0}; +uint8_t tSpiReadHeader[] = {READ, 0, 0, 0, 0}; // The magic number that resides at the end of the TX/RX buffer (1 byte after the allocated size) @@ -141,11 +141,11 @@ unsigned char tSpiReadHeader[] = {READ, 0, 0, 0, 0}; #define CC3000_BUFFER_MAGIC_NUMBER (0xDE) char spi_buffer[CC3000_RX_BUFFER_SIZE]; -unsigned char wlan_tx_buffer[CC3000_TX_BUFFER_SIZE]; +uint8_t wlan_tx_buffer[CC3000_TX_BUFFER_SIZE]; struct spi_dev_s *spi = NULL; -unsigned int SPIPump(unsigned char data) +unsigned int SPIPump(uint8_t data) { uint8_t rx; @@ -245,10 +245,10 @@ void SpiTriggerRxProcessing(void) //! \brief ... // //***************************************************************************** -void SpiReadDataSynchronous(unsigned char *data, unsigned short size) +void SpiReadDataSynchronous(uint8_t *data, uint16_t size) { long i = 0; - unsigned char *data_to_send = tSpiReadHeader; + uint8_t *data_to_send = tSpiReadHeader; for (i = 0; i < size; i ++) { data[i] = SPIPump(data_to_send[0]); @@ -267,7 +267,7 @@ void SpiReadDataSynchronous(unsigned char *data, unsigned short size) //! \brief ... // //***************************************************************************** -void SpiWriteDataSynchronous(unsigned char *data, unsigned short size) +void SpiWriteDataSynchronous(uint8_t *data, uint16_t size) { while (size) @@ -290,7 +290,7 @@ void SpiWriteDataSynchronous(unsigned char *data, unsigned short size) //! \brief ... // //***************************************************************************** -long SpiFirstWrite(unsigned char *ucBuf, unsigned short usLength) +long SpiFirstWrite(uint8_t *ucBuf, uint16_t usLength) { // // workaround for first transaction @@ -328,9 +328,9 @@ long SpiFirstWrite(unsigned char *ucBuf, unsigned short usLength) //! \brief ... // //***************************************************************************** -long SpiWrite(unsigned char *pUserBuffer, unsigned short usLength) +long SpiWrite(uint8_t *pUserBuffer, uint16_t usLength) { - unsigned char ucPad = 0; + uint8_t ucPad = 0; // // Figure out the total length of the packet in order to figure out if there is padding or not @@ -442,7 +442,7 @@ long SpiWrite(unsigned char *pUserBuffer, unsigned short usLength) long SpiReadDataCont(void) { long data_to_recv; - unsigned char *evnt_buff, type; + uint8_t *evnt_buff, type; // @@ -644,7 +644,7 @@ void SpiOpen(gcSpiHandleRx pfRxHandler) sSpiInformation.SPIRxHandler = pfRxHandler; sSpiInformation.usTxPacketLength = 0; sSpiInformation.pTxPacket = NULL; - sSpiInformation.pRxPacket = (unsigned char *)spi_buffer; + sSpiInformation.pRxPacket = (uint8_t *)spi_buffer; sSpiInformation.usRxPacketLength = 0; spi_buffer[CC3000_RX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER; wlan_tx_buffer[CC3000_TX_BUFFER_SIZE - 1] = CC3000_BUFFER_MAGIC_NUMBER; diff --git a/nuttx/drivers/wireless/cc3000/wlan.c b/nuttx/drivers/wireless/cc3000/wlan.c index b30b82c10..48735947b 100644 --- a/nuttx/drivers/wireless/cc3000/wlan.c +++ b/nuttx/drivers/wireless/cc3000/wlan.c @@ -1,1254 +1,1251 @@ -/***************************************************************************** -* -* wlan.c - 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. -* -*****************************************************************************/ - -//***************************************************************************** -// -//! \addtogroup wlan_api -//! @{ -// -//***************************************************************************** -#include -#include -#include -#include -#include -#include -#include -#include - - -volatile sSimplLinkInformation tSLInformation; - -#define SMART_CONFIG_PROFILE_SIZE 67 // 67 = 32 (max ssid) + 32 (max key) + 1 (SSID length) + 1 (security type) + 1 (key length) - -#ifndef CC3000_UNENCRYPTED_SMART_CONFIG -unsigned char akey[AES128_KEY_SIZE]; -unsigned char profileArray[SMART_CONFIG_PROFILE_SIZE]; -#endif //CC3000_UNENCRYPTED_SMART_CONFIG - -/* patches type */ -#define PATCHES_HOST_TYPE_WLAN_DRIVER 0x01 -#define PATCHES_HOST_TYPE_WLAN_FW 0x02 -#define PATCHES_HOST_TYPE_BOOTLOADER 0x03 - -#define SL_SET_SCAN_PARAMS_INTERVAL_LIST_SIZE (16) -#define SL_SIMPLE_CONFIG_PREFIX_LENGTH (3) -#define ETH_ALEN (6) -#define MAXIMAL_SSID_LENGTH (32) - -#define SL_PATCHES_REQUEST_DEFAULT (0) -#define SL_PATCHES_REQUEST_FORCE_HOST (1) -#define SL_PATCHES_REQUEST_FORCE_NONE (2) - - -#define WLAN_SEC_UNSEC (0) -#define WLAN_SEC_WEP (1) -#define WLAN_SEC_WPA (2) -#define WLAN_SEC_WPA2 (3) - - -#define WLAN_SL_INIT_START_PARAMS_LEN (1) -#define WLAN_PATCH_PARAMS_LENGTH (8) -#define WLAN_SET_CONNECTION_POLICY_PARAMS_LEN (12) -#define WLAN_DEL_PROFILE_PARAMS_LEN (4) -#define WLAN_SET_MASK_PARAMS_LEN (4) -#define WLAN_SET_SCAN_PARAMS_LEN (100) -#define WLAN_GET_SCAN_RESULTS_PARAMS_LEN (4) -#define WLAN_ADD_PROFILE_NOSEC_PARAM_LEN (24) -#define WLAN_ADD_PROFILE_WEP_PARAM_LEN (36) -#define WLAN_ADD_PROFILE_WPA_PARAM_LEN (44) -#define WLAN_CONNECT_PARAM_LEN (29) -#define WLAN_SMART_CONFIG_START_PARAMS_LEN (4) - - - - -//***************************************************************************** -// -//! SimpleLink_Init_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 Send HCI_CMND_SIMPLE_LINK_START to CC3000 -// -//***************************************************************************** -static void SimpleLink_Init_Start(unsigned short usPatchesAvailableAtHost) -{ - unsigned char *ptr; - unsigned char *args; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (unsigned char *)(ptr + HEADERS_SIZE_CMD); - - UINT8_TO_STREAM(args, ((usPatchesAvailableAtHost) ? SL_PATCHES_REQUEST_FORCE_HOST : SL_PATCHES_REQUEST_DEFAULT)); - - // IRQ Line asserted - send HCI_CMND_SIMPLE_LINK_START to CC3000 - hci_command_send(HCI_CMND_SIMPLE_LINK_START, ptr, WLAN_SL_INIT_START_PARAMS_LEN); - - printf ("Goind to call SimpleLinkWaitEvent...\n"); - SimpleLinkWaitEvent(HCI_CMND_SIMPLE_LINK_START, 0); -} - - - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -void wlan_init( tWlanCB sWlanCB, - tFWPatches sFWPatches, - tDriverPatches sDriverPatches, - tBootLoaderPatches sBootLoaderPatches, - tWlanReadInteruptPin sReadWlanInterruptPin, - tWlanInterruptEnable sWlanInterruptEnable, - tWlanInterruptDisable sWlanInterruptDisable, - tWriteWlanPin sWriteWlanPin) -{ - - tSLInformation.sFWPatches = sFWPatches; - tSLInformation.sDriverPatches = sDriverPatches; - tSLInformation.sBootLoaderPatches = sBootLoaderPatches; - - // init io callback - tSLInformation.ReadWlanInterruptPin = sReadWlanInterruptPin; - tSLInformation.WlanInterruptEnable = sWlanInterruptEnable; - tSLInformation.WlanInterruptDisable = sWlanInterruptDisable; - tSLInformation.WriteWlanPin = sWriteWlanPin; - - //init asynchronous events callback - tSLInformation.sWlanCB= sWlanCB; - - // By default TX Complete events are routed to host too - tSLInformation.InformHostOnTxComplete = 1; -} - -//***************************************************************************** -// -//! SpiReceiveHandler -//! -//! @param pvBuffer - pointer to the received data buffer -//! The function triggers Received event/data processing -//! -//! @param Pointer to the received data -//! @return none -//! -//! @brief The function triggers Received event/data processing. It is -//! called from the SPI library to receive the data -// -//***************************************************************************** -void SpiReceiveHandler(void *pvBuffer) -{ - tSLInformation.usEventOrDataReceived = 1; - tSLInformation.pucReceivedData = (unsigned char *)pvBuffer; - - hci_unsolicited_event_handler(); -} - - -//***************************************************************************** -// -//! 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 -//! -// -//***************************************************************************** - -void -wlan_start(unsigned short usPatchesAvailableAtHost) -{ - - unsigned long ulSpiIRQState; - - tSLInformation.NumberOfSentPackets = 0; - tSLInformation.NumberOfReleasedPackets = 0; - tSLInformation.usRxEventOpcode = 0; - tSLInformation.usNumberOfFreeBuffers = 0; - tSLInformation.usSlBufferLength = 0; - tSLInformation.usBufferSize = 0; - tSLInformation.usRxDataPending = 0; - tSLInformation.slTransmitDataError = 0; - tSLInformation.usEventOrDataReceived = 0; - tSLInformation.pucReceivedData = 0; - - // Allocate the memory for the RX/TX data transactions - tSLInformation.pucTxCommandBuffer = (unsigned char *)wlan_tx_buffer; - - // init spi - SpiOpen(SpiReceiveHandler); - - // Check the IRQ line - ulSpiIRQState = tSLInformation.ReadWlanInterruptPin(); - - // ASIC 1273 chip enable: toggle WLAN EN line - tSLInformation.WriteWlanPin( WLAN_ENABLE ); - - if (ulSpiIRQState) - { - // wait till the IRQ line goes low - while(tSLInformation.ReadWlanInterruptPin() != 0) - { - } - } - else - { - // wait till the IRQ line goes high and than low - while(tSLInformation.ReadWlanInterruptPin() == 0) - { - } - - while(tSLInformation.ReadWlanInterruptPin() != 0) - { - } - } - - printf("Going to call SimpleLink_Init_Start...\n"); - SimpleLink_Init_Start(usPatchesAvailableAtHost); - printf("Returned from SimpleLink_Init_Start...\n"); - - // Read Buffer's size and finish - hci_command_send(HCI_CMND_READ_BUFFER_SIZE, tSLInformation.pucTxCommandBuffer, 0); - SimpleLinkWaitEvent(HCI_CMND_READ_BUFFER_SIZE, 0); -} - - -//***************************************************************************** -// -//! wlan_stop -//! -//! @param none -//! -//! @return none -//! -//! @brief Stop WLAN device by putting it into reset state. -//! -//! @sa wlan_start -// -//***************************************************************************** - -void -wlan_stop(void) -{ - // ASIC 1273 chip disable - tSLInformation.WriteWlanPin( WLAN_DISABLE ); - - // Wait till IRQ line goes high... - while(tSLInformation.ReadWlanInterruptPin() == 0) - { - } - - // Free the used by WLAN Driver memory - if (tSLInformation.pucTxCommandBuffer) - { - tSLInformation.pucTxCommandBuffer = 0; - } - - SpiClose(); -} - - -//***************************************************************************** -// -//! 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 -long -wlan_connect(unsigned long ulSecType, char *ssid, long ssid_len, - unsigned char *bssid, unsigned char *key, long key_len) -{ - long ret; - unsigned char *ptr; - unsigned char *args; - unsigned char bssid_zero[] = {0, 0, 0, 0, 0, 0}; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in command buffer - args = UINT32_TO_STREAM(args, 0x0000001c); - args = UINT32_TO_STREAM(args, ssid_len); - args = UINT32_TO_STREAM(args, ulSecType); - args = UINT32_TO_STREAM(args, 0x00000010 + ssid_len); - args = UINT32_TO_STREAM(args, key_len); - args = UINT16_TO_STREAM(args, 0); - - // padding shall be zeroed - if(bssid) - { - ARRAY_TO_STREAM(args, bssid, ETH_ALEN); - } - else - { - ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); - } - - ARRAY_TO_STREAM(args, ssid, ssid_len); - - if(key_len && key) - { - ARRAY_TO_STREAM(args, key, key_len); - } - - // Initiate a HCI command - hci_command_send(HCI_CMND_WLAN_CONNECT, ptr, WLAN_CONNECT_PARAM_LEN + - ssid_len + key_len - 1); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_CONNECT, &ret); - errno = ret; - - return(ret); -} -#else -long -wlan_connect(char *ssid, long ssid_len) -{ - long ret; - unsigned char *ptr; - unsigned char *args; - unsigned char bssid_zero[] = {0, 0, 0, 0, 0, 0}; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in command buffer - args = UINT32_TO_STREAM(args, 0x0000001c); - args = UINT32_TO_STREAM(args, ssid_len); - args = UINT32_TO_STREAM(args, 0); - args = UINT32_TO_STREAM(args, 0x00000010 + ssid_len); - args = UINT32_TO_STREAM(args, 0); - args = UINT16_TO_STREAM(args, 0); - - // padding shall be zeroed - ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); - ARRAY_TO_STREAM(args, ssid, ssid_len); - - // Initiate a HCI command - hci_command_send(HCI_CMND_WLAN_CONNECT, ptr, WLAN_CONNECT_PARAM_LEN + - ssid_len - 1); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_CONNECT, &ret); - errno = ret; - - return(ret); -} -#endif - -//***************************************************************************** -// -//! wlan_disconnect -//! -//! @return 0 disconnected done, other CC3000 already disconnected -//! -//! @brief Disconnect connection from AP. -//! -//! @sa wlan_connect -// -//***************************************************************************** - -long -wlan_disconnect() -{ - long ret; - unsigned char *ptr; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - - hci_command_send(HCI_CMND_WLAN_DISCONNECT, ptr, 0); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_DISCONNECT, &ret); - errno = ret; - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -wlan_ioctl_set_connection_policy(unsigned long should_connect_to_open_ap, - unsigned long ulShouldUseFastConnect, - unsigned long ulUseProfiles) -{ - long ret; - unsigned char *ptr; - unsigned char *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (unsigned char *)(ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, should_connect_to_open_ap); - args = UINT32_TO_STREAM(args, ulShouldUseFastConnect); - args = UINT32_TO_STREAM(args, ulUseProfiles); - - // Initiate a HCI command - hci_command_send(HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY, - ptr, WLAN_SET_CONNECTION_POLICY_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY, &ret); - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -#ifndef CC3000_TINY_DRIVER -long -wlan_add_profile(unsigned long ulSecType, - unsigned char* ucSsid, - unsigned long ulSsidLen, - unsigned char *ucBssid, - unsigned long ulPriority, - unsigned long ulPairwiseCipher_Or_TxKeyLen, - unsigned long ulGroupCipher_TxKeyIndex, - unsigned long ulKeyMgmt, - unsigned char* ucPf_OrKey, - unsigned long ulPassPhraseLen) -{ - unsigned short arg_len = 0; - long ret; - unsigned char *ptr; - long i = 0; - unsigned char *args; - unsigned char bssid_zero[] = {0, 0, 0, 0, 0, 0}; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - args = UINT32_TO_STREAM(args, ulSecType); - - // Setup arguments in accordance with the security type - switch (ulSecType) - { - //OPEN - case WLAN_SEC_UNSEC: - { - args = UINT32_TO_STREAM(args, 0x00000014); - args = UINT32_TO_STREAM(args, ulSsidLen); - args = UINT16_TO_STREAM(args, 0); - if(ucBssid) - { - ARRAY_TO_STREAM(args, ucBssid, ETH_ALEN); - } - else - { - ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); - } - args = UINT32_TO_STREAM(args, ulPriority); - ARRAY_TO_STREAM(args, ucSsid, ulSsidLen); - - arg_len = WLAN_ADD_PROFILE_NOSEC_PARAM_LEN + ulSsidLen; - } - break; - - //WEP - case WLAN_SEC_WEP: - { - args = UINT32_TO_STREAM(args, 0x00000020); - args = UINT32_TO_STREAM(args, ulSsidLen); - args = UINT16_TO_STREAM(args, 0); - if(ucBssid) - { - ARRAY_TO_STREAM(args, ucBssid, ETH_ALEN); - } - else - { - ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); - } - args = UINT32_TO_STREAM(args, ulPriority); - args = UINT32_TO_STREAM(args, 0x0000000C + ulSsidLen); - args = UINT32_TO_STREAM(args, ulPairwiseCipher_Or_TxKeyLen); - args = UINT32_TO_STREAM(args, ulGroupCipher_TxKeyIndex); - ARRAY_TO_STREAM(args, ucSsid, ulSsidLen); - - for(i = 0; i < 4; i++) - { - unsigned char *p = &ucPf_OrKey[i * ulPairwiseCipher_Or_TxKeyLen]; - - ARRAY_TO_STREAM(args, p, ulPairwiseCipher_Or_TxKeyLen); - } - - arg_len = WLAN_ADD_PROFILE_WEP_PARAM_LEN + ulSsidLen + - ulPairwiseCipher_Or_TxKeyLen * 4; - - } - break; - - //WPA - //WPA2 - case WLAN_SEC_WPA: - case WLAN_SEC_WPA2: - { - args = UINT32_TO_STREAM(args, 0x00000028); - args = UINT32_TO_STREAM(args, ulSsidLen); - args = UINT16_TO_STREAM(args, 0); - if(ucBssid) - { - ARRAY_TO_STREAM(args, ucBssid, ETH_ALEN); - } - else - { - ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); - } - args = UINT32_TO_STREAM(args, ulPriority); - args = UINT32_TO_STREAM(args, ulPairwiseCipher_Or_TxKeyLen); - args = UINT32_TO_STREAM(args, ulGroupCipher_TxKeyIndex); - args = UINT32_TO_STREAM(args, ulKeyMgmt); - args = UINT32_TO_STREAM(args, 0x00000008 + ulSsidLen); - args = UINT32_TO_STREAM(args, ulPassPhraseLen); - ARRAY_TO_STREAM(args, ucSsid, ulSsidLen); - ARRAY_TO_STREAM(args, ucPf_OrKey, ulPassPhraseLen); - - arg_len = WLAN_ADD_PROFILE_WPA_PARAM_LEN + ulSsidLen + ulPassPhraseLen; - } - - break; - } - - // Initiate a HCI command - hci_command_send(HCI_CMND_WLAN_IOCTL_ADD_PROFILE, - ptr, arg_len); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_ADD_PROFILE, &ret); - - return(ret); -} -#else -long -wlan_add_profile(unsigned long ulSecType, - unsigned char* ucSsid, - unsigned long ulSsidLen, - unsigned char *ucBssid, - unsigned long ulPriority, - unsigned long ulPairwiseCipher_Or_TxKeyLen, - unsigned long ulGroupCipher_TxKeyIndex, - unsigned long ulKeyMgmt, - unsigned char* ucPf_OrKey, - unsigned long ulPassPhraseLen) -{ - return -1; -} -#endif - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -wlan_ioctl_del_profile(unsigned long ulIndex) -{ - long ret; - unsigned char *ptr; - unsigned char *args; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (unsigned char *)(ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, ulIndex); - ret = EFAIL; - - // Initiate a HCI command - hci_command_send(HCI_CMND_WLAN_IOCTL_DEL_PROFILE, - ptr, WLAN_DEL_PROFILE_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_DEL_PROFILE, &ret); - - return(ret); -} - -//***************************************************************************** -// -//! wlan_ioctl_get_scan_results -//! -//! @param[in] scan_timeout parameter not supported -//! @param[out] ucResults scan results (_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 -// -//***************************************************************************** - -#ifndef CC3000_TINY_DRIVER -long -wlan_ioctl_get_scan_results(unsigned long ulScanTimeout, - unsigned char *ucResults) -{ - unsigned char *ptr; - unsigned char *args; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, ulScanTimeout); - - // Initiate a HCI command - hci_command_send(HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS, - ptr, WLAN_GET_SCAN_RESULTS_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS, ucResults); - - return(0); -} -#endif - -//***************************************************************************** -// -//! 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 millisecond. 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 -// -//***************************************************************************** - -#ifndef CC3000_TINY_DRIVER -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) -{ - unsigned long uiRes; - unsigned char *ptr; - unsigned char *args; - - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - // Fill in temporary command buffer - args = UINT32_TO_STREAM(args, 36); - args = UINT32_TO_STREAM(args, uiEnable); - args = UINT32_TO_STREAM(args, uiMinDwellTime); - args = UINT32_TO_STREAM(args, uiMaxDwellTime); - args = UINT32_TO_STREAM(args, uiNumOfProbeRequests); - args = UINT32_TO_STREAM(args, uiChannelMask); - args = UINT32_TO_STREAM(args, iRSSIThreshold); - args = UINT32_TO_STREAM(args, uiSNRThreshold); - args = UINT32_TO_STREAM(args, uiDefaultTxPower); - ARRAY_TO_STREAM(args, aiIntervalList, sizeof(unsigned long) * - SL_SET_SCAN_PARAMS_INTERVAL_LIST_SIZE); - - // Initiate a HCI command - hci_command_send(HCI_CMND_WLAN_IOCTL_SET_SCANPARAM, - ptr, WLAN_SET_SCAN_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SET_SCANPARAM, &uiRes); - - return(uiRes); -} -#endif - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - -long -wlan_set_event_mask(unsigned long ulMask) -{ - long ret; - unsigned char *ptr; - unsigned char *args; - - - if ((ulMask & HCI_EVNT_WLAN_TX_COMPLETE) == HCI_EVNT_WLAN_TX_COMPLETE) - { - tSLInformation.InformHostOnTxComplete = 0; - - // Since an event is a virtual event - i.e. it is not coming from CC3000 - // there is no need to send anything to the device if it was an only event - if (ulMask == HCI_EVNT_WLAN_TX_COMPLETE) - { - return 0; - } - - ulMask &= ~HCI_EVNT_WLAN_TX_COMPLETE; - ulMask |= HCI_EVNT_WLAN_UNSOL_BASE; - } - else - { - tSLInformation.InformHostOnTxComplete = 1; - } - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (unsigned char *)(ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, ulMask); - - // Initiate a HCI command - hci_command_send(HCI_CMND_EVENT_MASK, - ptr, WLAN_SET_MASK_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_EVENT_MASK, &ret); - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -#ifndef CC3000_TINY_DRIVER -long -wlan_ioctl_statusget(void) -{ - long ret; - unsigned char *ptr; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - - hci_command_send(HCI_CMND_WLAN_IOCTL_STATUSGET, - ptr, 0); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_STATUSGET, &ret); - - return(ret); -} -#endif - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -wlan_smart_config_start(unsigned long algoEncryptedFlag) -{ - long ret; - unsigned char *ptr; - unsigned char *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (unsigned char *)(ptr + HEADERS_SIZE_CMD); - - // Fill in HCI packet structure - args = UINT32_TO_STREAM(args, algoEncryptedFlag); - ret = EFAIL; - - hci_command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START, ptr, - WLAN_SMART_CONFIG_START_PARAMS_LEN); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START, &ret); - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -wlan_smart_config_stop(void) -{ - long ret; - unsigned char *ptr; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - - hci_command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP, ptr, 0); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP, &ret); - - return(ret); -} - -//***************************************************************************** -// -//! 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 -// -//***************************************************************************** - -long -wlan_smart_config_set_prefix(char* cNewPrefix) -{ - long ret; - unsigned char *ptr; - unsigned char *args; - - ret = EFAIL; - ptr = tSLInformation.pucTxCommandBuffer; - args = (ptr + HEADERS_SIZE_CMD); - - if (cNewPrefix == NULL) - return ret; - else // with the new Smart Config, prefix must be TTT - { - *cNewPrefix = 'T'; - *(cNewPrefix + 1) = 'T'; - *(cNewPrefix + 2) = 'T'; - } - - ARRAY_TO_STREAM(args, cNewPrefix, SL_SIMPLE_CONFIG_PREFIX_LENGTH); - - hci_command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX, ptr, - SL_SIMPLE_CONFIG_PREFIX_LENGTH); - - // Wait for command complete event - SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX, &ret); - - return(ret); -} - -//***************************************************************************** -// -//! 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. -// -//***************************************************************************** - - -#ifndef CC3000_UNENCRYPTED_SMART_CONFIG -long -wlan_smart_config_process() -{ - signed long returnValue; - unsigned long ssidLen, keyLen; - unsigned char *decKeyPtr; - unsigned char *ssidPtr; - - // read the key from EEPROM - fileID 12 - returnValue = aes_read_key(akey); - - if (returnValue != 0) - return returnValue; - - // read the received data from fileID #13 and parse it according to the followings: - // 1) SSID LEN - not encrypted - // 2) SSID - not encrypted - // 3) KEY LEN - not encrypted. always 32 bytes long - // 4) Security type - not encrypted - // 5) KEY - encrypted together with true key length as the first byte in KEY - // to elaborate, there are two corner cases: - // 1) the KEY is 32 bytes long. In this case, the first byte does not represent KEY length - // 2) the KEY is 31 bytes long. In this case, the first byte represent KEY length and equals 31 - returnValue = nvmem_read(NVMEM_SHARED_MEM_FILEID, SMART_CONFIG_PROFILE_SIZE, 0, profileArray); - - if (returnValue != 0) - return returnValue; - - ssidPtr = &profileArray[1]; - - ssidLen = profileArray[0]; - - decKeyPtr = &profileArray[profileArray[0] + 3]; - - aes_decrypt(decKeyPtr, akey); - if (profileArray[profileArray[0] + 1] > 16) - aes_decrypt((unsigned char *)(decKeyPtr + 16), akey); - - if (*(unsigned char *)(decKeyPtr +31) != 0) - { - if (*decKeyPtr == 31) - { - keyLen = 31; - decKeyPtr++; - } - else - { - keyLen = 32; - } - } - else - { - keyLen = *decKeyPtr; - decKeyPtr++; - } - - // add a profile - switch (profileArray[profileArray[0] + 2]) - { - case WLAN_SEC_UNSEC://None - { - returnValue = wlan_add_profile(profileArray[profileArray[0] + 2], // security type - ssidPtr, // SSID - ssidLen, // SSID length - NULL, // BSSID - 1, // Priority - 0, 0, 0, 0, 0); - - break; - } - - case WLAN_SEC_WEP://WEP - { - returnValue = wlan_add_profile(profileArray[profileArray[0] + 2], // security type - ssidPtr, // SSID - ssidLen, // SSID length - NULL, // BSSID - 1, // Priority - keyLen, // KEY length - 0, // KEY index - 0, - decKeyPtr, // KEY - 0); - - break; - } - - case WLAN_SEC_WPA://WPA - case WLAN_SEC_WPA2://WPA2 - { - returnValue = wlan_add_profile(WLAN_SEC_WPA2, // security type - ssidPtr, - ssidLen, - NULL, // BSSID - 1, // Priority - 0x18, // PairwiseCipher - 0x1e, // GroupCipher - 2, // KEY management - decKeyPtr, // KEY - keyLen); // KEY length - - break; - } - } - - return returnValue; -} -#endif //CC3000_UNENCRYPTED_SMART_CONFIG - -//***************************************************************************** -// -// Close the Doxygen group. -//! @} -// -//***************************************************************************** +/***************************************************************************** +* +* wlan.c - 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. +* +*****************************************************************************/ + +//***************************************************************************** +// +//! \addtogroup wlan_api +//! @{ +// +//***************************************************************************** +#include +#include +#include +#include +#include +#include +#include +#include + + +volatile sSimplLinkInformation tSLInformation; + +#define SMART_CONFIG_PROFILE_SIZE 67 // 67 = 32 (max ssid) + 32 (max key) + 1 (SSID length) + 1 (security type) + 1 (key length) + +#ifndef CC3000_UNENCRYPTED_SMART_CONFIG +uint8_t akey[AES128_KEY_SIZE]; +uint8_t profileArray[SMART_CONFIG_PROFILE_SIZE]; +#endif //CC3000_UNENCRYPTED_SMART_CONFIG + +/* patches type */ +#define PATCHES_HOST_TYPE_WLAN_DRIVER 0x01 +#define PATCHES_HOST_TYPE_WLAN_FW 0x02 +#define PATCHES_HOST_TYPE_BOOTLOADER 0x03 + +#define SL_SET_SCAN_PARAMS_INTERVAL_LIST_SIZE (16) +#define SL_SIMPLE_CONFIG_PREFIX_LENGTH (3) +#define ETH_ALEN (6) +#define MAXIMAL_SSID_LENGTH (32) + +#define SL_PATCHES_REQUEST_DEFAULT (0) +#define SL_PATCHES_REQUEST_FORCE_HOST (1) +#define SL_PATCHES_REQUEST_FORCE_NONE (2) + + +#define WLAN_SEC_UNSEC (0) +#define WLAN_SEC_WEP (1) +#define WLAN_SEC_WPA (2) +#define WLAN_SEC_WPA2 (3) + + +#define WLAN_SL_INIT_START_PARAMS_LEN (1) +#define WLAN_PATCH_PARAMS_LENGTH (8) +#define WLAN_SET_CONNECTION_POLICY_PARAMS_LEN (12) +#define WLAN_DEL_PROFILE_PARAMS_LEN (4) +#define WLAN_SET_MASK_PARAMS_LEN (4) +#define WLAN_SET_SCAN_PARAMS_LEN (100) +#define WLAN_GET_SCAN_RESULTS_PARAMS_LEN (4) +#define WLAN_ADD_PROFILE_NOSEC_PARAM_LEN (24) +#define WLAN_ADD_PROFILE_WEP_PARAM_LEN (36) +#define WLAN_ADD_PROFILE_WPA_PARAM_LEN (44) +#define WLAN_CONNECT_PARAM_LEN (29) +#define WLAN_SMART_CONFIG_START_PARAMS_LEN (4) + + + + +//***************************************************************************** +// +//! SimpleLink_Init_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 Send HCI_CMND_SIMPLE_LINK_START to CC3000 +// +//***************************************************************************** +static void SimpleLink_Init_Start(uint16_t usPatchesAvailableAtHost) +{ + uint8_t *ptr; + uint8_t *args; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (uint8_t *)(ptr + HEADERS_SIZE_CMD); + + UINT8_TO_STREAM(args, ((usPatchesAvailableAtHost) ? SL_PATCHES_REQUEST_FORCE_HOST : SL_PATCHES_REQUEST_DEFAULT)); + + // IRQ Line asserted - send HCI_CMND_SIMPLE_LINK_START to CC3000 + hci_command_send(HCI_CMND_SIMPLE_LINK_START, ptr, WLAN_SL_INIT_START_PARAMS_LEN); + + SimpleLinkWaitEvent(HCI_CMND_SIMPLE_LINK_START, 0); +} + + + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +void wlan_init( tWlanCB sWlanCB, + tFWPatches sFWPatches, + tDriverPatches sDriverPatches, + tBootLoaderPatches sBootLoaderPatches, + tWlanReadInteruptPin sReadWlanInterruptPin, + tWlanInterruptEnable sWlanInterruptEnable, + tWlanInterruptDisable sWlanInterruptDisable, + tWriteWlanPin sWriteWlanPin) +{ + + tSLInformation.sFWPatches = sFWPatches; + tSLInformation.sDriverPatches = sDriverPatches; + tSLInformation.sBootLoaderPatches = sBootLoaderPatches; + + // init io callback + tSLInformation.ReadWlanInterruptPin = sReadWlanInterruptPin; + tSLInformation.WlanInterruptEnable = sWlanInterruptEnable; + tSLInformation.WlanInterruptDisable = sWlanInterruptDisable; + tSLInformation.WriteWlanPin = sWriteWlanPin; + + //init asynchronous events callback + tSLInformation.sWlanCB= sWlanCB; + + // By default TX Complete events are routed to host too + tSLInformation.InformHostOnTxComplete = 1; +} + +//***************************************************************************** +// +//! SpiReceiveHandler +//! +//! @param pvBuffer - pointer to the received data buffer +//! The function triggers Received event/data processing +//! +//! @param Pointer to the received data +//! @return none +//! +//! @brief The function triggers Received event/data processing. It is +//! called from the SPI library to receive the data +// +//***************************************************************************** +void SpiReceiveHandler(void *pvBuffer) +{ + tSLInformation.usEventOrDataReceived = 1; + tSLInformation.pucReceivedData = (uint8_t *)pvBuffer; + + hci_unsolicited_event_handler(); +} + + +//***************************************************************************** +// +//! 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 +//! +// +//***************************************************************************** + +void +wlan_start(uint16_t usPatchesAvailableAtHost) +{ + + unsigned long ulSpiIRQState; + + tSLInformation.NumberOfSentPackets = 0; + tSLInformation.NumberOfReleasedPackets = 0; + tSLInformation.usRxEventOpcode = 0; + tSLInformation.usNumberOfFreeBuffers = 0; + tSLInformation.usSlBufferLength = 0; + tSLInformation.usBufferSize = 0; + tSLInformation.usRxDataPending = 0; + tSLInformation.slTransmitDataError = 0; + tSLInformation.usEventOrDataReceived = 0; + tSLInformation.pucReceivedData = 0; + + // Allocate the memory for the RX/TX data transactions + tSLInformation.pucTxCommandBuffer = (uint8_t *)wlan_tx_buffer; + + // init spi + SpiOpen(SpiReceiveHandler); + + // Check the IRQ line + ulSpiIRQState = tSLInformation.ReadWlanInterruptPin(); + + // ASIC 1273 chip enable: toggle WLAN EN line + tSLInformation.WriteWlanPin( WLAN_ENABLE ); + + if (ulSpiIRQState) + { + // wait till the IRQ line goes low + while(tSLInformation.ReadWlanInterruptPin() != 0) + { + } + } + else + { + // wait till the IRQ line goes high and than low + while(tSLInformation.ReadWlanInterruptPin() == 0) + { + } + + while(tSLInformation.ReadWlanInterruptPin() != 0) + { + } + } + + SimpleLink_Init_Start(usPatchesAvailableAtHost); + + // Read Buffer's size and finish + hci_command_send(HCI_CMND_READ_BUFFER_SIZE, tSLInformation.pucTxCommandBuffer, 0); + SimpleLinkWaitEvent(HCI_CMND_READ_BUFFER_SIZE, 0); +} + + +//***************************************************************************** +// +//! wlan_stop +//! +//! @param none +//! +//! @return none +//! +//! @brief Stop WLAN device by putting it into reset state. +//! +//! @sa wlan_start +// +//***************************************************************************** + +void +wlan_stop(void) +{ + // ASIC 1273 chip disable + tSLInformation.WriteWlanPin( WLAN_DISABLE ); + + // Wait till IRQ line goes high... + while(tSLInformation.ReadWlanInterruptPin() == 0) + { + } + + // Free the used by WLAN Driver memory + if (tSLInformation.pucTxCommandBuffer) + { + tSLInformation.pucTxCommandBuffer = 0; + } + + SpiClose(); +} + + +//***************************************************************************** +// +//! 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 +long +wlan_connect(unsigned long ulSecType, char *ssid, long ssid_len, + uint8_t *bssid, uint8_t *key, long key_len) +{ + long ret; + uint8_t *ptr; + uint8_t *args; + uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0}; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in command buffer + args = UINT32_TO_STREAM(args, 0x0000001c); + args = UINT32_TO_STREAM(args, ssid_len); + args = UINT32_TO_STREAM(args, ulSecType); + args = UINT32_TO_STREAM(args, 0x00000010 + ssid_len); + args = UINT32_TO_STREAM(args, key_len); + args = UINT16_TO_STREAM(args, 0); + + // padding shall be zeroed + if(bssid) + { + ARRAY_TO_STREAM(args, bssid, ETH_ALEN); + } + else + { + ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); + } + + ARRAY_TO_STREAM(args, ssid, ssid_len); + + if(key_len && key) + { + ARRAY_TO_STREAM(args, key, key_len); + } + + // Initiate a HCI command + hci_command_send(HCI_CMND_WLAN_CONNECT, ptr, WLAN_CONNECT_PARAM_LEN + + ssid_len + key_len - 1); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_CONNECT, &ret); + errno = ret; + + return(ret); +} +#else +long +wlan_connect(char *ssid, long ssid_len) +{ + long ret; + uint8_t *ptr; + uint8_t *args; + uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0}; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in command buffer + args = UINT32_TO_STREAM(args, 0x0000001c); + args = UINT32_TO_STREAM(args, ssid_len); + args = UINT32_TO_STREAM(args, 0); + args = UINT32_TO_STREAM(args, 0x00000010 + ssid_len); + args = UINT32_TO_STREAM(args, 0); + args = UINT16_TO_STREAM(args, 0); + + // padding shall be zeroed + ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); + ARRAY_TO_STREAM(args, ssid, ssid_len); + + // Initiate a HCI command + hci_command_send(HCI_CMND_WLAN_CONNECT, ptr, WLAN_CONNECT_PARAM_LEN + + ssid_len - 1); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_CONNECT, &ret); + errno = ret; + + return(ret); +} +#endif + +//***************************************************************************** +// +//! wlan_disconnect +//! +//! @return 0 disconnected done, other CC3000 already disconnected +//! +//! @brief Disconnect connection from AP. +//! +//! @sa wlan_connect +// +//***************************************************************************** + +long +wlan_disconnect() +{ + long ret; + uint8_t *ptr; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + + hci_command_send(HCI_CMND_WLAN_DISCONNECT, ptr, 0); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_DISCONNECT, &ret); + errno = ret; + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +wlan_ioctl_set_connection_policy(unsigned long should_connect_to_open_ap, + unsigned long ulShouldUseFastConnect, + unsigned long ulUseProfiles) +{ + long ret; + uint8_t *ptr; + uint8_t *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (uint8_t *)(ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, should_connect_to_open_ap); + args = UINT32_TO_STREAM(args, ulShouldUseFastConnect); + args = UINT32_TO_STREAM(args, ulUseProfiles); + + // Initiate a HCI command + hci_command_send(HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY, + ptr, WLAN_SET_CONNECTION_POLICY_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY, &ret); + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +#ifndef CC3000_TINY_DRIVER +long +wlan_add_profile(unsigned long ulSecType, + uint8_t* ucSsid, + unsigned long ulSsidLen, + uint8_t *ucBssid, + unsigned long ulPriority, + unsigned long ulPairwiseCipher_Or_TxKeyLen, + unsigned long ulGroupCipher_TxKeyIndex, + unsigned long ulKeyMgmt, + uint8_t* ucPf_OrKey, + unsigned long ulPassPhraseLen) +{ + uint16_t arg_len = 0; + long ret; + uint8_t *ptr; + long i = 0; + uint8_t *args; + uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0}; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + args = UINT32_TO_STREAM(args, ulSecType); + + // Setup arguments in accordance with the security type + switch (ulSecType) + { + //OPEN + case WLAN_SEC_UNSEC: + { + args = UINT32_TO_STREAM(args, 0x00000014); + args = UINT32_TO_STREAM(args, ulSsidLen); + args = UINT16_TO_STREAM(args, 0); + if(ucBssid) + { + ARRAY_TO_STREAM(args, ucBssid, ETH_ALEN); + } + else + { + ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); + } + args = UINT32_TO_STREAM(args, ulPriority); + ARRAY_TO_STREAM(args, ucSsid, ulSsidLen); + + arg_len = WLAN_ADD_PROFILE_NOSEC_PARAM_LEN + ulSsidLen; + } + break; + + //WEP + case WLAN_SEC_WEP: + { + args = UINT32_TO_STREAM(args, 0x00000020); + args = UINT32_TO_STREAM(args, ulSsidLen); + args = UINT16_TO_STREAM(args, 0); + if(ucBssid) + { + ARRAY_TO_STREAM(args, ucBssid, ETH_ALEN); + } + else + { + ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); + } + args = UINT32_TO_STREAM(args, ulPriority); + args = UINT32_TO_STREAM(args, 0x0000000C + ulSsidLen); + args = UINT32_TO_STREAM(args, ulPairwiseCipher_Or_TxKeyLen); + args = UINT32_TO_STREAM(args, ulGroupCipher_TxKeyIndex); + ARRAY_TO_STREAM(args, ucSsid, ulSsidLen); + + for(i = 0; i < 4; i++) + { + uint8_t *p = &ucPf_OrKey[i * ulPairwiseCipher_Or_TxKeyLen]; + + ARRAY_TO_STREAM(args, p, ulPairwiseCipher_Or_TxKeyLen); + } + + arg_len = WLAN_ADD_PROFILE_WEP_PARAM_LEN + ulSsidLen + + ulPairwiseCipher_Or_TxKeyLen * 4; + + } + break; + + //WPA + //WPA2 + case WLAN_SEC_WPA: + case WLAN_SEC_WPA2: + { + args = UINT32_TO_STREAM(args, 0x00000028); + args = UINT32_TO_STREAM(args, ulSsidLen); + args = UINT16_TO_STREAM(args, 0); + if(ucBssid) + { + ARRAY_TO_STREAM(args, ucBssid, ETH_ALEN); + } + else + { + ARRAY_TO_STREAM(args, bssid_zero, ETH_ALEN); + } + args = UINT32_TO_STREAM(args, ulPriority); + args = UINT32_TO_STREAM(args, ulPairwiseCipher_Or_TxKeyLen); + args = UINT32_TO_STREAM(args, ulGroupCipher_TxKeyIndex); + args = UINT32_TO_STREAM(args, ulKeyMgmt); + args = UINT32_TO_STREAM(args, 0x00000008 + ulSsidLen); + args = UINT32_TO_STREAM(args, ulPassPhraseLen); + ARRAY_TO_STREAM(args, ucSsid, ulSsidLen); + ARRAY_TO_STREAM(args, ucPf_OrKey, ulPassPhraseLen); + + arg_len = WLAN_ADD_PROFILE_WPA_PARAM_LEN + ulSsidLen + ulPassPhraseLen; + } + + break; + } + + // Initiate a HCI command + hci_command_send(HCI_CMND_WLAN_IOCTL_ADD_PROFILE, + ptr, arg_len); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_ADD_PROFILE, &ret); + + return(ret); +} +#else +long +wlan_add_profile(unsigned long ulSecType, + uint8_t * ucSsid, + uint8_t ulSsidLen, + uint8_t *ucBssid, + unsigned long ulPriority, + unsigned long ulPairwiseCipher_Or_TxKeyLen, + unsigned long ulGroupCipher_TxKeyIndex, + unsigned long ulKeyMgmt, + uint8_t * ucPf_OrKey, + unsigned long ulPassPhraseLen) +{ + return -1; +} +#endif + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +wlan_ioctl_del_profile(unsigned long ulIndex) +{ + long ret; + uint8_t *ptr; + uint8_t *args; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (uint8_t *)(ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, ulIndex); + ret = EFAIL; + + // Initiate a HCI command + hci_command_send(HCI_CMND_WLAN_IOCTL_DEL_PROFILE, + ptr, WLAN_DEL_PROFILE_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_DEL_PROFILE, &ret); + + return(ret); +} + +//***************************************************************************** +// +//! wlan_ioctl_get_scan_results +//! +//! @param[in] scan_timeout parameter not supported +//! @param[out] ucResults scan results (_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 +// +//***************************************************************************** + +#ifndef CC3000_TINY_DRIVER +long +wlan_ioctl_get_scan_results(unsigned long ulScanTimeout, + uint8_t *ucResults) +{ + uint8_t *ptr; + uint8_t *args; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, ulScanTimeout); + + // Initiate a HCI command + hci_command_send(HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS, + ptr, WLAN_GET_SCAN_RESULTS_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS, ucResults); + + return(0); +} +#endif + +//***************************************************************************** +// +//! 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 millisecond. 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 +// +//***************************************************************************** + +#ifndef CC3000_TINY_DRIVER +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) +{ + unsigned long uiRes; + uint8_t *ptr; + uint8_t *args; + + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + // Fill in temporary command buffer + args = UINT32_TO_STREAM(args, 36); + args = UINT32_TO_STREAM(args, uiEnable); + args = UINT32_TO_STREAM(args, uiMinDwellTime); + args = UINT32_TO_STREAM(args, uiMaxDwellTime); + args = UINT32_TO_STREAM(args, uiNumOfProbeRequests); + args = UINT32_TO_STREAM(args, uiChannelMask); + args = UINT32_TO_STREAM(args, iRSSIThreshold); + args = UINT32_TO_STREAM(args, uiSNRThreshold); + args = UINT32_TO_STREAM(args, uiDefaultTxPower); + ARRAY_TO_STREAM(args, aiIntervalList, sizeof(unsigned long) * + SL_SET_SCAN_PARAMS_INTERVAL_LIST_SIZE); + + // Initiate a HCI command + hci_command_send(HCI_CMND_WLAN_IOCTL_SET_SCANPARAM, + ptr, WLAN_SET_SCAN_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SET_SCANPARAM, &uiRes); + + return(uiRes); +} +#endif + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + +long +wlan_set_event_mask(unsigned long ulMask) +{ + long ret; + uint8_t *ptr; + uint8_t *args; + + + if ((ulMask & HCI_EVNT_WLAN_TX_COMPLETE) == HCI_EVNT_WLAN_TX_COMPLETE) + { + tSLInformation.InformHostOnTxComplete = 0; + + // Since an event is a virtual event - i.e. it is not coming from CC3000 + // there is no need to send anything to the device if it was an only event + if (ulMask == HCI_EVNT_WLAN_TX_COMPLETE) + { + return 0; + } + + ulMask &= ~HCI_EVNT_WLAN_TX_COMPLETE; + ulMask |= HCI_EVNT_WLAN_UNSOL_BASE; + } + else + { + tSLInformation.InformHostOnTxComplete = 1; + } + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (uint8_t *)(ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, ulMask); + + // Initiate a HCI command + hci_command_send(HCI_CMND_EVENT_MASK, + ptr, WLAN_SET_MASK_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_EVENT_MASK, &ret); + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +#ifndef CC3000_TINY_DRIVER +long +wlan_ioctl_statusget(void) +{ + long ret; + uint8_t *ptr; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + + hci_command_send(HCI_CMND_WLAN_IOCTL_STATUSGET, + ptr, 0); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_STATUSGET, &ret); + + return(ret); +} +#endif + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +wlan_smart_config_start(unsigned long algoEncryptedFlag) +{ + long ret; + uint8_t *ptr; + uint8_t *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (uint8_t *)(ptr + HEADERS_SIZE_CMD); + + // Fill in HCI packet structure + args = UINT32_TO_STREAM(args, algoEncryptedFlag); + ret = EFAIL; + + hci_command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START, ptr, + WLAN_SMART_CONFIG_START_PARAMS_LEN); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START, &ret); + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +wlan_smart_config_stop(void) +{ + long ret; + uint8_t *ptr; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + + hci_command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP, ptr, 0); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP, &ret); + + return(ret); +} + +//***************************************************************************** +// +//! 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 +// +//***************************************************************************** + +long +wlan_smart_config_set_prefix(char* cNewPrefix) +{ + long ret; + uint8_t *ptr; + uint8_t *args; + + ret = EFAIL; + ptr = tSLInformation.pucTxCommandBuffer; + args = (ptr + HEADERS_SIZE_CMD); + + if (cNewPrefix == NULL) + return ret; + else // with the new Smart Config, prefix must be TTT + { + *cNewPrefix = 'T'; + *(cNewPrefix + 1) = 'T'; + *(cNewPrefix + 2) = 'T'; + } + + ARRAY_TO_STREAM(args, cNewPrefix, SL_SIMPLE_CONFIG_PREFIX_LENGTH); + + hci_command_send(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX, ptr, + SL_SIMPLE_CONFIG_PREFIX_LENGTH); + + // Wait for command complete event + SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX, &ret); + + return(ret); +} + +//***************************************************************************** +// +//! 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. +// +//***************************************************************************** + + +#ifndef CC3000_UNENCRYPTED_SMART_CONFIG +long +wlan_smart_config_process() +{ + signed long returnValue; + unsigned long ssidLen, keyLen; + uint8_t *decKeyPtr; + uint8_t *ssidPtr; + + // read the key from EEPROM - fileID 12 + returnValue = aes_read_key(akey); + + if (returnValue != 0) + return returnValue; + + // read the received data from fileID #13 and parse it according to the followings: + // 1) SSID LEN - not encrypted + // 2) SSID - not encrypted + // 3) KEY LEN - not encrypted. always 32 bytes long + // 4) Security type - not encrypted + // 5) KEY - encrypted together with true key length as the first byte in KEY + // to elaborate, there are two corner cases: + // 1) the KEY is 32 bytes long. In this case, the first byte does not represent KEY length + // 2) the KEY is 31 bytes long. In this case, the first byte represent KEY length and equals 31 + returnValue = nvmem_read(NVMEM_SHARED_MEM_FILEID, SMART_CONFIG_PROFILE_SIZE, 0, profileArray); + + if (returnValue != 0) + return returnValue; + + ssidPtr = &profileArray[1]; + + ssidLen = profileArray[0]; + + decKeyPtr = &profileArray[profileArray[0] + 3]; + + aes_decrypt(decKeyPtr, akey); + if (profileArray[profileArray[0] + 1] > 16) + aes_decrypt((uint8_t *)(decKeyPtr + 16), akey); + + if (*(uint8_t *)(decKeyPtr +31) != 0) + { + if (*decKeyPtr == 31) + { + keyLen = 31; + decKeyPtr++; + } + else + { + keyLen = 32; + } + } + else + { + keyLen = *decKeyPtr; + decKeyPtr++; + } + + // add a profile + switch (profileArray[profileArray[0] + 2]) + { + case WLAN_SEC_UNSEC://None + { + returnValue = wlan_add_profile(profileArray[profileArray[0] + 2], // security type + ssidPtr, // SSID + ssidLen, // SSID length + NULL, // BSSID + 1, // Priority + 0, 0, 0, 0, 0); + + break; + } + + case WLAN_SEC_WEP://WEP + { + returnValue = wlan_add_profile(profileArray[profileArray[0] + 2], // security type + ssidPtr, // SSID + ssidLen, // SSID length + NULL, // BSSID + 1, // Priority + keyLen, // KEY length + 0, // KEY index + 0, + decKeyPtr, // KEY + 0); + + break; + } + + case WLAN_SEC_WPA://WPA + case WLAN_SEC_WPA2://WPA2 + { + returnValue = wlan_add_profile(WLAN_SEC_WPA2, // security type + ssidPtr, + ssidLen, + NULL, // BSSID + 1, // Priority + 0x18, // PairwiseCipher + 0x1e, // GroupCipher + 2, // KEY management + decKeyPtr, // KEY + keyLen); // KEY length + + break; + } + } + + return returnValue; +} +#endif //CC3000_UNENCRYPTED_SMART_CONFIG + +//***************************************************************************** +// +// Close the Doxygen group. +//! @} +// +//***************************************************************************** diff --git a/nuttx/include/nuttx/cc3000/cc3000_common.h b/nuttx/include/nuttx/cc3000/cc3000_common.h index f8a868e08..e4dfe2d9f 100644 --- a/nuttx/include/nuttx/cc3000/cc3000_common.h +++ b/nuttx/include/nuttx/cc3000/cc3000_common.h @@ -1,359 +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 -#include -#include -#include - -//***************************************************************************** -// -// 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, unsigned char length ); - -typedef long (*tWlanReadInteruptPin)(void); - -typedef void (*tWlanInterruptEnable)(void); - -typedef void (*tWlanInterruptDisable)(void); - -typedef void (*tWriteWlanPin)(unsigned char val); - -typedef struct -{ - unsigned short usRxEventOpcode; - unsigned short usEventOrDataReceived; - unsigned char *pucReceivedData; - unsigned char *pucTxCommandBuffer; - - tFWPatches sFWPatches; - tDriverPatches sDriverPatches; - tBootLoaderPatches sBootLoaderPatches; - tWlanCB sWlanCB; - tWlanReadInteruptPin ReadWlanInterruptPin; - tWlanInterruptEnable WlanInterruptEnable; - tWlanInterruptDisable WlanInterruptDisable; - tWriteWlanPin WriteWlanPin; - - signed long slTransmitDataError; - unsigned short usNumberOfFreeBuffers; - unsigned short usSlBufferLength; - unsigned short usBufferSize; - unsigned short usRxDataPending; - - unsigned long NumberOfSentPackets; - unsigned long NumberOfReleasedPackets; - - unsigned char 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(unsigned short 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(unsigned char *pBuf, unsigned char *from, unsigned char *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 unsigned char* UINT32_TO_STREAM_f (unsigned char *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 unsigned char* UINT16_TO_STREAM_f (unsigned char *p, unsigned short 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 unsigned short STREAM_TO_UINT16_f(char* p, unsigned short 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, unsigned short 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 short _i; for (_i = 0; _i < l; _i++) *(p)++ = ((unsigned char *) 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 = (unsigned char)(*(_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 short _i; for (_i = 0; _i < l; _i++) *(a)++= ((unsigned char *) p)[_i];} - - - - -//***************************************************************************** -// -// Mark the end of the C bindings section for C++ compilers. -// -//***************************************************************************** -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // __COMMON_H__ +/***************************************************************************** +* +* 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 +#include +#include +#include + +//***************************************************************************** +// +// 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/cc3000/evnt_handler.h b/nuttx/include/nuttx/cc3000/evnt_handler.h index 6ad65393f..00e709642 100644 --- a/nuttx/include/nuttx/cc3000/evnt_handler.h +++ b/nuttx/include/nuttx/cc3000/evnt_handler.h @@ -1,166 +1,166 @@ -/***************************************************************************** -* -* 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 "hci.h" -#include "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 unsigned char *hci_event_handler(void *pRetParams, unsigned char *from, unsigned char *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 -{ - unsigned char 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__ - +/***************************************************************************** +* +* 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 "hci.h" +#include "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/cc3000/hci.h b/nuttx/include/nuttx/cc3000/hci.h index 4ef4abeb0..2894221b2 100644 --- a/nuttx/include/nuttx/cc3000/hci.h +++ b/nuttx/include/nuttx/cc3000/hci.h @@ -1,328 +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 "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 unsigned short hci_command_send(unsigned short usOpcode, - unsigned char *ucArgs, - unsigned char 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(unsigned char ucOpcode, - unsigned char *ucArgs, - unsigned short usArgsLength, - unsigned short usDataLength, - const unsigned char *ucTail, - unsigned short 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(unsigned short usOpcode, unsigned char *pucBuff, - unsigned char ucArgsLength, unsigned short 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(unsigned char ucOpcode, unsigned char *pucBuff, char *patch, unsigned short usDataLength); - - - -//***************************************************************************** -// -// Mark the end of the C bindings section for C++ compilers. -// -//***************************************************************************** -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // __HCI_H__ +/***************************************************************************** +* +* 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 "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/cc3000/netapp.h b/nuttx/include/nuttx/cc3000/netapp.h index 77b6b5692..fd38884b2 100644 --- a/nuttx/include/nuttx/cc3000/netapp.h +++ b/nuttx/include/nuttx/cc3000/netapp.h @@ -1,342 +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 -{ - unsigned char aucIP[4]; - unsigned char aucSubnetMask[4]; - unsigned char aucDefaultGateway[4]; - unsigned char aucDHCPServer[4]; - unsigned char aucDNSServer[4]; -}tNetappDhcpParams; - -typedef struct _netapp_ipconfig_ret_args_t -{ - unsigned char aucIP[4]; - unsigned char aucSubnetMask[4]; - unsigned char aucDefaultGateway[4]; - unsigned char aucDHCPServer[4]; - unsigned char aucDNSServer[4]; - unsigned char uaMacAddr[6]; - unsigned char 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( unsigned char *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__ - +/***************************************************************************** +* +* 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/cc3000/nvmem.h b/nuttx/include/nuttx/cc3000/nvmem.h index 7b05574f8..3f59d09d6 100644 --- a/nuttx/include/nuttx/cc3000/nvmem.h +++ b/nuttx/include/nuttx/cc3000/nvmem.h @@ -1,248 +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 "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, unsigned char *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, unsigned char *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 unsigned char nvmem_set_mac_address(unsigned char *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 unsigned char nvmem_get_mac_address(unsigned char *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 unsigned char nvmem_write_patch(unsigned long ulFileId, unsigned long spLength, const unsigned char *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 unsigned char nvmem_read_sp_version(unsigned char* 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__ +/***************************************************************************** +* +* 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 "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/cc3000/security.h b/nuttx/include/nuttx/cc3000/security.h index 9c4ef79b7..a53b05616 100644 --- a/nuttx/include/nuttx/cc3000/security.h +++ b/nuttx/include/nuttx/cc3000/security.h @@ -1,126 +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 "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(unsigned char *state, unsigned char *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(unsigned char *state, unsigned char *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(unsigned char *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(unsigned char *key); - -#endif //CC3000_UNENCRYPTED_SMART_CONFIG - -#endif +/***************************************************************************** +* +* 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 "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/cc3000/socket.h b/nuttx/include/nuttx/cc3000/socket.h index 552a94720..8933a0c5b 100644 --- a/nuttx/include/nuttx/cc3000/socket.h +++ b/nuttx/include/nuttx/cc3000/socket.h @@ -1,664 +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 -{ - unsigned short int sa_family; - unsigned char sa_data[14]; -} sockaddr; - -typedef struct _sockaddr_in_t -{ - short sin_family; // e.g. AF_INET - unsigned short 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, unsigned short 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(unsigned short mdnsEnabled, char * deviceServiceName, unsigned short deviceServiceNameLength); - -//***************************************************************************** -// -// Close the Doxygen group. -//! @} -// -//***************************************************************************** - - -//***************************************************************************** -// -// Mark the end of the C bindings section for C++ compilers. -// -//***************************************************************************** -#ifdef __cplusplus -} -#endif // __cplusplus - -#endif // __SOCKET_H__ +/***************************************************************************** +* +* 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/cc3000/spi.h b/nuttx/include/nuttx/cc3000/spi.h index 0d6aa0943..bf68b3eb1 100644 --- a/nuttx/include/nuttx/cc3000/spi.h +++ b/nuttx/include/nuttx/cc3000/spi.h @@ -34,12 +34,12 @@ void SpiOpen(gcSpiHandleRx pfRxHandler); void SpiClose(void); -long SpiWrite(unsigned char *pUserBuffer, unsigned short usLength); +long SpiWrite(uint8_t *pUserBuffer, uint16_t usLength); void SpiResumeSpi(void); int CC3000InterruptHandler(int irq, void *context); -short SPIInterruptsEnabled; +int16_t SPIInterruptsEnabled; -unsigned char wlan_tx_buffer[]; +uint8_t wlan_tx_buffer[]; diff --git a/nuttx/include/nuttx/cc3000/wlan.h b/nuttx/include/nuttx/cc3000/wlan.h index 170ac816e..f9e649f12 100644 --- a/nuttx/include/nuttx/cc3000/wlan.h +++ b/nuttx/include/nuttx/cc3000/wlan.h @@ -1,517 +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 "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(unsigned short 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, - unsigned char *bssid, unsigned char *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, unsigned char* ucSsid, - unsigned long ulSsidLen, - unsigned char *ucBssid, - unsigned long ulPriority, - unsigned long ulPairwiseCipher_Or_Key, - unsigned long ulGroupCipher_TxKeyLen, - unsigned long ulKeyMgmt, - unsigned char* 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, - unsigned char *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__ +/***************************************************************************** +* +* 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 "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__ -- cgit v1.2.3