summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2015-01-18 08:56:05 -0600
committerGregory Nutt <gnutt@nuttx.org>2015-01-18 08:56:05 -0600
commit0be3b3cd6dc53769b66c511e40e15be07f0a6ff9 (patch)
tree8133f9dd6247e0e0afebfff8184f408ff01f2b64 /nuttx
parent189b5eddca2641e86e7e9d9ab6ce3876cc68c7c9 (diff)
downloadpx4-nuttx-0be3b3cd6dc53769b66c511e40e15be07f0a6ff9.tar.gz
px4-nuttx-0be3b3cd6dc53769b66c511e40e15be07f0a6ff9.tar.bz2
px4-nuttx-0be3b3cd6dc53769b66c511e40e15be07f0a6ff9.zip
Networking: Final detangle off IPv4 and IPv6 TCP/UDP send logic. The Networking subsystem now compiles with IPv6 enabled
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/include/nuttx/net/ip.h4
-rw-r--r--nuttx/include/nuttx/net/tcp.h62
-rw-r--r--nuttx/include/nuttx/net/udp.h50
-rw-r--r--nuttx/net/devif/ipv4_input.c10
-rw-r--r--nuttx/net/devif/ipv6_input.c4
-rw-r--r--nuttx/net/socket/net_sendfile.c29
-rw-r--r--nuttx/net/socket/recvfrom.c117
-rw-r--r--nuttx/net/tcp/tcp.h1
-rw-r--r--nuttx/net/tcp/tcp_conn.c12
-rw-r--r--nuttx/net/tcp/tcp_send.c396
-rw-r--r--nuttx/net/tcp/tcp_send_buffered.c34
-rw-r--r--nuttx/net/tcp/tcp_send_unbuffered.c29
-rw-r--r--nuttx/net/udp/udp.h1
-rw-r--r--nuttx/net/udp/udp_conn.c8
-rw-r--r--nuttx/net/udp/udp_send.c133
-rw-r--r--nuttx/net/utils/Kconfig4
-rw-r--r--nuttx/net/utils/net_chksum.c67
-rw-r--r--nuttx/net/utils/utils.h18
18 files changed, 617 insertions, 362 deletions
diff --git a/nuttx/include/nuttx/net/ip.h b/nuttx/include/nuttx/net/ip.h
index e6a9f9c9d..a5d3df549 100644
--- a/nuttx/include/nuttx/net/ip.h
+++ b/nuttx/include/nuttx/net/ip.h
@@ -143,7 +143,7 @@ union ip_binding_u
#ifdef CONFIG_NET_IPv4
/* The IPv4 header */
-struct net_iphdr_s
+struct ipv4_hdr_s
{
uint8_t vhl; /* 8-bit Version (4) and header length (5 or 6) */
uint8_t tos; /* 8-bit Type of service (e.g., 6=TCP) */
@@ -161,7 +161,7 @@ struct net_iphdr_s
#ifdef CONFIG_NET_IPv6
/* The IPv6 header */
-struct net_ipv6hdr_s
+struct ipv6_hdr_s
{
uint8_t vtc; /* Bits 0-3: version, bits 4-7: traffic class (MS) */
uint8_t tcf; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */
diff --git a/nuttx/include/nuttx/net/tcp.h b/nuttx/include/nuttx/net/tcp.h
index c6b9ddf17..02dfa885c 100644
--- a/nuttx/include/nuttx/net/tcp.h
+++ b/nuttx/include/nuttx/net/tcp.h
@@ -156,68 +156,6 @@ struct tcp_hdr_s
uint8_t optdata[4];
};
-/* The TCP and IP headers */
-
-#ifdef CONFIG_NET_IPv4
-struct tcp_iphdr_s
-{
- /* IPv4 IP header */
-
- uint8_t vhl; /* 8-bit Version (4) and header length (5 or 6) */
- uint8_t tos; /* 8-bit Type of service (e.g., 6=TCP) */
- uint8_t len[2]; /* 16-bit Total length */
- uint8_t ipid[2]; /* 16-bit Identification */
- uint8_t ipoffset[2]; /* 16-bit IP flags + fragment offset */
- uint8_t ttl; /* 8-bit Time to Live */
- uint8_t proto; /* 8-bit Protocol */
- uint16_t ipchksum; /* 16-bit Header checksum */
- uint16_t srcipaddr[2]; /* 32-bit Source IP address */
- uint16_t destipaddr[2]; /* 32-bit Destination IP address */
-
- /* TCP header */
-
- uint16_t srcport;
- uint16_t destport;
- uint8_t seqno[4];
- uint8_t ackno[4];
- uint8_t tcpoffset;
- uint8_t flags;
- uint8_t wnd[2];
- uint16_t tcpchksum;
- uint8_t urgp[2];
- uint8_t optdata[4];
-};
-#endif
-
-#ifdef CONFIG_NET_IPv6
-struct tcp_ipv6hdr_s
-{
- /* IPv6 IP header */
-
- uint8_t vtc; /* Bits 0-3: version, bits 4-7: traffic class (MS) */
- uint8_t tcf; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */
- uint16_t flow; /* 16-bit flow label (LS) */
- uint8_t len[2]; /* 16-bit Payload length */
- uint8_t proto; /* 8-bit Next header (same as IPv4 protocol field) */
- uint8_t ttl; /* 8-bit Hop limit (like IPv4 TTL field) */
- net_ipv6addr_t srcipaddr; /* 128-bit Source address */
- net_ipv6addr_t destipaddr; /* 128-bit Destination address */
-
- /* TCP header */
-
- uint16_t srcport;
- uint16_t destport;
- uint8_t seqno[4];
- uint8_t ackno[4];
- uint8_t tcpoffset;
- uint8_t flags;
- uint8_t wnd[2];
- uint16_t tcpchksum;
- uint8_t urgp[2];
- uint8_t optdata[4];
-};
-#endif
-
/* The structure holding the TCP/IP statistics that are gathered if
* CONFIG_NET_STATISTICS is defined.
*/
diff --git a/nuttx/include/nuttx/net/udp.h b/nuttx/include/nuttx/net/udp.h
index 4b2d305d6..24b47452f 100644
--- a/nuttx/include/nuttx/net/udp.h
+++ b/nuttx/include/nuttx/net/udp.h
@@ -86,56 +86,6 @@ struct udp_hdr_s
uint16_t udpchksum;
};
-/* The UDP and IP headers */
-
-#ifdef CONFIG_NET_IPv4
-struct udp_iphdr_s
-{
- /* IPv4 header */
-
- uint8_t vhl; /* 8-bit Version (4) and header length (5 or 6) */
- uint8_t tos; /* 8-bit Type of service (e.g., 6=TCP) */
- uint8_t len[2]; /* 16-bit Total length */
- uint8_t ipid[2]; /* 16-bit Identification */
- uint8_t ipoffset[2]; /* 16-bit IP flags + fragment offset */
- uint8_t ttl; /* 8-bit Time to Live */
- uint8_t proto; /* 8-bit Protocol */
- uint16_t ipchksum; /* 16-bit Header checksum */
- uint16_t srcipaddr[2]; /* 32-bit Source IP address */
- uint16_t destipaddr[2]; /* 32-bit Destination IP address */
-
- /* UDP header */
-
- uint16_t srcport;
- uint16_t destport;
- uint16_t udplen;
- uint16_t udpchksum;
-};
-#endif
-
-#ifdef CONFIG_NET_IPv6
-struct udp_ipv6hdr_s
-{
- /* IPv6 Ip header */
-
- uint8_t vtc; /* Bits 0-3: version, bits 4-7: traffic class (MS) */
- uint8_t tcf; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */
- uint16_t flow; /* 16-bit flow label (LS) */
- uint8_t len[2]; /* 16-bit Payload length */
- uint8_t proto; /* 8-bit Next header (same as IPv4 protocol field) */
- uint8_t ttl; /* 8-bit Hop limit (like IPv4 TTL field) */
- net_ipv6addr_t srcipaddr; /* 128-bit Source address */
- net_ipv6addr_t destipaddr; /* 128-bit Destination address */
-
- /* UDP header */
-
- uint16_t srcport;
- uint16_t destport;
- uint16_t udplen;
- uint16_t udpchksum;
-};
-#endif
-
/* The structure holding the UDP statistics that are gathered if
* CONFIG_NET_STATISTICS is defined.
*/
diff --git a/nuttx/net/devif/ipv4_input.c b/nuttx/net/devif/ipv4_input.c
index 589e685ba..394b220a7 100644
--- a/nuttx/net/devif/ipv4_input.c
+++ b/nuttx/net/devif/ipv4_input.c
@@ -104,8 +104,8 @@
/* Macros */
-#define BUF ((FAR struct net_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#define FBUF ((FAR struct net_iphdr_s *)&g_reassembly_buffer[0])
+#define BUF ((FAR struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define FBUF ((FAR struct ipv4_hdr_s *)&g_reassembly_buffer[0])
/* IP fragment re-assembly */
@@ -151,8 +151,8 @@ static uint8_t g_reassembly_flags;
#if defined(CONFIG_NET_TCP_REASSEMBLY) && !defined(CONFIG_NET_IPv6)
static uint8_t devif_reassembly(void)
{
- FAR struct net_iphdr_s *pbuf = BUF;
- FAR struct net_iphdr_s *pfbuf = FBUF;
+ FAR struct ipv4_hdr_s *pbuf = BUF;
+ FAR struct ipv4_hdr_s *pfbuf = FBUF;
uint16_t offset;
uint16_t len;
uint16_t i;
@@ -311,7 +311,7 @@ nullreturn:
int ipv4_input(FAR struct net_driver_s *dev)
{
- FAR struct net_iphdr_s *pbuf = BUF;
+ FAR struct ipv4_hdr_s *pbuf = BUF;
uint16_t iplen;
/* This is where the input processing starts. */
diff --git a/nuttx/net/devif/ipv6_input.c b/nuttx/net/devif/ipv6_input.c
index e190e1911..3616b04f4 100644
--- a/nuttx/net/devif/ipv6_input.c
+++ b/nuttx/net/devif/ipv6_input.c
@@ -104,7 +104,7 @@
/* Macros */
-#define BUF ((FAR struct net_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define BUF ((FAR struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
/****************************************************************************
* Public Data
@@ -139,7 +139,7 @@
int ipv6_input(FAR struct net_driver_s *dev)
{
- FAR struct net_ipv6hdr_s *pbuf = BUF;
+ FAR struct ipv6_hdr_s *pbuf = BUF;
uint16_t iplen;
/* This is where the input processing starts. */
diff --git a/nuttx/net/socket/net_sendfile.c b/nuttx/net/socket/net_sendfile.c
index 0432626c5..b64d3d1c9 100644
--- a/nuttx/net/socket/net_sendfile.c
+++ b/nuttx/net/socket/net_sendfile.c
@@ -2,7 +2,7 @@
* net/socket/net_sendfile.c
*
* Copyright (C) 2013 UVC Ingenieure. All rights reserved.
- * Copyright (C) 2007-2014 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2015 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* Max Holtzberg <mh@uvc.de>
*
@@ -77,7 +77,8 @@
# define CONFIG_NET_TCP_SPLIT_SIZE 40
#endif
-#define TCPBUF ((struct tcp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define TCPIPv4BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
+#define TCPIPv6BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
/****************************************************************************
* Private Types
@@ -157,12 +158,36 @@ static uint16_t ack_interrupt(FAR struct net_driver_s *dev, FAR void *pvconn,
if ((flags & TCP_ACKDATA) != 0)
{
+ FAR struct tcp_hdr_s *tcp;
+
#ifdef CONFIG_NET_SOCKOPTS
/* Update the timeout */
pstate->snd_time = clock_systimer();
#endif
+ /* Get the offset address of the TCP header */
+
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
+#endif
+ {
+ DEBUGASSERT(pstate->snd_sock == PF_INET6);
+ tcp = TCPIPv6BUF;
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ else
+#endif
+ {
+ DEBUGASSERT(pstate->snd_sock == PF_INET);
+ tcp = TCPIPv4BUF;
+ }
+#endif /* CONFIG_NET_IPv4 */
+
/* The current acknowledgement number number is the (relative) offset
* of the of the next byte needed by the receiver. The snd_isn is the
* offset of the first byte to send to the receiver. The difference
diff --git a/nuttx/net/socket/recvfrom.c b/nuttx/net/socket/recvfrom.c
index 6bbe9deea..9421539d4 100644
--- a/nuttx/net/socket/recvfrom.c
+++ b/nuttx/net/socket/recvfrom.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/socket/recvfrom.c
*
- * Copyright (C) 2007-2009, 2011-2014 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011-2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -74,13 +74,14 @@
* Pre-processor Definitions
****************************************************************************/
-#if defined(CONFIG_NET_IPv4)
-# define UDPBUF ((struct udp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-# define TCPBUF ((struct tcp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#elif defined(CONFIG_NET_IPv6)
-# define UDPBUF ((struct udp_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-# define TCPBUF ((struct tcp_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#endif
+#define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+
+#define UDPIPv4BUF ((struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
+#define UDPIPv6BUF ((struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
+
+#define TCPIPv4BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
+#define TCPIPv6BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
/****************************************************************************
* Private Types
@@ -572,26 +573,52 @@ static uint16_t recvfrom_pktinterrupt(FAR struct net_driver_s *dev,
static inline void recvfrom_tcpsender(FAR struct net_driver_s *dev,
FAR struct recvfrom_s *pstate)
{
+ /* Get the family from the packet type, IP address from the IP header, and
+ * the port number from the TCP header.
+ */
+
#ifdef CONFIG_NET_IPv6
- FAR struct sockaddr_in6 *infrom = pstate->rf_from;
-#else
- FAR struct sockaddr_in *infrom = pstate->rf_from;
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
#endif
-
- if (infrom)
{
- infrom->sin_family = AF_INET;
- infrom->sin_port = TCPBUF->srcport;
+ FAR struct sockaddr_in6 *infrom = pstate->rf_from;
+
+ if (infrom)
+ {
+ FAR struct tcp_hdr_s *tcp = TCPIPv6BUF;
+ FAR struct ipv6_hdr_s *ipv6 = IPv6BUF;
+
+ infrom->sin_family = AF_INET6;
+ infrom->sin_port = tcp->srcport;
+
+ net_ipv6addr_copy(infrom->sin6_addr.s6_addr, ipv6->srcipaddr);
+ }
+ }
+#endif /* CONFIG_NET_IPv6 */
+#ifdef CONFIG_NET_IPv4
#ifdef CONFIG_NET_IPv6
- net_ipv6addr_copy(infrom->sin6_addr.s6_addr, TCPBUF->srcipaddr);
-#else
- net_ipv4addr_copy(infrom->sin_addr.s_addr,
- net_ip4addr_conv32(TCPBUF->srcipaddr));
+ else
#endif
+ {
+ FAR struct sockaddr_in *infrom = pstate->rf_from;
+
+ if (infrom)
+ {
+ FAR struct tcp_hdr_s *tcp = TCPIPv4BUF;
+ FAR struct ipv4_hdr_s *ipv4 = IPv4BUF;
+
+ infrom->sin_family = AF_INET;
+ infrom->sin_port = tcp->srcport;
+
+ net_ipv4addr_copy(infrom->sin_addr.s_addr,
+ net_ip4addr_conv32(ipv4->srcipaddr));
+ }
}
+#endif /* CONFIG_NET_IPv4 */
}
-#endif
+#endif /* CONFIG_NET_TCP */
/****************************************************************************
* Function: recvfrom_tcpinterrupt
@@ -819,26 +846,52 @@ static uint16_t recvfrom_tcpinterrupt(FAR struct net_driver_s *dev,
#ifdef CONFIG_NET_UDP
static inline void recvfrom_udpsender(struct net_driver_s *dev, struct recvfrom_s *pstate)
{
+ /* Get the family from the packet type, IP address from the IP header, and
+ * the port number from the UDP header.
+ */
+
#ifdef CONFIG_NET_IPv6
- FAR struct sockaddr_in6 *infrom = pstate->rf_from;
-#else
- FAR struct sockaddr_in *infrom = pstate->rf_from;
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
#endif
-
- if (infrom)
{
- infrom->sin_family = AF_INET;
- infrom->sin_port = UDPBUF->srcport;
+ FAR struct sockaddr_in6 *infrom = pstate->rf_from;
+
+ if (infrom)
+ {
+ FAR struct udp_hdr_s *udp = UDPIPv6BUF;
+ FAR struct ipv6_hdr_s *ipv6 = IPv6BUF;
+
+ infrom->sin_family = AF_INET6;
+ infrom->sin_port = udp->srcport;
+
+ net_ipv6addr_copy(infrom->sin6_addr.s6_addr, ipv6->srcipaddr);
+ }
+ }
+#endif /* CONFIG_NET_IPv6 */
+#ifdef CONFIG_NET_IPv4
#ifdef CONFIG_NET_IPv6
- net_ipv6addr_copy(infrom->sin6_addr.s6_addr, UDPBUF->srcipaddr);
-#else
- net_ipv4addr_copy(infrom->sin_addr.s_addr,
- net_ip4addr_conv32(UDPBUF->srcipaddr));
+ else
#endif
+ {
+ FAR struct sockaddr_in *infrom = pstate->rf_from;
+
+ if (infrom)
+ {
+ FAR struct udp_hdr_s *udp = UDPIPv4BUF;
+ FAR struct ipv4_hdr_s *ipv4 = IPv4BUF;
+
+ infrom->sin_family = AF_INET;
+ infrom->sin_port = udp->srcport;
+
+ net_ipv4addr_copy(infrom->sin_addr.s_addr,
+ net_ip4addr_conv32(ipv4->srcipaddr));
+ }
}
+#endif /* CONFIG_NET_IPv4 */
}
-#endif
+#endif /* CONFIG_NET_UDP */
/****************************************************************************
* Function: recvfrom_udpinterrupt
diff --git a/nuttx/net/tcp/tcp.h b/nuttx/net/tcp/tcp.h
index 16a5bbce8..1d6e78e8c 100644
--- a/nuttx/net/tcp/tcp.h
+++ b/nuttx/net/tcp/tcp.h
@@ -270,7 +270,6 @@ extern "C"
/* Defined in tcp_conn.c ****************************************************/
struct sockaddr; /* Forward reference */
-struct tcp_iphdr_s; /* Forward reference */
/****************************************************************************
* Name: tcp_initialize
diff --git a/nuttx/net/tcp/tcp_conn.c b/nuttx/net/tcp/tcp_conn.c
index b364e74ee..4c531dfa1 100644
--- a/nuttx/net/tcp/tcp_conn.c
+++ b/nuttx/net/tcp/tcp_conn.c
@@ -64,8 +64,8 @@
* Pre-processor Definitions
****************************************************************************/
-#define IPv4BUF ((struct net_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#define IPv6BUF ((struct net_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
/****************************************************************************
* Private Data
@@ -357,7 +357,7 @@ static int tcp_selectport(uint16_t portno)
static inline FAR struct tcp_conn_s *
tcp_ipv4_active(FAR struct net_driver_s *dev, FAR struct tcp_hdr_s *tcp)
{
- FAR struct net_iphdr_s *ip = IPv4BUF;
+ FAR struct ipv4_hdr_s *ip = IPv4BUF;
FAR struct tcp_conn_s *conn;
in_addr_t srcipaddr;
#ifdef CONFIG_NETDEV_MULTINIC
@@ -432,7 +432,7 @@ static inline FAR struct tcp_conn_s *
static inline FAR struct tcp_conn_s *
tcp_ipv6_active(FAR struct net_driver_s *dev, FAR struct tcp_hdr_s *tcp)
{
- FAR struct net_ipv6hdr_s *ip = IPv6BUF;
+ FAR struct ipv6_hdr_s *ip = IPv6BUF;
FAR struct tcp_conn_s *conn;
net_ipv6addr_t *srcipaddr;
#ifdef CONFIG_NETDEV_MULTINIC
@@ -952,7 +952,7 @@ FAR struct tcp_conn_s *tcp_alloc_accept(FAR struct net_driver_s *dev,
if (ipv6)
#endif
{
- FAR struct net_ipv6hdr_s *ip = IPv6BUF;
+ FAR struct ipv6_hdr_s *ip = IPv6BUF;
conn->mss = TCP_IPv6_INITIAL_MSS(dev);
net_ipv6addr_copy(conn->u.ipv6.raddr, ip->srcipaddr);
@@ -967,7 +967,7 @@ FAR struct tcp_conn_s *tcp_alloc_accept(FAR struct net_driver_s *dev,
else
#endif
{
- FAR struct net_iphdr_s *ip = IPv4BUF;
+ FAR struct ipv4_hdr_s *ip = IPv4BUF;
conn->mss = TCP_IPv4_INITIAL_MSS(dev);
net_ipv4addr_copy(conn->u.ipv4.raddr,
diff --git a/nuttx/net/tcp/tcp_send.c b/nuttx/net/tcp/tcp_send.c
index 5c23b657f..d63c595b0 100644
--- a/nuttx/net/tcp/tcp_send.c
+++ b/nuttx/net/tcp/tcp_send.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/tcp/tcp_send.c
*
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010, 2012, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Adapted for NuttX from logic in uIP which also has a BSD-like license:
@@ -62,7 +62,11 @@
* Pre-processor Definitions
****************************************************************************/
-#define BUF ((struct tcp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+
+#define TCPIPv4BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
+#define TCPIPv6BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
/****************************************************************************
* Public Variables
@@ -77,7 +81,42 @@
****************************************************************************/
/****************************************************************************
- * Name: tcp_sendcomplete
+ * Name: tcp_header
+ *
+ * Description:
+ * Get the length of the IP header
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ *
+ * Return:
+ * The length of the IP header (IPv4_HDRLEN or IPv6_HDRLEN)
+ *
+ ****************************************************************************/
+
+static inline FAR struct tcp_hdr_s *tcp_header(FAR struct net_driver_s *dev)
+{
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
+#endif
+ {
+ return TCPIPv6BUF;
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ else
+#endif
+ {
+ return TCPIPv4BUF;
+ }
+#endif /* CONFIG_NET_IPv4 */
+}
+
+/****************************************************************************
+ * Name: tcp_sendcomplete, tcp_ipv4_sendcomplete, and tcp_ipv6_sendcomplete
*
* Description:
* Complete the final portions of the send operation. This function sets
@@ -94,60 +133,143 @@
*
****************************************************************************/
-static void tcp_sendcomplete(FAR struct net_driver_s *dev)
+#ifdef CONFIG_NET_IPv4
+static inline void tcp_ipv4_sendcomplete(FAR struct net_driver_s *dev,
+ FAR struct tcp_hdr_s *tcp,
+ FAR struct ipv4_hdr_s *ipv4)
{
- FAR struct tcp_iphdr_s *pbuf = BUF;
+ /* Set up some IP header fields that are needed for TCP checksum
+ * calculation.
+ */
- pbuf->ttl = IP_TTL;
+ ipv4->proto = IP_PROTO_TCP;
+ ipv4->ttl = IP_TTL;
-#ifdef CONFIG_NET_IPv6
+ ipv4->len[0] = (dev->d_len >> 8);
+ ipv4->len[1] = (dev->d_len & 0xff);
- /* For IPv6, the IP length field does not include the IPv6 IP header
- * length.
- */
+ /* Calculate TCP checksum. */
- pbuf->len[0] = ((dev->d_len - IPv6_HDRLEN) >> 8);
- pbuf->len[1] = ((dev->d_len - IPv6_HDRLEN) & 0xff);
+ tcp->urgp[0] = 0;
+ tcp->urgp[1] = 0;
-#else /* CONFIG_NET_IPv6 */
+ tcp->tcpchksum = 0;
+ tcp->tcpchksum = ~tcp_ipv4_chksum(dev);
- pbuf->len[0] = (dev->d_len >> 8);
- pbuf->len[1] = (dev->d_len & 0xff);
+ /* Finish initializing the IP header and calculate the IP checksum */
-#endif /* CONFIG_NET_IPv6 */
+ ipv4->vhl = 0x45;
+ ipv4->tos = 0;
+ ipv4->ipoffset[0] = 0;
+ ipv4->ipoffset[1] = 0;
+ ++g_ipid;
+ ipv4->ipid[0] = g_ipid >> 8;
+ ipv4->ipid[1] = g_ipid & 0xff;
- pbuf->urgp[0] = pbuf->urgp[1] = 0;
+ /* Calculate IP checksum. */
- /* Calculate TCP checksum. */
+ ipv4->ipchksum = 0;
+ ipv4->ipchksum = ~ipv4_chksum(dev);
+}
+#endif /* CONFIG_NET_IPv4 */
- pbuf->tcpchksum = 0;
- pbuf->tcpchksum = ~(tcp_chksum(dev));
+/****************************************************************************
+ * Name: tcp_pv6_sendcomplete
+ *
+ * Description:
+ * Complete the final portions of the send operation. This function sets
+ * up IP header and computes the TCP checksum
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
#ifdef CONFIG_NET_IPv6
+static inline void tcp_ipv6_sendcomplete(FAR struct net_driver_s *dev,
+ FAR struct tcp_hdr_s *tcp,
+ FAR struct ipv6_hdr_s *ipv6)
+{
+ uint16_t iplen;
- pbuf->vtc = 0x60;
- pbuf->tcf = 0x00;
- pbuf->flow = 0x00;
+ /* Set up some IP header fields that are needed for TCP checksum
+ * calculation.
+ */
-#else /* CONFIG_NET_IPv6 */
+ ipv6->proto = IP_PROTO_TCP;
+ ipv6->ttl = IP_TTL;
- pbuf->vhl = 0x45;
- pbuf->tos = 0;
- pbuf->ipoffset[0] = 0;
- pbuf->ipoffset[1] = 0;
- ++g_ipid;
- pbuf->ipid[0] = g_ipid >> 8;
- pbuf->ipid[1] = g_ipid & 0xff;
+ /* For IPv6, the IP length field does not include the IPv6 IP header
+ * length.
+ */
- /* Calculate IP checksum. */
+ iplen = dev->d_len - IPv6_HDRLEN;
+ ipv6->len[0] = (iplen >> 8);
+ ipv6->len[1] = (iplen & 0xff);
+
+ /* Calculate TCP checksum. */
+
+ tcp->urgp[0] = 0;
+ tcp->urgp[1] = 0;
+
+ tcp->tcpchksum = 0;
+ tcp->tcpchksum = ~tcp_ipv6_chksum(dev);
+
+ /* Finish initializing the IP header (no IPv6 checksum) */
- pbuf->ipchksum = 0;
- pbuf->ipchksum = ~(ipv4_chksum(dev));
+ ipv6->vtc = 0x60;
+ ipv6->tcf = 0x00;
+ ipv6->flow = 0x00;
+}
+#endif /* CONFIG_NET_IPv6 */
+
+/****************************************************************************
+ * Name: tcp_sendcomplete
+ *
+ * Description:
+ * Complete the final portions of the send operation. This function sets
+ * up IP header and computes the TCP checksum
+ *
+ * Parameters:
+ * dev - The device driver structure to use in the send operation
+ *
+ * Return:
+ * None
+ *
+ * Assumptions:
+ * Called from the interrupt level or with interrupts disabled.
+ *
+ ****************************************************************************/
+static void tcp_sendcomplete(FAR struct net_driver_s *dev,
+ FAR struct tcp_hdr_s *tcp)
+{
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
+#endif
+ {
+ tcp_ipv6_sendcomplete(dev, tcp, IPv6BUF);
+ }
#endif /* CONFIG_NET_IPv6 */
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ else
+#endif
+ {
+ tcp_ipv4_sendcomplete(dev, tcp, IPv4BUF);
+ }
+#endif /* CONFIG_NET_IPv4 */
+
nllvdbg("Outgoing TCP packet length: %d (%d)\n",
- dev->d_len, (pbuf->len[0] << 8) | pbuf->len[1]);
+ dev->d_len, (tcp->len[0] << 8) | tcp->len[1]);
#ifdef CONFIG_NET_STATISTICS
g_netstats.tcp.sent++;
@@ -176,19 +298,42 @@ static void tcp_sendcomplete(FAR struct net_driver_s *dev)
****************************************************************************/
static void tcp_sendcommon(FAR struct net_driver_s *dev,
- FAR struct tcp_conn_s *conn)
+ FAR struct tcp_conn_s *conn,
+ FAR struct tcp_hdr_s *tcp)
{
- FAR struct tcp_iphdr_s *pbuf = BUF;
+ /* Copy the IP address into the IPv6 header */
- memcpy(pbuf->ackno, conn->rcvseq, 4);
- memcpy(pbuf->seqno, conn->sndseq, 4);
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
+#endif
+ {
+ FAR struct ipv6_hdr_s *ipv6 = IPv6BUF;
+ net_ipv6addr_hdrcopy(ipv6->srcipaddr, dev->d_ipv6addr);
+ net_ipv6addr_hdrcopy(ipv6->destipaddr, conn->u.ipv6.raddr);
+ }
+#endif /* CONFIG_NET_IPv6 */
- pbuf->proto = IP_PROTO_TCP;
- pbuf->srcport = conn->lport;
- pbuf->destport = conn->rport;
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ else
+#endif
+ {
+ FAR struct ipv4_hdr_s *ipv4 = IPv4BUF;
+ net_ipv4addr_hdrcopy(ipv4->srcipaddr, &dev->d_ipaddr);
+ net_ipv4addr_hdrcopy(ipv4->destipaddr, &conn->u.ipv4.raddr);
+ }
+#endif /* CONFIG_NET_IPv4 */
+
+ /* Set TCP sequence numbers and port numbers */
+
+ memcpy(tcp->ackno, conn->rcvseq, 4);
+ memcpy(tcp->seqno, conn->sndseq, 4);
- net_ipv4addr_hdrcopy(pbuf->srcipaddr, &dev->d_ipaddr);
- net_ipv4addr_hdrcopy(pbuf->destipaddr, &conn->u.ipv4.raddr);
+ tcp->srcport = conn->lport;
+ tcp->destport = conn->rport;
+
+ /* Set the TCP window */
if (conn->tcpstateflags & TCP_STOPPED)
{
@@ -196,20 +341,18 @@ static void tcp_sendcommon(FAR struct net_driver_s *dev,
* window so that the remote host will stop sending data.
*/
- pbuf->wnd[0] = 0;
- pbuf->wnd[1] = 0;
+ tcp->wnd[0] = 0;
+ tcp->wnd[1] = 0;
}
else
{
- pbuf->wnd[0] = ((NET_DEV_RCVWNDO(dev)) >> 8);
- pbuf->wnd[1] = ((NET_DEV_RCVWNDO(dev)) & 0xff);
+ tcp->wnd[0] = ((NET_DEV_RCVWNDO(dev)) >> 8);
+ tcp->wnd[1] = ((NET_DEV_RCVWNDO(dev)) & 0xff);
}
- /* Finish the IP portion of the message, calculate checksums and send
- * the message.
- */
+ /* Finish the IP portion of the message and calculate checksums */
- tcp_sendcomplete(dev);
+ tcp_sendcomplete(dev, tcp);
}
/****************************************************************************
@@ -239,12 +382,12 @@ static void tcp_sendcommon(FAR struct net_driver_s *dev,
void tcp_send(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn,
uint16_t flags, uint16_t len)
{
- FAR struct tcp_iphdr_s *pbuf = BUF;
+ FAR struct tcp_hdr_s *tcp = tcp_header(dev);
- pbuf->flags = flags;
+ tcp->flags = flags;
dev->d_len = len;
- pbuf->tcpoffset = (TCP_HDRLEN / 4) << 4;
- tcp_sendcommon(dev, conn);
+ tcp->tcpoffset = (TCP_HDRLEN / 4) << 4;
+ tcp_sendcommon(dev, conn, tcp);
}
/****************************************************************************
@@ -266,7 +409,7 @@ void tcp_send(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn,
void tcp_reset(FAR struct net_driver_s *dev)
{
- FAR struct tcp_iphdr_s *pbuf = BUF;
+ FAR struct tcp_hdr_s *tcp = tcp_header(dev);
uint16_t tmp16;
uint8_t seqbyte;
@@ -274,58 +417,92 @@ void tcp_reset(FAR struct net_driver_s *dev)
g_netstats.tcp.rst++;
#endif
- pbuf->flags = TCP_RST | TCP_ACK;
- dev->d_len = IPv4TCP_HDRLEN;
- pbuf->tcpoffset = 5 << 4;
+ /* TCP setup */
+
+ tcp->flags = TCP_RST | TCP_ACK;
+ tcp->tcpoffset = 5 << 4;
/* Flip the seqno and ackno fields in the TCP header. */
- seqbyte = pbuf->seqno[3];
- pbuf->seqno[3] = pbuf->ackno[3];
- pbuf->ackno[3] = seqbyte;
+ seqbyte = tcp->seqno[3];
+ tcp->seqno[3] = tcp->ackno[3];
+ tcp->ackno[3] = seqbyte;
- seqbyte = pbuf->seqno[2];
- pbuf->seqno[2] = pbuf->ackno[2];
- pbuf->ackno[2] = seqbyte;
+ seqbyte = tcp->seqno[2];
+ tcp->seqno[2] = tcp->ackno[2];
+ tcp->ackno[2] = seqbyte;
- seqbyte = pbuf->seqno[1];
- pbuf->seqno[1] = pbuf->ackno[1];
- pbuf->ackno[1] = seqbyte;
+ seqbyte = tcp->seqno[1];
+ tcp->seqno[1] = tcp->ackno[1];
+ tcp->ackno[1] = seqbyte;
- seqbyte = pbuf->seqno[0];
- pbuf->seqno[0] = pbuf->ackno[0];
- pbuf->ackno[0] = seqbyte;
+ seqbyte = tcp->seqno[0];
+ tcp->seqno[0] = tcp->ackno[0];
+ tcp->ackno[0] = seqbyte;
/* We also have to increase the sequence number we are
* acknowledging. If the least significant byte overflowed, we need
* to propagate the carry to the other bytes as well.
*/
- if (++(pbuf->ackno[3]) == 0)
+ if (++(tcp->ackno[3]) == 0)
{
- if (++(pbuf->ackno[2]) == 0)
+ if (++(tcp->ackno[2]) == 0)
{
- if (++(pbuf->ackno[1]) == 0)
+ if (++(tcp->ackno[1]) == 0)
{
- ++(pbuf->ackno[0]);
+ ++(tcp->ackno[0]);
}
}
}
/* Swap port numbers. */
- tmp16 = pbuf->srcport;
- pbuf->srcport = pbuf->destport;
- pbuf->destport = tmp16;
+ tmp16 = tcp->srcport;
+ tcp->srcport = tcp->destport;
+ tcp->destport = tmp16;
- /* Swap IP addresses. */
+ /* Set the packet length and swap IP addresses. */
- net_ipv4addr_hdrcopy(pbuf->destipaddr, pbuf->srcipaddr);
- net_ipv4addr_hdrcopy(pbuf->srcipaddr, &dev->d_ipaddr);
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
+#endif
+ {
+ FAR struct ipv6_hdr_s *ipv6 = IPv6BUF;
+
+ /* Set the packet length to the size of the IPv6 + TCP headers */
+
+ dev->d_len = IPv6TCP_HDRLEN;
+
+ /* Swap IPv6 addresses */
+
+ net_ipv6addr_hdrcopy(ipv6->destipaddr, ipv6->srcipaddr);
+ net_ipv6addr_hdrcopy(ipv6->srcipaddr, dev->d_ipv6addr);
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ else
+#endif
+ {
+ FAR struct ipv4_hdr_s *ipv4 = IPv4BUF;
+
+ /* Set the packet length to the size of the IPv4 + TCP headers */
+
+ dev->d_len = IPv4TCP_HDRLEN;
+
+ /* Swap IPv4 addresses */
+
+ net_ipv4addr_hdrcopy(ipv4->destipaddr, ipv4->srcipaddr);
+ net_ipv4addr_hdrcopy(ipv4->srcipaddr, &dev->d_ipaddr);
+ }
+#endif /* CONFIG_NET_IPv4 */
/* And send out the RST packet */
- tcp_sendcomplete(dev);
+ tcp_sendcomplete(dev, tcp);
}
/****************************************************************************
@@ -350,25 +527,58 @@ void tcp_reset(FAR struct net_driver_s *dev)
void tcp_ack(FAR struct net_driver_s *dev, FAR struct tcp_conn_s *conn,
uint8_t ack)
{
- struct tcp_iphdr_s *pbuf = BUF;
- uint16_t tcp_mss = TCP_IPv4_MSS(dev);
+ struct tcp_hdr_s *tcp;
+ uint16_t tcp_mss;
+
+ /* Get values that vary with the underlying IP domain */
+
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ if (IFF_IS_IPv6(dev->d_flags))
+#endif
+ {
+ /* Get the MSS value and offset TCP header address for this packet */
+
+ tcp = TCPIPv6BUF;
+ tcp_mss = TCP_IPv6_MSS(dev);
+
+ /* Set the the packet length for the TCP Maximum Segment Size */
+
+ dev->d_len = IPv6TCP_HDRLEN + TCP_OPT_MSS_LEN;
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ else
+#endif
+ {
+ /* Get the MSS value and offset TCP header address for this packet */
+
+ tcp = TCPIPv4BUF;
+ tcp_mss = TCP_IPv4_MSS(dev);
+
+ /* Set the the packet length for the TCP Maximum Segment Size */
+
+ dev->d_len = IPv4TCP_HDRLEN + TCP_OPT_MSS_LEN;
+ }
+#endif /* CONFIG_NET_IPv4 */
/* Save the ACK bits */
- pbuf->flags = ack;
+ tcp->flags = ack;
/* We send out the TCP Maximum Segment Size option with our ack. */
- pbuf->optdata[0] = TCP_OPT_MSS;
- pbuf->optdata[1] = TCP_OPT_MSS_LEN;
- pbuf->optdata[2] = tcp_mss >> 8;
- pbuf->optdata[3] = tcp_mss & 0xff;
- dev->d_len = IPv4TCP_HDRLEN + TCP_OPT_MSS_LEN;
- pbuf->tcpoffset = ((TCP_HDRLEN + TCP_OPT_MSS_LEN) / 4) << 4;
+ tcp->optdata[0] = TCP_OPT_MSS;
+ tcp->optdata[1] = TCP_OPT_MSS_LEN;
+ tcp->optdata[2] = tcp_mss >> 8;
+ tcp->optdata[3] = tcp_mss & 0xff;
+ tcp->tcpoffset = ((TCP_HDRLEN + TCP_OPT_MSS_LEN) / 4) << 4;
/* Complete the common portions of the TCP message */
- tcp_sendcommon(dev, conn);
+ tcp_sendcommon(dev, conn, tcp);
}
#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/tcp/tcp_send_buffered.c b/nuttx/net/tcp/tcp_send_buffered.c
index 3b53db91b..d7d495e7b 100644
--- a/nuttx/net/tcp/tcp_send_buffered.c
+++ b/nuttx/net/tcp/tcp_send_buffered.c
@@ -86,11 +86,8 @@
# define NEED_IPDOMAIN_SUPPORT 1
#endif
-#if defined(CONFIG_NET_IPv4)
-# define TCPBUF ((struct tcp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#elif defined(CONFIG_NET_IPv6)
-# define TCPBUF ((struct tcp_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#endif
+#define TCPIPv4BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
+#define TCPIPv6BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
/* Debug */
@@ -285,11 +282,36 @@ static uint16_t psock_send_interrupt(FAR struct net_driver_s *dev,
if ((flags & TCP_ACKDATA) != 0)
{
FAR struct tcp_wrbuffer_s *wrb;
+ FAR struct tcp_hdr_s *tcp;
FAR sq_entry_t *entry;
FAR sq_entry_t *next;
uint32_t ackno;
- ackno = tcp_getsequence(TCPBUF->ackno);
+ /* Get the offset address of the TCP header */
+
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ if (conn->domain == PF_INET))
+#endif
+ {
+ DEBUGASSERT(IFF_IS_IPv4(dev->d_flags));
+ tcp = TCPIPv4BUF;
+ }
+#endif /* CONFIG_NET_IPv4 */
+
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ else
+#endif
+ {
+ DEBUGASSERT(IFF_IS_IPv6(dev->d_flags));
+ tcp = TCPIPv6BUF;
+ }
+#endif /* CONFIG_NET_IPv6 */
+
+ /* Get the ACK number from the TCP header */
+
+ ackno = tcp_getsequence(tcp->ackno);
nllvdbg("ACK: ackno=%u flags=%04x\n", ackno, flags);
/* Look at every write buffer in the unacked_q. The unacked_q
diff --git a/nuttx/net/tcp/tcp_send_unbuffered.c b/nuttx/net/tcp/tcp_send_unbuffered.c
index f0156c85b..6e7fe3231 100644
--- a/nuttx/net/tcp/tcp_send_unbuffered.c
+++ b/nuttx/net/tcp/tcp_send_unbuffered.c
@@ -78,7 +78,8 @@
# define CONFIG_NET_TCP_SPLIT_SIZE 40
#endif
-#define TCPBUF ((struct tcp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define TCPIPv4BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
+#define TCPIPv6BUF ((struct tcp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
/****************************************************************************
* Private Types
@@ -232,19 +233,43 @@ static uint16_t tcpsend_interrupt(FAR struct net_driver_s *dev,
if ((flags & TCP_ACKDATA) != 0)
{
+ FAR struct tcp_hdr_s *tcp;
+
/* Update the timeout */
#ifdef CONFIG_NET_SOCKOPTS
pstate->snd_time = clock_systimer();
#endif
+ /* Get the offset address of the TCP header */
+
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ if (conn->domain == PF_INET))
+#endif
+ {
+ DEBUGASSERT(IFF_IS_IPv4(dev->d_flags));
+ tcp = TCPIPv4BUF;
+ }
+#endif /* CONFIG_NET_IPv4 */
+
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ else
+#endif
+ {
+ DEBUGASSERT(IFF_IS_IPv6(dev->d_flags));
+ tcp = TCPIPv6BUF;
+ }
+#endif /* CONFIG_NET_IPv6 */
+
/* The current acknowledgement number number is the (relative) offset
* of the of the next byte needed by the receiver. The snd_isn is the
* offset of the first byte to send to the receiver. The difference
* is the number of bytes to be acknowledged.
*/
- pstate->snd_acked = tcp_getsequence(TCPBUF->ackno) - pstate->snd_isn;
+ pstate->snd_acked = tcp_getsequence(tcp->ackno) - pstate->snd_isn;
nllvdbg("ACK: acked=%d sent=%d buflen=%d\n",
pstate->snd_acked, pstate->snd_sent, pstate->snd_buflen);
diff --git a/nuttx/net/udp/udp.h b/nuttx/net/udp/udp.h
index 2b5c0dba1..f20ebf377 100644
--- a/nuttx/net/udp/udp.h
+++ b/nuttx/net/udp/udp.h
@@ -96,7 +96,6 @@ extern "C"
****************************************************************************/
struct net_driver_s; /* Forward reference */
-struct udp_iphdr_s; /* Forward reference */
/* Defined in udp_conn.c ****************************************************/
/****************************************************************************
diff --git a/nuttx/net/udp/udp_conn.c b/nuttx/net/udp/udp_conn.c
index 5895b98ed..acce00d24 100644
--- a/nuttx/net/udp/udp_conn.c
+++ b/nuttx/net/udp/udp_conn.c
@@ -66,8 +66,8 @@
* Pre-processor Definitions
****************************************************************************/
-#define IPv4BUF ((struct net_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#define IPv6BUF ((struct net_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
/****************************************************************************
* Private Data
@@ -274,7 +274,7 @@ static uint16_t udp_select_port(void)
static inline FAR struct udp_conn_s *
udp_ipv4_active(FAR struct net_driver_s *dev, FAR struct udp_hdr_s *udp)
{
- FAR struct net_iphdr_s *ip = IPv4BUF;
+ FAR struct ipv4_hdr_s *ip = IPv4BUF;
FAR struct udp_conn_s *conn;
conn = (FAR struct udp_conn_s *)g_active_udp_connections.head;
@@ -342,7 +342,7 @@ static inline FAR struct udp_conn_s *
static inline FAR struct udp_conn_s *
udp_ipv6_active(FAR struct net_driver_s *dev, FAR struct udp_hdr_s *udp)
{
- FAR struct net_ipv6hdr_s *ip = IPv6BUF;
+ FAR struct ipv6_hdr_s *ip = IPv6BUF;
FAR struct udp_conn_s *conn;
conn = (FAR struct udp_conn_s *)g_active_udp_connections.head;
diff --git a/nuttx/net/udp/udp_send.c b/nuttx/net/udp/udp_send.c
index 8ceff0710..7a640888c 100644
--- a/nuttx/net/udp/udp_send.c
+++ b/nuttx/net/udp/udp_send.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/udp/udp_send.c
*
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2009, 2011, 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Adapted for NuttX from logic in uIP which also has a BSD-like license:
@@ -63,7 +63,11 @@
* Pre-processor Definitions
****************************************************************************/
-#define UDPBUF ((struct udp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+
+#define UDPIPv4BUF ((struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv4_HDRLEN])
+#define UDPIPv6BUF ((struct udp_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev) + IPv6_HDRLEN])
/****************************************************************************
* Public Variables
@@ -99,80 +103,114 @@
*
****************************************************************************/
-void udp_send(struct net_driver_s *dev, struct udp_conn_s *conn)
+void udp_send(FAR struct net_driver_s *dev, FAR struct udp_conn_s *conn)
{
- FAR struct udp_iphdr_s *pudpbuf = UDPBUF;
+ FAR struct udp_hdr_s *udp;
if (dev->d_sndlen > 0)
{
- /* The total length to send is the size of the application data plus
- * the IP and UDP headers (and, eventually, the Ethernet header)
- */
+ /* Initialize the IP header. */
- dev->d_len = dev->d_sndlen + IPv4UDP_HDRLEN;
+#ifdef CONFIG_NET_IPv4
+#ifdef CONFIG_NET_IPv6
+ if (conn->domain == PF_INET)
+#endif
+ {
+ /* Get pointers to the IPv4 header and the offset TCP header */
- /* Initialize the IP header. Note that for IPv6, the IP length field
- * does not include the IPv6 IP header length.
- */
+ FAR struct ipv4_hdr_s *ipv4 = IPv4BUF;
-#ifdef CONFIG_NET_IPv6
+ DEBUGASSERT(IFF_IS_IPv4(dev->d_flags));
+ udp = UDPIPv4BUF;
+
+ /* Initialize the IPv4 header. */
+
+ ipv4->vhl = 0x45;
+ ipv4->tos = 0;
+ ipv4->len[0] = (dev->d_len >> 8);
+ ipv4->len[1] = (dev->d_len & 0xff);
+ ++g_ipid;
+ ipv4->ipid[0] = g_ipid >> 8;
+ ipv4->ipid[1] = g_ipid & 0xff;
+ ipv4->ipoffset[0] = 0;
+ ipv4->ipoffset[1] = 0;
+ ipv4->ttl = conn->ttl;
+ ipv4->proto = IP_PROTO_UDP;
+
+ net_ipv4addr_hdrcopy(ipv4->srcipaddr, &dev->d_ipaddr);
+ net_ipv4addr_hdrcopy(ipv4->destipaddr, &conn->u.ipv4.raddr);
+
+ /* Calculate IP checksum. */
- pudpbuf->vtc = 0x60;
- pudpbuf->tcf = 0x00;
- pudpbuf->flow = 0x00;
- pudpbuf->len[0] = (dev->d_sndlen >> 8);
- pudpbuf->len[1] = (dev->d_sndlen & 0xff);
- pudpbuf->proto = IP_PROTO_UDP;
- pudpbuf->ttl = conn->ttl;
+ ipv4->ipchksum = 0;
+ ipv4->ipchksum = ~ipv4_chksum(dev);
- net_ipv6addr_copy(pudpbuf->srcipaddr, &dev->d_ipaddr);
- net_ipav6ddr_copy(pudpbuf->destipaddr, &conn->u.ipv4.raddr);
+ /* The total length to send is the size of the application data
+ * plus the IPv4 and UDP headers (and, eventually, the link layer
+ * header)
+ */
-#else /* CONFIG_NET_IPv6 */
+ dev->d_len = dev->d_sndlen + IPv4UDP_HDRLEN;
+ }
+#endif /* CONFIG_NET_IPv4 */
+
+#ifdef CONFIG_NET_IPv6
+#ifdef CONFIG_NET_IPv4
+ else
+#endif
+ {
+ /* Get pointers to the IPv6 header and the offset TCP header */
- pudpbuf->vhl = 0x45;
- pudpbuf->tos = 0;
- pudpbuf->len[0] = (dev->d_len >> 8);
- pudpbuf->len[1] = (dev->d_len & 0xff);
- ++g_ipid;
- pudpbuf->ipid[0] = g_ipid >> 8;
- pudpbuf->ipid[1] = g_ipid & 0xff;
- pudpbuf->ipoffset[0] = 0;
- pudpbuf->ipoffset[1] = 0;
- pudpbuf->ttl = conn->ttl;
- pudpbuf->proto = IP_PROTO_UDP;
+ FAR struct ipv6_hdr_s *ipv6 = IPv6BUF;
- net_ipv4addr_hdrcopy(pudpbuf->srcipaddr, &dev->d_ipaddr);
- net_ipv4addr_hdrcopy(pudpbuf->destipaddr, &conn->u.ipv4.raddr);
+ DEBUGASSERT(IFF_IS_IPv6(dev->d_flags));
+ udp = UDPIPv6BUF;
- /* Calculate IP checksum. */
+ /* Initialize the IPv6 header. Note that the IP length field
+ * does not include the IPv6 IP header length.
+ */
- pudpbuf->ipchksum = 0;
- pudpbuf->ipchksum = ~(ipv4_chksum(dev));
+ ipv6->vtc = 0x60;
+ ipv6->tcf = 0x00;
+ ipv6->flow = 0x00;
+ ipv6->len[0] = (dev->d_sndlen >> 8);
+ ipv6->len[1] = (dev->d_sndlen & 0xff);
+ ipv6->proto = IP_PROTO_UDP;
+ ipv6->ttl = conn->ttl;
+ net_ipv6addr_copy(ipv6->srcipaddr, dev->d_ipv6addr);
+ net_ipv6addr_copy(ipv6->destipaddr, conn->u.ipv6.raddr);
+
+ /* The total length to send is the size of the application data
+ * plus the IPv4 and UDP headers (and, eventually, the link layer
+ * header)
+ */
+
+ dev->d_len = dev->d_sndlen + IPv6UDP_HDRLEN;
+ }
#endif /* CONFIG_NET_IPv6 */
/* Initialize the UDP header */
- pudpbuf->srcport = conn->lport;
- pudpbuf->destport = conn->rport;
- pudpbuf->udplen = HTONS(dev->d_sndlen + UDP_HDRLEN);
+ udp->srcport = conn->lport;
+ udp->destport = conn->rport;
+ udp->udplen = HTONS(dev->d_sndlen + UDP_HDRLEN);
#ifdef CONFIG_NET_UDP_CHECKSUMS
/* Calculate UDP checksum. */
- pudpbuf->udpchksum = 0;
- pudpbuf->udpchksum = ~(udp_chksum(dev));
- if (pudpbuf->udpchksum == 0)
+ udp->udpchksum = 0;
+ udp->udpchksum = ~(udp_chksum(dev));
+ if (udp->udpchksum == 0)
{
- pudpbuf->udpchksum = 0xffff;
+ udp->udpchksum = 0xffff;
}
#else
- pudpbuf->udpchksum = 0;
+ udp->udpchksum = 0;
#endif
nllvdbg("Outgoing UDP packet length: %d (%d)\n",
- dev->d_len, (pudpbuf->len[0] << 8) | pudpbuf->len[1]);
+ dev->d_len, (udp->len[0] << 8) | udp->len[1]);
#ifdef CONFIG_NET_STATISTICS
g_netstats.udp.sent++;
@@ -180,5 +218,4 @@ void udp_send(struct net_driver_s *dev, struct udp_conn_s *conn)
#endif
}
}
-
#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/utils/Kconfig b/nuttx/net/utils/Kconfig
index 112b257e2..5ba6ffe3e 100644
--- a/nuttx/net/utils/Kconfig
+++ b/nuttx/net/utils/Kconfig
@@ -21,6 +21,6 @@ config NET_ARCH_CHKSUM
uint16_t net_chksum(FAR uint16_t *data, uint16_t len)
uint16_t ipv4_chksum(FAR struct net_driver_s *dev)
- uint16_t ipv6_chksum(FAR struct net_driver_s *dev)
- uint16_t tcp_chksum(FAR struct net_driver_s *dev);
+ uint16_t tcp_ipv4_chksum(FAR struct net_driver_s *dev);
+ uint16_t tcp_ipv6_chksum(FAR struct net_driver_s *dev);
uint16_t udp_chksum(FAR struct net_driver_s *dev);
diff --git a/nuttx/net/utils/net_chksum.c b/nuttx/net/utils/net_chksum.c
index 03e07fb47..033aa7e59 100644
--- a/nuttx/net/utils/net_chksum.c
+++ b/nuttx/net/utils/net_chksum.c
@@ -54,8 +54,8 @@
* Pre-processor Definitions
****************************************************************************/
-#define IPv4BUF ((struct net_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
-#define IPv6BUF ((struct net_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv4BUF ((struct ipv4_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
+#define IPv6BUF ((struct ipv6_hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
#define ICMPBUF ((struct icmp_iphdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
#define ICMPv6BUF ((struct icmp_ipv6hdr_s *)&dev->d_buf[NET_LL_HDRLEN(dev)])
@@ -119,7 +119,7 @@ static uint16_t chksum(uint16_t sum, FAR const uint8_t *data, uint16_t len)
static uint16_t ipv4_upperlayer_chksum(FAR struct net_driver_s *dev,
uint8_t proto)
{
- FAR struct net_iphdr_s *pbuf = IPv4BUF;
+ FAR struct ipv4_hdr_s *pbuf = IPv4BUF;
uint16_t upperlen;
uint16_t sum;
@@ -157,7 +157,7 @@ static uint16_t ipv4_upperlayer_chksum(FAR struct net_driver_s *dev,
static uint16_t ipv6_upperlayer_chksum(FAR struct net_driver_s *dev,
uint8_t proto)
{
- FAR struct net_ipv6hdr_s *pbuf = IPv6BUF;
+ FAR struct ipv6_hdr_s *pbuf = IPv6BUF;
uint16_t upperlen;
uint16_t sum;
@@ -314,34 +314,7 @@ uint16_t ipv4_chksum(FAR struct net_driver_s *dev)
#endif /* CONFIG_NET_ARCH_CHKSUM */
/****************************************************************************
- * Name: ipv6_chksum
- *
- * Description:
- * Calculate the IPv6 header checksum of the packet header in d_buf.
- *
- * The IPv6 header checksum is the Internet checksum of the 40 bytes of
- * the IPv6 header.
- *
- * If CONFIG_NET_ARCH_CHKSUM is defined, then this function must be
- * provided by architecture-specific logic.
- *
- * Returned Value:
- * The IPv6 header checksum of the IPv6 header in the d_buf buffer.
- *
- ****************************************************************************/
-
-#if defined(CONFIG_NET_IPv6) && !defined(CONFIG_NET_ARCH_CHKSUM)
-uint16_t ipv6_chksum(FAR struct net_driver_s *dev)
-{
- uint16_t sum;
-
- sum = chksum(0, &dev->d_buf[NET_LL_HDRLEN(dev)], IPv6_HDRLEN);
- return (sum == 0) ? 0xffff : htons(sum);
-}
-#endif /* CONFIG_NET_ARCH_CHKSUM */
-
-/****************************************************************************
- * Name: tcp_chksum
+ * Name: tcp_chksum, tcp_ipv4_chksum, and tcp_ipv6_chksum
*
* Description:
* Calculate the TCP checksum of the packet in d_buf and d_appdata.
@@ -360,26 +333,34 @@ uint16_t ipv6_chksum(FAR struct net_driver_s *dev)
****************************************************************************/
#if !CONFIG_NET_ARCH_CHKSUM
-uint16_t tcp_chksum(FAR struct net_driver_s *dev)
+#ifdef CONFIG_NET_IPv4
+uint16_t tcp_ipv4_chksum(FAR struct net_driver_s *dev)
+{
+ return ipv4_upperlayer_chksum(dev, IP_PROTO_TCP);
+}
+#endif /* CONFIG_NET_IPv4 */
+
+#ifdef CONFIG_NET_IPv6
+uint16_t tcp_ipv6_chksum(FAR struct net_driver_s *dev)
{
+ return ipv6_upperlayer_chksum(dev, IP_PROTO_TCP);
+}
+#endif /* CONFIG_NET_IPv6 */
+#endif /* !CONFIG_NET_ARCH_CHKSUM */
+
#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6)
+uint16_t tcp_chksum(FAR struct net_driver_s *dev)
+{
if (IFF_IS_IPv6(dev->d_flags))
{
- return ipv6_upperlayer_chksum(dev, IP_PROTO_TCP);
+ return tcp_ipv6_chksum(dev);
}
else
{
- return ipv4_upperlayer_chksum(dev, IP_PROTO_TCP);
+ return tcp_ipv4_chksum(dev);
}
-
-#elif defined(CONFIG_NET_IPv4)
- return ipv4_upperlayer_chksum(dev, IP_PROTO_TCP);
-
-#else /* if defined(CONFIG_NET_IPv6) */
- return ipv6_upperlayer_chksum(dev, IP_PROTO_TCP);
-#endif
}
-#endif /* CONFIG_NET_ARCH_CHKSUM */
+#endif
/****************************************************************************
* Name: udp_chksum
diff --git a/nuttx/net/utils/utils.h b/nuttx/net/utils/utils.h
index 76401a27a..6eabf097e 100644
--- a/nuttx/net/utils/utils.h
+++ b/nuttx/net/utils/utils.h
@@ -139,7 +139,7 @@ unsigned int net_dsec2tick(int dsec);
unsigned int net_timeval2dsec(FAR struct timeval *tv);
/****************************************************************************
- * Name: tcp_chksum
+ * Name: tcp_chksum, tcp_ipv4_chksum, and tcp_ipv6_chksum
*
* Description:
* Calculate the TCP checksum of the packet in d_buf and d_appdata.
@@ -157,7 +157,23 @@ unsigned int net_timeval2dsec(FAR struct timeval *tv);
*
****************************************************************************/
+#ifdef CONFIG_NET_IPv4
+uint16_t tcp_ipv4_chksum(FAR struct net_driver_s *dev);
+#endif
+
+#ifdef CONFIG_NET_IPv6
+/* REVIST: Is this used? */
+uint16_t tcp_ipv6_chksum(FAR struct net_driver_s *dev);
+#endif
+
+#if defined(CONFIG_NET_IPv4) && defined(CONFIG_NET_IPv6)
uint16_t tcp_chksum(FAR struct net_driver_s *dev);
+#elif defined(CONFIG_NET_IPv4)
+# define tcp_chksum(d) tcp_ipv4_chksum(d)
+#else /* if defined(CONFIG_NET_IPv6) */
+# define tcp_chksum(d) tcp_ipv6_chksum(d)
+#endif
+
/****************************************************************************
* Name: udp_chksum