summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/accept.c28
-rw-r--r--nuttx/net/connect.c16
-rw-r--r--nuttx/net/net_clone.c8
-rw-r--r--nuttx/net/net_close.c10
-rw-r--r--nuttx/net/net_poll.c16
-rw-r--r--nuttx/net/net_sockets.c12
-rw-r--r--nuttx/net/net_vfcntl.c6
-rw-r--r--nuttx/net/netdev_register.c2
-rw-r--r--nuttx/net/recvfrom.c32
-rw-r--r--nuttx/net/send.c16
-rw-r--r--nuttx/net/sendto.c16
-rw-r--r--nuttx/net/setsockopt.c7
-rw-r--r--nuttx/net/uip/Make.defs6
-rw-r--r--nuttx/net/uip/uip_callback.c18
-rw-r--r--nuttx/net/uip/uip_icmpping.c14
-rwxr-xr-xnuttx/net/uip/uip_igmpgroup.c20
-rwxr-xr-xnuttx/net/uip/uip_igmpleave.c8
-rwxr-xr-xnuttx/net/uip/uip_igmpmsg.c20
-rwxr-xr-xnuttx/net/uip/uip_igmptimer.c10
-rw-r--r--nuttx/net/uip/uip_initialize.c6
-rw-r--r--nuttx/net/uip/uip_listen.c14
-rw-r--r--nuttx/net/uip/uip_lock.c219
-rw-r--r--nuttx/net/uip/uip_tcpbacklog.c8
-rw-r--r--nuttx/net/uip/uip_tcpconn.c30
-rw-r--r--nuttx/net/uip/uip_udpconn.c24
25 files changed, 398 insertions, 168 deletions
diff --git a/nuttx/net/accept.c b/nuttx/net/accept.c
index ec6f40706..27e5d2b0a 100644
--- a/nuttx/net/accept.c
+++ b/nuttx/net/accept.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/accept.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -262,7 +262,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
#else
FAR struct sockaddr_in *inaddr = (struct sockaddr_in *)addr;
#endif
- irqstate_t save;
+ uip_lock_t save;
int newfd;
int err;
int ret;
@@ -344,7 +344,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
* for this listener.
*/
- save = irqsave();
+ save = uip_lock();
conn = (struct uip_conn *)psock->s_conn;
#ifdef CONFIG_NET_TCPBACKLOG
@@ -366,7 +366,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
else if (_SS_ISNONBLOCK(psock->s_flags))
{
err = EAGAIN;
- goto errout_with_irq;
+ goto errout_with_lock;
}
else
#endif
@@ -393,12 +393,12 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
conn->accept = accept_interrupt;
/* Wait for the send to complete or an error to occur: NOTES: (1)
- * sem_wait will also terminate if a signal is received, (2) interrupts
- * are disabled! They will be re-enabled while the task sleeps and
+ * uip_lockedwait will also terminate if a signal is received, (2) interrupts
+ * may be disabled! They will be re-enabled while the task sleeps and
* automatically re-enabled when the task restarts.
*/
- ret = sem_wait(&state.acpt_sem);
+ ret = uip_lockedwait(&state.acpt_sem);
/* Make sure that no further interrupts are processed */
@@ -418,20 +418,20 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
if (state.acpt_result != 0)
{
err = state.acpt_result;
- goto errout_with_irq;
+ goto errout_with_lock;
}
- /* If sem_wait failed, then we were probably reawakened by a signal. In
- * this case, sem_wait will have set errno appropriately.
+ /* If uip_lockedwait failed, then we were probably reawakened by a signal. In
+ * this case, uip_lockedwait will have set errno appropriately.
*/
if (ret < 0)
{
err = -ret;
- goto errout_with_irq;
+ goto errout_with_lock;
}
}
- irqrestore(save);
+ uip_unlock(save);
/* Initialize the socket structure and mark the socket as connected.
* (The reference count on the new connection structure was set in the
@@ -443,8 +443,8 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
pnewsock->s_flags |= _SF_CONNECTED;
return newfd;
-errout_with_irq:
- irqrestore(save);
+errout_with_lock:
+ uip_unlock(save);
errout_with_socket:
sockfd_release(newfd);
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index 6a5c2a8a2..ae4518ad0 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/connect.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -325,7 +325,7 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
#endif
{
struct tcp_connect_s state;
- irqstate_t flags;
+ uip_lock_t flags;
int ret = OK;
/* Interrupts must be disabled through all of the following because
@@ -333,7 +333,7 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
* setup.
*/
- flags = irqsave();
+ flags = uip_lock();
/* Get the connection reference from the socket */
@@ -356,19 +356,19 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
if (ret >= 0)
{
/* Wait for either the connect to complete or for an error/timeout
- * to occur. NOTES: (1) sem_wait will also terminate if a signal
- * is received, (2) interrupts are disabled! They will be re-
+ * to occur. NOTES: (1) uip_lockedwait will also terminate if a signal
+ * is received, (2) interrupts may be disabled! They will be re-
* enabled while the task sleeps and automatically re-disabled
* when the task restarts.
*/
- ret = sem_wait(&state.tc_sem);
+ ret = uip_lockedwait(&state.tc_sem);
/* Uninitialize the state structure */
(void)sem_destroy(&state.tc_sem);
- /* If sem_wait failed, recover the negated error (probably -EINTR) */
+ /* If uip_lockedwait failed, recover the negated error (probably -EINTR) */
if (ret < 0)
{
@@ -401,7 +401,7 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
}
}
- irqrestore(flags);
+ uip_unlock(flags);
return ret;
}
#endif /* CONFIG_NET_TCP */
diff --git a/nuttx/net/net_clone.c b/nuttx/net/net_clone.c
index 542f59050..8100e63d2 100644
--- a/nuttx/net/net_clone.c
+++ b/nuttx/net/net_clone.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/net_clone.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -62,12 +62,12 @@
int net_clone(FAR struct socket *psock1, FAR struct socket *psock2)
{
- irqstate_t flags;
+ uip_lock_t flags;
int ret = OK;
/* Parts of this operation need to be atomic */
- flags = irqsave();
+ flags = uip_lock();
/* Duplicate the socket state */
@@ -110,7 +110,7 @@ int net_clone(FAR struct socket *psock1, FAR struct socket *psock2)
ret = -EBADF;
}
- irqrestore(flags);
+ uip_unlock(flags);
return ret;
}
diff --git a/nuttx/net/net_close.c b/nuttx/net/net_close.c
index 50421cb55..ca2e2999c 100644
--- a/nuttx/net/net_close.c
+++ b/nuttx/net/net_close.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/net_close.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -146,11 +146,11 @@ static uint16_t netclose_interrupt(struct uip_driver_s *dev, void *pvconn,
static inline void netclose_disconnect(FAR struct socket *psock)
{
struct tcp_close_s state;
- irqstate_t flags;
+ uip_lock_t flags;
/* Interrupts are disabled here to avoid race conditions */
- flags = irqsave();
+ flags = uip_lock();
/* Is the TCP socket in a connected state? */
@@ -180,7 +180,7 @@ static inline void netclose_disconnect(FAR struct socket *psock)
/* Wait for the disconnect event */
- (void)sem_wait(&state.cl_sem);
+ (void)uip_lockedwait(&state.cl_sem);
/* We are now disconnected */
@@ -190,7 +190,7 @@ static inline void netclose_disconnect(FAR struct socket *psock)
}
}
- irqrestore(flags);
+ uip_unlock(flags);
}
#endif
diff --git a/nuttx/net/net_poll.c b/nuttx/net/net_poll.c
index 7f24a1b7f..fa63c8d45 100644
--- a/nuttx/net/net_poll.c
+++ b/nuttx/net/net_poll.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/net_poll.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -166,7 +166,7 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
{
FAR struct uip_conn *conn = psock->s_conn;
FAR struct uip_callback_s *cb;
- irqstate_t flags;
+ uip_lock_t flags;
int ret;
/* Sanity check */
@@ -180,7 +180,7 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
/* Some of the following must be atomic */
- flags = irqsave();
+ flags = uip_lock();
/* Allocate a TCP/IP callback structure */
@@ -219,11 +219,11 @@ static inline int net_pollsetup(FAR struct socket *psock, struct pollfd *fds)
sem_post(fds->sem);
}
}
- irqrestore(flags);
+ uip_unlock(flags);
return OK;
errout_with_irq:
- irqrestore(flags);
+ uip_unlock(flags);
return ret;
}
#endif /* HAVE_NETPOLL */
@@ -247,7 +247,7 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds)
{
FAR struct uip_conn *conn = psock->s_conn;
FAR struct uip_callback_s *cb;
- irqstate_t flags;
+ uip_lock_t flags;
/* Sanity check */
@@ -265,9 +265,9 @@ static inline int net_pollteardown(FAR struct socket *psock, struct pollfd *fds)
{
/* Release the callback */
- flags = irqsave();
+ flags = uip_lock();
uip_tcpcallbackfree(conn, cb);
- irqrestore(flags);
+ uip_unlock(flags);
/* Release the poll/select data slot */
diff --git a/nuttx/net/net_sockets.c b/nuttx/net/net_sockets.c
index 6e54c8719..dce8aa1f0 100644
--- a/nuttx/net/net_sockets.c
+++ b/nuttx/net/net_sockets.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/net_sockets.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -78,7 +78,7 @@ static void _net_semtake(FAR struct socketlist *list)
{
/* Take the semaphore (perhaps waiting) */
- while (sem_wait(&list->sl_sem) != 0)
+ while (uip_lockedwait(&list->sl_sem) != 0)
{
/* The only case that an error should occr here is if
* the wait was awakened by a signal.
@@ -149,9 +149,9 @@ int net_addreflist(FAR struct socketlist *list)
* on semaphores.
*/
- register irqstate_t flags = irqsave();
+ register uip_lock_t flags = uip_lock();
list->sl_crefs++;
- irqrestore(flags);
+ uip_unlock(flags);
}
return OK;
}
@@ -173,9 +173,9 @@ int net_releaselist(FAR struct socketlist *list)
* on semaphores.
*/
- irqstate_t flags = irqsave();
+ uip_lock_t flags = uip_lock();
crefs = --(list->sl_crefs);
- irqrestore(flags);
+ uip_unlock(flags);
/* If the count decrements to zero, then there is no reference
* to the structure and it should be deallocated. Since there
diff --git a/nuttx/net/net_vfcntl.c b/nuttx/net/net_vfcntl.c
index 3ea710425..e1f84a419 100644
--- a/nuttx/net/net_vfcntl.c
+++ b/nuttx/net/net_vfcntl.c
@@ -62,7 +62,7 @@
int net_vfcntl(int sockfd, int cmd, va_list ap)
{
FAR struct socket *psock = sockfd_socket(sockfd);
- irqstate_t flags;
+ uip_lock_t flags;
int err = 0;
int ret = 0;
@@ -76,7 +76,7 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
/* Interrupts must be disabled in order to perform operations on socket structures */
- flags = irqsave();
+ flags = uip_lock();
switch (cmd)
{
case F_DUPFD:
@@ -219,7 +219,7 @@ int net_vfcntl(int sockfd, int cmd, va_list ap)
break;
}
- irqrestore(flags);
+ uip_unlock(flags);
errout:
if (err != 0)
diff --git a/nuttx/net/netdev_register.c b/nuttx/net/netdev_register.c
index d9387c796..fd5656cfc 100644
--- a/nuttx/net/netdev_register.c
+++ b/nuttx/net/netdev_register.c
@@ -102,7 +102,7 @@ void netdev_semtake(void)
{
/* Take the semaphore (perhaps waiting) */
- while (sem_wait(&g_netdev_sem) != 0)
+ while (uip_lockedwait(&g_netdev_sem) != 0)
{
/* The only case that an error should occr here is if
* the wait was awakened by a signal.
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 17e5b2775..c35937cce 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/recvfrom.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -691,7 +691,7 @@ static void recvfrom_init(FAR struct socket *psock, FAR void *buf, size_t len,
* Evaluate the result of the recv operations
*
* Parameters:
- * result The result of the sem_wait operation (may indicate EINTR)
+ * result The result of the uip_lockedwait operation (may indicate EINTR)
* pstate A pointer to the state structure to be initialized
*
* Returned Value:
@@ -721,8 +721,8 @@ static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate)
return pstate->rf_result;
}
- /* If sem_wait failed, then we were probably reawakened by a signal. In
- * this case, sem_wait will have set errno appropriately.
+ /* If uip_lockedwait failed, then we were probably reawakened by a signal. In
+ * this case, uip_lockedwait will have set errno appropriately.
*/
if (result < 0)
@@ -765,7 +765,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
{
struct uip_udp_conn *conn = (struct uip_udp_conn *)psock->s_conn;
struct recvfrom_s state;
- irqstate_t save;
+ uip_lock_t save;
int ret;
/* Perform the UDP recvfrom() operation */
@@ -775,7 +775,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
* are ready.
*/
- save = irqsave();
+ save = uip_lock();
recvfrom_init(psock, buf, len, infrom, &state);
/* Setup the UDP remote connection */
@@ -783,7 +783,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
ret = uip_udpconnect(conn, NULL);
if (ret < 0)
{
- irqrestore(save);
+ uip_unlock(save);
return ret;
}
@@ -803,18 +803,18 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
uip_udpenable(conn);
/* Wait for either the receive to complete or for an error/timeout to occur.
- * NOTES: (1) sem_wait will also terminate if a signal is received, (2)
+ * NOTES: (1) uip_lockedwait will also terminate if a signal is received, (2)
* interrupts are disabled! They will be re-enabled while the task sleeps
* and automatically re-enabled when the task restarts.
*/
- ret = sem_wait(&state. rf_sem);
+ ret = uip_lockedwait(&state. rf_sem);
/* Make sure that no further interrupts are processed */
uip_udpdisable(conn);
uip_udpcallbackfree(conn, state.rf_cb);
- irqrestore(save);
+ uip_unlock(save);
ret = recvfrom_result(ret, &state);
}
else
@@ -856,7 +856,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
#endif
{
struct recvfrom_s state;
- irqstate_t save;
+ uip_lock_t save;
int ret = OK;
/* Verify that the SOCK_STREAM has been connected */
@@ -873,7 +873,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
* are ready.
*/
- save = irqsave();
+ save = uip_lock();
recvfrom_init(psock, buf, len, infrom, &state);
#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
@@ -925,12 +925,12 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
state.rf_cb->event = recvfrom_tcpinterrupt;
/* Wait for either the receive to complete or for an error/timeout to occur.
- * NOTES: (1) sem_wait will also terminate if a signal is received, (2)
- * interrupts are disabled! They will be re-enabled while the task sleeps
+ * NOTES: (1) uip_lockedwait will also terminate if a signal is received, (2)
+ * interrupts may be disabled! They will be re-enabled while the task sleeps
* and automatically re-enabled when the task restarts.
*/
- ret = sem_wait(&state.rf_sem);
+ ret = uip_lockedwait(&state.rf_sem);
/* Make sure that no further interrupts are processed */
@@ -943,7 +943,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
}
}
- irqrestore(save);
+ uip_unlock(save);
return ret;
}
#endif /* CONFIG_NET_TCP */
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index 475344c03..b1583f5b3 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -405,7 +405,7 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
{
FAR struct socket *psock = sockfd_socket(sockfd);
struct send_s state;
- irqstate_t save;
+ uip_lock_t save;
int err;
int ret = OK;
@@ -436,7 +436,7 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
* are ready.
*/
- save = irqsave();
+ save = uip_lock();
memset(&state, 0, sizeof(struct send_s));
(void)sem_init(&state. snd_sem, 0, 0); /* Doesn't really fail */
state.snd_sock = psock; /* Socket descriptor to use */
@@ -478,12 +478,12 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
netdev_txnotify(&conn->ripaddr);
/* Wait for the send to complete or an error to occur: NOTES: (1)
- * sem_wait will also terminate if a signal is received, (2) interrupts
- * are disabled! They will be re-enabled while the task sleeps and
+ * uip_lockedwait will also terminate if a signal is received, (2) interrupts
+ * may be disabled! They will be re-enabled while the task sleeps and
* automatically re-enabled when the task restarts.
*/
- ret = sem_wait(&state. snd_sem);
+ ret = uip_lockedwait(&state. snd_sem);
/* Make sure that no further interrupts are processed */
@@ -492,7 +492,7 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
}
sem_destroy(&state. snd_sem);
- irqrestore(save);
+ uip_unlock(save);
/* Set the socket state to idle */
@@ -508,8 +508,8 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
goto errout;
}
- /* If sem_wait failed, then we were probably reawakened by a signal. In
- * this case, sem_wait will have set errno appropriately.
+ /* If uip_lockedwait failed, then we were probably reawakened by a signal. In
+ * this case, uip_lockedwait will have set errno appropriately.
*/
if (ret < 0)
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
index 89f478810..8e2bf29b2 100644
--- a/nuttx/net/sendto.c
+++ b/nuttx/net/sendto.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/sendto.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -233,7 +233,7 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
FAR const struct sockaddr_in *into = (const struct sockaddr_in *)to;
#endif
struct sendto_s state;
- irqstate_t save;
+ uip_lock_t save;
int ret;
#endif
int err;
@@ -294,7 +294,7 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
* are ready.
*/
- save = irqsave();
+ save = uip_lock();
memset(&state, 0, sizeof(struct sendto_s));
sem_init(&state.st_sem, 0, 0);
state.st_buflen = len;
@@ -306,7 +306,7 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
ret = uip_udpconnect(conn, into);
if (ret < 0)
{
- irqrestore(save);
+ uip_unlock(save);
err = -ret;
goto errout;
}
@@ -329,19 +329,19 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
netdev_txnotify(&conn->ripaddr);
/* Wait for either the receive to complete or for an error/timeout to occur.
- * NOTES: (1) sem_wait will also terminate if a signal is received, (2)
- * interrupts are disabled! They will be re-enabled while the task sleeps
+ * NOTES: (1) uip_lockedwait will also terminate if a signal is received, (2)
+ * interrupts may be disabled! They will be re-enabled while the task sleeps
* and automatically re-enabled when the task restarts.
*/
- sem_wait(&state.st_sem);
+ uip_lockedwait(&state.st_sem);
/* Make sure that no further interrupts are processed */
uip_udpdisable(conn);
uip_udpcallbackfree(conn, state.st_cb);
}
- irqrestore(save);
+ uip_unlock(save);
sem_destroy(&state.st_sem);
diff --git a/nuttx/net/setsockopt.c b/nuttx/net/setsockopt.c
index 41fe2e3c3..f8de93cff 100644
--- a/nuttx/net/setsockopt.c
+++ b/nuttx/net/setsockopt.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/setsockopt.c
*
- * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -103,7 +103,7 @@
int setsockopt(int sockfd, int level, int option, const void *value, socklen_t value_len)
{
FAR struct socket *psock;
- irqstate_t flags;
+ uip_lock_t flags;
int err;
/* Get the underlying socket structure */
@@ -160,7 +160,7 @@ int setsockopt(int sockfd, int level, int option, const void *value, socklen_t v
* level access to options.
*/
- flags = irqsave();
+ flags = uip_lock();
/* Set or clear the option bit */
@@ -172,6 +172,7 @@ int setsockopt(int sockfd, int level, int option, const void *value, socklen_t v
{
_SO_CLROPT(psock->s_options, option);
}
+ uip_unlock(flags);
}
break;
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index c544765ac..8bd8d1839 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -43,6 +43,12 @@ ifeq ($(CONFIG_NET),y)
UIP_CSRCS += uip_initialize.c uip_setipid.c uip_input.c uip_send.c \
uip_poll.c uip_chksum.c uip_callback.c
+# Non-interrupt level support required?
+
+ifeq ($(CONFIG_NET_NOINTS),y)
+UIP_CSRCS += uip_lock.c
+endif
+
# ARP supported is not provided for SLIP (Ethernet only)
ifneq ($(CONFIG_NET_SLIP),y)
diff --git a/nuttx/net/uip/uip_callback.c b/nuttx/net/uip/uip_callback.c
index ad8a704b1..1270fd567 100644
--- a/nuttx/net/uip/uip_callback.c
+++ b/nuttx/net/uip/uip_callback.c
@@ -104,11 +104,11 @@ void uip_callbackinit(void)
FAR struct uip_callback_s *uip_callbackalloc(FAR struct uip_callback_s **list)
{
struct uip_callback_s *ret;
- irqstate_t save;
+ uip_lock_t save;
/* Check the head of the free list */
- save = irqsave();
+ save = uip_lock();
ret = g_cbfreelist;
if (ret)
{
@@ -136,7 +136,7 @@ FAR struct uip_callback_s *uip_callbackalloc(FAR struct uip_callback_s **list)
}
#endif
- irqrestore(save);
+ uip_unlock(save);
return ret;
}
@@ -157,13 +157,13 @@ void uip_callbackfree(FAR struct uip_callback_s *cb, FAR struct uip_callback_s *
{
FAR struct uip_callback_s *prev;
FAR struct uip_callback_s *curr;
- irqstate_t save;
+ uip_lock_t save;
if (cb)
{
/* Find the callback structure in the connection's list */
- save = irqsave();
+ save = uip_lock();
if (list)
{
for (prev = NULL, curr = *list;
@@ -189,7 +189,7 @@ void uip_callbackfree(FAR struct uip_callback_s *cb, FAR struct uip_callback_s *
cb->flink = g_cbfreelist;
g_cbfreelist = cb;
- irqrestore(save);
+ uip_unlock(save);
}
}
@@ -210,13 +210,13 @@ uint16_t uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
uint16_t flags, FAR struct uip_callback_s *list)
{
FAR struct uip_callback_s *next;
- irqstate_t save;
+ uip_lock_t save;
/* Loop for each callback in the list and while there are still events
* set in the flags set.
*/
- save = irqsave();
+ save = uip_lock();
while (list && flags)
{
/* Save the pointer to the next callback in the lists. This is done
@@ -244,7 +244,7 @@ uint16_t uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
list = next;
}
- irqrestore(save);
+ uip_unlock(save);
return flags;
}
diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c
index b83b8b106..0799d1412 100644
--- a/nuttx/net/uip/uip_icmpping.c
+++ b/nuttx/net/uip/uip_icmpping.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_icmpping.c
*
- * Copyright (C) 2008-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -315,7 +315,7 @@ int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno,
uint16_t datalen, int dsecs)
{
struct icmp_ping_s state;
- irqstate_t save;
+ uip_lock_t save;
/* Initialize the state structure */
@@ -328,7 +328,7 @@ int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno,
state.png_datlen = datalen; /* The length of data to send in the ECHO request */
state.png_sent = false; /* ECHO request not yet sent */
- save = irqsave();
+ save = uip_lock();
state.png_time = g_system_timer;
/* Set up the callback */
@@ -346,18 +346,18 @@ int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno,
netdev_txnotify(&state.png_addr);
/* Wait for either the full round trip transfer to complete or
- * for timeout to occur. (1) sem_wait will also terminate if a
- * signal is received, (2) interrupts are disabled! They will
+ * for timeout to occur. (1) uip_lockedwait will also terminate if a
+ * signal is received, (2) interrupts may be disabled! They will
* be re-enabled while the task sleeps and automatically
* re-enabled when the task restarts.
*/
nlldbg("Start time: 0x%08x seqno: %d\n", state.png_time, seqno);
- sem_wait(&state.png_sem);
+ uip_lockedwait(&state.png_sem);
uip_icmpcallbackfree(state.png_cb);
}
- irqrestore(save);
+ uip_unlock(save);
/* Return the negated error number in the event of a failure, or the
* sequence number of the ECHO reply on success.
diff --git a/nuttx/net/uip/uip_igmpgroup.c b/nuttx/net/uip/uip_igmpgroup.c
index af1ecd93e..076e990f9 100755
--- a/nuttx/net/uip/uip_igmpgroup.c
+++ b/nuttx/net/uip/uip_igmpgroup.c
@@ -219,7 +219,7 @@ FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
FAR const uip_ipaddr_t *addr)
{
FAR struct igmp_group_s *group;
- irqstate_t flags;
+ uip_lock_t flags;
nllvdbg("addr: %08x dev: %p\n", *addr, dev);
if (up_interrupt_context())
@@ -255,12 +255,12 @@ FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
/* Interrupts must be disabled in order to modify the group list */
- flags = irqsave();
+ flags = uip_lock();
/* Add the group structure to the list in the device structure */
sq_addfirst((FAR sq_entry_t*)group, &dev->grplist);
- irqrestore(flags);
+ uip_unlock(flags);
}
return group;
}
@@ -280,7 +280,7 @@ FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
FAR const uip_ipaddr_t *addr)
{
FAR struct igmp_group_s *group;
- irqstate_t flags;
+ uip_lock_t flags;
grplldbg("Searching for addr %08x\n", (int)*addr);
@@ -288,7 +288,7 @@ FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
* called from.
*/
- flags = irqsave();
+ flags = uip_lock();
for (group = (FAR struct igmp_group_s *)dev->grplist.head;
group;
group = group->next)
@@ -300,7 +300,7 @@ FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
break;
}
}
- irqrestore(flags);
+ uip_unlock(flags);
return group;
}
@@ -343,13 +343,13 @@ FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev,
void uip_grpfree(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group)
{
- irqstate_t flags;
+ uip_lock_t flags;
grplldbg("Free: %p flags: %02x\n", group, group->flags);
/* Cancel the wdog */
- flags = irqsave();
+ flags = uip_lock();
wd_cancel(group->wdog);
/* Remove the group structure from the group list in the device structure */
@@ -373,7 +373,7 @@ void uip_grpfree(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group)
{
grplldbg("Put back on free list\n");
sq_addlast((FAR sq_entry_t*)group, &g_freelist);
- irqrestore(flags);
+ uip_unlock(flags);
}
else
#endif
@@ -382,7 +382,7 @@ void uip_grpfree(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group)
* this function is executing within an interrupt handler.
*/
- irqrestore(flags);
+ uip_unlock(flags);
grplldbg("Call sched_free()\n");
sched_free(group);
}
diff --git a/nuttx/net/uip/uip_igmpleave.c b/nuttx/net/uip/uip_igmpleave.c
index 23067f70a..bbc25a830 100755
--- a/nuttx/net/uip/uip_igmpleave.c
+++ b/nuttx/net/uip/uip_igmpleave.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_igmpleave.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* The NuttX implementation of IGMP was inspired by the IGMP add-on for the
@@ -130,7 +130,7 @@
int igmp_leavegroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
{
struct igmp_group_s *group;
- irqstate_t flags;
+ uip_lock_t flags;
DEBUGASSERT(dev && grpaddr);
@@ -146,11 +146,11 @@ int igmp_leavegroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
* could interfere with the Leave Group.
*/
- flags = irqsave();
+ flags = uip_lock();
wd_cancel(group->wdog);
CLR_SCHEDMSG(group->flags);
CLR_WAITMSG(group->flags);
- irqrestore(flags);
+ uip_unlock(flags);
IGMP_STATINCR(uip_stat.igmp.leaves);
diff --git a/nuttx/net/uip/uip_igmpmsg.c b/nuttx/net/uip/uip_igmpmsg.c
index d9837d04a..182d7b92d 100755
--- a/nuttx/net/uip/uip_igmpmsg.c
+++ b/nuttx/net/uip/uip_igmpmsg.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_igmpmgs.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* The NuttX implementation of IGMP was inspired by the IGMP add-on for the
@@ -79,15 +79,15 @@
void uip_igmpschedmsg(FAR struct igmp_group_s *group, uint8_t msgid)
{
- irqstate_t flags = irqsave();
+ uip_lock_t flags;
/* The following should be atomic */
- flags = irqsave();
+ flags = uip_lock();
DEBUGASSERT(!IS_SCHEDMSG(group->flags));
group->msgid = msgid;
SET_SCHEDMSG(group->flags);
- irqrestore(flags);
+ uip_unlock(flags);
}
/****************************************************************************
@@ -99,17 +99,17 @@ void uip_igmpschedmsg(FAR struct igmp_group_s *group, uint8_t msgid)
*
* Assumptions:
* This function cannot be called from an interrupt handler (if you try it,
- * sem_wait will assert).
+ * uip_lockedwait will assert).
*
****************************************************************************/
void uip_igmpwaitmsg(FAR struct igmp_group_s *group, uint8_t msgid)
{
- irqstate_t flags;
+ uip_lock_t flags;
/* Schedule to send the message */
- flags = irqsave();
+ flags = uip_lock();
DEBUGASSERT(!IS_WAITMSG(group->flags));
SET_WAITMSG(group->flags);
uip_igmpschedmsg(group, msgid);
@@ -120,9 +120,9 @@ void uip_igmpwaitmsg(FAR struct igmp_group_s *group, uint8_t msgid)
{
/* Wait for the semaphore to be posted */
- while (sem_wait(&group->sem) != 0)
+ while (uip_lockedwait(&group->sem) != 0)
{
- /* The only error that should occur from sem_wait() is if
+ /* The only error that should occur from uip_lockedwait() is if
* the wait is awakened by a signal.
*/
@@ -133,7 +133,7 @@ void uip_igmpwaitmsg(FAR struct igmp_group_s *group, uint8_t msgid)
/* The message has been sent and we are no longer waiting */
CLR_WAITMSG(group->flags);
- irqrestore(flags);
+ uip_unlock(flags);
}
#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmptimer.c b/nuttx/net/uip/uip_igmptimer.c
index 2ae844341..4d454b091 100755
--- a/nuttx/net/uip/uip_igmptimer.c
+++ b/nuttx/net/uip/uip_igmptimer.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_igmptimer.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* The NuttX implementation of IGMP was inspired by the IGMP add-on for the
@@ -220,14 +220,14 @@ void uip_igmpstarttimer(FAR struct igmp_group_s *group, uint8_t decisecs)
bool uip_igmpcmptimer(FAR struct igmp_group_s *group, int maxticks)
{
- irqstate_t flags;
+ uip_lock_t flags;
int remaining;
/* Disable interrupts so that there is no race condition with the actual
* timer expiration.
*/
- flags = irqsave();
+ flags = uip_lock();
/* Get the timer remaining on the watchdog. A time of <= zero means that
* the watchdog was never started.
@@ -246,11 +246,11 @@ bool uip_igmpcmptimer(FAR struct igmp_group_s *group, int maxticks)
/* Cancel the watchdog timer and return true */
wd_cancel(group->wdog);
- irqrestore(flags);
+ uip_unlock(flags);
return true;
}
- irqrestore(flags);
+ uip_unlock(flags);
return false;
}
diff --git a/nuttx/net/uip/uip_initialize.c b/nuttx/net/uip/uip_initialize.c
index 08f9485a7..765a20ecd 100644
--- a/nuttx/net/uip/uip_initialize.c
+++ b/nuttx/net/uip/uip_initialize.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_initialize.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Adapted for NuttX from logic in uIP which also has a BSD-like license:
@@ -115,6 +115,10 @@ uint8_t uip_reasstmr;
void uip_initialize(void)
{
+ /* Initialize the locking facility */
+
+ uip_lockinit();
+
/* Initialize callback support */
uip_callbackinit();
diff --git a/nuttx/net/uip/uip_listen.c b/nuttx/net/uip/uip_listen.c
index a913abc25..8052ca236 100644
--- a/nuttx/net/uip/uip_listen.c
+++ b/nuttx/net/uip/uip_listen.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_listen.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* A direct leverage of logic from uIP which also has b BSD style license
@@ -139,11 +139,11 @@ void uip_listeninit(void)
int uip_unlisten(struct uip_conn *conn)
{
- irqstate_t flags;
+ uip_lock_t flags;
int ndx;
int ret = -EINVAL;
- flags = irqsave();
+ flags = uip_lock();
for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
{
if (uip_listenports[ndx] == conn)
@@ -154,7 +154,7 @@ int uip_unlisten(struct uip_conn *conn)
}
}
- irqrestore(flags);
+ uip_unlock(flags);
return ret;
}
@@ -171,7 +171,7 @@ int uip_unlisten(struct uip_conn *conn)
int uip_listen(struct uip_conn *conn)
{
- irqstate_t flags;
+ uip_lock_t flags;
int ndx;
int ret;
@@ -179,7 +179,7 @@ int uip_listen(struct uip_conn *conn)
* is accessed from interrupt level as well.
*/
- flags = irqsave();
+ flags = uip_lock();
/* First, check if there is already a socket listening on this port */
@@ -214,7 +214,7 @@ int uip_listen(struct uip_conn *conn)
}
}
- irqrestore(flags);
+ uip_unlock(flags);
return ret;
}
diff --git a/nuttx/net/uip/uip_lock.c b/nuttx/net/uip/uip_lock.c
new file mode 100644
index 000000000..f11ae1c0e
--- /dev/null
+++ b/nuttx/net/uip/uip_lock.c
@@ -0,0 +1,219 @@
+/****************************************************************************
+ * net/uip/uip_lock.c
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. 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.
+ * 3. Neither the name NuttX 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <semaphore.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/arch.h>
+#include <net/uip/uip.h>
+
+#if defined(CONFIG_NET) && defined(CONFIG_NET_NOINTS)
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define NO_HOLDER (pid_t)-1
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static sem_t g_uipsem;
+static pid_t g_holder = NO_HOLDER;
+static unsigned int g_count = 0;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_takesem
+ *
+ * Description:
+ * Take the semaphore
+ *
+ ****************************************************************************/
+
+static void uip_takesem(void)
+{
+ while (sem_wait(&g_uipsem) != 0)
+ {
+ /* The only case that an error should occur here is if the wait was
+ * awakened by a signal.
+ */
+
+ ASSERT(errno == EINTR);
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: uip_lockinit
+ *
+ * Description:
+ * Initialize the locking facility
+ *
+ ****************************************************************************/
+
+void uip_lockinit(void)
+{
+ sem_init(&g_uipsem, 0, 1);
+}
+
+/****************************************************************************
+ * Function: uip_lock
+ *
+ * Description:
+ * Take the lock
+ *
+ ****************************************************************************/
+
+uip_lock_t uip_lock(void)
+{
+ pid_t me = getpid();
+
+ /* Does this thread already hold the semaphore? */
+
+ if (g_holder == me)
+ {
+ /* Yes.. just increment the reference count */
+
+ g_count++;
+ }
+ else
+ {
+ /* No.. take the semaphore (perhaps waiting) */
+
+ uip_takesem();
+
+ /* Now this thread holds the semaphore */
+
+ g_holder = me;
+ g_count = 1;
+ }
+
+ return 0;
+}
+
+/****************************************************************************
+ * Function: uip_unlock
+ *
+ * Description:
+ * Release the lock.
+ *
+ ****************************************************************************/
+
+void uip_unlock(uip_lock_t flags)
+{
+ DEBUGASSERT(g_holder == getpid() && g_count > 0);
+
+ /* If the count would go to zero, then release the semaphore */
+
+ if (g_count == 1)
+ {
+ /* We no longer hold the semaphored */
+
+ g_holder = NO_HOLDER;
+ g_count = 0;
+ sem_post(&g_uipsem);
+ }
+ else
+ {
+ /* We still hold the seamphore. Just decrement the count */
+
+ g_count--;
+ }
+}
+
+/****************************************************************************
+ * Function: uip_lockedwait
+ *
+ * Description:
+ * Atomically wait for sem while temporarilty releasing.
+ *
+ ****************************************************************************/
+
+int uip_lockedwait(sem_t *sem)
+{
+ pid_t me = getpid();
+ unsigned int count;
+ irqstate_t flags;
+ int ret;
+
+ flags = irqsave(); /* No interrupts */
+ sched_lock(); /* No context switches */
+ if (g_holder == me)
+ {
+ /* Release the uIP semaphore, remembering the count */
+
+ count = g_count;
+ g_holder = NO_HOLDER;
+ g_count = 0;
+ sem_post(&g_uipsem);
+
+ /* Now take semaphore */
+
+ ret = sem_wait(sem);
+
+ /* Recover the uIP semaphore at the proper count */
+
+ uip_takesem();
+ g_holder = me;
+ g_count = count;
+ }
+ else
+ {
+ ret = sem_wait(sem);
+ }
+
+ sched_unlock();
+ irqrestore(flags);
+ return ret;
+ }
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_tcpbacklog.c b/nuttx/net/uip/uip_tcpbacklog.c
index b3cdba13a..198bbd6b5 100644
--- a/nuttx/net/uip/uip_tcpbacklog.c
+++ b/nuttx/net/uip/uip_tcpbacklog.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_tcpbacklog.c
*
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -79,7 +79,7 @@ int uip_backlogcreate(FAR struct uip_conn *conn, int nblg)
{
FAR struct uip_backlog_s *bls = NULL;
FAR struct uip_blcontainer_s *blc;
- irqstate_t flags;
+ uip_lock_t flags;
int size;
int offset;
int i;
@@ -131,7 +131,7 @@ int uip_backlogcreate(FAR struct uip_conn *conn, int nblg)
/* Destroy any existing backlog (shouldn't be any) */
- flags = irqsave();
+ flags = uip_lock();
uip_backlogdestroy(conn);
/* Now install the backlog tear-off in the connection. NOTE that bls may
@@ -141,7 +141,7 @@ int uip_backlogcreate(FAR struct uip_conn *conn, int nblg)
*/
conn->backlog = bls;
- irqrestore(flags);
+ uip_unlock(flags);
return OK;
}
diff --git a/nuttx/net/uip/uip_tcpconn.c b/nuttx/net/uip/uip_tcpconn.c
index 60eb16bc9..932aad2f7 100644
--- a/nuttx/net/uip/uip_tcpconn.c
+++ b/nuttx/net/uip/uip_tcpconn.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_tcpconn.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Large parts of this file were leveraged from uIP logic:
@@ -208,14 +208,14 @@ void uip_tcpinit(void)
struct uip_conn *uip_tcpalloc(void)
{
struct uip_conn *conn;
- irqstate_t flags;
+ uip_lock_t flags;
/* Because this routine is called from both interrupt level and
* and from user level, we have not option but to disable interrupts
* while accessing g_free_tcp_connections[];
*/
- flags = irqsave();
+ flags = uip_lock();
/* Return the entry from the head of the free list */
@@ -258,7 +258,7 @@ struct uip_conn *uip_tcpalloc(void)
}
#endif
- irqrestore(flags);
+ uip_unlock(flags);
/* Mark the connection allocated */
@@ -284,7 +284,7 @@ void uip_tcpfree(struct uip_conn *conn)
#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
struct uip_readahead_s *readahead;
#endif
- irqstate_t flags;
+ uip_lock_t flags;
/* Because g_free_tcp_connections is accessed from user level and interrupt
* level, code, it is necessary to keep interrupts disabled during this
@@ -292,7 +292,7 @@ void uip_tcpfree(struct uip_conn *conn)
*/
DEBUGASSERT(conn->crefs == 0);
- flags = irqsave();
+ flags = uip_lock();
/* UIP_ALLOCATED means that that the connection is not in the active list
* yet.
@@ -336,7 +336,7 @@ void uip_tcpfree(struct uip_conn *conn)
conn->tcpstateflags = UIP_CLOSED;
dq_addlast(&conn->node, &g_free_tcp_connections);
- irqrestore(flags);
+ uip_unlock(flags);
}
/****************************************************************************
@@ -508,14 +508,14 @@ int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in6 *addr)
int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr)
#endif
{
- irqstate_t flags;
+ uip_lock_t flags;
int port;
/* Verify or select a local port */
- flags = irqsave();
+ flags = uip_lock();
port = uip_selectport(ntohs(addr->sin_port));
- irqrestore(flags);
+ uip_unlock(flags);
if (port < 0)
{
@@ -566,7 +566,7 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in6 *addr)
int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
#endif
{
- irqstate_t flags;
+ uip_lock_t flags;
int port;
/* The connection is expected to be in the UIP_ALLOCATED state.. i.e.,
@@ -583,9 +583,9 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
* one now.
*/
- flags = irqsave();
+ flags = uip_lock();
port = uip_selectport(ntohs(conn->lport));
- irqrestore(flags);
+ uip_unlock(flags);
if (port < 0)
{
@@ -626,9 +626,9 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
* this operation.
*/
- flags = irqsave();
+ flags = uip_lock();
dq_addlast(&conn->node, &g_active_tcp_connections);
- irqrestore(flags);
+ uip_unlock(flags);
return OK;
}
diff --git a/nuttx/net/uip/uip_udpconn.c b/nuttx/net/uip/uip_udpconn.c
index b01d58f43..0180a9c14 100644
--- a/nuttx/net/uip/uip_udpconn.c
+++ b/nuttx/net/uip/uip_udpconn.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip_udpconn.c
*
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Large parts of this file were leveraged from uIP logic:
@@ -99,9 +99,9 @@ static inline void _uip_semtake(sem_t *sem)
{
/* Take the semaphore (perhaps waiting) */
- while (sem_wait(sem) != 0)
+ while (uip_lockedwait(sem) != 0)
{
- /* The only case that an error should occr here is if
+ /* The only case that an error should occur here is if
* the wait was awakened by a signal.
*/
@@ -165,7 +165,7 @@ static uint16_t uip_selectport(void)
* listen port number that is not being used by any other connection.
*/
- irqstate_t flags = irqsave();
+ uip_lock_t flags = uip_lock();
do
{
/* Guess that the next available port number will be the one after
@@ -188,7 +188,7 @@ static uint16_t uip_selectport(void)
*/
portno = g_last_udp_port;
- irqrestore(flags);
+ uip_unlock(flags);
return portno;
}
@@ -367,7 +367,7 @@ int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
#endif
{
int ret = -EADDRINUSE;
- irqstate_t flags;
+ uip_lock_t flags;
/* Is the user requesting to bind to any port? */
@@ -382,7 +382,7 @@ int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
{
/* Interrupts must be disabled while access the UDP connection list */
- flags = irqsave();
+ flags = uip_lock();
/* Is any other UDP connection bound to this port? */
@@ -394,7 +394,7 @@ int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
ret = OK;
}
- irqrestore(flags);
+ uip_unlock(flags);
}
return ret;
}
@@ -471,9 +471,9 @@ void uip_udpenable(struct uip_udp_conn *conn)
* access it safely.
*/
- irqstate_t flags = irqsave();
+ uip_lock_t flags = uip_lock();
dq_addlast(&conn->node, &g_active_udp_connections);
- irqrestore(flags);
+ uip_unlock(flags);
}
void uip_udpdisable(struct uip_udp_conn *conn)
@@ -483,9 +483,9 @@ void uip_udpdisable(struct uip_udp_conn *conn)
* access it safely.
*/
- irqstate_t flags = irqsave();
+ uip_lock_t flags = uip_lock();
dq_rem(&conn->node, &g_active_udp_connections);
- irqrestore(flags);
+ uip_unlock(flags);
}
#endif /* CONFIG_NET && CONFIG_NET_UDP */