summaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-11-28 08:52:52 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-11-28 08:52:52 -0600
commitcff032b6c18d90b3ab83474e03c3ee249c9b6ee8 (patch)
tree928d1c5c7881cf8b5762b5776d548bda2e1ab60c /nuttx/drivers
parent78e84804cf4308f4c867d88880ad5981a2e8e20e (diff)
downloadpx4-nuttx-cff032b6c18d90b3ab83474e03c3ee249c9b6ee8.tar.gz
px4-nuttx-cff032b6c18d90b3ab83474e03c3ee249c9b6ee8.tar.bz2
px4-nuttx-cff032b6c18d90b3ab83474e03c3ee249c9b6ee8.zip
This commit is a set of patches 02/11 through 03/11 correcting issues with the CC3000 networking (01/11 was committed separated). Among these 10 patches:
03/11: CC3000 driver was getting stuck at recv() when remote host closed connection and application tried to read data from remotely shutdown socket. This patch adds proper handling for remotely closed socket event. 07/11: Socket state initialization was done in 'register', while it should be initialized in 'open' and deinitialized in 'close'. Old way caused problems when device is closed, power-cycled and then reopened as old socket state was left enabled. 08/11: Select thread was getting stuck after 'close, power-cycle, reopen', since selectsem was not properly setup and cleaned up. 09/11 'maxFD' was not properly reset in select worker and not checked for before calling cc3000_select(). 10/11: After wlan_stop()/cc3000_close(), irqsem was left with count '-1'. Therefore on next wlan_start()/cc3000_open(), initial value for irqsem was wrong. Additional repeated wlan_start()/wlan_stop() decreased irqsem value further. Obviously this causes driver not to function correctly and freeze. Patch moves initialization and destruction of waitsem, irqsem and readysem to cc3000_open/cc3000_close. All are: Signed-off-by: Jussi Kivilinna <jussi.kivilinna@haltian.com>
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/wireless/cc3000/cc3000.c228
-rw-r--r--nuttx/drivers/wireless/cc3000/cc3000.h5
-rw-r--r--nuttx/drivers/wireless/cc3000/cc3000_socket.h1
-rw-r--r--nuttx/drivers/wireless/cc3000/cc3000drv.c67
-rw-r--r--nuttx/drivers/wireless/cc3000/cc3000drv.h1
-rw-r--r--nuttx/drivers/wireless/cc3000/evnt_handler.c13
-rw-r--r--nuttx/drivers/wireless/cc3000/socket.c60
-rw-r--r--nuttx/drivers/wireless/cc3000/wlan.c22
8 files changed, 303 insertions, 94 deletions
diff --git a/nuttx/drivers/wireless/cc3000/cc3000.c b/nuttx/drivers/wireless/cc3000/cc3000.c
index f14be5311..dbda7f374 100644
--- a/nuttx/drivers/wireless/cc3000/cc3000.c
+++ b/nuttx/drivers/wireless/cc3000/cc3000.c
@@ -163,6 +163,7 @@ static int cc3000_accept_socket(FAR struct cc3000_dev_s *priv, int sd,
socklen_t *addrlen);
static int cc3000_add_socket(FAR struct cc3000_dev_s *priv, int sd);
static int cc3000_remove_socket(FAR struct cc3000_dev_s *priv, int sd);
+static int cc3000_remote_closed_socket(FAR struct cc3000_dev_s *priv, int sd);
/****************************************************************************
* Private Data
@@ -488,6 +489,7 @@ 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;
+ TICC3000fd_set exceptsds;
int ret = 0;
int maxFD = 0;
int s = 0;
@@ -506,7 +508,9 @@ static void * select_thread_func(FAR void *arg)
sem_post(&priv->selectsem);
+ maxFD = -1;
CC3000_FD_ZERO(&readsds);
+ CC3000_FD_ZERO(&exceptsds);
/* Ping correct socket descriptor param for select */
@@ -536,6 +540,7 @@ static void * select_thread_func(FAR void *arg)
}
CC3000_FD_SET(priv->sockets[s].sd, &readsds);
+ CC3000_FD_SET(priv->sockets[s].sd, &exceptsds);
if (maxFD <= priv->sockets[s].sd)
{
maxFD = priv->sockets[s].sd + 1;
@@ -543,9 +548,18 @@ static void * select_thread_func(FAR void *arg)
}
}
+ if (maxFD < 0)
+ {
+ /* Handled only socket close. */
+
+ continue;
+ }
+
/* Polling instead of blocking here to process "accept" below */
- ret = cc3000_select(maxFD, (fd_set *) &readsds, NULL, NULL, &timeout);
+ ret = cc3000_select(maxFD, (fd_set *) &readsds, NULL,
+ (fd_set *) &exceptsds, &timeout);
+
if (priv->selecttid == -1)
{
/* driver close will terminate the thread and by that all sync
@@ -555,16 +569,26 @@ static void * select_thread_func(FAR void *arg)
return OK;
}
- if (ret > 0)
+ for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
- for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
+ if ((priv->sockets[s].sd != FREE_SLOT ||
+ priv->sockets[s].sd != CLOSE_SLOT) && /* Check that the socket is valid */
+ priv->sockets[s].sd != priv->accepting_socket.acc.sd) /* Verify this is not an accept socket */
{
- if ((priv->sockets[s].sd != FREE_SLOT ||
- priv->sockets[s].sd != CLOSE_SLOT) && /* Check that the socket is valid */
- priv->sockets[s].sd != priv->accepting_socket.acc.sd && /* Verify this is not an accept socket */
- CC3000_FD_ISSET(priv->sockets[s].sd, &readsds)) /* and has pending data */
+ if (ret > 0 && CC3000_FD_ISSET(priv->sockets[s].sd, &readsds)) /* and has pending data */
+ {
+ waitlldbg("Signaled %d\n", priv->sockets[s].sd);
+ sem_post(&priv->sockets[s].semwait); /* release the waiting thread */
+ }
+ else if (ret > 0 && CC3000_FD_ISSET(priv->sockets[s].sd, &exceptsds)) /* or has pending exception */
+ {
+ waitlldbg("Signaled %d (exception)\n", priv->sockets[s].sd);
+ sem_post(&priv->sockets[s].semwait); /* release the waiting thread */
+ }
+ else if (priv->sockets[s].received_closed_event) /* or remote has closed connection and we have now read all of HW buffer. */
{
- waitlldbg("Signaled %d\n",priv->sockets[s].sd);
+ waitlldbg("Signaled %d (closed & empty)\n", priv->sockets[s].sd);
+ priv->sockets[s].emptied_and_remotely_closed = true;
sem_post(&priv->sockets[s].semwait); /* release the waiting thread */
}
}
@@ -775,11 +799,15 @@ static int cc3000_open(FAR struct file *filep)
FAR struct inode *inode;
struct mq_attr attr;
pthread_attr_t tattr;
+ pthread_t threadid;
struct sched_param param;
char queuename[QUEUE_NAMELEN];
FAR struct cc3000_dev_s *priv;
uint8_t tmp;
int ret;
+#ifdef CONFIG_CC3000_MT
+ int s;
+#endif
DEBUGASSERT(filep);
inode = filep->f_inode;
@@ -807,7 +835,7 @@ static int cc3000_open(FAR struct file *filep)
/* More than 255 opens; uint8_t overflows to zero */
ret = -EMFILE;
- goto errout_with_sem;
+ goto out_with_sem;
}
/* When the reference increments to 1, this is the first open event
@@ -816,6 +844,22 @@ static int cc3000_open(FAR struct file *filep)
if (tmp == 1)
{
+ 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 */
+
+#ifdef CONFIG_CC3000_MT
+ 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;
+ priv->sockets[s].received_closed_event = false;
+ priv->sockets[s].emptied_and_remotely_closed = false;
+ sem_init(&priv->sockets[s].semwait, 0, 0);
+ }
+#endif
+
/* Ensure the power is off so we get the falling edge of IRQ*/
priv->config->power_enable(priv->config, false);
@@ -839,9 +883,8 @@ static int cc3000_open(FAR struct file *filep)
priv->queue = mq_open(queuename,O_WRONLY|O_CREAT, 0666, &attr);
if (priv->queue < 0)
{
- priv->crefs--;
ret = -errno;
- goto errout_with_sem;
+ goto errout_sem_destroy;
}
pthread_attr_init(&tattr);
@@ -853,27 +896,22 @@ static int cc3000_open(FAR struct file *filep)
(pthread_addr_t)priv);
if (ret != 0)
{
- mq_close(priv->queue);
- priv->queue = 0;
- ret = -errno;
- goto errout_with_sem;
+ ret = -ret; /* pthread_create does not modify errno. */
+ goto errout_mq_close;
}
pthread_attr_init(&tattr);
tattr.stacksize = CONFIG_CC3000_SELECT_STACKSIZE;
param.sched_priority = CONFIG_CC3000_SELECT_THREAD_PRIORITY;
pthread_attr_setschedparam(&tattr, &param);
+
+ sem_init(&priv->selectsem, 0, 0);
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);
- mq_close(priv->queue);
- priv->queue = 0;
- ret = -errno;
- goto errout_with_sem;
+ ret = -ret; /* pthread_create does not modify errno. */
+ goto errout_worker_cancel;
}
/* Do late allocation with hopes of realloc not fragmenting */
@@ -882,9 +920,8 @@ static int cc3000_open(FAR struct file *filep)
DEBUGASSERT(priv->rx_buffer.pbuffer);
if (!priv->rx_buffer.pbuffer)
{
- priv->crefs--;
ret = -errno;
- goto errout_with_sem;
+ goto errout_select_cancel;
}
priv->state = eSPI_STATE_POWERUP;
@@ -903,8 +940,43 @@ static int cc3000_open(FAR struct file *filep)
/* Save the new open count on success */
priv->crefs = tmp;
+ ret = OK;
-errout_with_sem:
+ goto out_with_sem;
+
+errout_select_cancel:
+ threadid = priv->selecttid;
+ priv->selecttid = -1;
+ pthread_cancel(threadid);
+ pthread_join(threadid, NULL);
+ sem_destroy(&priv->selectsem);
+
+errout_worker_cancel:
+ threadid = priv->workertid;
+ priv->workertid = -1;
+ pthread_cancel(threadid);
+ pthread_join(threadid, NULL);
+
+errout_mq_close:
+ mq_close(priv->queue);
+ priv->queue = 0;
+
+errout_sem_destroy:
+#ifdef CONFIG_CC3000_MT
+ sem_destroy(&priv->accepting_socket.acc.semwait);
+
+ for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
+ {
+ priv->sockets[s].sd = FREE_SLOT;
+ sem_destroy(&priv->sockets[s].semwait);
+ }
+#endif
+
+ sem_destroy(&priv->waitsem);
+ sem_destroy(&priv->irqsem);
+ sem_destroy(&priv->readysem);
+
+out_with_sem:
cc3000_devgive(priv);
return ret;
}
@@ -918,6 +990,9 @@ static int cc3000_close(FAR struct file *filep)
FAR struct inode *inode;
FAR struct cc3000_dev_s *priv;
int ret;
+#ifdef CONFIG_CC3000_MT
+ int s;
+#endif
DEBUGASSERT(filep);
inode = filep->f_inode;
@@ -954,6 +1029,7 @@ static int cc3000_close(FAR struct file *filep)
priv->selecttid = -1;
pthread_cancel(id);
pthread_join(id, NULL);
+ sem_destroy(&priv->selectsem);
priv->config->irq_enable(priv->config, false);
priv->config->irq_clear(priv->config);
@@ -970,6 +1046,19 @@ static int cc3000_close(FAR struct file *filep)
kmm_free(priv->rx_buffer.pbuffer);
priv->rx_buffer.pbuffer = 0;
+#ifdef CONFIG_CC3000_MT
+ sem_destroy(&priv->accepting_socket.acc.semwait);
+
+ for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
+ {
+ priv->sockets[s].sd = FREE_SLOT;
+ sem_destroy(&priv->sockets[s].semwait);
+ }
+#endif
+
+ sem_destroy(&priv->waitsem);
+ sem_destroy(&priv->irqsem);
+ sem_destroy(&priv->readysem);
}
cc3000_devgive(priv);
@@ -1301,6 +1390,14 @@ static int cc3000_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
break;
}
+ case CC3000IOC_REMOTECLOSEDSOCKET:
+ {
+ FAR int *pfd = (FAR int *)(arg);
+ DEBUGASSERT(pfd != NULL);
+ *pfd = cc3000_remote_closed_socket(priv, *pfd);
+ break;
+ }
+
case CC3000IOC_SELECTDATA:
{
FAR int *pfd = (FAR int *)(arg);
@@ -1465,10 +1562,6 @@ int cc3000_register(FAR struct spi_dev_s *spi,
FAR struct cc3000_dev_s *priv;
char drvname[DEV_NAMELEN];
char semname[SEM_NAMELEN];
-#ifdef CONFIG_CC3000_MT
- int s;
-#endif
-
#ifdef CONFIG_CC3000_MULTIPLE
irqstate_t flags;
#endif
@@ -1504,22 +1597,12 @@ int cc3000_register(FAR struct spi_dev_s *spi,
priv->rx_buffer_max_len = config->max_rx_size;
sem_init(&priv->devsem, 0, 1); /* Initialize device structure semaphore */
- 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 */
(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 */
@@ -1565,20 +1648,11 @@ 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
@@ -1605,7 +1679,7 @@ errout_with_priv:
static int cc3000_wait_data(FAR struct cc3000_dev_s *priv, int sockfd)
{
- int s;
+ int s;
for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
{
@@ -1618,7 +1692,18 @@ static int cc3000_wait_data(FAR struct cc3000_dev_s *priv, int sockfd)
sem_wait(&priv->selectsem); /* Sleep select thread */
cc3000_devtake(priv);
sched_unlock();
- return priv->sockets[s].sd == sockfd ? OK : -1;
+
+ if (!priv->sockets[s].sd == sockfd)
+ {
+ return -1;
+ }
+
+ if (priv->sockets[s].emptied_and_remotely_closed)
+ {
+ return -ECONNABORTED;
+ }
+
+ return OK;
}
}
@@ -1697,6 +1782,8 @@ static int cc3000_add_socket(FAR struct cc3000_dev_s *priv, int sd)
{
if (priv->sockets[s].sd == FREE_SLOT)
{
+ priv->sockets[s].received_closed_event = false;
+ priv->sockets[s].emptied_and_remotely_closed = false;
priv->sockets[s].sd = sd;
break;
}
@@ -1744,6 +1831,8 @@ static int cc3000_remove_socket(FAR struct cc3000_dev_s *priv, int sd)
{
if (priv->sockets[s].sd == sd)
{
+ priv->sockets[s].received_closed_event = false;
+ priv->sockets[s].emptied_and_remotely_closed = false;
priv->sockets[s].sd = CLOSE_SLOT;
ps = &priv->sockets[s].semwait;
break;
@@ -1764,3 +1853,42 @@ static int cc3000_remove_socket(FAR struct cc3000_dev_s *priv, int sd)
return s >= CONFIG_WL_MAX_SOCKETS ? -1 : OK;
}
+
+/****************************************************************************
+ * Name: cc3000_remote_closed_socket
+ *
+ * Description:
+ * Mark socket as closed by remote host
+ *
+ * Input Parameters:
+ * sd cc3000 socket handle
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a -1 value is
+ * returned to indicate socket not found.
+ *
+ ****************************************************************************/
+
+static int cc3000_remote_closed_socket(FAR struct cc3000_dev_s *priv, int sd)
+{
+ irqstate_t flags;
+ int s;
+
+ if (sd < 0)
+ {
+ return sd;
+ }
+
+ flags = irqsave();
+ for (s = 0; s < CONFIG_WL_MAX_SOCKETS; s++)
+ {
+ if (priv->sockets[s].sd == sd)
+ {
+ priv->sockets[s].received_closed_event = true;
+ }
+ }
+
+ irqrestore(flags);
+
+ return s >= CONFIG_WL_MAX_SOCKETS ? -1 : OK;
+}
diff --git a/nuttx/drivers/wireless/cc3000/cc3000.h b/nuttx/drivers/wireless/cc3000/cc3000.h
index 630f21794..9339e0275 100644
--- a/nuttx/drivers/wireless/cc3000/cc3000.h
+++ b/nuttx/drivers/wireless/cc3000/cc3000.h
@@ -91,7 +91,7 @@
****************************************************************************/
#ifdef CONFIG_CC3000_MT
-/* lock to serialze access to driver (spi protocol is window size 1) */
+/* lock to serialize access to driver (SPI protocol is window size 1) */
extern pthread_mutex_t g_cc3000_mut;
@@ -101,6 +101,8 @@ typedef struct cc3000_socket_ent
{
volatile int sd;
long status;
+ bool received_closed_event:1;
+ bool emptied_and_remotely_closed:1;
sem_t semwait;
} cc3000_socket_ent;
@@ -156,6 +158,7 @@ struct cc3000_dev_s
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'.
diff --git a/nuttx/drivers/wireless/cc3000/cc3000_socket.h b/nuttx/drivers/wireless/cc3000/cc3000_socket.h
index 0e3f969b0..02144fe90 100644
--- a/nuttx/drivers/wireless/cc3000/cc3000_socket.h
+++ b/nuttx/drivers/wireless/cc3000/cc3000_socket.h
@@ -77,6 +77,7 @@
#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_TX_TEST_RAW 150 /* Raw 802.11 Tx Test packet */
#define CC3000_IPPROTO_RAW 255 /* Raw IP packet */
#define CC3000_IPPROTO_MAX 256
diff --git a/nuttx/drivers/wireless/cc3000/cc3000drv.c b/nuttx/drivers/wireless/cc3000/cc3000drv.c
index 948a98657..0f94c42e9 100644
--- a/nuttx/drivers/wireless/cc3000/cc3000drv.c
+++ b/nuttx/drivers/wireless/cc3000/cc3000drv.c
@@ -91,7 +91,10 @@ static struct
mqd_t queue;
sem_t *done;
sem_t unsoliced_thread_wakesem;
-} spiconf;
+} spiconf =
+{
+ -1,
+};
/*****************************************************************************
* Public Functions
@@ -113,7 +116,7 @@ static struct
void cc3000_resume(void)
{
- DEBUGASSERT(spiconf.cc3000fd && spiconf.done);
+ DEBUGASSERT(spiconf.cc3000fd >= 0 && spiconf.done);
sem_post(spiconf.done);
nllvdbg("Done\n");
}
@@ -134,7 +137,7 @@ void cc3000_resume(void)
long cc3000_write(uint8_t *pUserBuffer, uint16_t usLength)
{
- DEBUGASSERT(spiconf.cc3000fd);
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
return write(spiconf.cc3000fd,pUserBuffer,usLength) == usLength ? 0 : -errno;
}
@@ -143,7 +146,7 @@ long cc3000_write(uint8_t *pUserBuffer, uint16_t usLength)
*
* Description:
* This function enter point for read flow. This function will block the
- * caller untinlthere is data Available
+ * caller until there is data available
*
* Input Parameters:
* pUserBuffer
@@ -155,7 +158,7 @@ long cc3000_write(uint8_t *pUserBuffer, uint16_t usLength)
long cc3000_read(uint8_t *pUserBuffer, uint16_t usLength)
{
- DEBUGASSERT(spiconf.cc3000fd);
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
return read(spiconf.cc3000fd,pUserBuffer,usLength);
}
@@ -174,7 +177,7 @@ long cc3000_read(uint8_t *pUserBuffer, uint16_t usLength)
uint8_t *cc3000_wait(void)
{
- DEBUGASSERT(spiconf.cc3000fd);
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
mq_receive(spiconf.queue, &spiconf.rx_buffer, sizeof(spiconf.rx_buffer), 0);
return spiconf.rx_buffer.pbuffer;
@@ -185,7 +188,7 @@ uint8_t *cc3000_wait(void)
*
* Description:
* This is the thread for unsolicited events. This function will block the
- * caller untinlthere is data Available
+ * caller until there is data available
*
* Input Parameters:
* parameter
@@ -234,7 +237,7 @@ static void *unsoliced_thread_func(void *parameter)
* Name: cc3000_open
*
* Description:
- * Open the cc3000 driver
+ * Open the cc3000 driver
*
* Input Parameters:
* pfRxHandler the Rx handler for messages
@@ -249,10 +252,10 @@ void cc3000_open(gcSpiHandleRx pfRxHandler)
int status;
int fd;
- DEBUGASSERT(spiconf.cc3000fd == 0);
+ DEBUGASSERT(spiconf.cc3000fd == -1);
fd = open("/dev/wireless0",O_RDWR|O_BINARY);
- if (fd > 0)
+ if (fd >= 0)
{
spiconf.pfRxHandler = pfRxHandler;
spiconf.cc3000fd = fd;
@@ -279,7 +282,7 @@ void cc3000_open(gcSpiHandleRx pfRxHandler)
}
}
- DEBUGASSERT(spiconf.cc3000fd);
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
}
/*****************************************************************************
@@ -298,7 +301,7 @@ void cc3000_open(gcSpiHandleRx pfRxHandler)
void cc3000_close(void)
{
- if (spiconf.cc3000fd)
+ if (spiconf.cc3000fd >= 0)
{
int status;
spiconf.run = false;
@@ -307,7 +310,9 @@ void cc3000_close(void)
pthread_join(spiconf.unsoliced_thread, (pthread_addr_t*)&status);
close(spiconf.cc3000fd);
- spiconf.cc3000fd = 0;
+
+ memset(&spiconf, 0, sizeof(spiconf));
+ spiconf.cc3000fd = -1;
}
}
@@ -328,8 +333,9 @@ void cc3000_close(void)
int cc3000_wait_data(int sockfd)
{
- DEBUGASSERT(spiconf.cc3000fd);
int rv = sockfd;
+
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
ioctl(spiconf.cc3000fd, CC3000IOC_SELECTDATA, (unsigned long)&rv);
return rv;
}
@@ -349,12 +355,13 @@ int cc3000_wait_data(int sockfd)
* returned to indicate socket not found.
*
****************************************************************************/
+
int to_cc3000_accept_socket(int sockfd, struct sockaddr *addr, socklen_t *addrlen);
int cc3000_accept_socket(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
{
//return to_cc3000_accept_socket(sockfd, addr,addrlen);
- DEBUGASSERT(spiconf.cc3000fd);
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
cc3000_acceptcfg cfg;
cfg.sockfd = sockfd;
@@ -382,8 +389,9 @@ int cc3000_accept_socket(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
int cc3000_add_socket(int sockfd)
{
- DEBUGASSERT(spiconf.cc3000fd);
int rv = sockfd;
+
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
ioctl(spiconf.cc3000fd, CC3000IOC_ADDSOCKET, (unsigned long)&rv);
return rv;
}
@@ -406,8 +414,33 @@ int cc3000_add_socket(int sockfd)
int cc3000_remove_socket(int sockfd)
{
- DEBUGASSERT(spiconf.cc3000fd);
int rv = sockfd;
+
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
ioctl(spiconf.cc3000fd, CC3000IOC_REMOVESOCKET, (unsigned long)&rv);
return rv;
}
+
+/****************************************************************************
+ * Name: cc3000_remote_closed_socket
+ *
+ * Description:
+ * Mark socket as closed by remote host
+ *
+ * Input Parameters:
+ * sd cc3000 socket handle
+ *
+ * Returned Value:
+ * Zero is returned on success. Otherwise, a -1 value is
+ * returned to indicate socket not found.
+ *
+ ****************************************************************************/
+
+int cc3000_remote_closed_socket(int sockfd)
+{
+ int rv = sockfd;
+
+ DEBUGASSERT(spiconf.cc3000fd >= 0);
+ ioctl(spiconf.cc3000fd, CC3000IOC_REMOTECLOSEDSOCKET, (unsigned long)&rv);
+ return rv;
+}
diff --git a/nuttx/drivers/wireless/cc3000/cc3000drv.h b/nuttx/drivers/wireless/cc3000/cc3000drv.h
index 72745d5fc..f23eaf164 100644
--- a/nuttx/drivers/wireless/cc3000/cc3000drv.h
+++ b/nuttx/drivers/wireless/cc3000/cc3000drv.h
@@ -79,6 +79,7 @@ int cc3000_accept_socket(int sockfd, struct sockaddr *addr,
socklen_t *addrlen);
int cc3000_add_socket(int sockfd);
int cc3000_remove_socket(int sockfd);
+int cc3000_remote_closed_socket(int sockfd);
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/drivers/wireless/cc3000/evnt_handler.c b/nuttx/drivers/wireless/cc3000/evnt_handler.c
index 28901e3c3..9a1a2eee8 100644
--- a/nuttx/drivers/wireless/cc3000/evnt_handler.c
+++ b/nuttx/drivers/wireless/cc3000/evnt_handler.c
@@ -576,6 +576,11 @@ long hci_unsol_event_handler(char *event_hdr)
STREAM_TO_UINT16(event_hdr, HCI_EVENT_OPCODE_OFFSET,event_type);
+ if (event_type == HCI_EVNT_PATCHES_REQ)
+ {
+ hci_unsol_handle_patch_request(event_hdr);
+ }
+
if (event_type & HCI_EVNT_UNSOL_BASE)
{
switch(event_type)
@@ -677,6 +682,14 @@ long hci_unsol_event_handler(char *event_hdr)
case HCI_EVNT_BSD_TCP_CLOSE_WAIT:
{
+ int sockfd;
+
+ data = (char*)(event_hdr) + HCI_EVENT_HEADER_SIZE;
+ STREAM_TO_UINT32(data, NETAPP_PING_PACKETS_SENT_OFFSET, sockfd);
+ data += 4;
+
+ (void)cc3000_remote_closed_socket(sockfd);
+
if (tSLInformation.sWlanCB)
{
tSLInformation.sWlanCB(event_type, NULL, 0);
diff --git a/nuttx/drivers/wireless/cc3000/socket.c b/nuttx/drivers/wireless/cc3000/socket.c
index 122687a58..e15cf500d 100644
--- a/nuttx/drivers/wireless/cc3000/socket.c
+++ b/nuttx/drivers/wireless/cc3000/socket.c
@@ -101,7 +101,7 @@ static const int bsd2ti_types[] =
/*****************************************************************************
* Name: socket
*
- * Decription:
+ * Description:
* 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.
@@ -131,20 +131,22 @@ int cc3000_socket(int domain, int type, int protocol)
return -1;
}
- switch(domain)
+ switch (domain)
{
case AF_INET:
domain = CC3000_AF_INET;
break;
+
case AF_INET6:
domain = CC3000_AF_INET6;
break;
+
default:
errno = EAFNOSUPPORT;
return -1;
}
- switch(protocol)
+ switch (protocol)
{
case CC3000_IPPROTO_IP:
case CC3000_IPPROTO_ICMP:
@@ -152,6 +154,7 @@ int cc3000_socket(int domain, int type, int protocol)
case CC3000_IPPROTO_UDP:
case CC3000_IPPROTO_IPV6:
case CC3000_IPPROTO_NONE:
+ case CC3000_IPPROTO_TX_TEST_RAW:
case CC3000_IPPROTO_RAW:
case CC3000_IPPROTO_MAX:
break;
@@ -174,7 +177,7 @@ int cc3000_socket(int domain, int type, int protocol)
/*****************************************************************************
* Name: closesocket
*
- * Decription:
+ * Description:
* The socket function closes a created socket.
*
* Input Parameters:
@@ -204,7 +207,7 @@ int cc3000_closesocket(int sockfd)
/*****************************************************************************
* Name: accept, cc3000_do_accept
*
- * Decription:
+ * Description:
* 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
@@ -259,7 +262,7 @@ int cc3000_do_accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
int cc3000_accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
#ifdef CONFIG_CC3000_MT
{
- short non_blocking=CC3000_SOCK_ON;
+ short non_blocking = CC3000_SOCK_ON;
if (setsockopt(sockfd, CC3000_SOL_SOCKET, CC3000_SOCKOPT_ACCEPT_NONBLOCK,
&non_blocking, sizeof(non_blocking)) < 0)
{
@@ -273,7 +276,7 @@ int cc3000_accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
#else
{
cc3000_accept_socket(sockfd,0);
- short nonBlocking=CC3000_SOCK_OFF;
+ short nonBlocking = CC3000_SOCK_OFF;
if (setsockopt(sockfd, CC3000_SOL_SOCKET, CC3000_SOCKOPT_ACCEPT_NONBLOCK,
&nonBlocking, sizeof(nonBlocking)) < 0)
@@ -289,7 +292,7 @@ int cc3000_accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
/*****************************************************************************
* Name: bind
*
- * Decription:
+ * Description:
* 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
@@ -322,7 +325,7 @@ int cc3000_bind(int sockfd, FAR const struct sockaddr *addr, socklen_t addrlen)
/*****************************************************************************
* Name: listen
*
- * Decription:
+ * Description:
* listen for connections on a socket
* The willingness to accept incoming connections and a queue
* limit for incoming connections are specified with listen(),
@@ -356,7 +359,7 @@ int cc3000_listen(int sockfd, int backlog)
/*****************************************************************************
* Name: connect
*
- * Decription:
+ * Description:
* 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
@@ -396,7 +399,7 @@ int cc3000_connect(int sockfd, FAR const struct sockaddr *addr, socklen_t addrle
/*****************************************************************************
* Name: select
*
- * Decription:
+ * Description:
* Monitor socket activity
* Select allow a program to monitor multiple file descriptors,
* waiting until one or more of the file descriptors become
@@ -439,8 +442,8 @@ int cc3000_select(int nfds, fd_set *readfds, fd_set *writefds,fd_set *exceptfds,
cc3000_lib_lock();
ret = cc3000_select_impl(nfds, (TICC3000fd_set *)readfds,
- (TICC3000fd_set *)writefds,
- (TICC3000fd_set *)exceptfds, timeout);
+ (TICC3000fd_set *)writefds,
+ (TICC3000fd_set *)exceptfds, timeout);
cc3000_lib_unlock();
return ret;
}
@@ -449,7 +452,7 @@ int cc3000_select(int nfds, fd_set *readfds, fd_set *writefds,fd_set *exceptfds,
/*****************************************************************************
* Name: setsockopt
*
- * Decription:
+ * Description:
* set socket options
* This function manipulate the options associated with a socket.
* Options may exist at multiple protocol levels; they are always
@@ -509,7 +512,7 @@ int cc3000_setsockopt(int sockfd, int level, int option,
/*****************************************************************************
* Name: getsockopt
*
- * Decription:
+ * Description:
* set socket options
* This function manipulate the options associated with a socket.
* Options may exist at multiple protocol levels; they are always
@@ -568,7 +571,7 @@ int cc3000_getsockopt(int sockfd, int level, int option, FAR void *value,
/*****************************************************************************
* Name: recv
*
- * Decription:
+ * Description:
* function receives a message from a connection-mode socket
*
* NOTE: On this version, only blocking mode is supported.
@@ -595,7 +598,13 @@ ssize_t cc3000_recv(int sockfd, FAR void *buf, size_t len, int flags)
waitlldbg("wait\n");
ret = cc3000_wait_data(sockfd);
waitlldbg("wait %d\n", ret);
- if (ret != OK )
+
+ if (ret == -ECONNABORTED)
+ {
+ return 0;
+ }
+
+ if (ret != OK)
{
return -1;
}
@@ -612,7 +621,7 @@ ssize_t cc3000_recv(int sockfd, FAR void *buf, size_t len, int flags)
/*****************************************************************************
* Name: recvfrom
*
- * Decription:
+ * Description:
* read data from socket
* function receives a message from a connection-mode or
* connectionless-mode socket. Note that raw sockets are not
@@ -645,7 +654,12 @@ ssize_t cc3000_recvfrom(int sockfd, FAR void *buf, size_t len, int flags,
#ifdef CONFIG_CC3000_MT
ret = cc3000_wait_data(sockfd);
- if (ret != OK )
+ if (ret == -ECONNABORTED)
+ {
+ return 0;
+ }
+
+ if (ret != OK)
{
return -1;
}
@@ -660,7 +674,7 @@ ssize_t cc3000_recvfrom(int sockfd, FAR void *buf, size_t len, int flags,
/*****************************************************************************
* Name: send
*
- * Decription:
+ * Description:
* Write data to TCP socket
* This function is used to transmit a message to another
* socket.
@@ -692,7 +706,7 @@ ssize_t cc3000_send(int sockfd, FAR const void *buf, size_t len, int flags)
/*****************************************************************************
* Name: sendto
*
- * Decription:
+ * Description:
* Write data to TCP socket
* This function is used to transmit a message to another
* socket.
@@ -729,7 +743,7 @@ ssize_t cc3000_sendto(int sockfd, FAR const void *buf, size_t len, int flags,
/*****************************************************************************
* Name: gethostbyname
*
- * Decription:
+ * Description:
* Get host IP by name. Obtain the IP Address of machine on network,
* by its name.
*
@@ -765,7 +779,7 @@ int cc3000_gethostbyname(char * hostname, uint16_t usNameLen, unsigned long* out
/*****************************************************************************
* Name: mdnsAdvertiser
*
- * Decription:
+ * Description:
* Set CC3000 in mDNS advertiser mode in order to advertise itself.
*
* Input Parameters:
diff --git a/nuttx/drivers/wireless/cc3000/wlan.c b/nuttx/drivers/wireless/cc3000/wlan.c
index dd41b67a4..0036d34ea 100644
--- a/nuttx/drivers/wireless/cc3000/wlan.c
+++ b/nuttx/drivers/wireless/cc3000/wlan.c
@@ -142,8 +142,13 @@ 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));
+ if (usPatchesAvailableAtHost <= SL_PATCHES_REQUEST_DEFAULT ||
+ usPatchesAvailableAtHost > SL_PATCHES_REQUEST_FORCE_NONE)
+ {
+ usPatchesAvailableAtHost = SL_PATCHES_REQUEST_DEFAULT;
+ }
+
+ UINT8_TO_STREAM(args, usPatchesAvailableAtHost);
/* IRQ Line asserted - send HCI_CMND_SIMPLE_LINK_START to CC3000 */
@@ -196,6 +201,8 @@ void wlan_init(size_t max_tx_len,
tDriverPatches sDriverPatches,
tBootLoaderPatches sBootLoaderPatches)
{
+ void *old = NULL;
+
cc3000_lib_lock();
tSLInformation.sFWPatches = sFWPatches;
tSLInformation.sDriverPatches = sDriverPatches;
@@ -203,11 +210,15 @@ void wlan_init(size_t max_tx_len,
/* Allocate the memory for the RX/TX data transactions */
+ if (tSLInformation.pucTxCommandBuffer != NULL)
+ {
+ old = tSLInformation.pucTxCommandBuffer;
+ }
+
tSLInformation.pucTxCommandBuffer = malloc(max_tx_len);
tSLInformation.usrBuffer.pbuffer = &tSLInformation.pucTxCommandBuffer[MAX_HCI_CMD_LENGTH];
tSLInformation.usrBuffer.len = max_tx_len - MAX_HCI_CMD_LENGTH;
-
/* Init I/O callback */
/* Init asynchronous events callback */
@@ -217,6 +228,11 @@ void wlan_init(size_t max_tx_len,
tSLInformation.InformHostOnTxComplete = 1;
cc3000_lib_unlock();
+
+ if (old)
+ {
+ free(old);
+ }
}
/*****************************************************************************