summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-19 22:05:12 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-12-19 22:05:12 +0000
commit9f6ea5af87d527ee2e8b4a125881bcf0741aabad (patch)
treecffda222cfdd6e55ebd5ad9372ea4ef81f5f0e9d /nuttx/net
parent6082f71dcfd8f55b731a32ef27abf441ddee0b3c (diff)
downloadpx4-nuttx-9f6ea5af87d527ee2e8b4a125881bcf0741aabad.tar.gz
px4-nuttx-9f6ea5af87d527ee2e8b4a125881bcf0741aabad.tar.bz2
px4-nuttx-9f6ea5af87d527ee2e8b4a125881bcf0741aabad.zip
Fix an error in the handling of TCP/IP sequence numbers
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2392 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/send.c58
-rw-r--r--nuttx/net/uip/Make.defs2
-rw-r--r--nuttx/net/uip/uip_chksum.c13
-rw-r--r--nuttx/net/uip/uip_internal.h7
-rw-r--r--nuttx/net/uip/uip_tcpconn.c35
-rw-r--r--nuttx/net/uip/uip_tcpinput.c22
-rwxr-xr-xnuttx/net/uip/uip_tcpseqno.c173
7 files changed, 208 insertions, 102 deletions
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index b31723293..edb3d359a 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -88,54 +88,6 @@ struct send_s
****************************************************************************/
/****************************************************************************
- * Function: send_getisn
- *
- * Description:
- * Get the next initial sequence number from the connection stucture
- *
- * Parameters:
- * conn The connection structure associated with the socket
- *
- * Returned Value:
- * None
- *
- * Assumptions:
- * Running at the interrupt level
- *
- ****************************************************************************/
-
-static uint32_t send_getisn(struct uip_conn *conn)
-{
- uint32_t tmp;
- memcpy(&tmp, conn->snd_nxt, 4);
- return ntohl(tmp);
-}
-
-/****************************************************************************
- * Function: send_getackno
- *
- * Description:
- * Extract the current acknowledgement sequence number from the incoming packet
- *
- * Parameters:
- * dev - The sructure of the network driver that caused the interrupt
- *
- * Returned Value:
- * None
- *
- * Assumptions:
- * Running at the interrupt level
- *
- ****************************************************************************/
-
-static uint32_t send_getackno(struct uip_driver_s *dev)
-{
- uint32_t tmp;
- memcpy(&tmp, TCPBUF->ackno, 4);
- return ntohl(tmp);
-}
-
-/****************************************************************************
* Function: send_timeout
*
* Description:
@@ -216,7 +168,7 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
* is the number of bytes to be acknowledged.
*/
- pstate->snd_acked = send_getackno(dev) - pstate->snd_isn;
+ pstate->snd_acked = uip_tcpgetsequence(TCPBUF->ackno) - pstate->snd_isn;
nllvdbg("ACK: acked=%d sent=%d buflen=%d\n",
pstate->snd_acked, pstate->snd_sent, pstate->snd_buflen);
@@ -259,7 +211,7 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
}
/* Check if the outgoing packet is available (it may have been claimed
- * by a sendto interrupt serving a different thread.
+ * by a sendto interrupt serving a different thread).
*/
#if 0 /* We can't really support multiple senders on the same TCP socket */
@@ -289,6 +241,10 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
sndlen = uip_mss(conn);
}
+ /* Set the sequence number for this packet */
+
+ uip_tcpsetsequence(conn->snd_nxt, pstate->snd_sent + pstate->snd_isn);
+
/* Then send that amount of data */
uip_send(dev, &pstate->snd_buffer[pstate->snd_sent], sndlen);
@@ -459,7 +415,7 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
{
/* Get the initial sequence number that will be used */
- state.snd_isn = send_getisn(conn); /* Initial sequence number */
+ state.snd_isn = uip_tcpgetsequence(conn->snd_nxt);
/* Update the initial time for calculating timeouts */
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index e67c73243..ce102ff62 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -51,7 +51,7 @@ endif
ifeq ($(CONFIG_NET_TCP),y)
-UIP_CSRCS += uip_tcpconn.c uip_tcppoll.c uip_tcptimer.c uip_tcpsend.c \
+UIP_CSRCS += uip_tcpconn.c uip_tcpseqno.c uip_tcppoll.c uip_tcptimer.c uip_tcpsend.c \
uip_tcpinput.c uip_tcpappsend.c uip_listen.c uip_tcpcallback.c \
uip_tcpreadahead.c uip_tcpbacklog.c
diff --git a/nuttx/net/uip/uip_chksum.c b/nuttx/net/uip/uip_chksum.c
index b35808e8a..538e56a04 100644
--- a/nuttx/net/uip/uip_chksum.c
+++ b/nuttx/net/uip/uip_chksum.c
@@ -148,7 +148,7 @@ static uint16_t uip_icmp6chksum(struct uip_driver_s *dev)
/* Calculate the Internet checksum over a buffer. */
#if !UIP_ARCH_ADD32
-static void uip_carry32(uint8_t *sum, uint16_t op16)
+static inline void uip_carry32(uint8_t *sum, uint16_t op16)
{
if (sum[2] < (op16 >> 8))
{
@@ -173,17 +173,6 @@ static void uip_carry32(uint8_t *sum, uint16_t op16)
}
}
-void uip_add32(const uint8_t *op32, uint16_t op16, uint8_t *sum)
-{
- /* op32 and the sum are in network order (big-endian); op16 is host order. */
-
- sum[3] = op32[3] + (op16 & 0xff);
- sum[2] = op32[2] + (op16 >> 8);
- sum[1] = op32[1];
- sum[0] = op32[0];
- uip_carry32(sum, op16);
-}
-
void uip_incr32(uint8_t *op32, uint16_t op16)
{
op32[3] += (op16 & 0xff);
diff --git a/nuttx/net/uip/uip_internal.h b/nuttx/net/uip/uip_internal.h
index 948a85e51..65928e01a 100644
--- a/nuttx/net/uip/uip_internal.h
+++ b/nuttx/net/uip/uip_internal.h
@@ -110,6 +110,13 @@ EXTERN struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf);
EXTERN struct uip_conn *uip_nexttcpconn(struct uip_conn *conn);
EXTERN struct uip_conn *uip_tcplistener(uint16_t portno);
EXTERN struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf);
+
+/* Defined in uip_tcpseqno.c ************************************************/
+
+EXTERN void uip_tcpsetsequence(FAR uint8_t *seqno, uint32_t value);
+EXTERN uint32_t uip_tcpgetsequence(FAR uint8_t *seqno);
+EXTERN uint32_t uip_tcpaddsequence(FAR uint8_t *seqno, uint16_t len);
+EXTERN void uip_tcpinitsequence(FAR uint8_t *seqno);
EXTERN void uip_tcpnextsequence(void);
/* Defined in uip_tcppoll.c *************************************************/
diff --git a/nuttx/net/uip/uip_tcpconn.c b/nuttx/net/uip/uip_tcpconn.c
index 323640812..a16950ddd 100644
--- a/nuttx/net/uip/uip_tcpconn.c
+++ b/nuttx/net/uip/uip_tcpconn.c
@@ -85,10 +85,6 @@ static dq_queue_t g_active_tcp_connections;
static uint16_t g_last_tcp_port;
-/* g_tcp_sequence[] is used to generate TCP sequence numbers */
-
-static uint8_t g_tcp_sequence[4];
-
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -469,7 +465,7 @@ struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf)
uip_ipaddr_copy(conn->ripaddr, uip_ip4addr_conv(buf->srcipaddr));
conn->tcpstateflags = UIP_SYN_RCVD;
- memcpy(conn->snd_nxt, g_tcp_sequence, 4);
+ uip_tcpinitsequence(conn->snd_nxt);
conn->len = 1;
/* rcv_nxt should be the seqno from the incoming packet + 1. */
@@ -492,33 +488,6 @@ struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf)
}
/****************************************************************************
- * Name: uip_tcpnextsequence()
- *
- * Description:
- * Increment the TCP/IP sequence number
- *
- * Assumptions:
- * This function is called from the interrupt level
- *
- ****************************************************************************/
-
-void uip_tcpnextsequence(void)
-{
- /* This inplements a byte-by-byte big-endian increment */
-
- if (++g_tcp_sequence[3] == 0)
- {
- if (++g_tcp_sequence[2] == 0)
- {
- if (++g_tcp_sequence[1] == 0)
- {
- ++g_tcp_sequence[0];
- }
- }
- }
-}
-
-/****************************************************************************
* Name: uip_tcpbind()
*
* Description:
@@ -626,7 +595,7 @@ int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr)
/* Initialize and return the connection structure, bind it to the port number */
conn->tcpstateflags = UIP_SYN_SENT;
- memcpy(conn->snd_nxt, g_tcp_sequence, 4);
+ uip_tcpinitsequence(conn->snd_nxt);
conn->initialmss = conn->mss = UIP_TCP_MSS;
conn->len = 1; /* TCP length of the SYN is one. */
diff --git a/nuttx/net/uip/uip_tcpinput.c b/nuttx/net/uip/uip_tcpinput.c
index e3a8196f6..f882ed1b9 100644
--- a/nuttx/net/uip/uip_tcpinput.c
+++ b/nuttx/net/uip/uip_tcpinput.c
@@ -328,16 +328,28 @@ found:
if ((pbuf->flags & TCP_ACK) && uip_outstanding(conn))
{
- /* Temporary variables. */
+ uint32_t seqno;
+ uint32_t ackno;
- uint8_t acc32[4];
- uip_add32(conn->snd_nxt, conn->len, acc32);
+ /* The next sequence number is equal to the current sequence
+ * number (snd_nxt) plus the size of the oustanding data (len).
+ */
+
+ seqno = uip_tcpaddsequence(conn->snd_nxt, conn->len);
+
+ /* Check if all of the outstanding bytes have been acknowledged. For
+ * a "generic" send operation, this should always be true. However,
+ * the send() API sends data ahead when it can without waiting for
+ * the ACK. In this case, the 'ackno' could be less than then the
+ * new sequence number.
+ */
- if (memcmp(pbuf->ackno, acc32, 4) == 0)
+ ackno = uip_tcpgetsequence(pbuf->ackno);
+ if (ackno <= seqno)
{
/* Update sequence number. */
- memcpy(conn->snd_nxt, acc32, 4);
+ uip_tcpsetsequence(conn->snd_nxt, seqno);
/* Do RTT estimation, unless we have done retransmissions. */
diff --git a/nuttx/net/uip/uip_tcpseqno.c b/nuttx/net/uip/uip_tcpseqno.c
new file mode 100755
index 000000000..8c19eb257
--- /dev/null
+++ b/nuttx/net/uip/uip_tcpseqno.c
@@ -0,0 +1,173 @@
+/****************************************************************************
+ * net/uip/uip_tcpseqno.c
+ *
+ * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Large parts of this file were leveraged from uIP logic:
+ *
+ * Copyright (c) 2001-2003, Adam Dunkels.
+ * All rights reserved.
+ *
+ * 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. The name of the author may not be used to endorse or promote
+ * products derived from this software without specific prior
+ * written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``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 AUTHOR 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
+
+#include <stdint.h>
+#include <debug.h>
+
+#include <net/uip/uipopt.h>
+#include <net/uip/uip.h>
+#include <net/uip/uip-arch.h>
+
+#include "uip_internal.h"
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* g_tcpsequence is used to generate initial TCP sequence numbers */
+
+static uint32_t g_tcpsequence;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpsetsequence
+ *
+ * Description:
+ * Set the TCP/IP sequence number
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+void uip_tcpsetsequence(FAR uint8_t *seqno, uint32_t value)
+{
+ /* Copy the sequence number in network (big-endian) order */
+
+ *seqno++ = value >> 24;
+ *seqno++ = (value >> 16) & 0xff;
+ *seqno++ = (value >> 8) & 0xff;
+ *seqno = value & 0xff;
+}
+
+/****************************************************************************
+ * Name: uip_tcpgetsequence
+ *
+ * Description:
+ * Get the TCP/IP sequence number
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+uint32_t uip_tcpgetsequence(FAR uint8_t *seqno)
+{
+ uint32_t value;
+
+ /* Combine the sequence number from network (big-endian) order */
+
+ value = (uint32_t)seqno[0] << 24 |
+ (uint32_t)seqno[1] << 16 |
+ (uint32_t)seqno[2] << 8 |
+ (uint32_t)seqno[3];
+ return value;
+}
+
+/****************************************************************************
+ * Name: uip_tcpaddsequence
+ *
+ * Description:
+ * Add the length to get the next TCP sequence number.
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+uint32_t uip_tcpaddsequence(FAR uint8_t *seqno, uint16_t len)
+{
+ return uip_tcpgetsequence(seqno) + (uint32_t)len;
+}
+
+/****************************************************************************
+ * Name: uip_tcpinitsequence
+ *
+ * Description:
+ * Set the (initial) the TCP/IP sequence number when a TCP connection is
+ * established.
+ *
+ * Assumptions:
+ * This function may called from the interrupt level
+ *
+ ****************************************************************************/
+
+void uip_tcpinitsequence(FAR uint8_t *seqno)
+{
+ uip_tcpsetsequence(seqno, g_tcpsequence);
+}
+
+/****************************************************************************
+ * Name: uip_tcpnextsequence
+ *
+ * Description:
+ * Increment the TCP/IP sequence number
+ *
+ * Assumptions:
+ * This function is called from the interrupt level
+ *
+ ****************************************************************************/
+
+void uip_tcpnextsequence(void)
+{
+ g_tcpsequence++;
+}
+
+#endif /* CONFIG_NET && CONFIG_NET_TCP */