summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/sim/src/up_tapdev.c2
-rw-r--r--nuttx/arch/sim/src/up_uipdriver.c2
-rw-r--r--nuttx/configs/sim/defconfig2
-rw-r--r--nuttx/include/arpa/inet.h2
-rw-r--r--nuttx/include/net/uip/uip-arch.h45
-rw-r--r--nuttx/include/net/uip/uip.h225
-rw-r--r--nuttx/include/netinet/in.h58
-rw-r--r--nuttx/include/netinet/ip6.h54
-rw-r--r--nuttx/include/nuttx/net.h20
-rw-r--r--nuttx/include/sys/socket.h23
-rw-r--r--nuttx/net/Makefile1
-rw-r--r--nuttx/net/bind.c25
-rw-r--r--nuttx/net/connect.c74
-rw-r--r--nuttx/net/net_internal.h2
-rw-r--r--nuttx/net/socket.c16
-rw-r--r--nuttx/net/uip/Make.defs2
-rw-r--r--nuttx/net/uip/uip-internal.h86
-rw-r--r--nuttx/net/uip/uip-tcpconn.c405
-rw-r--r--nuttx/net/uip/uip-udpconn.c170
-rw-r--r--nuttx/net/uip/uip.c565
-rw-r--r--nuttx/netutils/resolv/resolv.c1
-rw-r--r--nuttx/netutils/smtp/smtp.c44
-rw-r--r--nuttx/netutils/webclient/webclient.c42
-rw-r--r--nuttx/netutils/webserver/httpd-cgi.c162
-rw-r--r--nuttx/tools/mkconfig.c23
25 files changed, 1426 insertions, 625 deletions
diff --git a/nuttx/arch/sim/src/up_tapdev.c b/nuttx/arch/sim/src/up_tapdev.c
index dd7cbde2c..f07b118e6 100644
--- a/nuttx/arch/sim/src/up_tapdev.c
+++ b/nuttx/arch/sim/src/up_tapdev.c
@@ -198,7 +198,7 @@ void tapdev_init(void)
struct ifreq ifr;
memset(&ifr, 0, sizeof(ifr));
ifr.ifr_flags = IFF_TAP|IFF_NO_PI;
- if (up_ioctl(gtapdevfd, TUNSETIFF, (void *) &ifr) < 0)
+ if (up_ioctl(gtapdevfd, TUNSETIFF, (unsigned long *) &ifr) < 0)
{
lib_rawprintf(buf);
return;
diff --git a/nuttx/arch/sim/src/up_uipdriver.c b/nuttx/arch/sim/src/up_uipdriver.c
index ea6d349ae..a54063ea2 100644
--- a/nuttx/arch/sim/src/up_uipdriver.c
+++ b/nuttx/arch/sim/src/up_uipdriver.c
@@ -145,7 +145,7 @@ void uipdriver_loop(void)
timer_reset(&periodic_timer);
for(i = 0; i < UIP_CONNS; i++)
{
- uip_periodic(i);
+ uip_tcppoll(i);
/* If the above function invocation resulted in data that
* should be sent out on the network, the global variable
diff --git a/nuttx/configs/sim/defconfig b/nuttx/configs/sim/defconfig
index 8dff468a9..3d363786f 100644
--- a/nuttx/configs/sim/defconfig
+++ b/nuttx/configs/sim/defconfig
@@ -231,7 +231,7 @@ CONFIG_FS_FAT=y
# CONFIG_NET_FWCACHE_SIZE - number of packets to remember when looking for duplicates
CONFIG_NET=n
CONFIG_NET_IPv6=n
-CONFIG_NSOCKET_DESCRIPTORS=8
+CONFIG_NSOCKET_DESCRIPTORS=0
CONFIG_NET_MAX_CONNECTIONS=40
CONFIG_NET_MAX_LISTENPORTS=40
CONFIG_NET_BUFFER_SIZE=420
diff --git a/nuttx/include/arpa/inet.h b/nuttx/include/arpa/inet.h
index 74e3bbda4..d97ee9ff5 100644
--- a/nuttx/include/arpa/inet.h
+++ b/nuttx/include/arpa/inet.h
@@ -64,7 +64,7 @@
# define HTONS(ns) \
(uint16)((((uint16) (ns)) << 8) | (((uint16) (ns)) >> 8))
# define HTONL(nl) htonl(nl) \
- ((uint32)HTONS((uint16)((hs) << 16)) | (uint32)HTONS((uint16)((hs) & 0xffff)))
+ (((uint32)HTONS((uint16)((hs) & 0xffff)) << 16) | (uint32)HTONS((uint16)((uint16)((hs) >> 16))))
#endif
#define NTOHS(hs) HTONS(hs)
diff --git a/nuttx/include/net/uip/uip-arch.h b/nuttx/include/net/uip/uip-arch.h
index e0cbb84f2..31552e082 100644
--- a/nuttx/include/net/uip/uip-arch.h
+++ b/nuttx/include/net/uip/uip-arch.h
@@ -141,38 +141,39 @@
* The ususal way of calling the function is through a for() loop like
* this:
*
- * for(i = 0; i < UIP_CONNS; ++i) {
- * uip_periodic(i);
- * if(uip_len > 0) {
- * devicedriver_send();
+ * for(i = 0; i < UIP_CONNS; ++i)
+ * {
+ * uip_tcppoll(i);
+ * if (uip_len > 0)
+ * {
+ * devicedriver_send();
+ * }
* }
- * }
*
* Note: If you are writing a uIP device driver that needs ARP
* (Address Resolution Protocol), e.g., when running uIP over
* Ethernet, you will need to call the uip_arp_out() function before
* calling the device driver:
*
- * for(i = 0; i < UIP_CONNS; ++i) {
- * uip_periodic(i);
- * if(uip_len > 0) {
- * uip_arp_out();
- * ethernet_devicedriver_send();
+ * for(i = 0; i < UIP_CONNS; ++i)
+ * {
+ * uip_tcppoll(i);
+ * if (uip_len > 0)
+ * {
+ * uip_arp_out();
+ * ethernet_devicedriver_send();
+ * }
* }
- * }
*
* conn The number of the connection which is to be periodically polled.
*/
-#define uip_periodic(conn) do { uip_conn = &uip_conns[conn]; \
- uip_interrupt(UIP_TIMER); } while (0)
-
-#define uip_conn_active(conn) (uip_conns[conn].tcpstateflags != UIP_CLOSED)
+extern void uip_tcppoll( unsigned int conn );
/* Perform periodic processing for a connection identified by a pointer
* to its structure.
*
- * Same as uip_periodic() but takes a pointer to the actual uip_conn
+ * Same as uip_tcppoll() but takes a pointer to the actual uip_conn
* struct instead of an integer as its argument. This function can be
* used to force periodic processing of a specific connection.
*
@@ -180,11 +181,11 @@
* be processed.
*/
-#define uip_periodic_conn(conn) do { uip_conn = conn; uip_interrupt(UIP_TIMER); } while (0)
+#define uip_tcppoll_conn(conn) do { uip_conn = conn; uip_interrupt(UIP_TIMER); } while (0)
/* Request that a particular connection should be polled.
*
- * Similar to uip_periodic_conn() but does not perform any timer
+ * Similar to uip_tcppoll_conn() but does not perform any timer
* processing. The application is polled for new data.
*
* conn A pointer to the uip_conn struct for the connection to
@@ -197,9 +198,9 @@
#ifdef CONFIG_NET_UDP
/* Periodic processing for a UDP connection identified by its number.
*
- * This function is essentially the same as uip_periodic(), but for
+ * This function is essentially the same as uip_tcppoll(), but for
* UDP connections. It is called in a similar fashion as the
- * uip_periodic() function:
+ * uip_tcppoll() function:
*
* for(i = 0; i < UIP_UDP_CONNS; i++) {
* uip_udp_periodic(i);
@@ -208,7 +209,7 @@
* }
* }
*
- * Note: As for the uip_periodic() function, special care has to be
+ * Note: As for the uip_tcppoll() function, special care has to be
* taken when using uIP together with ARP and Ethernet:
*
* for(i = 0; i < UIP_UDP_CONNS; i++) {
@@ -287,9 +288,7 @@ extern void uip_interrupt(uint8 flag);
* op16 A 16-bit integer in host byte order.
*/
-#if UIP_ARCH_ADD32
extern void uip_add32(uint8 *op32, uint16 op16);
-#endif
/* Calculate the Internet checksum over a buffer.
*
diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h
index 043d6d377..6815e3527 100644
--- a/nuttx/include/net/uip/uip.h
+++ b/nuttx/include/net/uip/uip.h
@@ -86,17 +86,18 @@
/* The TCP states used in the uip_conn->tcpstateflags. */
-#define UIP_CLOSED 0
-#define UIP_SYN_RCVD 1
-#define UIP_SYN_SENT 2
-#define UIP_ESTABLISHED 3
-#define UIP_FIN_WAIT_1 4
-#define UIP_FIN_WAIT_2 5
-#define UIP_CLOSING 6
-#define UIP_TIME_WAIT 7
-#define UIP_LAST_ACK 8
-#define UIP_TS_MASK 15
+#define UIP_CLOSED 0 /* The connection is not in use and available */
+#define UIP_ALLOCATED 1 /* The connection is allocated, but not yet initialized */
+#define UIP_SYN_RCVD 2
+#define UIP_SYN_SENT 3
+#define UIP_ESTABLISHED 4
+#define UIP_FIN_WAIT_1 5
+#define UIP_FIN_WAIT_2 6
+#define UIP_CLOSING 7
+#define UIP_TIME_WAIT 8
+#define UIP_LAST_ACK 9
+#define UIP_TS_MASK 15
#define UIP_STOPPED 16
/* The buffer size available for user data in the \ref uip_buf buffer.
@@ -112,18 +113,19 @@
#define UIP_APPDATA_SIZE (UIP_BUFSIZE - UIP_LLH_LEN - UIP_TCPIP_HLEN)
-
#define UIP_PROTO_ICMP 1
#define UIP_PROTO_TCP 6
#define UIP_PROTO_UDP 17
#define UIP_PROTO_ICMP6 58
/* Header sizes. */
+
#ifdef CONFIG_NET_IPv6
# define UIP_IPH_LEN 40
#else /* CONFIG_NET_IPv6 */
# define UIP_IPH_LEN 20 /* Size of IP header */
#endif /* CONFIG_NET_IPv6 */
+
#define UIP_UDPH_LEN 8 /* Size of UDP header */
#define UIP_TCPH_LEN 20 /* Size of TCP header */
#define UIP_IPUDPH_LEN (UIP_UDPH_LEN + UIP_IPH_LEN) /* Size of IP + UDP header */
@@ -188,7 +190,7 @@ struct uip_conn
void *private;
};
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
/* Representation of a uIP UDP connection. */
struct uip_udp_conn
@@ -206,13 +208,14 @@ struct uip_udp_conn
};
#endif /* CONFIG_NET_UDP */
-/**
- * The structure holding the TCP/IP statistics that are gathered if
+/* The structure holding the TCP/IP statistics that are gathered if
* UIP_STATISTICS is set to 1.
- *
*/
-struct uip_stats {
- struct {
+
+struct uip_stats
+{
+ struct
+ {
uip_stats_t drop; /* Number of dropped packets at the IP layer. */
uip_stats_t recv; /* Number of received packets at the IP layer. */
uip_stats_t sent; /* Number of sent packets at the IP layer. */
@@ -229,13 +232,15 @@ struct uip_stats {
uip_stats_t protoerr; /* Number of packets dropped since they
were neither ICMP, UDP nor TCP. */
} ip; /* IP statistics. */
- struct {
+ struct
+ {
uip_stats_t drop; /* Number of dropped ICMP packets. */
uip_stats_t recv; /* Number of received ICMP packets. */
uip_stats_t sent; /* Number of sent ICMP packets. */
uip_stats_t typeerr; /* Number of ICMP packets with a wrong type. */
} icmp; /* ICMP statistics. */
- struct {
+ struct
+ {
uip_stats_t drop; /* Number of dropped TCP segments. */
uip_stats_t recv; /* Number of recived TCP segments. */
uip_stats_t sent; /* Number of sent TCP segments. */
@@ -248,8 +253,9 @@ struct uip_stats {
uip_stats_t synrst; /* Number of SYNs for closed ports,
triggering a RST. */
} tcp; /* TCP statistics. */
- #ifdef CONFIG_NET_UDP
- struct {
+#ifdef CONFIG_NET_UDP
+ struct
+ {
uip_stats_t drop; /* Number of dropped UDP segments. */
uip_stats_t recv; /* Number of recived UDP segments. */
uip_stats_t sent; /* Number of sent UDP segments. */
@@ -260,70 +266,76 @@ struct uip_stats {
/* The TCP and IP headers. */
-struct uip_tcpip_hdr {
+struct uip_tcpip_hdr
+{
#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
- uint8 vtc,
- tcflow;
+ uint8 vtc;
+ uint8 tcflow;
uint16 flow;
uint8 len[2];
uint8 proto, ttl;
uip_ip6addr_t srcipaddr, destipaddr;
+
#else /* CONFIG_NET_IPv6 */
/* IPv4 header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
+ uint16 srcipaddr[2];
+ uint16 destipaddr[2];
#endif /* CONFIG_NET_IPv6 */
/* TCP header. */
- uint16 srcport,
- destport;
- uint8 seqno[4],
- ackno[4],
- tcpoffset,
- flags,
- wnd[2];
+ uint16 srcport;
+ uint16 destport;
+ uint8 seqno[4];
+ uint8 ackno[4];
+ uint8 tcpoffset;
+ uint8 flags;
+ uint8 wnd[2];
uint16 tcpchksum;
- uint8 urgp[2];
- uint8 optdata[4];
+ uint8 urgp[2];
+ uint8 optdata[4];
};
/* The ICMP and IP headers. */
-struct uip_icmpip_hdr {
+struct uip_icmpip_hdr
+{
#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
- uint8 vtc,
- tcf;
+ uint8 vtc;
+ uint8 tcf;
uint16 flow;
- uint8 len[2];
- uint8 proto, ttl;
- uip_ip6addr_t srcipaddr, destipaddr;
+ uint8 len[2];
+ uint8 proto;
+ uint8 ttl;
+ uip_ip6addr_t srcipaddr;
+ uip_ip6addr_t destipaddr;
+
#else /* CONFIG_NET_IPv6 */
/* IPv4 header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
+ uint16 srcipaddr[2];
+ uint16 destipaddr[2];
#endif /* CONFIG_NET_IPv6 */
/* ICMP (echo) header. */
@@ -340,42 +352,45 @@ struct uip_icmpip_hdr {
/* The UDP and IP headers. */
-struct uip_udpip_hdr {
+struct uip_udpip_hdr
+{
#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
- uint8 vtc,
- tcf;
+ uint8 vtc;
+ uint8 tcf;
uint16 flow;
uint8 len[2];
uint8 proto, ttl;
- uip_ip6addr_t srcipaddr, destipaddr;
+ uip_ip6addr_t srcipaddr;
+ uip_ip6addr_t destipaddr;
#else /* CONFIG_NET_IPv6 */
/* IP header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
+ uint16 srcipaddr[2];
+ uint16 destipaddr[2];
#endif /* CONFIG_NET_IPv6 */
/* UDP header. */
- uint16 srcport,
- destport;
+ uint16 srcport;
+ uint16 destport;
uint16 udplen;
uint16 udpchksum;
};
/* Representation of a 48-bit Ethernet address. */
-struct uip_eth_addr {
+struct uip_eth_addr
+{
uint8 addr[6];
};
@@ -463,16 +478,13 @@ extern uint16 uip_urglen, uip_surglen;
extern struct uip_conn *uip_conn;
-/* The array containing all uIP connections. */
-extern struct uip_conn uip_conns[UIP_CONNS];
-
/* 4-byte array used for the 32-bit sequence number calculations.*/
extern uint8 uip_acc32[4];
/* The current UDP connection. */
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
extern struct uip_udp_conn *uip_udp_conn;
extern struct uip_udp_conn uip_udp_conns[UIP_UDP_CONNS];
#endif /* CONFIG_NET_UDP */
@@ -601,9 +613,27 @@ void uip_setipid(uint16 id);
* detected that may be of interest to the application.
*/
-void uip_interrupt_event(void);
- #ifdef CONFIG_NET_UDP
-void uip_interrupt_udp_event(void);
+extern void uip_interrupt_event(void);
+#ifdef CONFIG_NET_UDP
+extern void uip_interrupt_udp_event(void);
+#endif
+
+/* Find a free connection structure and allocate it for use. This is
+ * normally something done by the implementation of the socket() API
+ */
+
+extern struct uip_conn *uip_tcpalloc(void);
+#ifdef CONFIG_NET_UDP
+extern struct uip_udp_conn *uip_udpalloc(void);
+#endif
+
+/* Free a connection structure that is no longer in use. This should
+ * be done by the implementation of close()
+ */
+
+extern void uip_tcpfree(struct uip_conn *conn);
+#ifdef CONFIG_NET_UDP
+extern void uip_udpfree(struct uip_udp_conn *conn);
#endif
/* Start listening to the specified port.
@@ -626,37 +656,6 @@ void uip_listen(uint16 port);
void uip_unlisten(uint16 port);
-/* Connect to a remote host using TCP.
- *
- * This function is used to start a new connection to the specified
- * port on the specied host. It allocates a new connection identifier,
- * sets the connection to the SYN_SENT state and sets the
- * retransmission timer to 0. This will cause a TCP SYN segment to be
- * sent out the next time this connection is periodically processed,
- * which usually is done within 0.5 seconds after the call to
- * uip_connect().
- *
- * Note: Since this function requires the port number to be in network
- * byte order, a conversion using HTONS() or htons() is necessary.
- *
- * Example:
- *
- * uip_ipaddr_t ipaddr;
- *
- * uip_ipaddr(&ipaddr, 192,168,1,2);
- * uip_connect(&ipaddr, HTONS(80));
- *
- * ripaddr The IP address of the remote hot.
- *
- * port A 16-bit port number in network byte order.
- *
- * Return: A pointer to the uIP connection identifier for the new connection,
- * or NULL if no connection could be allocated.
- */
-
-struct uip_conn *uip_connect(uip_ipaddr_t *ripaddr, uint16 port);
-
-
/* Check if a connection has outstanding (i.e., unacknowledged) data.
*
* conn A pointer to the uip_conn structure for the connection.
@@ -837,7 +836,7 @@ void uip_send(const void *data, int len);
* connection.
*/
-#define uip_initialmss() (uip_conn->initialmss)
+#define uip_initialmss() (uip_conn->initialmss)
/* Get the current maxium segment size that can be sent on the current
* connection.
@@ -848,7 +847,7 @@ void uip_send(const void *data, int len);
* uip_initialmss()).
*/
-#define uip_mss() (uip_conn->mss)
+#define uip_mss() (uip_conn->mss)
/* Set up a new UDP connection.
*
diff --git a/nuttx/include/netinet/in.h b/nuttx/include/netinet/in.h
index e2ed78363..dd518388a 100644
--- a/nuttx/include/netinet/in.h
+++ b/nuttx/include/netinet/in.h
@@ -43,34 +43,68 @@
#include <sys/types.h>
/****************************************************************************
- * Public Type Definitions
+ * Public Macro Definitions
****************************************************************************/
-/* Address to accept any incoming messages. */
-#define INADDR_ANY ((in_addr_t)0x00000000)
+/* Values for protocol argument to socket() */
+
+#define IPPROTO_TCP 1
+#define IPPROTO_UDP 2
+
+/* Special values of in_addr_t */
+
+#define INADDR_ANY ((in_addr_t)0x00000000) /* Address to accept any incoming messages */
+#define INADDR_BROADCAST ((in_addr_t)0xffffffff) /* Address to send to all hosts */
+#define INADDR_NONE ((in_addr_t)0xffffffff) /* Address indicating an error return */
+
+#define IN6ADDR_ANY_INIT {{{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}}}
-/* Address to send to all hosts. */
-#define INADDR_BROADCAST ((in_addr_t)0xffffffff)
+/* struct in6_addr union selectors */
-/* Address indicating an error return. */
-#define INADDR_NONE ((in_addr_t)0xffffffff)
+#define s6_addr in6_u.u6_addr8
+#define s6_addr16 in6_u.u6_addr16
+#define s6_addr32 in6_u.u6_addr32
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
/****************************************************************************
* Public Type Definitions
****************************************************************************/
-/* Internet address. */
+/* IPv4 Internet address */
+
typedef uint32 in_addr_t;
struct in_addr
{
- in_addr_t s_addr; /* address in network byte order */
+ in_addr_t s_addr; /* Address (network byte order) */
};
struct sockaddr_in
{
- sa_family_t sin_family; /* address family: AF_INET */
- uint16 sin_port; /* port in network byte order */
- struct in_addr sin_addr; /* internet address */
+ sa_family_t sin_family; /* address family: AF_INET */
+ uint16 sin_port; /* port in network byte order */
+ struct in_addr sin_addr; /* internet address */
+};
+
+/* IPv6 Internet address */
+
+struct in6_addr
+{
+ union
+ {
+ uint8 u6_addr8[16];
+ uint16 u6_addr16[8];
+ uint32 u6_addr32[4];
+ } in6_u;
+};
+
+struct sockaddr_in6
+{
+ sa_family_t sin_family; /* Address family: AF_INET */
+ uint16 sin_port; /* Port in network byte order */
+ struct in6_addr sin6_addr; /* IPv6 internet address */
};
/****************************************************************************
diff --git a/nuttx/include/netinet/ip6.h b/nuttx/include/netinet/ip6.h
new file mode 100644
index 000000000..cc6a5295c
--- /dev/null
+++ b/nuttx/include/netinet/ip6.h
@@ -0,0 +1,54 @@
+/****************************************************************************
+ * netinet/ip6.h
+ *
+ * Copyright (C) 2007 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 Gregory Nutt 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.
+ *
+ ****************************************************************************/
+
+#ifndef __NETINET_IP6_H
+#define __NETINET_IP6_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/socket.h>
+#include <netinet/in.h>
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#endif /* __NETINET_IP6_H */
diff --git a/nuttx/include/nuttx/net.h b/nuttx/include/nuttx/net.h
index c51c4f281..bb8ec8da3 100644
--- a/nuttx/include/nuttx/net.h
+++ b/nuttx/include/nuttx/net.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * net.h
+ * nuttx/net.h
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -73,23 +73,9 @@
struct socket
{
- /* Socket state info */
-
- int s_crefs; /* Reference counts on the socket */
+ int s_crefs; /* Reference count on the socket */
uint8 s_type; /* Protocol type: Only SOCK_STREAM or SOCK_DGRAM */
-
- /* Proto-socket */
-
- struct psock s_psock;
-
- /* Connection */
-
- union
- {
- struct uip_udp_conn udp;
- struct uip_conn tcp;
- }
- s_conn;
+ void *s_conn; /* Connection: struct uip_conn * or uip_udp_conn * */
};
/* This defines a list of sockets indexed by the socket descriptor */
diff --git a/nuttx/include/sys/socket.h b/nuttx/include/sys/socket.h
index 0223e0375..589fafe13 100644
--- a/nuttx/include/sys/socket.h
+++ b/nuttx/include/sys/socket.h
@@ -50,6 +50,8 @@
* the protocol family which will be used for communication.
*/
+/* Protocol families */
+
#define PF_UNIX 0 /* Local communication */
#define PF_LOCAL 1 /* Local communication */
#define PF_INET 2 /* IPv4 Internet protocols */
@@ -62,6 +64,20 @@
#define PF_APPLETALK 9 /* Appletalk */
#define PF_PACKET 10 /* Low level packet interface */
+/* Address families */
+
+#define AF_UNIX PF_UNIX
+#define AF_LOCAL PF_LOCAL
+#define AF_INET PF_INET
+#define AF_INET6 PF_INET6
+#define AF_IPX PF_IPX
+#define AF_NETLINK PF_NETLINK
+#define AF_X25 PF_X25
+#define AF_AX25 PF_AX25
+#define AF_ATMPVC PF_ATMPVC
+#define AF_APPLETALK PF_APPLETALK
+#define AF_PACKET PF_PACKET
+
/*The socket created by socket() has the indicated type, which specifies
* the communication semantics.
*/
@@ -100,9 +116,12 @@ extern "C" {
#endif
EXTERN int socket(int domain, int type, int protocol);
-EXTERN int bind(int sockfd, const struct sockaddr *my_addr, socklen_t addrlen);
-EXTERN int connect(int sockfd, const struct sockaddr *serv_addr, socklen_t addrlen);
+EXTERN int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
+EXTERN int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
+EXTERN ssize_t send(int s, const void *buf, size_t len, int flags);
+EXTERN ssize_t sendto(int s, const void *buf, size_t len, int flags,
+ const struct sockaddr *to, socklen_t tolen);
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index 9caa4f8ff..25b5c46df 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -34,6 +34,7 @@
############################################################
-include $(TOPDIR)/Make.defs
+CFLAGS += -I./uip
MKDEP = $(TOPDIR)/tools/mkdeps.sh
diff --git a/nuttx/net/bind.c b/nuttx/net/bind.c
index daeb70a87..332214d33 100644
--- a/nuttx/net/bind.c
+++ b/nuttx/net/bind.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * bind.c
+ * net/bind.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -82,9 +82,14 @@
*
****************************************************************************/
-int bind(int sockfd, const struct sockaddr *my_addr, socklen_t addrlen)
+int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
{
FAR struct socket *psock = sockfd_socket(sockfd);
+#ifdef CONFIG_NET_IPv6
+ FAR const struct sockaddr_in6 *inaddr = (const struct sockaddr_in6 *)addr;
+#else
+ FAR const struct sockaddr_in *inaddr = (const struct sockaddr_in *)addr;
+#endif
int err;
/* Verify that the sockfd corresponds to valid, allocated socket */
@@ -95,16 +100,28 @@ int bind(int sockfd, const struct sockaddr *my_addr, socklen_t addrlen)
goto errout;
}
+ /* Verify that a valid address has been provided */
+
+#ifdef CONFIG_NET_IPv6
+ if (addr->sa_family != AF_INET6 || addrlen < sizeof(struct sockaddr_in6))
+#else
+ if (addr->sa_family != AF_INET || addrlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EBADF;
+ goto errout;
+ }
+
/* Perform the binding depending on the protocol type */
switch (psock->s_type)
{
case SOCK_STREAM:
- /* Put TCP/IP binding logic here */
+#warning Put TCP/IP binding logic here
break;
#ifdef CONFIG_NET_UDP
case SOCK_DGRAM:
- /* Put UDP binding logic here */
+#warning Put UDP binding logic here
break;
#endif
default:
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index 5cff6210e..2fcb8bc79 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * connect.c
+ * net/connect.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -44,6 +44,8 @@
#include <sys/socket.h>
#include <errno.h>
+#include "net_internal.h"
+
/****************************************************************************
* Global Functions
****************************************************************************/
@@ -117,9 +119,75 @@
*
****************************************************************************/
-int connect(int sockfd, const struct sockaddr *serv_addr, socklen_t addrlen)
+int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
{
- *get_errno_ptr() = ENOSYS;
+ FAR struct socket *psock = sockfd_socket(sockfd);
+#ifdef CONFIG_NET_IPv6
+ FAR const struct sockaddr_in6 *inaddr = (const struct sockaddr_in6 *)addr;
+#else
+ FAR const struct sockaddr_in *inaddr = (const struct sockaddr_in *)addr;
+#endif
+ int err;
+
+ /* Verify that the sockfd corresponds to valid, allocated socket */
+
+ if (!psock || psock->s_crefs <= 0)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Verify that a valid address has been provided */
+
+#ifdef CONFIG_NET_IPv6
+ if (addr->sa_family != AF_INET6 || addrlen < sizeof(struct sockaddr_in6))
+#else
+ if (addr->sa_family != AF_INET || addrlen < sizeof(struct sockaddr_in))
+#endif
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Perform the binding depending on the protocol type */
+ switch (psock->s_type)
+ {
+ case SOCK_STREAM:
+ {
+ int ret = uip_tcpconnect(psock->s_conn, inaddr);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+ }
+ break;
+
+#ifdef CONFIG_NET_UDP
+ case SOCK_DGRAM:
+#warning Put UDP connect logic here
+#if 0
+ {
+ int ret = uip_udpconnect(psock->s_conn, inaddr);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
+ }
+ break;
+#endif
+#endif
+ default:
+ err = EBADF;
+ goto errout;
+ }
+
+ err = ENOSYS;
+ /*return OK;*/
+
+errout:
+ *get_errno_ptr() = err;
return ERROR;
}
diff --git a/nuttx/net/net_internal.h b/nuttx/net/net_internal.h
index d45dcef7d..2bc7e4d7d 100644
--- a/nuttx/net/net_internal.h
+++ b/nuttx/net/net_internal.h
@@ -45,6 +45,8 @@
#include <nuttx/net.h>
+#include "net_internal.h"
+
/****************************************************************************
* Definitions
****************************************************************************/
diff --git a/nuttx/net/socket.c b/nuttx/net/socket.c
index 8fe3e395a..ad3ef1e92 100644
--- a/nuttx/net/socket.c
+++ b/nuttx/net/socket.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * socket.c
+ * net/socket.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -129,15 +129,25 @@ int socket(int domain, int type, int protocol)
/* Initialize the socket structure */
-#ifdef CONFIG_NET_UDP
psock = sockfd_socket(sockfd);
if (psock)
{
/* Save the protocol type */
psock->s_type = type;
+
+ /* Allocate a TCP connection structure */
+
+ psock->s_conn = uip_tcpalloc();
+ if (!psock->s_conn)
+ {
+ /* Failed to reserve a connection structure */
+
+ sockfd_release(sockfd);
+ err = ENFILE;
+ goto errout;
+ }
}
-#endif
return sockfd;
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index 85d61d0d9..716682547 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -34,5 +34,5 @@
############################################################################
UIP_ASRCS =
-UIP_CSRCS = psock.c uip-arp.c uip.c uip-fw.c uip-neighbor.c uip-split.c uip-wait.c
+UIP_CSRCS = psock.c uip-arp.c uip.c uip-fw.c uip-neighbor.c uip-split.c uip-tcpconn.c uip-wait.c
diff --git a/nuttx/net/uip/uip-internal.h b/nuttx/net/uip/uip-internal.h
new file mode 100644
index 000000000..987b650c7
--- /dev/null
+++ b/nuttx/net/uip/uip-internal.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ * net/uip/uip-internal.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * This logic was leveraged from uIP which also has a BSD-style license:
+ *
+ * Author Adam Dunkels <adam@dunkels.com>
+ * 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.
+ *
+ ****************************************************************************/
+
+#ifndef __UIP_INTERNAL_H
+#define __UIP_INTERNAL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/types.h>
+
+/****************************************************************************
+ * Public Macro Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* g_tcp_sequence[] is used to generate TCP sequence numbers */
+
+extern uint8 g_tcp_sequence[4];
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/* Defined in uip_tcpconn.c *************************************************/
+
+EXTERN void uip_tcpinit(void);
+EXTERN struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf);
+EXTERN void uip_tcpnextsequence(void);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __UIP_INTERNAL_H */
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
new file mode 100644
index 000000000..c877de2c4
--- /dev/null
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -0,0 +1,405 @@
+/****************************************************************************
+ * uip_tcpbind.c
+ *
+ * Copyright (C) 2007 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 Gregory Nutt 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
+
+#include <sys/types.h>
+#include <string.h>
+#include <arch/irq.h>
+
+#include <net/uip/uipopt.h>
+#include <net/uip/uip.h>
+#include <net/uip/uip-arch.h>
+
+#include "uip-internal.h"
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/* g_tcp_sequence[] is used to generate TCP sequence numbers */
+
+uint8 g_tcp_sequence[4];
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* The array containing all uIP connections. */
+
+static struct uip_conn g_tcp_connections[UIP_CONNS];
+
+/* Last port used by a TCP connection connection. */
+
+static uint16 g_last_tcp_port;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/* Given a port number, find the socket bound to the port number.
+ * Primary use: to determine if a port number is available.
+ */
+
+static struct uip_conn *uip_find_conn(uint16 portno)
+{
+ struct uip_conn *conn;
+ int i;
+
+ /* Check if this port number is already in use, and if so try to find
+ * another one.
+ */
+
+ for (i = 0; i < UIP_CONNS; i++)
+ {
+ conn = &g_tcp_connections[i];
+ if (conn->tcpstateflags != UIP_CLOSED && conn->lport == htons(g_last_tcp_port))
+ {
+ /* The portnumber is in use */
+
+ return conn;
+ }
+ }
+
+ return NULL;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uip_tcpinit()
+ *
+ * Description:
+ * Initialize the TCP/IP connection structures. Called only from the UIP
+ * layer.
+ *
+ ****************************************************************************/
+
+void uip_tcpinit(void)
+{
+ int i;
+ for (i = 0; i < UIP_CONNS; i++)
+ {
+ g_tcp_connections[i].tcpstateflags = UIP_CLOSED;
+ }
+
+ g_last_tcp_port = 1024;
+}
+
+/****************************************************************************
+ * Name: uip_tcpalloc()
+ *
+ * Description:
+ * Find a free TCP/IP connection structure and allocate it
+ * for use. This is normally something done by the implementation of the
+ * socket() API but is also called from the interrupt level when a TCP
+ * packet is received while "listening"
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_tcpalloc(void)
+{
+#if 0 /* Revisit */
+ struct uip_conn *oldest = NULL;
+#endif
+ irqstate_t flags;
+ unsigned int i;
+
+ /* 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_tcp_connections[];
+ */
+
+ flags = irqsave();
+
+ /* Check if there are any available connections. */
+
+ for (i = 0; i < UIP_CONNS; i++)
+ {
+ /* First, check if any connections structures are marked as
+ * CLOSED in the table of pre-allocated connection structures.
+ */
+
+ if (g_tcp_connections[i].tcpstateflags == UIP_CLOSED)
+ {
+ /* We found an unused structure. Mark as allocated, but not
+ * initialized.
+ */
+
+ memset(&g_tcp_connections[i], 0, sizeof(struct uip_conn));
+ g_tcp_connections[i].tcpstateflags = UIP_ALLOCATED;
+
+ irqrestore(flags);
+ return &g_tcp_connections[i];
+ }
+
+#if 0 /* Revisit */
+ /* As a fallback, check for connection structures in the TIME_WAIT
+ * state. If no CLOSED connections are found, then take the oldest
+ */
+
+ if (g_tcp_connections[i].tcpstateflags == UIP_TIME_WAIT)
+ {
+ if (!oldest || g_tcp_connections[i].timer > oldest->timer)
+ {
+ oldest = &g_tcp_connections[i];
+ }
+ }
+ }
+ return oldest;
+#else
+ }
+
+ irqrestore(flags);
+ return NULL;
+#endif
+}
+
+/****************************************************************************
+ * Name: uip_tcpfree()
+ *
+ * Description:
+ * Free a connection structure that is no longer in use. This should be
+ * done by the implementation of close()
+ *
+ ****************************************************************************/
+
+void uip_tcpfree(struct uip_conn *conn)
+{
+ /* this action is atomic and should require no special protetion */
+
+ conn->tcpstateflags = UIP_CLOSED;
+}
+
+/****************************************************************************
+ * Name: uip_tcpactive()
+ *
+ * Description:
+ * Find a connection structure that is the appropriate
+ * connection to be used withi the provided TCP/IP header
+ *
+ * Assumptions:
+ * This function is called from UIP logic at interrupt level
+ *
+ ****************************************************************************/
+
+struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf)
+{
+ struct uip_conn *conn;
+ for (conn = g_tcp_connections; conn <= &g_tcp_connections[UIP_CONNS - 1]; conn++)
+ {
+ /* Find an open connection matching the tcp input */
+
+ if (conn->tcpstateflags != UIP_CLOSED &&
+ buf->destport == conn->lport && buf->srcport == conn->rport &&
+ uip_ipaddr_cmp(buf->srcipaddr, conn->ripaddr))
+ {
+ return conn;
+ }
+ }
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: uip_tcppoll()
+ *
+ * Description:
+ * Periodic processing for a connection identified by its number.
+ * This function does the necessary periodic processing (timers,
+ * polling) for a uIP TCP conneciton, and should be called by the UIP
+ * device driver when the periodic uIP timer goes off. It should be
+ * called for every connection, regardless of whether they are open of
+ * closed.
+ *
+ * Assumptions:
+ * This function is called from the CAN device driver may be called from
+ * the timer interrupt/watchdog handle level.
+ *
+ ****************************************************************************/
+
+void uip_tcppoll(unsigned int conn)
+{
+ uip_conn = &g_tcp_connections[conn];
+ uip_interrupt(UIP_TIMER);
+}
+
+/****************************************************************************
+ * Name: uip_tcpactive()
+ *
+ * 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:
+ * This function implements the UIP specific parts of the standard TCP
+ * bind() operation.
+ *
+ * Assumptions:
+ * This function is called from normal user level code.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in6 *addr)
+#else
+int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr)
+#endif
+{
+#warning "Need to implement bind logic"
+ return ERROR;
+}
+
+/****************************************************************************
+ * Name: uip_tcpbind()
+ *
+ * Description:
+ * This function implements the UIP specific parts of the standard
+ * TCP connect() operation: It connects to a remote host using TCP.
+ *
+ * This function is used to start a new connection to the specified
+ * port on the specied host. It uses the connection structure that was
+ * allocated by a preceding socket() call. It sets the connection to
+ * the SYN_SENT state and sets the retransmission timer to 0. This will
+ * cause a TCP SYN segment to be sent out the next time this connection
+ * is periodically processed, which usually is done within 0.5 seconds
+ * after the call to uip_tcpconnect().
+ *
+ * Assumptions:
+ * This function is called from normal user level code.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_IPv6
+int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in6 *addr )
+#else
+int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr )
+#endif
+{
+ uint16 port;
+ int i;
+
+ /* If the TCP port has not alread been bound to a local port, then select
+ * one now.
+ */
+
+ port = ntohs(conn->lport);
+ if (port == 0)
+ {
+ /* No local port assigned. Loop until we find a valid listen port number\
+ * that is not being used by any other connection.
+ */
+
+ do
+ {
+ /* Guess that the next available port number will be the one after
+ * the last port number assigned.
+ */
+#warning "This need protection from other threads and from interrupts"
+ port = ++g_last_tcp_port;
+
+ /* Make sure that the port number is within range */
+
+ if (g_last_tcp_port >= 32000)
+ {
+ g_last_tcp_port = 4096;
+ }
+ }
+ while (uip_find_conn(g_last_tcp_port));
+ }
+
+ /* Initialize and return the connection structure, bind it to the port number */
+
+ conn->tcpstateflags = UIP_SYN_SENT;
+
+ 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->initialmss = conn->mss = UIP_TCP_MSS;
+
+ conn->len = 1; /* TCP length of the SYN is one. */
+ conn->nrtx = 0;
+ conn->timer = 1; /* Send the SYN next time around. */
+ conn->rto = UIP_RTO;
+ conn->sa = 0;
+ conn->sv = 16; /* Initial value of the RTT variance. */
+ conn->lport = htons(port);
+
+ /* The sockaddr port is 16 bits and already in network order */
+
+ conn->rport = addr->sin_port;
+
+ /* The sockaddr address is 32-bits in network order. */
+
+ uip_ipaddr_copy(&conn->ripaddr, addr->sin_addr.s_addr);
+ return OK;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip-udpconn.c b/nuttx/net/uip/uip-udpconn.c
new file mode 100644
index 000000000..3b7f06fa6
--- /dev/null
+++ b/nuttx/net/uip/uip-udpconn.c
@@ -0,0 +1,170 @@
+/************************************************************
+ * uip-udpconn.c
+ *
+ * Copyright (C) 2007 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 Gregory Nutt 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.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Compilation Switches
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+struct uip_udp_conn *uip_udpalloc(void);
+void uip_udpfree(struct uip_udp_conn *conn);
+
+#ifdef CONFIG_NET_IPv6
+int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr);
+#else
+int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr);
+#endif
+
+#ifdef CONFIG_NET_IPv6
+int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr )
+#else
+int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
+#endif
+{
+ uint16 ipaddr[2];
+
+ if (pdhcpc->state == STATE_INITIAL)
+ {
+ uip_ipaddr(ipaddr, 0,0,0,0);
+ uip_sethostaddr(ipaddr);
+ }
+ return OK;
+}
+
+/* Set up a new UDP connection.
+ *
+ * This function sets up a new UDP connection. The function will
+ * automatically allocate an unused local port for the new
+ * connection. However, another port can be chosen by using the
+ * uip_udp_bind() call, after the uip_udp_new() function has been
+ * called.
+ *
+ * Example:
+ *
+ * uip_ipaddr_t addr;
+ * struct uip_udp_conn *c;
+ *
+ * uip_ipaddr(&addr, 192,168,2,1);
+ * c = uip_udp_new(&addr, HTONS(12345));
+ * if(c != NULL) {
+ * uip_udp_bind(c, HTONS(12344));
+ * }
+ *
+ * ripaddr The IP address of the remote host.
+ *
+ * rport The remote port number in network byte order.
+ *
+ * Return: The uip_udp_conn structure for the new connection or NULL
+ * if no connection could be allocated.
+ */
+
+struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport)
+{
+ struct uip_udp_conn *conn;
+ int i;
+
+ /* Find an unused local port number. Loop until we find a valid listen port
+ * number that is not being used by any other connection.
+ */
+
+ do
+ {
+ /* Guess that the next available port number will be the one after
+ * the last port number assigned.
+ */
+
+ ++g_last_udp_port;
+
+ /* Make sure that the port number is within range */
+ if (g_last_udp_port >= 32000)
+ {
+ g_last_udp_port = 4096;
+ }
+ }
+ while (uip_find_udp_conn(g_last_udp_port));
+
+ /* Now find an available UDP connection structure */
+
+ conn = 0;
+ for (i = 0; i < UIP_UDP_CONNS; i++)
+ {
+ if (uip_udp_conns[c].lport == 0)
+ {
+ conn = &uip_udp_conns[c];
+ break;
+ }
+ }
+
+ /* Return an error if no connection is available */
+
+ if (conn == 0)
+ {
+ return 0;
+ }
+
+ /* Initialize and return the connection structure, bind it to the port number */
+
+ conn->lport = HTONS(g_last_udp_port);
+ conn->rport = rport;
+
+ if (ripaddr == NULL)
+ {
+ memset(conn->ripaddr, 0, sizeof(uip_ipaddr_t));
+ }
+ else
+ {
+ uip_ipaddr_copy(&conn->ripaddr, ripaddr);
+ }
+
+ conn->ttl = UIP_TTL;
+
+ return conn;
+}
+
+#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index 7fa2e3b7e..830f34551 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -93,6 +93,8 @@ extern void uip_log(char *msg);
# define UIP_LOG(m)
#endif /* UIP_LOGGING == 1 */
+#include "uip-internal.h"
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -175,11 +177,9 @@ uint16 uip_flags; /* The uip_flags variable is used for communica
* program. */
struct uip_conn *uip_conn; /* uip_conn always points to the current connection. */
-struct uip_conn uip_conns[UIP_CONNS];
- /* The uip_conns array holds all TCP connections. */
uint16 uip_listenports[UIP_LISTENPORTS];
/* The uip_listenports list all currently listning ports. */
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_udp_conn;
struct uip_udp_conn uip_udp_conns[UIP_UDP_CONNS];
#endif /* CONFIG_NET_UDP */
@@ -222,11 +222,10 @@ struct uip_eth_addr uip_ethaddr = {{ 0,0,0,0,0,0 }};
static uint16 ipid; /* Ths ipid variable is an increasing number that is
* used for the IP ID field. */
-static uint8 iss[4]; /* The iss variable is used for the TCP initial
- * sequence number. */
-
-static uint16 lastport; /* Keeps track of the last port used for a new
+#ifdef CONFIG_NET_UDP
+static uint16 g_last_udp_port; /* Keeps track of the last port used for a new
* connection. */
+#endif
/* Temporary variables. */
static uint8 c, opt;
@@ -236,38 +235,6 @@ static uint16 tmp16;
* Private Functions
****************************************************************************/
-#if !UIP_ARCH_ADD32
-static void uip_add32(uint8 *op32, uint16 op16)
-{
- uip_acc32[3] = op32[3] + (op16 & 0xff);
- uip_acc32[2] = op32[2] + (op16 >> 8);
- uip_acc32[1] = op32[1];
- uip_acc32[0] = op32[0];
-
- if (uip_acc32[2] < (op16 >> 8))
- {
- ++uip_acc32[1];
- if (uip_acc32[1] == 0)
- {
- ++uip_acc32[0];
- }
- }
-
- if (uip_acc32[3] < (op16 & 0xff))
- {
- ++uip_acc32[2];
- if (uip_acc32[2] == 0)
- {
- ++uip_acc32[1];
- if (uip_acc32[1] == 0)
- {
- ++uip_acc32[0];
- }
- }
- }
-}
-#endif /* UIP_ARCH_ADD32 */
-
#if !UIP_ARCH_CHKSUM
static uint16 chksum(uint16 sum, const uint8 *data, uint16 len)
{
@@ -340,34 +307,7 @@ static uint16 uip_icmp6chksum(void)
#endif /* UIP_ARCH_CHKSUM */
-/* Given a port number, find the socket bound to the port number.
- * Primary use: to determine if a port number is available.
- */
-
-struct uip_conn *uip_find_conn( uint16 portno )
-{
- struct uip_conn *conn;
- int i;
-
- /* Check if this port number is already in use, and if so try to find
- * another one.
- */
-
- for (i = 0; i < UIP_CONNS; i++)
- {
- conn = &uip_conns[i];
- if (conn->tcpstateflags != UIP_CLOSED && conn->lport == htons(lastport))
- {
- /* The portnumber is in use */
-
- return conn;
- }
- }
-
- return NULL;
-}
-
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_find_udp_conn( uint16 portno )
{
struct uip_udp_conn *conn;
@@ -375,7 +315,7 @@ struct uip_udp_conn *uip_find_udp_conn( uint16 portno )
for (i = 0; i < UIP_UDP_CONNS; i++)
{
- if (uip_udp_conns[i].lport == htons(lastport))
+ if (uip_udp_conns[i].lport == htons(g_last_udp_port))
{
return conn;
}
@@ -398,6 +338,38 @@ void uip_setipid(uint16 id)
/* Calculate the Internet checksum over a buffer. */
+#if !UIP_ARCH_ADD32
+void uip_add32(uint8 *op32, uint16 op16)
+{
+ uip_acc32[3] = op32[3] + (op16 & 0xff);
+ uip_acc32[2] = op32[2] + (op16 >> 8);
+ uip_acc32[1] = op32[1];
+ uip_acc32[0] = op32[0];
+
+ if (uip_acc32[2] < (op16 >> 8))
+ {
+ ++uip_acc32[1];
+ if (uip_acc32[1] == 0)
+ {
+ ++uip_acc32[0];
+ }
+ }
+
+ if (uip_acc32[3] < (op16 & 0xff))
+ {
+ ++uip_acc32[2];
+ if (uip_acc32[2] == 0)
+ {
+ ++uip_acc32[1];
+ if (uip_acc32[1] == 0)
+ {
+ ++uip_acc32[0];
+ }
+ }
+ }
+}
+#endif /* UIP_ARCH_ADD32 */
+
#if !UIP_ARCH_CHKSUM
uint16 uip_chksum(uint16 *data, uint16 len)
{
@@ -426,7 +398,7 @@ uint16 uip_tcpchksum(void)
/* Calculate the UDP checksum of the packet in uip_buf and uip_appdata. */
- #ifdef CONFIG_NET_UDP_CHECKSUMS
+#ifdef CONFIG_NET_UDP_CHECKSUMS
uint16 uip_udpchksum(void)
{
return upper_layer_chksum(UIP_PROTO_UDP);
@@ -441,17 +413,19 @@ void uip_init(void)
uip_listenports[c] = 0;
}
- for (c = 0; c < UIP_CONNS; ++c)
- {
- uip_conns[c].tcpstateflags = UIP_CLOSED;
- }
- lastport = 1024;
+ /* Initialize the TCP/IP connection structures */
+
+ uip_tcpinit();
+
+ /* Initialize the UDP connection structures */
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
for (c = 0; c < UIP_UDP_CONNS; ++c)
{
uip_udp_conns[c].lport = 0;
}
+
+ g_last_udp_port = 1024;
#endif /* CONFIG_NET_UDP */
/* IPv4 initialization. */
@@ -460,83 +434,6 @@ void uip_init(void)
#endif /* UIP_FIXEDADDR */
}
-struct uip_conn *uip_connect(uip_ipaddr_t *ripaddr, uint16 rport)
-{
- struct uip_conn *conn, *cconn;
- int i;
-
- /* Find an unused local port number. Loop until we find a valid listen port
- * number that is not being used by any other connection.
- */
-
- do
- {
- /* Guess that the next available port number will be the one after
- * the last port number assigned.
- */
-
- ++lastport;
-
- /* Make sure that the port number is within range */
- if (lastport >= 32000)
- {
- lastport = 4096;
- }
- }
- while (uip_find_conn(lastport));
-
- /* Now find an available connection structure */
-
- conn = 0;
- for (i = 0; i < UIP_CONNS; i++)
- {
- cconn = &uip_conns[i];
- if (cconn->tcpstateflags == UIP_CLOSED)
- {
- conn = cconn;
- break;
- }
-
- if (cconn->tcpstateflags == UIP_TIME_WAIT)
- {
- if (conn == 0 || cconn->timer > conn->timer)
- {
- conn = cconn;
- }
- }
- }
-
- /* Return an error if no connection is available */
-
- if (conn == 0)
- {
- return 0;
- }
-
- /* Initialize and return the connection structure, bind it to the port number */
-
- conn->tcpstateflags = UIP_SYN_SENT;
-
- conn->snd_nxt[0] = iss[0];
- conn->snd_nxt[1] = iss[1];
- conn->snd_nxt[2] = iss[2];
- conn->snd_nxt[3] = iss[3];
-
- conn->initialmss = conn->mss = UIP_TCP_MSS;
-
- conn->len = 1; /* TCP length of the SYN is one. */
- conn->nrtx = 0;
- conn->timer = 1; /* Send the SYN next time around. */
- conn->rto = UIP_RTO;
- conn->sa = 0;
- conn->sv = 16; /* Initial value of the RTT variance. */
- conn->lport = htons(lastport);
- conn->rport = rport;
- uip_ipaddr_copy(&conn->ripaddr, ripaddr);
-
- return conn;
-}
-
#ifdef CONFIG_NET_UDP
struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport)
{
@@ -553,15 +450,15 @@ struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport)
* the last port number assigned.
*/
- ++lastport;
+ ++g_last_udp_port;
/* Make sure that the port number is within range */
- if (lastport >= 32000)
+ if (g_last_udp_port >= 32000)
{
- lastport = 4096;
+ g_last_udp_port = 4096;
}
}
- while (uip_find_udp_conn(lastport));
+ while (uip_find_udp_conn(g_last_udp_port));
/* Now find an available UDP connection structure */
@@ -584,7 +481,7 @@ struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport)
/* Initialize and return the connection structure, bind it to the port number */
- conn->lport = HTONS(lastport);
+ conn->lport = HTONS(g_last_udp_port);
conn->rport = rport;
if (ripaddr == NULL)
@@ -616,15 +513,17 @@ void uip_unlisten(uint16 port)
void uip_listen(uint16 port)
{
- for (c = 0; c < UIP_LISTENPORTS; ++c) {
- if (uip_listenports[c] == 0) {
- uip_listenports[c] = port;
- return;
+ for (c = 0; c < UIP_LISTENPORTS; ++c)
+ {
+ if (uip_listenports[c] == 0)
+ {
+ uip_listenports[c] = port;
+ return;
+ }
}
- }
}
-/* XXX: IP fragment reassembly: not well-tested. */
+/* IP fragment reassembly: not well-tested. */
#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
#define UIP_REASS_BUFSIZE (UIP_BUFSIZE - UIP_LLH_LEN)
@@ -644,113 +543,133 @@ static uint8 uip_reass(void)
uint16 i;
/* If ip_reasstmr is zero, no packet is present in the buffer, so we
- write the IP header of the fragment into the reassembly
- buffer. The timer is updated with the maximum age. */
- if (uip_reasstmr == 0) {
- memcpy(uip_reassbuf, &BUF->vhl, UIP_IPH_LEN);
- uip_reasstmr = UIP_REASS_MAXAGE;
- uip_reassflags = 0;
- /* Clear the bitmap. */
- memset(uip_reassbitmap, 0, sizeof(uip_reassbitmap));
- }
+ * write the IP header of the fragment into the reassembly
+ * buffer. The timer is updated with the maximum age.
+ */
- /* Check if the incoming fragment matches the one currently present
- in the reasembly buffer. If so, we proceed with copying the
- fragment into the buffer. */
- if (BUF->srcipaddr[0] == FBUF->srcipaddr[0] &&
- BUF->srcipaddr[1] == FBUF->srcipaddr[1] &&
- BUF->destipaddr[0] == FBUF->destipaddr[0] &&
- BUF->destipaddr[1] == FBUF->destipaddr[1] &&
- BUF->ipid[0] == FBUF->ipid[0] &&
- BUF->ipid[1] == FBUF->ipid[1]) {
-
- len = (BUF->len[0] << 8) + BUF->len[1] - (BUF->vhl & 0x0f) * 4;
- offset = (((BUF->ipoffset[0] & 0x3f) << 8) + BUF->ipoffset[1]) * 8;
-
- /* If the offset or the offset + fragment length overflows the
- reassembly buffer, we discard the entire packet. */
- if (offset > UIP_REASS_BUFSIZE ||
- offset + len > UIP_REASS_BUFSIZE) {
- uip_reasstmr = 0;
- goto nullreturn;
+ if (uip_reasstmr == 0)
+ {
+ memcpy(uip_reassbuf, &BUF->vhl, UIP_IPH_LEN);
+ uip_reasstmr = UIP_REASS_MAXAGE;
+ uip_reassflags = 0;
+
+ /* Clear the bitmap. */
+ memset(uip_reassbitmap, 0, sizeof(uip_reassbitmap));
}
- /* Copy the fragment into the reassembly buffer, at the right
- offset. */
- memcpy(&uip_reassbuf[UIP_IPH_LEN + offset],
- (char *)BUF + (int)((BUF->vhl & 0x0f) * 4),
- len);
+ /* Check if the incoming fragment matches the one currently present
+ * in the reasembly buffer. If so, we proceed with copying the
+ * fragment into the buffer.
+ */
+
+ if (BUF->srcipaddr[0] == FBUF->srcipaddr[0] && BUF->srcipaddr[1] == FBUF->srcipaddr[1] &&
+ BUF->destipaddr[0] == FBUF->destipaddr[0] && BUF->destipaddr[1] == FBUF->destipaddr[1] &&
+ BUF->ipid[0] == FBUF->ipid[0] && BUF->ipid[1] == FBUF->ipid[1])
+ {
+ len = (BUF->len[0] << 8) + BUF->len[1] - (BUF->vhl & 0x0f) * 4;
+ offset = (((BUF->ipoffset[0] & 0x3f) << 8) + BUF->ipoffset[1]) * 8;
+
+ /* If the offset or the offset + fragment length overflows the
+ * reassembly buffer, we discard the entire packet.
+ */
+
+ if (offset > UIP_REASS_BUFSIZE || offset + len > UIP_REASS_BUFSIZE)
+ {
+ uip_reasstmr = 0;
+ goto nullreturn;
+ }
+
+ /* Copy the fragment into the reassembly buffer, at the right offset. */
+
+ memcpy(&uip_reassbuf[UIP_IPH_LEN + offset], (char *)BUF + (int)((BUF->vhl & 0x0f) * 4), len);
/* Update the bitmap. */
- if (offset / (8 * 8) == (offset + len) / (8 * 8)) {
- /* If the two endpoints are in the same byte, we only update
- that byte. */
-
- uip_reassbitmap[offset / (8 * 8)] |=
- bitmap_bits[(offset / 8 ) & 7] &
- ~bitmap_bits[((offset + len) / 8 ) & 7];
- } else {
- /* If the two endpoints are in different bytes, we update the
- bytes in the endpoints and fill the stuff inbetween with
- 0xff. */
- uip_reassbitmap[offset / (8 * 8)] |=
- bitmap_bits[(offset / 8 ) & 7];
- for (i = 1 + offset / (8 * 8); i < (offset + len) / (8 * 8); ++i) {
- uip_reassbitmap[i] = 0xff;
- }
- uip_reassbitmap[(offset + len) / (8 * 8)] |=
- ~bitmap_bits[((offset + len) / 8 ) & 7];
- }
- /* If this fragment has the More Fragments flag set to zero, we
- know that this is the last fragment, so we can calculate the
- size of the entire packet. We also set the
- IP_REASS_FLAG_LASTFRAG flag to indicate that we have received
- the final fragment. */
+ if (offset / (8 * 8) == (offset + len) / (8 * 8))
+ {
+ /* If the two endpoints are in the same byte, we only update that byte. */
+
+ uip_reassbitmap[offset / (8 * 8)] |=
+ bitmap_bits[(offset / 8 ) & 7] & ~bitmap_bits[((offset + len) / 8 ) & 7];
- if ((BUF->ipoffset[0] & IP_MF) == 0) {
- uip_reassflags |= UIP_REASS_FLAG_LASTFRAG;
- uip_reasslen = offset + len;
- }
+ }
+ else
+ {
+ /* If the two endpoints are in different bytes, we update the bytes
+ * in the endpoints and fill the stuff inbetween with 0xff.
+ */
- /* Finally, we check if we have a full packet in the buffer. We do
- this by checking if we have the last fragment and if all bits
- in the bitmap are set. */
- if (uip_reassflags & UIP_REASS_FLAG_LASTFRAG) {
- /* Check all bytes up to and including all but the last byte in
- the bitmap. */
- for (i = 0; i < uip_reasslen / (8 * 8) - 1; ++i) {
- if (uip_reassbitmap[i] != 0xff) {
- goto nullreturn;
- }
+ uip_reassbitmap[offset / (8 * 8)] |= bitmap_bits[(offset / 8 ) & 7];
+ for (i = 1 + offset / (8 * 8); i < (offset + len) / (8 * 8); ++i)
+ {
+ uip_reassbitmap[i] = 0xff;
+ }
+ uip_reassbitmap[(offset + len) / (8 * 8)] |= ~bitmap_bits[((offset + len) / 8 ) & 7];
}
- /* Check the last byte in the bitmap. It should contain just the
- right amount of bits. */
- if (uip_reassbitmap[uip_reasslen / (8 * 8)] !=
- (uint8)~bitmap_bits[uip_reasslen / 8 & 7]) {
- goto nullreturn;
+ /* If this fragment has the More Fragments flag set to zero, we know that
+ * this is the last fragment, so we can calculate the size of the entire
+ * packet. We also set the IP_REASS_FLAG_LASTFRAG flag to indicate that
+ * we have received the final fragment.
+ */
+
+ if ((BUF->ipoffset[0] & IP_MF) == 0)
+ {
+ uip_reassflags |= UIP_REASS_FLAG_LASTFRAG;
+ uip_reasslen = offset + len;
}
- /* If we have come this far, we have a full packet in the
- buffer, so we allocate a pbuf and copy the packet into it. We
- also reset the timer. */
- uip_reasstmr = 0;
- memcpy(BUF, FBUF, uip_reasslen);
-
- /* Pretend to be a "normal" (i.e., not fragmented) IP packet
- from now on. */
- BUF->ipoffset[0] = BUF->ipoffset[1] = 0;
- BUF->len[0] = uip_reasslen >> 8;
- BUF->len[1] = uip_reasslen & 0xff;
- BUF->ipchksum = 0;
- BUF->ipchksum = ~(uip_ipchksum());
-
- return uip_reasslen;
- }
+ /* Finally, we check if we have a full packet in the buffer. We do this
+ * by checking if we have the last fragment and if all bits in the bitmap
+ * are set.
+ */
+
+ if (uip_reassflags & UIP_REASS_FLAG_LASTFRAG)
+ {
+ /* Check all bytes up to and including all but the last byte in
+ * the bitmap.
+ */
+
+ for (i = 0; i < uip_reasslen / (8 * 8) - 1; ++i)
+ {
+ if (uip_reassbitmap[i] != 0xff)
+ {
+ goto nullreturn;
+ }
+ }
+
+ /* Check the last byte in the bitmap. It should contain just the
+ * right amount of bits.
+ */
+
+ if (uip_reassbitmap[uip_reasslen / (8 * 8)] != (uint8)~bitmap_bits[uip_reasslen / 8 & 7])
+ {
+ goto nullreturn;
+ }
+
+ /* If we have come this far, we have a full packet in the buffer,
+ * so we allocate a pbuf and copy the packet into it. We also reset
+ * the timer.
+ */
+
+ uip_reasstmr = 0;
+ memcpy(BUF, FBUF, uip_reasslen);
+
+ /* Pretend to be a "normal" (i.e., not fragmented) IP packet from
+ * now on.
+ */
+
+ BUF->ipoffset[0] = BUF->ipoffset[1] = 0;
+ BUF->len[0] = uip_reasslen >> 8;
+ BUF->len[1] = uip_reasslen & 0xff;
+ BUF->ipchksum = 0;
+ BUF->ipchksum = ~(uip_ipchksum());
+
+ return uip_reasslen;
+ }
}
- nullreturn:
+nullreturn:
return 0;
}
#endif /* UIP_REASSEMBLY */
@@ -768,7 +687,7 @@ void uip_interrupt(uint8 flag)
{
register struct uip_conn *uip_connr = uip_conn;
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
if (flag == UIP_UDP_SEND_CONN)
{
goto udp_send;
@@ -805,22 +724,13 @@ void uip_interrupt(uint8 flag)
}
#endif /* UIP_REASSEMBLY */
- /* Increase the initial sequence number */
+ /* Increase the TCP sequence number */
- if (++iss[3] == 0)
- {
- if (++iss[2] == 0)
- {
- if (++iss[1] == 0)
- {
- ++iss[0];
- }
- }
- }
+ uip_tcpnextsequence();
/* Reset the length variables. */
- uip_len = 0;
+ uip_len = 0;
uip_slen = 0;
/* Check if the connection is in a state in which we simply wait
@@ -935,7 +845,7 @@ void uip_interrupt(uint8 flag)
goto drop;
}
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
if (flag == UIP_UDP_TIMER)
{
if (uip_udp_conn->lport != 0)
@@ -1105,7 +1015,7 @@ void uip_interrupt(uint8 flag)
goto tcp_input;
}
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
if (BUF->proto == UIP_PROTO_UDP)
{
goto udp_input;
@@ -1247,14 +1157,14 @@ void uip_interrupt(uint8 flag)
#endif /* !CONFIG_NET_IPv6 */
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
/* UDP input processing. */
udp_input:
/* UDP processing is really just a hack. We don't do anything to the
UDP/IP headers, but let the UDP application do all the hard
work. If the application sets uip_slen, it has a packet to
send. */
- #ifdef CONFIG_NET_UDP_CHECKSUMS
+#ifdef CONFIG_NET_UDP_CHECKSUMS
uip_len = uip_len - UIP_IPUDPH_LEN;
uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
if (UDPBUF->udpchksum != 0 && uip_udpchksum() != 0xffff)
@@ -1269,9 +1179,8 @@ void uip_interrupt(uint8 flag)
#endif /* UIP_UDP_CHECKSUMS */
/* Demultiplex this UDP packet between the UDP "connections". */
- for (uip_udp_conn = &uip_udp_conns[0];
- uip_udp_conn < &uip_udp_conns[UIP_UDP_CONNS];
- ++uip_udp_conn)
+
+ for (uip_udp_conn = &uip_udp_conns[0]; uip_udp_conn < &uip_udp_conns[UIP_UDP_CONNS]; uip_udp_conn++)
{
/* If the local UDP port is non-zero, the connection is considered
* to be used. If so, the local port number is checked against the
@@ -1282,13 +1191,12 @@ void uip_interrupt(uint8 flag)
* address of the packet is checked.
*/
- if (uip_udp_conn->lport != 0 &&
- UDPBUF->destport == uip_udp_conn->lport &&
+ if (uip_udp_conn->lport != 0 && UDPBUF->destport == uip_udp_conn->lport &&
(uip_udp_conn->rport == 0 ||
- UDPBUF->srcport == uip_udp_conn->rport) &&
- (uip_ipaddr_cmp(uip_udp_conn->ripaddr, all_zeroes_addr) ||
- uip_ipaddr_cmp(uip_udp_conn->ripaddr, all_ones_addr) ||
- uip_ipaddr_cmp(BUF->srcipaddr, uip_udp_conn->ripaddr)))
+ UDPBUF->srcport == uip_udp_conn->rport) &&
+ (uip_ipaddr_cmp(uip_udp_conn->ripaddr, all_zeroes_addr) ||
+ uip_ipaddr_cmp(uip_udp_conn->ripaddr, all_ones_addr) ||
+ uip_ipaddr_cmp(BUF->srcipaddr, uip_udp_conn->ripaddr)))
{
goto udp_found;
}
@@ -1336,7 +1244,7 @@ void uip_interrupt(uint8 flag)
uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPTCPH_LEN];
- #ifdef CONFIG_NET_UDP_CHECKSUMS
+#ifdef CONFIG_NET_UDP_CHECKSUMS
/* Calculate UDP checksum. */
UDPBUF->udpchksum = ~(uip_udpchksum());
if (UDPBUF->udpchksum == 0)
@@ -1357,30 +1265,27 @@ void uip_interrupt(uint8 flag)
if (uip_tcpchksum() != 0xffff)
{
/* Compute and check the TCP checksum. */
+
UIP_STAT(++uip_stat.tcp.drop);
UIP_STAT(++uip_stat.tcp.chkerr);
UIP_LOG("tcp: bad checksum.");
goto drop;
}
- /* Demultiplex this segment. */
- /* First check any active connections. */
- for (uip_connr = &uip_conns[0]; uip_connr <= &uip_conns[UIP_CONNS - 1];
- ++uip_connr)
+ /* Demultiplex this segment. First check any active connections. */
+
+ uip_connr = uip_tcpactive(BUF);
+ if (uip_connr)
{
- if (uip_connr->tcpstateflags != UIP_CLOSED &&
- BUF->destport == uip_connr->lport &&
- BUF->srcport == uip_connr->rport &&
- uip_ipaddr_cmp(BUF->srcipaddr, uip_connr->ripaddr))
- {
- goto found;
- }
+ goto found;
}
/* If we didn't find and active connection that expected the packet,
- either this packet is an old duplicate, or this is a SYN packet
- destined for a connection in LISTEN. If the SYN flag isn't set,
- it is an old packet and we send a RST. */
+ * either this packet is an old duplicate, or this is a SYN packet
+ * destined for a connection in LISTEN. If the SYN flag isn't set,
+ * it is an old packet and we send a RST.
+ */
+
if ((BUF->flags & TCP_CTL) != TCP_SYN)
{
goto reset;
@@ -1455,57 +1360,43 @@ void uip_interrupt(uint8 flag)
goto tcp_send_noconn;
/* This label will be jumped to if we matched the incoming packet
- with a connection in LISTEN. In that case, we should create a new
- connection and send a SYNACK in return. */
- found_listen:
- /* First we check if there are any connections avaliable. Unused
- connections are kept in the same table as used connections, but
- unused ones have the tcpstate set to CLOSED. Also, connections in
- TIME_WAIT are kept track of and we'll use the oldest one if no
- CLOSED connections are found. Thanks to Eddie C. Dost for a very
- nice algorithm for the TIME_WAIT search. */
- uip_connr = 0;
- for (c = 0; c < UIP_CONNS; ++c)
- {
- if (uip_conns[c].tcpstateflags == UIP_CLOSED)
- {
- uip_connr = &uip_conns[c];
- break;
- }
- if (uip_conns[c].tcpstateflags == UIP_TIME_WAIT)
- {
- if (uip_connr == 0 || uip_conns[c].timer > uip_connr->timer)
- {
- uip_connr = &uip_conns[c];
- }
- }
- }
+ * with a connection in LISTEN. In that case, we should create a new
+ * connection and send a SYNACK in return.
+ */
- if (uip_connr == 0)
+found_listen:
+
+ /* First allocate a new connection structure */
+
+ uip_connr = uip_tcpalloc();
+ if (!uip_connr)
{
/* All connections are used already, we drop packet and hope that
- the remote end will retransmit the packet at a time when we
- have more spare connections. */
+ * the remote end will retransmit the packet at a time when we
+ * have more spare connections.
+ */
+
UIP_STAT(++uip_stat.tcp.syndrop);
- UIP_LOG("tcp: found no unused connections.");
- goto drop;
- }
+ UIP_LOG("tcp: found no unused connections.");
+ goto drop;
+ }
uip_conn = uip_connr;
/* Fill in the necessary fields for the new connection. */
- uip_connr->rto = uip_connr->timer = UIP_RTO;
- uip_connr->sa = 0;
- uip_connr->sv = 4;
- uip_connr->nrtx = 0;
+
+ uip_connr->rto = uip_connr->timer = UIP_RTO;
+ uip_connr->sa = 0;
+ uip_connr->sv = 4;
+ uip_connr->nrtx = 0;
uip_connr->lport = BUF->destport;
uip_connr->rport = BUF->srcport;
uip_ipaddr_copy(uip_connr->ripaddr, BUF->srcipaddr);
uip_connr->tcpstateflags = UIP_SYN_RCVD;
- uip_connr->snd_nxt[0] = iss[0];
- uip_connr->snd_nxt[1] = iss[1];
- uip_connr->snd_nxt[2] = iss[2];
- uip_connr->snd_nxt[3] = iss[3];
+ uip_connr->snd_nxt[0] = g_tcp_sequence[0];
+ uip_connr->snd_nxt[1] = g_tcp_sequence[1];
+ uip_connr->snd_nxt[2] = g_tcp_sequence[2];
+ uip_connr->snd_nxt[3] = g_tcp_sequence[3];
uip_connr->len = 1;
/* rcv_nxt should be the seqno from the incoming packet + 1. */
@@ -2119,7 +2010,7 @@ void uip_interrupt(uint8 flag)
BUF->tcpchksum = 0;
BUF->tcpchksum = ~(uip_tcpchksum());
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
ip_send_nolen:
#endif /* CONFIG_NET_UDP */
diff --git a/nuttx/netutils/resolv/resolv.c b/nuttx/netutils/resolv/resolv.c
index 14159e906..f149c6a80 100644
--- a/nuttx/netutils/resolv/resolv.c
+++ b/nuttx/netutils/resolv/resolv.c
@@ -52,6 +52,7 @@
#include <sys/types.h>
#include <string.h>
+#include <debug.h>
#include <net/uip/uip.h>
#include <net/uip/resolv.h>
diff --git a/nuttx/netutils/smtp/smtp.c b/nuttx/netutils/smtp/smtp.c
index 8ea6ca275..09d131057 100644
--- a/nuttx/netutils/smtp/smtp.c
+++ b/nuttx/netutils/smtp/smtp.c
@@ -50,6 +50,7 @@
#include <string.h>
#include <stdlib.h>
#include <semaphore.h>
+#include <sys/socket.h>
#include <net/uip/uip.h>
#include <net/uip/psock.h>
@@ -260,17 +261,10 @@ void smtp_configure(void *handle, char *lhostname, void *server)
int smtp_send(void *handle, char *to, char *cc, char *from, char *subject, char *msg, int msglen)
{
struct smtp_state *psmtp = (struct smtp_state *)handle;
- struct uip_conn *conn;
+ struct sockaddr_in server;
+ int sockfd;
- /* This is the moral equivalent of socket() + bind(). It returns the
- * initialized connection structure
- */
-
- conn = uip_connect(&psmtp->smtpserver, HTONS(25));
- if (conn == NULL)
- {
- return ERROR;
- }
+ /* Setup */
psmtp->connected = TRUE;
psmtp->to = to;
@@ -281,11 +275,35 @@ int smtp_send(void *handle, char *to, char *cc, char *from, char *subject, char
psmtp->msglen = msglen;
psmtp->result = OK;
- /* Make this instance globally visible */
+ /* Create a socket */
+
+ sockfd = socket(AF_INET, SOCK_STREAM, 0);
+ if (sockfd < 0)
+ {
+ return ERROR;
+ }
- gpsmtp = psmtp;
+ /* Make this instance globally visible (we will get interrupts as
+ * soon as we connect
+ */
+
+ gpsmtp = psmtp;
+
+ /* Connect to server. First we have to set some fields in the
+ * 'server' structure. The system will assign me an arbitrary
+ * local port that is not in use.
+ */
+
+ server.sin_family = AF_INET;
+ memcpy(&server.sin_addr.s_addr, &psmtp->smtpserver, sizeof(in_addr_t));
+ server.sin_port = HTONS(25);
+
+ if (connect(sockfd, (struct sockaddr *)&server, sizeof(struct sockaddr_in)) < 0)
+ {
+ return ERROR;
+ }
- /* Initialized the psock structure inside the smtp state structure */
+ /* Initialize the psock structure inside the smtp state structure */
psock_init(&psmtp->psock, psmtp->buffer, SMTP_INPUT_BUFFER_SIZE);
diff --git a/nuttx/netutils/webclient/webclient.c b/nuttx/netutils/webclient/webclient.c
index 30718e723..a89647ab5 100644
--- a/nuttx/netutils/webclient/webclient.c
+++ b/nuttx/netutils/webclient/webclient.c
@@ -38,12 +38,13 @@
*
* This file is part of the uIP TCP/IP stack.
*
- * $Id: webclient.c,v 1.1.1.1 2007-08-26 23:07:05 patacongo Exp $
+ * $Id: webclient.c,v 1.2 2007-09-02 21:58:34 patacongo Exp $
*
*/
#include <sys/types.h>
#include <string.h>
+#include <sys/socket.h>
#include <net/uip/uip.h>
#include <net/uip/resolv.h>
@@ -118,24 +119,43 @@ void webclient_close(void)
unsigned char webclient_get(char *host, uint16 port, char *file)
{
- struct uip_conn *conn;
uip_ipaddr_t *ipaddr;
static uip_ipaddr_t addr;
+ struct sockaddr_in server;
+ int sockfd;
/* First check if the host is an IP address. */
+
ipaddr = &addr;
- if (uiplib_ipaddrconv(host, (unsigned char *)addr) == 0) {
- ipaddr = (uip_ipaddr_t *)resolv_lookup(host);
+ if (uiplib_ipaddrconv(host, (unsigned char *)addr) == 0)
+ {
+ ipaddr = (uip_ipaddr_t *)resolv_lookup(host);
- if (ipaddr == NULL) {
- return 0;
- }
+ if (ipaddr == NULL) {
+ return 0;
+ }
}
- conn = uip_connect(ipaddr, htons(port));
+ /* Create a socket */
- if (conn == NULL) {
- return 0;
+ sockfd = socket(AF_INET, SOCK_STREAM, 0);
+ if (sockfd < 0)
+ {
+ return ERROR;
+ }
+
+ /* Connect to server. First we have to set some fields in the
+ * 'server' structure. The system will assign me an arbitrary
+ * local port that is not in use.
+ */
+
+ server.sin_family = AF_INET;
+ memcpy(&server.sin_addr.s_addr, &host, sizeof(in_addr_t));
+ server.sin_port = htons(port);
+
+ if (connect(sockfd, (struct sockaddr *)&server, sizeof(struct sockaddr_in)) < 0)
+ {
+ return ERROR;
}
s.port = port;
@@ -143,7 +163,7 @@ unsigned char webclient_get(char *host, uint16 port, char *file)
strncpy(s.host, host, sizeof(s.host));
init_connection();
- return 1;
+ return OK;
}
static char *copy_string(char *dest, const char *src, int len)
diff --git a/nuttx/netutils/webserver/httpd-cgi.c b/nuttx/netutils/webserver/httpd-cgi.c
index 5c9609ee7..2b68040a2 100644
--- a/nuttx/netutils/webserver/httpd-cgi.c
+++ b/nuttx/netutils/webserver/httpd-cgi.c
@@ -39,21 +39,73 @@
#include <stdio.h>
#include <string.h>
+#define CONFIG_HTTPDCGI_FILESTATS 1
+#undef CONFIG_HTTPDCGI_DCPSTATS
+#define CONFIG_HTTPDCGI_NETSTATS 1
+
HTTPD_CGI_CALL(file, "file-stats", file_stats);
+#if CONFIG_HTTPDCGI_TCPSTATS
HTTPD_CGI_CALL(tcp, "tcp-connections", tcp_stats);
+#endif
HTTPD_CGI_CALL(net, "net-stats", net_stats);
+#if 0 /* Revisit */
static const struct httpd_cgi_call *calls[] = { &file, &tcp, &net, NULL };
+#else
+static const struct httpd_cgi_call *calls[] = {
+
+#ifdef CONFIG_HTTPDCGI_FILESTATS
+ &file,
+#endif
+#ifdef CONFIG_HTTPDCGI_DCPSTATS
+ &tcp,
+#endif
+#ifdef CONFIG_HTTPDCGI_NETSTATS
+ &net,
+#endif
+ NULL
+};
+#endif
+
+static const char closed[] = /* "CLOSED",*/
+{0x43, 0x4c, 0x4f, 0x53, 0x45, 0x44, 0};
+static const char syn_rcvd[] = /* "SYN-RCVD",*/
+{0x53, 0x59, 0x4e, 0x2d, 0x52, 0x43, 0x56, 0x44, 0};
+static const char syn_sent[] = /* "SYN-SENT",*/
+{0x53, 0x59, 0x4e, 0x2d, 0x53, 0x45, 0x4e, 0x54, 0};
+static const char established[] = /* "ESTABLISHED",*/
+{0x45, 0x53, 0x54, 0x41, 0x42, 0x4c, 0x49, 0x53, 0x48, 0x45, 0x44, 0};
+static const char fin_wait_1[] = /* "FIN-WAIT-1",*/
+{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49, 0x54, 0x2d, 0x31, 0};
+static const char fin_wait_2[] = /* "FIN-WAIT-2",*/
+{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49, 0x54, 0x2d, 0x32, 0};
+static const char closing[] = /* "CLOSING",*/
+{0x43, 0x4c, 0x4f, 0x53, 0x49, 0x4e, 0x47, 0};
+static const char time_wait[] = /* "TIME-WAIT,"*/
+{0x54, 0x49, 0x4d, 0x45, 0x2d, 0x57, 0x41, 0x49, 0x54, 0};
+static const char last_ack[] = /* "LAST-ACK"*/
+{0x4c, 0x41, 0x53, 0x54, 0x2d, 0x41, 0x43, 0x4b, 0};
-/*---------------------------------------------------------------------------*/
-static
-void nullfunction(struct httpd_state *s, char *ptr)
+#if CONFIG_HTTPDCGI_TCPSTATS
+static const char *states[] =
+{
+ closed,
+ syn_rcvd,
+ syn_sent,
+ established,
+ fin_wait_1,
+ fin_wait_2,
+ closing,
+ time_wait,
+ last_ack
+};
+#endif
+
+static void nullfunction(struct httpd_state *s, char *ptr)
{
}
-/*---------------------------------------------------------------------------*/
-httpd_cgifunction
-httpd_cgi(char *name)
+httpd_cgifunction httpd_cgi(char *name)
{
const struct httpd_cgi_call **f;
@@ -66,66 +118,26 @@ httpd_cgi(char *name)
#warning REVISIT -- must wait to return
return nullfunction;
}
-/*---------------------------------------------------------------------------*/
-static unsigned short
-generate_file_stats(void *arg)
+
+#ifdef CONFIG_HTTPDCGI_FILESTATS
+static unsigned short generate_file_stats(void *arg)
{
char *f = (char *)arg;
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE, "%5u", httpd_fs_count(f));
}
-/*---------------------------------------------------------------------------*/
-static
-void file_stats(struct httpd_state *s, char *ptr)
+
+static void file_stats(struct httpd_state *s, char *ptr)
{
psock_generator_send(&s->sout, generate_file_stats, strchr(ptr, ' ') + 1);
}
+#endif
-/*---------------------------------------------------------------------------*/
-static const char closed[] = /* "CLOSED",*/
-{0x43, 0x4c, 0x4f, 0x53, 0x45, 0x44, 0};
-static const char syn_rcvd[] = /* "SYN-RCVD",*/
-{0x53, 0x59, 0x4e, 0x2d, 0x52, 0x43, 0x56,
- 0x44, 0};
-static const char syn_sent[] = /* "SYN-SENT",*/
-{0x53, 0x59, 0x4e, 0x2d, 0x53, 0x45, 0x4e,
- 0x54, 0};
-static const char established[] = /* "ESTABLISHED",*/
-{0x45, 0x53, 0x54, 0x41, 0x42, 0x4c, 0x49, 0x53, 0x48,
- 0x45, 0x44, 0};
-static const char fin_wait_1[] = /* "FIN-WAIT-1",*/
-{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,
- 0x54, 0x2d, 0x31, 0};
-static const char fin_wait_2[] = /* "FIN-WAIT-2",*/
-{0x46, 0x49, 0x4e, 0x2d, 0x57, 0x41, 0x49,
- 0x54, 0x2d, 0x32, 0};
-static const char closing[] = /* "CLOSING",*/
-{0x43, 0x4c, 0x4f, 0x53, 0x49,
- 0x4e, 0x47, 0};
-static const char time_wait[] = /* "TIME-WAIT,"*/
-{0x54, 0x49, 0x4d, 0x45, 0x2d, 0x57, 0x41,
- 0x49, 0x54, 0};
-static const char last_ack[] = /* "LAST-ACK"*/
-{0x4c, 0x41, 0x53, 0x54, 0x2d, 0x41, 0x43,
- 0x4b, 0};
-
-static const char *states[] = {
- closed,
- syn_rcvd,
- syn_sent,
- established,
- fin_wait_1,
- fin_wait_2,
- closing,
- time_wait,
- last_ack};
-
-
-static unsigned short
-generate_tcp_stats(void *arg)
+#if CONFIG_HTTPDCGI_TCPSTATS
+static unsigned short generate_tcp_stats(void *arg)
{
struct uip_conn *conn;
struct httpd_state *s = (struct httpd_state *)arg;
-
+
conn = &uip_conns[s->count];
return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,
"<tr><td>%d</td><td>%u.%u.%u.%u:%u</td><td>%s</td><td>%u</td><td>%u</td><td>%c %c</td></tr>\r\n",
@@ -141,38 +153,34 @@ generate_tcp_stats(void *arg)
(uip_outstanding(conn))? '*':' ',
(uip_stopped(conn))? '!':' ');
}
-/*---------------------------------------------------------------------------*/
-static
-void tcp_stats(struct httpd_state *s, char *ptr)
+
+static void tcp_stats(struct httpd_state *s, char *ptr)
{
- for(s->count = 0; s->count < UIP_CONNS; ++s->count) {
- if((uip_conns[s->count].tcpstateflags & UIP_TS_MASK) != UIP_CLOSED) {
- psock_generator_send(&s->sout, generate_tcp_stats, s);
+ for(s->count = 0; s->count < UIP_CONNS; ++s->count)
+ {
+ if((uip_conns[s->count].tcpstateflags & UIP_TS_MASK) != UIP_CLOSED)
+ {
+ psock_generator_send(&s->sout, generate_tcp_stats, s);
+ }
}
- }
}
+#endif
-/*---------------------------------------------------------------------------*/
-static unsigned short
-generate_net_stats(void *arg)
+#ifdef CONFIG_HTTPDCGI_NETSTATS
+static unsigned short generate_net_stats(void *arg)
{
struct httpd_state *s = (struct httpd_state *)arg;
- return snprintf((char *)uip_appdata, UIP_APPDATA_SIZE,
+ return snprintf((char*)uip_appdata, UIP_APPDATA_SIZE,
"%5u\n", ((uip_stats_t *)&uip_stat)[s->count]);
}
-static
-void net_stats(struct httpd_state *s, char *ptr)
+static void net_stats(struct httpd_state *s, char *ptr)
{
#if UIP_STATISTICS
-
- for(s->count = 0; s->count < sizeof(uip_stat) / sizeof(uip_stats_t);
- ++s->count) {
- psock_generator_send(&s->sout, generate_net_stats, s);
- }
-
+ for(s->count = 0; s->count < sizeof(uip_stat) / sizeof(uip_stats_t); ++s->count)
+ {
+ psock_generator_send(&s->sout, generate_net_stats, s);
+ }
#endif /* UIP_STATISTICS */
}
-
-/*---------------------------------------------------------------------------*/
-/** @} */
+#endif
diff --git a/nuttx/tools/mkconfig.c b/nuttx/tools/mkconfig.c
index 20611ff1e..ccd8a077a 100644
--- a/nuttx/tools/mkconfig.c
+++ b/nuttx/tools/mkconfig.c
@@ -235,19 +235,32 @@ int main(int argc, char **argv, char **envp)
printf("#ifndef CONFIG_MM_REGIONS\n");
printf("# define CONFIG_MM_REGIONS 1\n");
printf("#endif\n\n");
- printf("/* If no file streams are configured, then make certain that\n");
- printf(" * buffered I/O support is disabled.\n");
+ printf("/* If no file streams are configured, then make certain that buffered I/O\n");
+ printf(" * support is disabled\n");
printf(" */\n\n");
printf("#if CONFIG_NFILE_STREAMS == 0\n");
printf("# undef CONFIG_STDIO_BUFFER_SIZE\n");
printf("# define CONFIG_STDIO_BUFFER_SIZE 0\n");
printf("#endif\n\n");
- printf("/* If mountpoint support in not included, then no filesystem can\n");
- printf(" * be supported.\n");
- printf(" */\n\n");
+ printf("/* If mountpoint support in not included, then no filesystem can be supported */\n\n");
printf("#ifdef CONFIG_DISABLE_MOUNTPOINT\n");
printf("# undef CONFIG_FS_FAT\n");
printf("#endif\n\n");
+ printf("/* There can be no network support with no socket descriptors */\n\n");
+ printf("#if CONFIG_NSOCKET_DESCRIPTORS <= 0\n");
+ printf("# undef CONFIG_NET\n");
+ printf("#endif\n\n");
+ printf("/* Conversely, if there is no network support, there is no need for\n");
+ printf(" * socket descriptors\n");
+ printf(" */\n\n");
+ printf("#ifndef CONFIG_NET\n");
+ printf("# undef CONFIG_NSOCKET_DESCRIPTORS\n");
+ printf("# define CONFIG_NSOCKET_DESCRIPTORS 0\n");
+ printf("#endif\n\n");
+ printf("/* UDP support can only be provided on top of basic network support */\n\n");
+ printf("#ifndef CONFIG_NET\n");
+ printf("# undef CONFIG_NET_UDP\n");
+ printf("#endif\n\n");
printf("/* Verbose debug only makes sense if debug is enabled */\n\n");
printf("#ifndef CONFIG_DEBUG\n");
printf("# undef CONFIG_DEBUG_VERBOSE\n");