summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/accept.c19
-rw-r--r--nuttx/net/bind.c2
-rw-r--r--nuttx/net/uip/uip-initialize.c3
-rw-r--r--nuttx/net/uip/uip-listen.c2
-rw-r--r--nuttx/net/uip/uip-tcpcallback.c1
-rw-r--r--nuttx/net/uip/uip-tcpconn.c80
6 files changed, 72 insertions, 35 deletions
diff --git a/nuttx/net/accept.c b/nuttx/net/accept.c
index 34318190d..02557d6fc 100644
--- a/nuttx/net/accept.c
+++ b/nuttx/net/accept.c
@@ -42,9 +42,12 @@
#include <sys/types.h>
#include <sys/socket.h>
+
#include <semaphore.h>
#include <string.h>
#include <errno.h>
+#include <debug.h>
+
#include <arch/irq.h>
#include "net-internal.h"
@@ -95,6 +98,7 @@ static int accept_interrupt(struct uip_conn *listener, struct uip_conn *conn)
{
struct accept_s *pstate = (struct accept_s *)listener->accept_private;
int ret = -EINVAL;
+
if (pstate)
{
/* Get the connection address */
@@ -112,6 +116,7 @@ static int accept_interrupt(struct uip_conn *listener, struct uip_conn *conn)
listener->accept = NULL;
ret = OK;
}
+
return ret;
}
@@ -265,12 +270,12 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
}
pnewsock = sockfd_socket(newfd);
- if (newfd)
+ if (!pnewsock)
{
err = ENFILE;
goto errout_with_socket;
}
-
+
/* Set the socket state to accepting */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_ACCEPT);
@@ -286,6 +291,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
state.acpt_addr = inaddr;
state.acpt_newconn = NULL;
state.acpt_result = OK;
+ sem_init(&state.acpt_sem, 0, 0);
/* Set up the callback in the connection */
@@ -299,7 +305,7 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
* automatically re-enabled when the task restarts.
*/
- ret = sem_wait(&state. acpt_sem);
+ ret = sem_wait(&state.acpt_sem);
/* Make sure that no further interrupts are processed */
@@ -333,10 +339,11 @@ int accept(int sockfd, struct sockaddr *addr, socklen_t *addrlen)
goto errout_with_socket;
}
- /* Initialize the socket structure */
+ /* Initialize the socket structure and mark the socket as connected */
- pnewsock->s_type = SOCK_STREAM;
- pnewsock->s_conn = state.acpt_newconn;
+ pnewsock->s_type = SOCK_STREAM;
+ pnewsock->s_conn = state.acpt_newconn;
+ pnewsock->s_flags |= _SF_CONNECTED;
return newfd;
errout_with_socket:
diff --git a/nuttx/net/bind.c b/nuttx/net/bind.c
index f1d5dbbd9..f5d36a9f1 100644
--- a/nuttx/net/bind.c
+++ b/nuttx/net/bind.c
@@ -128,7 +128,7 @@ int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
break;
#endif
default:
- err = -EBADF;
+ err = EBADF;
goto errout;
}
diff --git a/nuttx/net/uip/uip-initialize.c b/nuttx/net/uip/uip-initialize.c
index baed0f878..3a7701cbe 100644
--- a/nuttx/net/uip/uip-initialize.c
+++ b/nuttx/net/uip/uip-initialize.c
@@ -1,6 +1,5 @@
/****************************************************************************
- * net/uip/uip-udppoll.c
- * Poll for the availability of UDP TX data
+ * net/uip/uip-initialize.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/net/uip/uip-listen.c b/nuttx/net/uip/uip-listen.c
index f1097c40c..e7ee8ffc3 100644
--- a/nuttx/net/uip/uip-listen.c
+++ b/nuttx/net/uip/uip-listen.c
@@ -45,6 +45,8 @@
#ifdef CONFIG_NET
#include <sys/types.h>
+#include <debug.h>
+
#include <net/uip/uipopt.h>
#include "uip-internal.h"
diff --git a/nuttx/net/uip/uip-tcpcallback.c b/nuttx/net/uip/uip-tcpcallback.c
index 761283bb0..973a2f2a2 100644
--- a/nuttx/net/uip/uip-tcpcallback.c
+++ b/nuttx/net/uip/uip-tcpcallback.c
@@ -115,6 +115,7 @@ uint8 uip_tcpcallback(struct uip_driver_s *dev, struct uip_conn *conn, uint8 fla
dbg("No listener on connection\n");
#ifdef CONFIG_NET_STATISTICS
+ uip_stat.tcp.syndrop++;
uip_stat.tcp.drop++;
#endif
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
index 0dc9f9f25..c0c151570 100644
--- a/nuttx/net/uip/uip-tcpconn.c
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -105,7 +105,12 @@ static uint8 g_tcp_sequence[4];
* selected.
*
* Return:
- * 0 on success, -ERRNO on failure
+ * 0 on success, negated errno on failure:
+ *
+ * EADDRINUSE
+ * The given address is already in use.
+ * EADDRNOTAVAIL
+ * Cannot assign requested address (unlikely)
*
* Assumptions:
* Interrupts are disabled
@@ -117,7 +122,9 @@ static int uip_selectport(uint16 portno)
if (portno == 0)
{
/* No local port assigned. Loop until we find a valid listen port number
- * that is not being used by any other connection.
+ * that is not being used by any other connection. NOTE the following loop
+ * is assumed to terminate but could not if all 32000-4096+1 ports are
+ * in used (unlikely).
*/
do
@@ -134,7 +141,7 @@ static int uip_selectport(uint16 portno)
g_last_tcp_port = 4096;
}
}
- while (uip_tcplistener(g_last_tcp_port));
+ while (uip_tcplistener(htons(g_last_tcp_port)));
}
else
{
@@ -150,7 +157,7 @@ static int uip_selectport(uint16 portno)
}
}
- /* Return the selecte or verified port number */
+ /* Return the selected or verified port number */
return portno;
}
@@ -372,8 +379,8 @@ struct uip_conn *uip_nexttcpconn(struct uip_conn *conn)
* Name: uip_tcplistener()
*
* Description:
- * Given a local port number, find the TCP connection that listens on this
- * this port.
+ * Given a local port number (in network byte order), find the TCP
+ * connection that listens on this this port.
*
* Primary uses: (1) to determine if a port number is available, (2) to
* To idenfity the socket that will accept new connections on a local port.
@@ -390,7 +397,7 @@ struct uip_conn *uip_tcplistener(uint16 portno)
for (i = 0; i < UIP_CONNS; i++)
{
conn = &g_tcp_connections[i];
- if (conn->tcpstateflags != UIP_CLOSED && conn->lport == htons(g_last_tcp_port))
+ if (conn->tcpstateflags != UIP_CLOSED && conn->lport == portno)
{
/* The portnumber is in use, return the connection */
@@ -420,27 +427,34 @@ struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf)
{
/* Fill in the necessary fields for the new connection. */
- conn->rto = conn->timer = UIP_RTO;
- conn->sa = 0;
- conn->sv = 4;
- conn->nrtx = 0;
- conn->lport = buf->destport;
- conn->rport = buf->srcport;
- uip_ipaddr_copy(conn->ripaddr, buf->srcipaddr);
+ conn->rto = UIP_RTO;
+ conn->timer = UIP_RTO;
+ conn->sa = 0;
+ conn->sv = 4;
+ conn->nrtx = 0;
+ conn->lport = buf->destport;
+ conn->rport = buf->srcport;
+ uip_ipaddr_copy(conn->ripaddr, uip_ip4addr_conv(buf->srcipaddr));
conn->tcpstateflags = UIP_SYN_RCVD;
- conn->snd_nxt[0] = g_tcp_sequence[0];
- conn->snd_nxt[1] = g_tcp_sequence[1];
- conn->snd_nxt[2] = g_tcp_sequence[2];
- conn->snd_nxt[3] = g_tcp_sequence[3];
- conn->len = 1;
+ conn->snd_nxt[0] = g_tcp_sequence[0];
+ conn->snd_nxt[1] = g_tcp_sequence[1];
+ conn->snd_nxt[2] = g_tcp_sequence[2];
+ conn->snd_nxt[3] = g_tcp_sequence[3];
+ conn->len = 1;
/* rcv_nxt should be the seqno from the incoming packet + 1. */
- conn->rcv_nxt[3] = buf->seqno[3];
- conn->rcv_nxt[2] = buf->seqno[2];
- conn->rcv_nxt[1] = buf->seqno[1];
- conn->rcv_nxt[0] = buf->seqno[0];
+ conn->rcv_nxt[3] = buf->seqno[3];
+ conn->rcv_nxt[2] = buf->seqno[2];
+ conn->rcv_nxt[1] = buf->seqno[1];
+ conn->rcv_nxt[0] = buf->seqno[0];
+
+ /* And, finally, put the connection structure into the active list.
+ * Interrupts should already be disabled in this context.
+ */
+
+ dq_addlast(&conn->node, &g_active_tcp_connections);
}
return conn;
}
@@ -479,6 +493,9 @@ void uip_tcpnextsequence(void)
* This function implements the UIP specific parts of the standard TCP
* bind() operation.
*
+ * Return:
+ * 0 on success or -EADDRINUSE on failure
+ *
* Assumptions:
* This function is called from normal user level code.
*
@@ -496,7 +513,7 @@ int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr)
/* Verify or select a local port */
flags = irqsave();
- port = uip_selectport(ntohs(conn->lport));
+ port = uip_selectport(ntohs(addr->sin_port));
irqrestore(flags);
if (port < 0)
@@ -504,8 +521,19 @@ int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr)
return port;
}
-#warning "Need to implement bind logic"
- return -ENOSYS;
+ /* Save the local address in the connection structure. Note that the requested
+ * local IP address is saved but not used. At present, only a single network
+ * interface is supported, the IP address is not of importance.
+ */
+
+ conn->lport = addr->sin_port;
+#ifdef CONFIG_NET_IPv6
+ uip_ipaddr_copy(conn->lipaddr, addr->sin6_addr.in6_u.u6_addr16);
+#else
+ uip_ipaddr_copy(conn->lipaddr, addr->sin_addr.s_addr);
+#endif
+
+ return OK;
}
/****************************************************************************