CC3000 driver update from David Sidrane

This commit is contained in:
Gregory Nutt 2013-10-25 16:23:53 -06:00
parent ad3539209b
commit 607acec781
13 changed files with 3030 additions and 1120 deletions

View File

@ -38,7 +38,7 @@ ifeq ($(CONFIG_WL_CC3000),y)
# Include cc3000 drivers
CSRCS += cc3000.c cc3000_common.c evnt_handler.c hci.c netapp.c nvmem.c
CSRCS += security.c socket.c spi.c wlan.c
CSRCS += security.c socket.c socket_imp.c spi.c wlan.c
# Include wireless devices build support

View File

@ -74,6 +74,7 @@
#include <nuttx/wireless/cc3000/include/cc3000_upif.h>
#include <nuttx/wireless/cc3000/cc3000_common.h>
#include <nuttx/wireless/cc3000/hci.h>
#include "cc3000_socket.h"
#include "cc3000.h"
@ -90,6 +91,8 @@
#endif
#define NUMBER_OF_MSGS 2
#define FREE_SLOT -1
/****************************************************************************
* Private Types
****************************************************************************/
@ -444,6 +447,96 @@ static void cc3000_notify(FAR struct cc3000_dev_s *priv)
#endif
}
/****************************************************************************
* Name: cc3000_worker
****************************************************************************/
static void * select_thread_func(FAR void *arg)
{
FAR struct cc3000_dev_s *priv = (FAR struct cc3000_dev_s *)arg;
struct timeval timeout;
TICC3000fd_set readsds;
int ret = 0;
int maxFD = 0;
int s = 0;
memset(&timeout, 0, sizeof(struct timeval));
timeout.tv_sec = 0;
timeout.tv_usec = (500 * 1000); /* 500 msecs */
while (1)
{
sem_wait(&priv->selectsem);
/* Increase the count back by one to be decreased by the original caller */
sem_post(&priv->selectsem);
CC3000_FD_ZERO(&readsds);
/* Ping correct socket descriptor param for select */
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
if (priv->sockets[s].sd != FREE_SLOT)
{
CC3000_FD_SET(priv->sockets[s].sd, &readsds);
if (maxFD <= priv->sockets[s].sd)
{
maxFD = priv->sockets[s].sd + 1;
}
}
}
/* Polling instead of blocking here to process "accept" below */
ret = cc3000_select(maxFD, (fd_set *) &readsds, NULL, NULL, &timeout);
if (priv->selecttid == -1)
{
/* driver close will terminate the thread and by that all sync
* objects owned by it will be released
*/
return OK;
}
if (ret > 0)
{
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
if (priv->sockets[s].sd != FREE_SLOT && /* Check that the socket is valid */
priv->sockets[s].sd != priv->accepting_socket.acc.sd && /* Verify this is not an accept socket */
C3000_FD_ISSET(priv->sockets[s].sd, &readsds)) /* and has pending data */
{
sem_post(&priv->sockets[s].semwait); /* release the semaphore */
}
}
}
if (priv->accepting_socket.acc.sd != FREE_SLOT) /* if accept polling in needed */
{
ret = cc3000_do_accept(priv->accepting_socket.acc.sd,
&priv->accepting_socket.addr,
&priv->accepting_socket.addrlen);
if (ret != CC3000_SOC_IN_PROGRESS)
{
priv->accepting_socket.acc.sd = FREE_SLOT;
priv->accepting_socket.acc.status = ret;
if (ret != CC3000_SOC_ERROR)
{
/* New Socket */
cc3000_add_socket(ret,priv->minor);
}
sem_post(&priv->accepting_socket.acc.semwait); /* release the semaphore */
}
}
}
return OK;
}
/****************************************************************************
* Name: cc3000_worker
****************************************************************************/
@ -549,7 +642,7 @@ static void * cc3000_worker(FAR void *arg)
cc3000_devgive(priv);
nllvdbg("Wait On Completion\n");
sem_wait(&priv->wrkwaitsem);
sem_wait(priv->wrkwaitsem);
nllvdbg("Completed S:%d irq :%d\n",priv->state,priv->config->irq_read(priv->config));
sem_getvalue(&priv->irqsem, &count);
@ -574,8 +667,10 @@ static void * cc3000_worker(FAR void *arg)
} /* end switch */
} /* end if */
cc3000_devgive(priv);
} /* while(1) */
cc3000_devgive(priv);
} /* while(1) */
return OK;
}
/****************************************************************************
@ -690,7 +785,8 @@ static int cc3000_open(FAR struct file *filep)
param.sched_priority = SCHED_PRIORITY_MAX;
pthread_attr_setschedparam(&tattr, &param);
ret = pthread_create(&priv->workertid, &tattr, cc3000_worker, (pthread_addr_t)priv);
ret = pthread_create(&priv->workertid, &tattr, cc3000_worker,
(pthread_addr_t)priv);
if (ret < 0)
{
mq_close(priv->queue);
@ -699,6 +795,23 @@ static int cc3000_open(FAR struct file *filep)
goto errout_with_sem;
}
pthread_attr_init(&tattr);
param.sched_priority = SCHED_PRIORITY_DEFAULT+10;
pthread_attr_setschedparam(&tattr, &param);
ret = pthread_create(&priv->selecttid, &tattr, select_thread_func,
(pthread_addr_t)priv);
if (ret < 0)
{
pthread_t workertid = priv->workertid;
priv->workertid = -1;
pthread_cancel(workertid);
pthread_join(workertid,NULL);
mq_close(priv->queue);
priv->queue = 0;
ret = -errno;
goto errout_with_sem;
}
priv->state = eSPI_STATE_POWERUP;
priv->config->irq_clear(priv->config);
@ -735,7 +848,7 @@ static int cc3000_close(FAR struct file *filep)
inode = filep->f_inode;
DEBUGASSERT(inode && inode->i_private);
priv = (FAR struct cc3000_dev_s *)inode->i_private;
priv = (FAR struct cc3000_dev_s *)inode->i_private;
nllvdbg("crefs: %d\n", priv->crefs);
@ -760,13 +873,20 @@ static int cc3000_close(FAR struct file *filep)
if (tmp == 1)
{
pthread_t id = priv->selecttid;
priv->selecttid = -1;
pthread_cancel(id);
pthread_join(id, NULL);
priv->config->irq_enable(priv->config, false);
priv->config->irq_clear(priv->config);
priv->config->power_enable(priv->config, false);
pthread_t workertid = priv->workertid;
id = priv->workertid;
priv->workertid = -1;
pthread_cancel(workertid);
pthread_join(workertid,NULL);
pthread_cancel(id);
pthread_join(id, NULL);
mq_close(priv->queue);
priv->queue = 0;
}
@ -778,6 +898,7 @@ static int cc3000_close(FAR struct file *filep)
/****************************************************************************
* Name: cc3000_read
****************************************************************************/
static ssize_t cc3000_read(FAR struct file *filep, FAR char *buffer, size_t len)
{
FAR struct inode *inode;
@ -963,19 +1084,26 @@ static ssize_t cc3000_write(FAR struct file *filep, FAR const char *buffer, size
tx_len += SPI_HEADER_SIZE;
/* The first write transaction to occur after release of the shutdown has slightly different timing than the others.
* The normal Master SPI write sequence is nCS low, followed by IRQ low (CC3000 host), indicating that
* the CC3000 core device is ready to accept data. However, after power up the sequence is slightly different,
* as shown in the following Figure: http://processors.wiki.ti.com/index.php/File:CC3000_Master_SPI_Write_Sequence_After_Power_Up.png
* The following is a sequence of operations:
* The master detects the IRQ line low: in this case the detection of
* IRQ low does not indicate the intention of the CC3000 device to communicate with the
* master but rather CC3000 readiness after power up.
* The master asserts nCS.
* The master introduces a delay of at least 50 μs before starting actual transmission of data.
* The master transmits the first 4 bytes of the SPI header.
* The master introduces a delay of at least an additional 50 μs.
* The master transmits the rest of the packet.
/* The first write transaction to occur after release of the shutdown has
* slightly different timing than the others. The normal Master SPI
* write sequence is nCS low, followed by IRQ low (CC3000 host),
* indicating that the CC3000 core device is ready to accept data.
* However, after power up the sequence is slightly different, as shown
* in the following Figure:
*
* http://processors.wiki.ti.com/index.php/File:CC3000_Master_SPI_Write_Sequence_After_Power_Up.png
*
* The following is a sequence of operations:
* - The master detects the IRQ line low: in this case the detection of
* IRQ low does not indicate the intention of the CC3000 device to
* communicate with the master but rather CC3000 readiness after power
* up.
* - The master asserts nCS.
* - The master introduces a delay of at least 50 μs before starting
* actual transmission of data.
* - The master transmits the first 4 bytes of the SPI header.
* - The master introduces a delay of at least an additional 50 μs.
* - The master transmits the rest of the packet.
*/
if (priv->state == eSPI_STATE_POWERUP)
@ -1044,7 +1172,7 @@ static int cc3000_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
inode = filep->f_inode;
DEBUGASSERT(inode && inode->i_private);
priv = (FAR struct cc3000_dev_s *)inode->i_private;
priv = (FAR struct cc3000_dev_s *)inode->i_private;
/* Get exclusive access to the driver data structure */
@ -1061,14 +1189,7 @@ static int cc3000_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
ret = OK;
switch (cmd)
{
case CC3000IOC_COMPLETE: /* arg: Pointer to uint32_t frequency value */
{
DEBUGASSERT(priv->config);
sem_post(&priv->wrkwaitsem);
}
break;
case CC3000IOC_GETQUEID:
case CC3000IOC_GETQUESEMID:
{
FAR int *pid = (FAR int *)(arg);
DEBUGASSERT(pid != NULL);
@ -1176,10 +1297,6 @@ errout:
}
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
@ -1207,7 +1324,11 @@ int cc3000_register(FAR struct spi_dev_s *spi,
FAR struct cc3000_config_s *config, int minor)
{
FAR struct cc3000_dev_s *priv;
char devname[DEV_NAMELEN];
char drvname[DEV_NAMELEN];
char semname[SEM_NAMELEN];
#ifdef CONFIG_CC3000_MT
int s;
#endif
#ifdef CONFIG_CC3000_MULTIPLE
irqstate_t flags;
@ -1245,7 +1366,20 @@ int cc3000_register(FAR struct spi_dev_s *spi,
sem_init(&priv->waitsem, 0, 0); /* Initialize event wait semaphore */
sem_init(&priv->irqsem, 0, 0); /* Initialize IRQ Ready semaphore */
sem_init(&priv->readysem, 0, 0); /* Initialize Device Ready semaphore */
sem_init(&priv->wrkwaitsem, 0, 0); /* Initialize Worker Wait semaphore */
(void)snprintf(semname, SEM_NAMELEN, SEM_FORMAT, minor);
priv->wrkwaitsem = sem_open(semname,O_CREAT,0,0); /* Initialize Worker Wait semaphore */
#ifdef CONFIG_CC3000_MT
pthread_mutex_init(&g_cc3000_mut, NULL);
priv->accepting_socket.acc.sd = FREE_SLOT;
sem_init(&priv->accepting_socket.acc.semwait, 0, 0);
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
priv->sockets[s].sd = FREE_SLOT;
sem_init(&priv->sockets[s].semwait, 0, 0);
}
#endif
/* Make sure that interrupts are disabled */
@ -1263,10 +1397,10 @@ int cc3000_register(FAR struct spi_dev_s *spi,
/* Register the device as an input device */
(void)snprintf(devname, DEV_NAMELEN, DEV_FORMAT, minor);
nllvdbg("Registering %s\n", devname);
(void)snprintf(drvname, DEV_NAMELEN, DEV_FORMAT, minor);
nllvdbg("Registering %s\n", drvname);
ret = register_driver(devname, &cc3000_fops, 0666, priv);
ret = register_driver(drvname, &cc3000_fops, 0666, priv);
if (ret < 0)
{
idbg("register_driver() failed: %d\n", ret);
@ -1290,8 +1424,220 @@ int cc3000_register(FAR struct spi_dev_s *spi,
errout_with_priv:
sem_destroy(&priv->devsem);
sem_destroy(&priv->waitsem);
sem_destroy(&priv->irqsem);
sem_destroy(&priv->readysem);
sem_close(priv->wrkwaitsem);
sem_unlink(semname);
#ifdef CONFIG_CC3000_MT
pthread_mutex_destroy(&g_cc3000_mut);
sem_destroy(&priv->accepting_socket.acc.semwait);
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
sem_destroy(&priv->sockets[s].semwait);
}
#endif
#ifdef CONFIG_CC3000_MULTIPLE
kfree(priv);
#endif
return ret;
}
/****************************************************************************
* Name: cc3000_accept_socket
*
* Description:
* Adds this socket for monitoring for the accept operation
*
* Input Parameters:
* sd cc3000 socket handle or -1 tp remove it
* minor - The input device minor number
*
* Returned Value:
* Zero is returned on success. Otherwise, a -1 value is
* returned to indicate socket not found.
*
****************************************************************************/
int cc3000_wait_data(int sockfd, int minor)
{
FAR struct cc3000_dev_s *priv;
int s;
#ifndef CONFIG_CC3000_MULTIPLE
priv = &g_cc3000;
#else
for (priv = g_cc3000list;
priv && priv->minor != minor;
priv = priv->flink);
ASSERT(priv != NULL);
#endif
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
if (priv->sockets[s].sd == sockfd)
{
sem_post(&priv->selectsem); /* Wake select thread if need be */
sem_wait(&priv->sockets[s].semwait); /* Wait caller on select to finish */
sem_wait(&priv->selectsem); /* Sleep select thread */
break;
}
}
return (s >= CONFIG_WL_MAX_SOCKETS || priv->selecttid == -1) ? -1 : OK;
}
/****************************************************************************
* Name: cc3000_accept_socket
*
* Description:
* Adds this socket for monitoring for the accept operation
*
* Input Parameters:
* sd cc3000 socket handle or -1 tp remove it
* minor - The input device minor number
*
* Returned Value:
* Zero is returned on success. Otherwise, a -1 value is
* returned to indicate socket not found.
*
****************************************************************************/
int cc3000_accept_socket(int sd, int minor, struct sockaddr *addr,
socklen_t *addrlen)
{
FAR struct cc3000_dev_s *priv;
#ifndef CONFIG_CC3000_MULTIPLE
priv = &g_cc3000;
#else
for (priv = g_cc3000list;
priv && priv->minor != minor;
priv = priv->flink);
ASSERT(priv != NULL);
#endif
priv->accepting_socket.acc.status = CC3000_SOC_ERROR;
priv->accepting_socket.acc.sd = sd;
sem_post(&priv->selectsem); /* Wake select thread if need be */
sem_wait(&priv->accepting_socket.acc.semwait); /* Wait caller on select to finish */
sem_wait(&priv->selectsem); /* Sleep select thread */
if (priv->accepting_socket.acc.status != CC3000_SOC_ERROR)
{
*addr = priv->accepting_socket.addr;
*addrlen = priv->accepting_socket.addrlen;
}
return priv->accepting_socket.acc.status;
}
/****************************************************************************
* Name: cc3000_add_socket
*
* Description:
* Adds a socket to the list for monitoring for long operation
*
* Input Parameters:
* sd cc3000 socket handle
* minor - The input device minor number
*
* Returned Value:
* Zero is returned on success. Otherwise, a -1 value is
* returned to indicate socket not found.
*
****************************************************************************/
int cc3000_add_socket(int sd, int minor)
{
FAR struct cc3000_dev_s *priv;
irqstate_t flags;
int s;
if (sd < 0)
{
return sd;
}
#ifndef CONFIG_CC3000_MULTIPLE
priv = &g_cc3000;
#else
for (priv = g_cc3000list;
priv && priv->minor != minor;
priv = priv->flink);
ASSERT(priv != NULL);
#endif
flags = irqsave();
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
if (priv->sockets[s].sd == FREE_SLOT)
{
priv->sockets[s].sd = sd;
break;
}
}
irqrestore(flags);
return s >= CONFIG_WL_MAX_SOCKETS ? -1 : OK;
}
/****************************************************************************
* Name: cc3000_remove_socket
*
* Description:
* Removes a socket from the list of monitoring for long operation
*
* Input Parameters:
* sd cc3000 socket handle
* minor - The input device minor number
*
* Returned Value:
* Zero is returned on success. Otherwise, a -1 value is
* returned to indicate socket not found.
*
****************************************************************************/
int cc3000_remove_socket(int sd, int minor)
{
FAR struct cc3000_dev_s *priv;
irqstate_t flags;
int s;
if (sd < 0)
{
return sd;
}
#ifndef CONFIG_CC3000_MULTIPLE
priv = &g_cc3000;
#else
for (priv = g_cc3000list;
priv && priv->minor != minor;
priv = priv->flink);
ASSERT(priv != NULL);
#endif
flags = irqsave();
if (priv->accepting_socket.acc.sd == sd)
{
priv->accepting_socket.acc.sd = FREE_SLOT;
priv->accepting_socket.addrlen = 0;
}
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
if (priv->sockets[s].sd == sd)
{
priv->sockets[s].sd = FREE_SLOT;
break;
}
}
irqrestore(flags);
return s >= CONFIG_WL_MAX_SOCKETS ? -1 : OK;
}

View File

@ -47,20 +47,29 @@
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdint.h>
#include <mqueue.h>
#include <pthread.h>
#include <nuttx/spi/spi.h>
#include <nuttx/irq.h>
#include <nuttx/wireless/wireless.h>
#include <nuttx/wireless/cc3000.h>
#include <nuttx/wireless/cc3000/cc3000_common.h>
#include "spi.h"
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
#define CONFIG_CC3000_MT /* Indicate multi threaded version */
#ifdef CONFIG_CC3000_MT
# define CONFIG_WL_MAX_SOCKETS 5
#endif
/* CC3000 Interfaces ********************************************************/
/* Driver support ***********************************************************/
@ -82,8 +91,26 @@
* Public Types
****************************************************************************/
#ifdef CONFIG_CC3000_MT
/* lock to serialze access to driver (spi protocol is window size 1) */
extern pthread_mutex_t g_cc3000_mut;
/* This structure describes the state of one CC3000 driver instance */
typedef struct cc3000_socket_ent
{
int sd;
long status;
sem_t semwait;
} cc3000_socket_ent;
typedef struct cc3000_accept_ent
{
cc3000_socket_ent acc;
struct sockaddr addr;
socklen_t addrlen;
} cc3000_accept_ent;
#endif
typedef enum
{
eSPI_STATE_POWERUP = 0,
@ -107,7 +134,7 @@ struct cc3000_dev_s
uint8_t nwaiters; /* Number of threads waiting for CC3000 data */
uint8_t minor; /* minor */
sem_t devsem; /* Manages exclusive access to this structure */
sem_t wrkwaitsem; /* Suspend and resume the delivery of messages */
sem_t *wrkwaitsem; /* Suspend and resume the delivery of messages */
sem_t waitsem; /* Used to wait for the availability of data */
sem_t irqsem; /* Used to signal irq from cc3000 */
sem_t readysem; /* Used to wait for Ready Condition from the cc3000 */
@ -122,6 +149,15 @@ struct cc3000_dev_s
uint8_t tx_buffer[CC3000_TX_BUFFER_SIZE];
ssize_t tx_buffer_len;
/* The following is a list if socket structures of threads waiting
* long operations to finish;
*/
#ifdef CONFIG_CC3000_MT
pthread_t selecttid; /* Handle for the select thread */
sem_t selectsem; /* Used to sleep the select thread */
cc3000_socket_ent sockets[CONFIG_WL_MAX_SOCKETS];
cc3000_accept_ent accepting_socket;
#endif
/* The following is a list if poll structures of threads waiting for
* driver events. The 'struct pollfd' reference for each open is also
* retained in the f_priv field of the 'struct file'.
@ -143,6 +179,28 @@ extern "C" {
#define EXTERN extern
#endif
static inline void cc3000_lib_lock(void)
{
#ifdef CONFIG_CC3000_MT
int status = pthread_mutex_lock(&g_cc3000_mut);
DEBUGASSERT(status == 0);
#endif
}
static inline void cc3000_lib_unlock(void)
{
#ifdef CONFIG_CC3000_MT
int status = pthread_mutex_unlock(&g_cc3000_mut);
DEBUGASSERT(status == 0);
#endif
}
int cc3000_do_accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen);
int cc3000_wait_data(int sockfd, int minor);
int cc3000_accept_socket(int sd, int minor, struct sockaddr *addr, socklen_t *addrlen);
int cc3000_add_socket(int sd, int minor);
int cc3000_remove_socket(int sd, int minor);
#undef EXTERN
#ifdef __cplusplus
}

View File

@ -38,11 +38,6 @@
#include <nuttx/config.h>
#include <stdint.h>
#include <nuttx/wireless/cc3000/cc3000_common.h>
#include <nuttx/wireless/cc3000/include/sys/socket.h>
#include <nuttx/wireless/cc3000/wlan.h>
#include <nuttx/wireless/cc3000/evnt_handler.h>
/*****************************************************************************
* Name:__error__
*

View File

@ -0,0 +1,660 @@
/*****************************************************************************
* drivers/wireless/cc3000_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 __DRIVERS_WIRELESS_CC3000_SOCKET_H
#define __DRIVERS_WIRELESS_CC3000_SOCKET_H
/****************************************************************************
* Included Files
****************************************************************************/
#include <sys/types.h>
#include <sys/select.h>
#include <sys/socket.h>
/*****************************************************************************
* Pre-processor Definitions
*****************************************************************************/
#define CC3000_HOSTNAME_MAX_LENGTH (230) /* 230 bytes + header shouldn't exceed 8
* bit value */
/*--------- Address Families --------*/
#define CC3000_AF_INET 2
#define CC3000_AF_INET6 23
/*------------ Socket Types ------------*/
#define CC3000_SOCK_STREAM 1
#define CC3000_SOCK_DGRAM 2
#define CC3000_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 CC3000_SOCK_RDM 4
#define CC3000_SOCK_SEQPACKET 5
/*----------- Socket Protocol ----------*/
#define CC3000_IPPROTO_IP 0 /* Dummy for IP */
#define CC3000_IPPROTO_ICMP 1 /* Control message protocol */
#define CC3000_IPPROTO_IPV4 CC3000_IPPROTO_IP /* IP inside IP */
#define CC3000_IPPROTO_TCP 6 /* TCP */
#define CC3000_IPPROTO_UDP 17 /* User datagram protocol */
#define CC3000_IPPROTO_IPV6 41 /* IPv6 in IPv6 */
#define CC3000_IPPROTO_NONE 59 /* No next header */
#define CC3000_IPPROTO_RAW 255 /* Raw IP packet */
#define CC3000_IPPROTO_MAX 256
/*----------- Socket retunr codes -----------*/
#define CC3000_SOC_ERROR (-1) /* Error */
#define CC3000_SOC_IN_PROGRESS (-2) /* Socket in progress */
/*----------- Socket Options -----------*/
#define CC3000_SOL_SOCKET 0xffff /* Socket level */
#define CC3000_SOCKOPT_RECV_NONBLOCK 0 /* recv non block mode, set SOCK_ON or
* SOCK_OFF (default block mode) */
#define CC3000_SOCKOPT_RECV_TIMEOUT 1 /* optname to configure recv and recvfromtimeout */
#define CC3000_SOCKOPT_ACCEPT_NONBLOCK 2 /* accept non block mode, set SOCK_ON or SOCK_OFF
* (default block mode) */
#define CC3000_SOCK_ON 0 /* socket non-blocking mode is enabled */
#define CC3000_SOCK_OFF 1 /* socket blocking mode is enabled */
#define CC3000_TCP_NODELAY 0x0001
#define CC3000_TCP_BSDURGENT 0x7000
#define CC3000_MAX_PACKET_SIZE 1500
#define CC3000_MAX_LISTEN_QUEUE 4
#define CC3000_IOCTL_SOCKET_EVENTMASK
#define CC3000_FD_SETSIZE 32
#define CC3000_ASIC_ADDR_LEN 8
#define CC3000_NO_QUERY_RECIVED -3
/* 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))
#define __FDS_BITS(set) ((set)->fds_bits)
/* 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 CC3000_FD_SET(fd, fdsetp) __FD_SET (fd, fdsetp)
#define CC3000_FD_CLR(fd, fdsetp) __FD_CLR (fd, fdsetp)
#define CC3000_FD_ISSET(fd, fdsetp) __FD_ISSET (fd, fdsetp)
#define CC3000_FD_ZERO(fdsetp) __FD_ZERO (fdsetp)
/* 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;
/*****************************************************************************
* Public Types
*****************************************************************************/
/* The fd_set member is required to be an array of longs. */
typedef long int __fd_mask;
/* fd_set for select and pselect. */
typedef struct
{
__fd_mask fds_bits[CC3000_FD_SETSIZE / __NFDBITS];
} TICC3000fd_set;
/*****************************************************************************
* Public Data
*****************************************************************************/
#ifdef __cplusplus
extern "C" {
#endif
/*****************************************************************************
* Public Function Prototypes
*****************************************************************************/
/*****************************************************************************
* Name: cc3000_socket_impl
*
* Decription:
* 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.
*
* Input Parameters:
* domain selects the protocol family which will be used for
* communication. On this version only AF_INET is supported
* type specifies the communication semantics. On this version
* only SOCK_STREAM, SOCK_DGRAM, SOCK_RAW are supported
* protocol specifies a particular protocol to be used with the
* socket IPPROTO_TCP, IPPROTO_UDP or IPPROTO_RAW are
* supported.
*
* Returned Value:
* On success, socket handle that is used for consequent socket
* operations. On error, -1 is returned.
*
*****************************************************************************/
int cc3000_socket_impl(long domain, long type, long protocol);
/*****************************************************************************
* Name: cc3000_closesocket_impl
*
* Decription:
* The socket function closes a created socket.
*
* Input Parameters:
* sd socket handle.
*
* Returned Value:
* On success, zero is returned. On error, -1 is returned.
*
*****************************************************************************/
long cc3000_closesocket_impl(long sd);
/*****************************************************************************
* Name: cc3000_accept_impl
*
* Decription:
* 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.
*
* Input Parameters:
* sd socket descriptor (handle)
* 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.
* addrlen The addrlen argument is a value-result argument:
* it should initially contain the size of the structure
* pointed to by addr.
*
* Returned Value:
* 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)
*
*****************************************************************************/
long cc3000_accept_impl(long sd, struct sockaddr *addr, socklen_t *addrlen);
/*****************************************************************************
* Name: cc3000_bind_impl
*
* Decription:
* 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.
*
* Input Parameters:
* sd socket descriptor (handle)
* addr specifies the destination address. On this version
* only AF_INET is supported.
* addrlen contains the size of the structure pointed to by addr.
*
* Returned Value:
* On success, zero is returned. On error, -1 is returned.
*
*****************************************************************************/
long cc3000_bind_impl(long sd, FAR const struct sockaddr *addr, socklen_t addrlen);
/*****************************************************************************
* Name: cc3000_listen_impl
*
* Decription:
* 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.
*
* NOTE: On this version, backlog is not supported
*
* Input Parameters:
* sd socket descriptor (handle)
* backlog specifies the listen queue depth. On this version
* backlog is not supported.
*
* Returned Value:
* On success, zero is returned. On error, -1 is returned.
*
*****************************************************************************/
long cc3000_listen_impl(long sd, long backlog);
/*****************************************************************************
* Name: cc3000_connect_impl
*
* Decription:
* 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.
*
* Input Parameters:
* sd socket descriptor (handle)
* addr specifies the destination addr. On this version
* only AF_INET is supported.
* addrlen contains the size of the structure pointed to by addr
*
* Returned Value:
* On success, zero is returned. On error, -1 is returned
*
*****************************************************************************/
long cc3000_connect_impl(long sd, FAR const struct sockaddr *addr, socklen_t addrlen);
/*****************************************************************************
* Name: cc3000_select_impl
*
* Decription:
* 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
*
* Input Parameters:
* nfds the highest-numbered file descriptor in any of the
* three sets, plus 1.
* readfds socket descriptors list for read monitoring
* writefds socket descriptors list for write monitoring
* exceptfds socket descriptors list for exception monitoring
* 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.
*
* Returned Value:
* 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.
* *readfds - return the sockets on which Read request will
* return without delay with valid data.
* *writefds - return the sockets on which Write request
* will return without delay.
* *exceptfds - return the sockets which closed recently.
*
*****************************************************************************/
int cc3000_select_impl(long nfds, TICC3000fd_set *readfds, TICC3000fd_set *writefds,TICC3000fd_set *exceptfds,
struct timeval *timeout);
int cc3000_select(int nfds, fd_set *readfds, fd_set *writefds,fd_set *exceptfds, struct timeval *timeout);
#ifndef CC3000_TINY_DRIVER
/*****************************************************************************
* Name: cc3000_setsockopt_impl
*
* Decription:
* 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).
*
* Input Parameters:
* sd socket handle
* level defines the protocol level for this option
* optname defines the option name to Interrogate
* optval specifies a value for the option
* optlen specifies the length of the option value
*
* Returned Value:
* On success, zero is returned. On error, -1 is returned
*
*****************************************************************************/
int cc3000_setsockopt_impl(long sd, long level, long optname, const void *optval, socklen_t optlen);
#endif
/*****************************************************************************
* Name: cc3000_getsockopt_impl
*
* Decription:
* 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).
*
* Input Parameters:
* sd socket handle
* level defines the protocol level for this option
* optname defines the option name to Interrogate
* optval specifies a value for the option
* optlen specifies the length of the option value
*
* Returned Value:
* On success, zero is returned. On error, -1 is returned
*
*****************************************************************************/
int cc3000_getsockopt_impl(long sd, long level, long optname, void *optval, socklen_t *optlen);
/*****************************************************************************
* Name: cc3000_recv_impl
*
* Decription:
* function receives a message from a connection-mode socket
*
* NOTE: On this version, only blocking mode is supported.
*
* Input Parameters:
* sd socket handle
* buf Points to the buffer where the message should be stored
* len Specifies the length in bytes of the buffer pointed to
* by the buffer argument.
* flags Specifies the type of message reception.
* On this version, this parameter is not supported.
*
* Returned Value:
* Return the number of bytes received, or -1 if an error
* occurred
*
*****************************************************************************/
int cc3000_recv_impl(long sd, void *buf, long len, long flags);
/*****************************************************************************
* Name: cc3000_recvfrom_impl
*
* Decription:
* read data from socket
* function receives a message from a connection-mode or
* connectionless-mode socket. Note that raw sockets are not
* supported.
*
* NOTE: On this version, only blocking mode is supported.
*
* Input Parameters:
* sd socket handle
* buf Points to the buffer where the message should be stored
* len Specifies the length in bytes of the buffer pointed to
* by the buffer argument.
* flags Specifies the type of message reception.
* On this version, this parameter is not supported.
* from pointer to an address structure indicating the source
* address: sockaddr. On this version only AF_INET is
* supported.
* fromlen source address tructure size
*
* Returned Value:
* Return the number of bytes received, or -1 if an error
* occurred
*
*****************************************************************************/
int cc3000_recvfrom_impl(long sd, void *buf, long len, long flags,
struct sockaddr *from, socklen_t *fromlen);
/*****************************************************************************
* Name: cc3000_send_impl
*
* Decription:
* 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.
*
* Input Parameters:
* sd socket handle
* buf Points to a buffer containing the message to be sent
* len message size in bytes
* flags On this version, this parameter is not supported
*
* Returned Value:
* Return the number of bytes transmitted, or -1 if an
* error occurred
*
*****************************************************************************/
int cc3000_send_impl(long sd, const void *buf, long len, long flags);
/*****************************************************************************
* Name: cc3000_sendto_impl
*
* Decription:
* 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.
*
* Input Parameters:
* sd socket handle
* buf Points to a buffer containing the message to be sent
* len message size in bytes
* flags On this version, this parameter is not supported
* to pointer to an address structure indicating the destination
* address: sockaddr. On this version only AF_INET is
* supported.
* tolen destination address structure size
*
* Returned Value:
* Return the number of bytes transmitted, or -1 if an
* error occurred
*
*****************************************************************************/
int cc3000_sendto_impl(long sd, FAR const void *buf, long len, long flags,
FAR const struct sockaddr *to, socklen_t tolen);
#ifndef CC3000_TINY_DRIVER
/*****************************************************************************
* Name: cc3000_gethostbyname_impl
*
* Decription:
* 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.
*
* Input Parameters:
* hostname host name
* usNameLen name length
* 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.
*
* Returned Value:
* On success, positive is returned. On error, negative is returned
*
*****************************************************************************/
//struct hostent *gethostbyname(const char *name);
int cc3000_gethostbyname_impl(char * hostname, uint16_t usNameLen, unsigned long* out_ip_addr);
#endif
/*****************************************************************************
* Name: cc3000_mdnsAdvertiser_impl
*
* Decription:
* Set CC3000 in mDNS advertiser mode in order to advertise itself.
*
* Input Parameters:
* mdnsEnabled flag to enable/disable the mDNS feature
* deviceServiceName Service name as part of the published
* canonical domain name
* deviceServiceNameLength Length of the service name
*
* Returned Value:
* On success, zero is returned, return SOC_ERROR if socket was not
* opened successfully, or if an error occurred.
*
*****************************************************************************/
int cc3000_mdnsadvertiser_impl(uint16_t mdnsEnabled, char * deviceServiceName,
uint16_t deviceServiceNameLength);
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // __DRIVERS_WIRELESS_CC3000_SOCKET_H

View File

@ -37,6 +37,7 @@
******************************************************************************/
#include <nuttx/config.h>
#include <string.h>
#include <assert.h>
#include <unistd.h>
@ -46,7 +47,7 @@
#include <nuttx/wireless/cc3000/hci.h>
#include <nuttx/wireless/cc3000/evnt_handler.h>
#include <nuttx/wireless/cc3000/wlan.h>
#include <nuttx/wireless/cc3000/include/sys/socket.h>
#include "cc3000_socket.h"
#include <nuttx/wireless/cc3000/netapp.h>
#include "spi.h"
@ -344,7 +345,7 @@ uint8_t *hci_event_handler(void *pRetParams, uint8_t *from, uint8_t *fromlen)
memcpy((uint8_t *)pRetParams,
pucReceivedParams + ACCEPT_ADDRESS__OFFSET,
sizeof(sockaddr));
sizeof(struct sockaddr));
}
break;
@ -910,21 +911,22 @@ void SimpleLinkWaitEvent(uint16_t usOpcode, void *pRetParams)
do
{
nllvdbg("SpiWait\n");
tSLInformation.pucReceivedData = SpiWait();
tSLInformation.usEventOrDataReceived = 1;
STREAM_TO_UINT16((char *)tSLInformation.pucReceivedData, HCI_EVENT_OPCODE_OFFSET,event_type);
if (*tSLInformation.pucReceivedData == HCI_TYPE_EVNT)
{
nllvdbg("Evtn:0x%x\n",event_type);
}
nllvdbg("Evtn:0x%x\n",event_type);
}
if (event_type != usOpcode)
{
if (hci_unsolicited_event_handler() == 1)
{
nllvdbg("Processed Event 0x%x want 0x%x\n",event_type, usOpcode);
}
if (hci_unsolicited_event_handler() == 1)
{
nllvdbg("Processed Event 0x%x want 0x%x\n",event_type, usOpcode);
}
}
else
{

View File

@ -36,7 +36,11 @@
* Included Files
******************************************************************************/
#include <nuttx/config.h>
#include <debug.h>
#include <string.h>
#include <nuttx/wireless/cc3000/cc3000_common.h>
#include <nuttx/wireless/cc3000/hci.h>
#include "spi.h"
@ -74,6 +78,7 @@ uint16_t hci_command_send(uint16_t usOpcode, uint8_t *pucBuff, uint8_t ucArgsLen
stream = (pucBuff + SPI_HEADER_SIZE);
nllvdbg("Send 0x%x\n",usOpcode);
UINT8_TO_STREAM(stream, HCI_TYPE_CMND);
stream = UINT16_TO_STREAM(stream, usOpcode);
UINT8_TO_STREAM(stream, ucArgsLength);
@ -81,6 +86,7 @@ uint16_t hci_command_send(uint16_t usOpcode, uint8_t *pucBuff, uint8_t ucArgsLen
/* Update the opcode of the event we will be waiting for */
SpiWrite(pucBuff, ucArgsLength + SIMPLE_LINK_HCI_CMND_HEADER_SIZE);
nllvdbg("Send of 0x%x Completed\n",usOpcode);
return 0;
}

View File

@ -37,12 +37,15 @@
******************************************************************************/
#include <string.h>
#include <nuttx/wireless/cc3000/netapp.h>
#include <nuttx/wireless/cc3000/hci.h>
#include <nuttx/wireless/cc3000/include/sys/socket.h>
#include <nuttx/wireless/cc3000/evnt_handler.h>
#include <nuttx/wireless/cc3000/nvmem.h>
#include "cc3000.h"
#include "cc3000_socket.h"
/******************************************************************************
* Pre-processor Definitions
******************************************************************************/
@ -118,6 +121,8 @@ long netapp_dhcp(unsigned long *aucIP, unsigned long *aucSubnetMask,
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
scRet = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -138,6 +143,8 @@ long netapp_dhcp(unsigned long *aucIP, unsigned long *aucSubnetMask,
SimpleLinkWaitEvent(HCI_NETAPP_DHCP, &scRet);
cc3000_lib_unlock();
return(scRet);
}
@ -200,6 +207,8 @@ long netapp_timeout_values(unsigned long *aucDHCP, unsigned long *aucARP,
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
scRet = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -226,11 +235,12 @@ long netapp_timeout_values(unsigned long *aucDHCP, unsigned long *aucARP,
SimpleLinkWaitEvent(HCI_NETAPP_SET_TIMERS, &scRet);
cc3000_lib_unlock();
return scRet;
}
#endif
/******************************************************************************
* Name: netapp_ping_send
*
@ -262,6 +272,8 @@ long netapp_ping_send(unsigned long *ip, unsigned long ulPingAttempts,
int8_t scRet;
uint8_t *ptr, *args;
cc3000_lib_lock();
scRet = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -281,6 +293,8 @@ long netapp_ping_send(unsigned long *ip, unsigned long ulPingAttempts,
SimpleLinkWaitEvent(HCI_NETAPP_PING_SEND, &scRet);
cc3000_lib_unlock();
return scRet;
}
#endif
@ -319,6 +333,8 @@ void netapp_ping_report(void)
ptr = tSLInformation.pucTxCommandBuffer;
int8_t scRet;
cc3000_lib_lock();
scRet = EFAIL;
/* Initiate a HCI command */
@ -328,6 +344,8 @@ void netapp_ping_report(void)
/* Wait for command complete event */
SimpleLinkWaitEvent(HCI_NETAPP_PING_REPORT, &scRet);
cc3000_lib_unlock();
}
#endif
@ -351,6 +369,8 @@ long netapp_ping_stop(void)
int8_t scRet;
uint8_t *ptr;
cc3000_lib_lock();
scRet = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
@ -362,6 +382,8 @@ long netapp_ping_stop(void)
SimpleLinkWaitEvent(HCI_NETAPP_PING_STOP, &scRet);
cc3000_lib_unlock();
return(scRet);
}
#endif
@ -401,6 +423,8 @@ void netapp_ipconfig(tNetappIpconfigRetArgs * ipconfig)
{
uint8_t *ptr;
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
/* Initiate a HCI command */
@ -410,6 +434,8 @@ void netapp_ipconfig(tNetappIpconfigRetArgs * ipconfig)
/* Wait for command complete event */
SimpleLinkWaitEvent(HCI_NETAPP_IPCONFIG, ipconfig);
cc3000_lib_unlock();
}
#else
void netapp_ipconfig(tNetappIpconfigRetArgs * ipconfig)
@ -437,6 +463,9 @@ long netapp_arp_flush(void)
int8_t scRet;
uint8_t *ptr;
cc3000_lib_lock();
scRet = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
@ -448,6 +477,8 @@ long netapp_arp_flush(void)
SimpleLinkWaitEvent(HCI_NETAPP_ARP_FLUSH, &scRet);
cc3000_lib_unlock();
return scRet;
}
#endif
@ -484,6 +515,8 @@ long netapp_set_debug_level(unsigned long ulLevel)
int8_t scRet;
uint8_t *ptr, *args;
cc3000_lib_lock();
scRet = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -500,6 +533,8 @@ long netapp_set_debug_level(unsigned long ulLevel)
SimpleLinkWaitEvent(HCI_NETAPP_SET_DEBUG_LEVEL, &scRet);
cc3000_lib_unlock();
return scRet;
}
#endif

View File

@ -41,8 +41,8 @@
#include <nuttx/wireless/cc3000/nvmem.h>
#include <nuttx/wireless/cc3000/hci.h>
#include <nuttx/wireless/cc3000/include/sys/socket.h>
#include <nuttx/wireless/cc3000/evnt_handler.h>
#include "cc3000.h"
/******************************************************************************
* Pre-processor Definitions
@ -88,6 +88,8 @@ signed long nvmem_read(unsigned long ulFileId, unsigned long ulLength,
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -113,6 +115,8 @@ signed long nvmem_read(unsigned long ulFileId, unsigned long ulLength,
SimpleLinkWaitData(buff, 0, 0);
cc3000_lib_unlock();
return ucStatus;
}
@ -146,6 +150,8 @@ signed long nvmem_write(unsigned long ulFileId, unsigned long ulLength,
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
iRes = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
@ -168,6 +174,8 @@ signed long nvmem_write(unsigned long ulFileId, unsigned long ulLength,
SimpleLinkWaitEvent(HCI_EVNT_NVMEM_WRITE, &iRes);
cc3000_lib_unlock();
return iRes;
}
@ -285,6 +293,8 @@ uint8_t nvmem_read_sp_version(uint8_t *patchVer)
/* 1st byte is the status and the rest is the SP version */
uint8_t retBuf[5];
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
/* Initiate a HCI command, no args are required */
@ -300,6 +310,8 @@ uint8_t nvmem_read_sp_version(uint8_t *patchVer)
*(patchVer+1) = retBuf[4];
cc3000_lib_unlock();
return retBuf[0];
}
#endif
@ -332,6 +344,8 @@ signed long nvmem_create_entry(unsigned long ulFileId, unsigned long ulNewLen)
uint8_t *args;
uint16_t retval;
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -346,5 +360,7 @@ signed long nvmem_create_entry(unsigned long ulFileId, unsigned long ulNewLen)
SimpleLinkWaitEvent(HCI_CMND_NVMEM_CREATE_ENTRY, &retval);
cc3000_lib_unlock();
return retval;
}

File diff suppressed because it is too large Load Diff

File diff suppressed because it is too large Load Diff

View File

@ -71,6 +71,7 @@ static struct
bool run;
uint8_t rx_buffer[CC3000_RX_BUFFER_SIZE];
mqd_t queue;
sem_t *done;
} spiconf;
@ -95,12 +96,9 @@ static struct
void SpiResumeSpi(void)
{
DEBUGASSERT(spiconf.cc3000fd);
if (ioctl(spiconf.cc3000fd,CC3000IOC_COMPLETE,0))
{
printf("ioctl:CC3000IOC_COMPLETE failed: %s\n", strerror(errno));
}
DEBUGASSERT(spiconf.cc3000fd && spiconf.done);
sem_post(spiconf.done);
nllvdbg("Done\n");
}
/*****************************************************************************
@ -158,10 +156,9 @@ long SpiRead(uint8_t *pUserBuffer, uint16_t usLength)
uint8_t *SpiWait(void)
{
int nbytes;
DEBUGASSERT(spiconf.cc3000fd);
nbytes = mq_receive(spiconf.queue, spiconf.rx_buffer, CC3000_RX_BUFFER_SIZE, 0);
mq_receive(spiconf.queue, spiconf.rx_buffer, CC3000_RX_BUFFER_SIZE, 0);
return spiconf.rx_buffer;
}
@ -181,14 +178,19 @@ uint8_t *SpiWait(void)
static void *unsoliced_thread_func(void *parameter)
{
char queuename[QUEUE_NAMELEN];
char buff[QUEUE_NAMELEN];
int status = 0;
int nbytes = 0;
int minor = 0;
ioctl(spiconf.cc3000fd, CC3000IOC_GETQUEID, (unsigned long)&minor);
snprintf(queuename, QUEUE_NAMELEN, QUEUE_FORMAT, minor);
spiconf.queue = mq_open(queuename,O_RDONLY);
ioctl(spiconf.cc3000fd, CC3000IOC_GETQUESEMID, (unsigned long)&minor);
snprintf(buff, QUEUE_NAMELEN, QUEUE_FORMAT, minor);
spiconf.queue = mq_open(buff,O_RDONLY);
DEBUGASSERT(spiconf.queue != (mqd_t) -1);
DEBUGASSERT(SEM_NAMELEN == QUEUE_NAMELEN);
snprintf(buff, SEM_NAMELEN, SEM_FORMAT, minor);
spiconf.done = sem_open(buff,O_RDONLY);
DEBUGASSERT(spiconf.done != (sem_t *)-1);
while(spiconf.run)
{
@ -196,12 +198,13 @@ static void *unsoliced_thread_func(void *parameter)
nbytes = mq_receive(spiconf.queue, spiconf.rx_buffer, CC3000_RX_BUFFER_SIZE, 0);
if (nbytes > 0)
{
spivdbg("%d Processed\n",nbytes);
nlldbg("%d Processed\n",nbytes);
spiconf.pfRxHandler(spiconf.rx_buffer);
}
}
mq_close(spiconf.queue);
sem_close(spiconf.done);
pthread_exit((pthread_addr_t)status);
return (pthread_addr_t)status;
}
@ -223,9 +226,11 @@ static void *unsoliced_thread_func(void *parameter)
void SpiOpen(gcSpiHandleRx pfRxHandler)
{
int status;
int fd;
DEBUGASSERT(spiconf.cc3000fd == 0);
int fd = open("/dev/wireless0",O_RDWR|O_BINARY);
fd = open("/dev/wireless0",O_RDWR|O_BINARY);
if (fd > 0)
{
spiconf.pfRxHandler = pfRxHandler;

View File

@ -41,16 +41,18 @@
#include <stdint.h>
#include <string.h>
#include <debug.h>
#include <nuttx/wireless/cc3000/cc3000_common.h>
#include <nuttx/wireless/cc3000/wlan.h>
#include <nuttx/wireless/cc3000/hci.h>
#include "spi.h"
#include <nuttx/wireless/cc3000/include/sys/socket.h>
#include <nuttx/wireless/cc3000/nvmem.h>
#include <nuttx/wireless/cc3000/security.h>
#include <nuttx/wireless/cc3000/evnt_handler.h>
#include "spi.h"
#include "cc3000.h"
/*****************************************************************************
* Preprocessor Definitions
*****************************************************************************/
@ -137,7 +139,8 @@ static void SimpleLink_Init_Start(uint16_t usPatchesAvailableAtHost)
ptr = tSLInformation.pucTxCommandBuffer;
args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
UINT8_TO_STREAM(args, ((usPatchesAvailableAtHost) ? SL_PATCHES_REQUEST_FORCE_HOST : SL_PATCHES_REQUEST_DEFAULT));
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 */
@ -194,23 +197,14 @@ static void SimpleLink_Init_Start(uint16_t usPatchesAvailableAtHost)
void wlan_init(tWlanCB sWlanCB, tFWPatches sFWPatches,
tDriverPatches sDriverPatches,
tBootLoaderPatches sBootLoaderPatches,
tWlanReadInteruptPin sReadWlanInterruptPin,
tWlanInterruptEnable sWlanInterruptEnable,
tWlanInterruptDisable sWlanInterruptDisable,
tWriteWlanPin sWriteWlanPin)
tBootLoaderPatches sBootLoaderPatches)
{
cc3000_lib_lock();
tSLInformation.sFWPatches = sFWPatches;
tSLInformation.sDriverPatches = sDriverPatches;
tSLInformation.sBootLoaderPatches = sBootLoaderPatches;
/* Init I/O callback */
tSLInformation.ReadWlanInterruptPin = sReadWlanInterruptPin;
tSLInformation.WlanInterruptEnable = sWlanInterruptEnable;
tSLInformation.WlanInterruptDisable = sWlanInterruptDisable;
tSLInformation.WriteWlanPin = sWriteWlanPin;
/* Init asynchronous events callback */
tSLInformation.sWlanCB= sWlanCB;
@ -218,6 +212,7 @@ void wlan_init(tWlanCB sWlanCB, tFWPatches sFWPatches,
/* By default TX Complete events are routed to host too */
tSLInformation.InformHostOnTxComplete = 1;
cc3000_lib_unlock();
}
/*****************************************************************************
@ -237,8 +232,12 @@ void wlan_init(tWlanCB sWlanCB, tFWPatches sFWPatches,
void SpiReceiveHandler(void *pvBuffer)
{
tSLInformation.usEventOrDataReceived = 1;
tSLInformation.pucReceivedData = (uint8_t *)pvBuffer;
tSLInformation.usEventOrDataReceived = 1;
uint16_t event_type;
STREAM_TO_UINT16((char *)tSLInformation.pucReceivedData, HCI_EVENT_OPCODE_OFFSET,event_type);
nllvdbg("Evtn:0x%x\n", event_type);
hci_unsolicited_event_handler();
}
@ -272,7 +271,7 @@ void SpiReceiveHandler(void *pvBuffer)
void wlan_start(uint16_t usPatchesAvailableAtHost)
{
unsigned long ulSpiIRQState;
cc3000_lib_lock();
tSLInformation.NumberOfSentPackets = 0;
tSLInformation.NumberOfReleasedPackets = 0;
@ -293,41 +292,13 @@ void wlan_start(uint16_t usPatchesAvailableAtHost)
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);
cc3000_lib_unlock();
}
/*****************************************************************************
@ -346,24 +317,9 @@ void wlan_start(uint16_t usPatchesAvailableAtHost)
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;
}
cc3000_lib_lock();
SpiClose();
cc3000_lib_unlock();
}
/*****************************************************************************
@ -407,6 +363,8 @@ long wlan_connect(unsigned long ulSecType, char *ssid, long ssid_len,
uint8_t *args;
uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0};
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -447,7 +405,7 @@ long wlan_connect(unsigned long ulSecType, char *ssid, long ssid_len,
SimpleLinkWaitEvent(HCI_CMND_WLAN_CONNECT, &ret);
errno = ret;
cc3000_lib_unlock();
return ret;
}
#else
@ -458,6 +416,8 @@ long wlan_connect(char *ssid, long ssid_len)
uint8_t *args;
uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0};
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -486,6 +446,8 @@ long wlan_connect(char *ssid, long ssid_len)
SimpleLinkWaitEvent(HCI_CMND_WLAN_CONNECT, &ret);
errno = ret;
cc3000_lib_unlock();
return ret;
}
#endif
@ -509,6 +471,8 @@ long wlan_disconnect(void)
long ret;
uint8_t *ptr;
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
@ -519,6 +483,8 @@ long wlan_disconnect(void)
SimpleLinkWaitEvent(HCI_CMND_WLAN_DISCONNECT, &ret);
errno = ret;
cc3000_lib_unlock();
return ret;
}
@ -562,6 +528,8 @@ long wlan_ioctl_set_connection_policy(unsigned long should_connect_to_open_ap,
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
@ -581,6 +549,7 @@ long wlan_ioctl_set_connection_policy(unsigned long should_connect_to_open_ap,
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SET_CONNECTION_POLICY, &ret);
cc3000_lib_unlock();
return ret;
}
@ -628,6 +597,8 @@ long wlan_add_profile(unsigned long ulSecType, uint8_t* ucSsid,
uint8_t *args;
uint8_t bssid_zero[] = {0, 0, 0, 0, 0, 0};
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -733,7 +704,7 @@ long wlan_add_profile(unsigned long ulSecType, uint8_t* ucSsid,
/* Wait for command complete event */
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_ADD_PROFILE, &ret);
cc3000_lib_unlock();
return ret;
}
#else
@ -770,6 +741,8 @@ long wlan_ioctl_del_profile(unsigned long ulIndex)
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
@ -787,6 +760,8 @@ long wlan_ioctl_del_profile(unsigned long ulIndex)
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_DEL_PROFILE, &ret);
cc3000_lib_unlock();
return ret;
}
@ -829,6 +804,8 @@ long wlan_ioctl_get_scan_results(unsigned long ulScanTimeout, uint8_t *ucResults
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -845,6 +822,8 @@ long wlan_ioctl_get_scan_results(unsigned long ulScanTimeout, uint8_t *ucResults
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_GET_SCAN_RESULTS, ucResults);
cc3000_lib_unlock();
return 0;
}
#endif
@ -900,6 +879,8 @@ long wlan_ioctl_set_scan_params(unsigned long uiEnable,
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -926,6 +907,8 @@ long wlan_ioctl_set_scan_params(unsigned long uiEnable,
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SET_SCANPARAM, &uiRes);
cc3000_lib_unlock();
return uiRes;
}
#endif
@ -960,6 +943,8 @@ long wlan_set_event_mask(unsigned long ulMask)
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
if ((ulMask & HCI_EVNT_WLAN_TX_COMPLETE) == HCI_EVNT_WLAN_TX_COMPLETE)
{
tSLInformation.InformHostOnTxComplete = 0;
@ -998,6 +983,8 @@ long wlan_set_event_mask(unsigned long ulMask)
SimpleLinkWaitEvent(HCI_CMND_EVENT_MASK, &ret);
cc3000_lib_unlock();
return ret;
}
@ -1022,6 +1009,8 @@ long wlan_ioctl_statusget(void)
long ret;
uint8_t *ptr;
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
@ -1032,6 +1021,8 @@ long wlan_ioctl_statusget(void)
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_STATUSGET, &ret);
cc3000_lib_unlock();
return ret;
}
#endif
@ -1063,6 +1054,8 @@ long wlan_smart_config_start(unsigned long algoEncryptedFlag)
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (uint8_t *)(ptr + HEADERS_SIZE_CMD);
@ -1079,6 +1072,7 @@ long wlan_smart_config_start(unsigned long algoEncryptedFlag)
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_START, &ret);
cc3000_lib_unlock();
return ret;
}
@ -1101,6 +1095,8 @@ long wlan_smart_config_stop(void)
long ret;
uint8_t *ptr;
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
@ -1110,6 +1106,7 @@ long wlan_smart_config_stop(void)
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_STOP, &ret);
cc3000_lib_unlock();
return ret;
}
@ -1136,6 +1133,8 @@ long wlan_smart_config_set_prefix(char* cNewPrefix)
uint8_t *ptr;
uint8_t *args;
cc3000_lib_lock();
ret = EFAIL;
ptr = tSLInformation.pucTxCommandBuffer;
args = (ptr + HEADERS_SIZE_CMD);
@ -1163,6 +1162,8 @@ long wlan_smart_config_set_prefix(char* cNewPrefix)
SimpleLinkWaitEvent(HCI_CMND_WLAN_IOCTL_SIMPLE_CONFIG_SET_PREFIX, &ret);
cc3000_lib_unlock();
return ret;
}