summaryrefslogtreecommitdiff
path: root/nuttx/include/net/uip/uip.h
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-22 18:36:46 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-22 18:36:46 +0000
commitc5148ad9e5d0c44c891f843bc7927bdcce0aee1a (patch)
tree6f54ddc25051c52d0ce5226bfac63c0054137b7c /nuttx/include/net/uip/uip.h
parent7d4b2f6253d8ac898def6839b2ccc2ae61e24135 (diff)
downloadpx4-nuttx-c5148ad9e5d0c44c891f843bc7927bdcce0aee1a.tar.gz
px4-nuttx-c5148ad9e5d0c44c891f843bc7927bdcce0aee1a.tar.bz2
px4-nuttx-c5148ad9e5d0c44c891f843bc7927bdcce0aee1a.zip
TCP and ICMP protocols may now be disabled
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@398 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include/net/uip/uip.h')
-rw-r--r--nuttx/include/net/uip/uip.h501
1 files changed, 53 insertions, 448 deletions
diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h
index 59bd615bc..e2f171253 100644
--- a/nuttx/include/net/uip/uip.h
+++ b/nuttx/include/net/uip/uip.h
@@ -1,10 +1,9 @@
/****************************************************************************
- * uip.h
- * Header file for the uIP TCP/IP stack.
+ * net/uip/uip.h
*
- * The uIP TCP/IP stack header file contains definitions for a number
- * of C macros that are used by uIP programs as well as internal uIP
- * structures, TCP/IP header structures and function declarations.
+ * The uIP header file contains definitions for a number of C macros that
+ * are used by uIP programs as well as internal uIP structures and function
+ * declarations.
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -18,6 +17,7 @@
* 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
@@ -49,11 +49,12 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
#include <queue.h>
#include <arpa/inet.h>
-#include <net/uip/uipopt.h>
+#include <net/uip/uipopt.h>
/****************************************************************************
* Definitions
****************************************************************************/
@@ -85,22 +86,6 @@
#define UIP_DATA_EVENTS (UIP_ACKDATA|UIP_NEWDATA|UIP_REXMIT|UIP_POLL)
#define UIP_CONN_EVENTS (UIP_CLOSE|UIP_ABORT|UIP_CONNECTED|UIP_TIMEDOUT)
-/* The TCP states used in the struct uip_conn tcpstateflags field */
-
-#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 d_buf buffer.
*
* This macro holds the available size for user data in the
@@ -122,16 +107,10 @@
/* Header sizes */
#ifdef CONFIG_NET_IPv6
-# define UIP_IPH_LEN 40
-#else /* CONFIG_NET_IPv6 */
+# define UIP_IPH_LEN 40 /* Size of IP header */
+#else
# 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 */
-#define UIP_IPTCPH_LEN (UIP_TCPH_LEN + UIP_IPH_LEN) /* Size of IP + TCP header */
-#define UIP_TCPIP_HLEN UIP_IPTCPH_LEN
+#endif
/****************************************************************************
* Public Type Definitions
@@ -144,176 +123,13 @@ typedef uint16 uip_ip6addr_t[8];
#ifdef CONFIG_NET_IPv6
typedef uip_ip6addr_t uip_ipaddr_t;
-#else /* CONFIG_NET_IPv6 */
+#else
typedef uip_ip4addr_t uip_ipaddr_t;
-#endif /* CONFIG_NET_IPv6 */
-
-/* Representation of a uIP TCP connection.
- *
- * The uip_conn structure is used for identifying a connection. All
- * but one field in the structure are to be considered read-only by an
- * application. The only exception is the "private: field whos purpose
- * is to let the application store application-specific state (e.g.,
- * file pointers) for the connection.
- */
-
-struct uip_driver_s; /* Forward reference */
-struct uip_conn
-{
- dq_entry_t node; /* Implements a doubly linked list */
-#if 0 /* Not used */
- uip_ipaddr_t lipaddr; /* The local IP address */
-#endif
- uip_ipaddr_t ripaddr; /* The IP address of the remote host */
- uint16 lport; /* The local TCP port, in network byte order */
- uint16 rport; /* The remoteTCP port, in network byte order */
- uint8 rcv_nxt[4]; /* The sequence number that we expect to
- * receive next */
- uint8 snd_nxt[4]; /* The sequence number that was last sent by us */
- uint16 len; /* Length of the data that was previously sent */
- uint16 mss; /* Current maximum segment size for the
- * connection */
- uint16 initialmss; /* Initial maximum segment size for the
- * connection */
- uint8 sa; /* Retransmission time-out calculation state
- * variable */
- uint8 sv; /* Retransmission time-out calculation state
- * variable */
- uint8 rto; /* Retransmission time-out */
- uint8 tcpstateflags; /* TCP state and flags */
- uint8 timer; /* The retransmission timer (units: half-seconds) */
- uint8 nrtx; /* The number of retransmissions for the last
- * segment sent */
-
- /* Read-ahead buffering */
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- sq_queue_t readahead;
-#endif
-
- /* Higher level logic can retain application specific information
- * in the following:
- *
- * data_event() is called on all events. Normally, the input flags are
- * returned, however, the implemenation may set one of the following:
- *
- * UIP_CLOSE - Gracefully close the current connection
- * UIP_ABORT - Abort (reset) the current connection on an error that
- * prevents UIP_CLOSE from working.
- *
- * Or clear the following:
- *
- * UIP_NEWDATA - May be cleared to suppress returning the ACK response.
- * (dev->d_len should also be set to zero in this case).
- *
- * accept() is called when the TCP logic has created a connection
- * connection_event() is called on any of the subset of connection-related events
- */
-
- void *data_private;
- uint8 (*data_event)(struct uip_driver_s *dev, struct uip_conn *conn, uint8 flags);
-
- void *accept_private;
- int (*accept)(struct uip_conn *listener, struct uip_conn *conn);
-
- void *connection_private;
- void (*connection_event)(struct uip_conn *conn, uint8 flags);
-};
-
-/* The following structure is used to handle read-ahead buffering for TCP
- * connection. When incoming TCP data is received while no application is
- * listening for the data, that data will be retained in these read-ahead
- * buffers so that no data is lost.
- */
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
-struct uip_readahead_s
-{
- sq_entry_t rh_node; /* Supports a singly linked list */
- uint16 rh_nbytes; /* Number of bytes available in this buffer */
- uint8 rh_buffer[CONFIG_NET_TCP_READAHEAD_BUFSIZE];
-};
#endif
-#ifdef CONFIG_NET_UDP
-/* Representation of a uIP UDP connection */
-
-struct uip_udp_conn
-{
- dq_entry_t node; /* Supports a doubly linked list */
- uip_ipaddr_t ripaddr; /* The IP address of the remote peer */
- uint16 lport; /* The local port number in network byte order */
- uint16 rport; /* The remote port number in network byte order */
- uint8 ttl; /* Default time-to-live */
-
- /* Defines the UDP callback */
-
- void *private;
- void (*event)(struct uip_driver_s *dev, struct uip_udp_conn *conn, uint8 flags);
-};
-#endif /* CONFIG_NET_UDP */
-
-/* The structure holding the TCP/IP statistics that are gathered if
- * CONFIG_NET_STATISTICS is defined.
- */
-
-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 */
- uip_stats_t vhlerr; /* Number of packets dropped due to wrong
- IP version or header length */
- uip_stats_t hblenerr; /* Number of packets dropped due to wrong
- IP length, high byte */
- uip_stats_t lblenerr; /* Number of packets dropped due to wrong
- IP length, low byte */
- uip_stats_t fragerr; /* Number of packets dropped since they
- were IP fragments */
- uip_stats_t chkerr; /* Number of packets dropped due to IP
- checksum errors */
- uip_stats_t protoerr; /* Number of packets dropped since they
- were neither ICMP, UDP nor TCP */
- } ip; /* IP statistics */
-
- 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
- {
- uip_stats_t drop; /* Number of dropped TCP segments */
- uip_stats_t recv; /* Number of received TCP segments */
- uip_stats_t sent; /* Number of sent TCP segments */
- uip_stats_t chkerr; /* Number of TCP segments with a bad checksum */
- uip_stats_t ackerr; /* Number of TCP segments with a bad ACK number */
- uip_stats_t rst; /* Number of recevied TCP RST (reset) segments */
- uip_stats_t rexmit; /* Number of retransmitted TCP segments */
- uip_stats_t syndrop; /* Number of dropped SYNs due to too few
- available connections */
- uip_stats_t synrst; /* Number of SYNs for closed ports triggering a RST */
- } tcp; /* TCP statistics */
-
-#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 */
- uip_stats_t chkerr; /* Number of UDP segments with a bad checksum */
- } udp; /* UDP statistics */
-#endif /* CONFIG_NET_UDP */
-};
-
-/* The TCP and IP headers */
+/* The IP header */
-struct uip_tcpip_hdr
+struct uip_ip_hdr
{
#ifdef CONFIG_NET_IPv6
@@ -344,119 +160,55 @@ struct uip_tcpip_hdr
uint16 destipaddr[2]; /* 32-bit Destination IP address */
#endif /* CONFIG_NET_IPv6 */
-
- /* TCP header */
-
- 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];
};
-/* The ICMP and IP headers */
-
-struct uip_icmpip_hdr
-{
-#ifdef CONFIG_NET_IPv6
-
- /* IPv6 Ip header */
-
- uint8 vtc; /* Bits 0-3: version, bits 4-7: traffic class (MS) */
- uint8 tcf; /* Bits 0-3: traffic class (LS), bits 4-7: flow label (MS) */
- uint16 flow; /* 16-bit flow label (LS) */
- uint8 len[2]; /* 16-bit Payload length */
- uint8 proto; /* 8-bit Next header (same as IPv4 protocol field) */
- uint8 ttl; /* 8-bit Hop limit (like IPv4 TTL field) */
- uip_ip6addr_t srcipaddr; /* 128-bit Source address */
- uip_ip6addr_t destipaddr; /* 128-bit Destination address */
-
-#else /* CONFIG_NET_IPv6 */
-
- /* IPv4 IP header */
-
- uint8 vhl; /* 8-bit Version (4) and header length (5 or 6) */
- uint8 tos; /* 8-bit Type of service (e.g., 6=TCP) */
- uint8 len[2]; /* 16-bit Total length */
- uint8 ipid[2]; /* 16-bit Identification */
- uint8 ipoffset[2]; /* 16-bit IP flags + fragment offset */
- uint8 ttl; /* 8-bit Time to Live */
- uint8 proto; /* 8-bit Protocol */
- uint16 ipchksum; /* 16-bit Header checksum */
- uint16 srcipaddr[2]; /* 32-bit Source IP address */
- uint16 destipaddr[2]; /* 32-bit Destination IP address */
-
-#endif /* CONFIG_NET_IPv6 */
-
- /* ICMP (echo) header */
-
- uint8 type;
- uint8 icode;
- uint16 icmpchksum;
+/* Protocol-specific support */
-#ifndef CONFIG_NET_IPv6
-
- uint16 id;
- uint16 seqno;
-
-#else /* !CONFIG_NET_IPv6 */
+#include <net/uip/uip-tcp.h>
+#include <net/uip/uip-udp.h>
+#include <net/uip/uip-icmp.h>
- uint8 flags;
- uint8 reserved1;
- uint8 reserved2;
- uint8 reserved3;
- uint8 icmp6data[16];
- uint8 options[1];
+/* The structure holding the uIP statistics that are gathered if
+ * CONFIG_NET_STATISTICS is defined.
+ */
-#endif /* !CONFIG_NET_IPv6 */
+#ifdef CONFIG_NET_STATISTICS
+struct uip_ip_stats_s
+{
+ 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 */
+ uip_stats_t vhlerr; /* Number of packets dropped due to wrong
+ IP version or header length */
+ uip_stats_t hblenerr; /* Number of packets dropped due to wrong
+ IP length, high byte */
+ uip_stats_t lblenerr; /* Number of packets dropped due to wrong
+ IP length, low byte */
+ uip_stats_t fragerr; /* Number of packets dropped since they
+ were IP fragments */
+ uip_stats_t chkerr; /* Number of packets dropped due to IP
+ checksum errors */
+ uip_stats_t protoerr; /* Number of packets dropped since they
+ were neither ICMP, UDP nor TCP */
};
-/* The UDP and IP headers */
-
-struct uip_udpip_hdr
+struct uip_stats
{
-#ifdef CONFIG_NET_IPv6
-
- /* IPv6 Ip header */
+ struct uip_ip_stats_s ip; /* IP statistics */
- uint8 vtc; /* Bits 0-3: version, bits 4-7: traffic class (MS) */
- uint8 tcf; /* Bits 0-3: traffic class (LS), 4-bits: flow label (MS) */
- uint16 flow; /* 16-bit flow label (LS) */
- uint8 len[2]; /* 16-bit Payload length */
- uint8 proto; /* 8-bit Next header (same as IPv4 protocol field) */
- uint8 ttl; /* 8-bit Hop limit (like IPv4 TTL field) */
- uip_ip6addr_t srcipaddr; /* 128-bit Source address */
- uip_ip6addr_t destipaddr; /* 128-bit Destination address */
-
-#else /* CONFIG_NET_IPv6 */
-
- /* IPv4 header */
-
- uint8 vhl; /* 8-bit Version (4) and header length (5 or 6) */
- uint8 tos; /* 8-bit Type of service (e.g., 6=TCP) */
- uint8 len[2]; /* 16-bit Total length */
- uint8 ipid[2]; /* 16-bit Identification */
- uint8 ipoffset[2]; /* 16-bit IP flags + fragment offset */
- uint8 ttl; /* 8-bit Time to Live */
- uint8 proto; /* 8-bit Protocol */
- uint16 ipchksum; /* 16-bit Header checksum */
- uint16 srcipaddr[2]; /* 32-bit Source IP address */
- uint16 destipaddr[2]; /* 32-bit Destination IP address */
-
-#endif /* CONFIG_NET_IPv6 */
+#ifdef CONFIG_NET_ICMP
+ struct uip_icmp_stats_s icmp; /* ICMP statistics */
+#endif
- /* UDP header */
+#ifdef CONFIG_NET_TCP
+ struct uip_tcp_stats_s tcp; /* TCP statistics */
+#endif
- uint16 srcport;
- uint16 destport;
- uint16 udplen;
- uint16 udpchksum;
+#ifdef CONFIG_NET_UDP
+ struct uip_udp_stats_s udp; /* UDP statistics */
+#endif
};
+#endif /* CONFIG_NET_STATISTICS */
/* Representation of a 48-bit Ethernet address */
@@ -469,18 +221,11 @@ struct uip_eth_addr
* Public Data
****************************************************************************/
-/* The current UDP connection */
-
-#ifdef CONFIG_NET_UDP
-extern struct uip_udp_conn *uip_udp_conn;
-#endif /* CONFIG_NET_UDP */
-
-/* The uIP TCP/IP statistics.
- *
- * This is the variable in which the uIP TCP/IP statistics are gathered.
- */
+/* This is the structure in which the statistics are gathered. */
+#ifdef CONFIG_NET_STATISTICS
extern struct uip_stats uip_stat;
+#endif
/****************************************************************************
* Public Function Prototypes
@@ -505,65 +250,8 @@ extern void uip_setipid(uint16 id);
* Functions used by an application running of top of uIP. This includes
* functions for opening and closing connections, sending and receiving
* data, etc.
- *
- * 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
-
-/* Bind a TCP connection to a local address */
-
-#ifdef CONFIG_NET_IPv6
-extern int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in6 *addr);
-#else
-extern int uip_tcpbind(struct uip_conn *conn, const struct sockaddr_in *addr);
-#endif
-
-/* 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().
- *
- * This function is called from normal user level code.
*/
-#ifdef CONFIG_NET_IPv6
-extern int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in6 *addr);
-#else
-extern int uip_tcpconnect(struct uip_conn *conn, const struct sockaddr_in *addr);
-#endif
-
-/* Start listening to the port bound to the specified TCP connection */
-
-extern int uip_listen(struct uip_conn *conn);
-
-/* Stop listening to the port bound to the specified TCP connection */
-
-extern int uip_unlisten(struct uip_conn *conn);
-
-/* Check if a connection has outstanding (i.e., unacknowledged) data */
-
-#define uip_outstanding(conn) ((conn)->len)
-
/* Send data on the current connection.
*
* This function is used to send out a single segment of TCP
@@ -589,13 +277,6 @@ extern int uip_unlisten(struct uip_conn *conn);
extern void uip_send(struct uip_driver_s *dev, const void *buf, int len);
-/* Access to TCP read-ahead buffers */
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
-extern struct uip_readahead_s *uip_tcpreadaheadalloc(void);
-extern void uip_tcpreadaheadrelease(struct uip_readahead_s *buf);
-#endif /* CONFIG_NET_NTCP_READAHEAD_BUFFERS */
-
/* The length of any incoming data that is currently avaliable (if avaliable)
* in the d_appdata buffer.
*
@@ -605,34 +286,6 @@ extern void uip_tcpreadaheadrelease(struct uip_readahead_s *buf);
#define uip_datalen(dev) ((dev)->d_len)
-/* Tell the sending host to stop sending data.
- *
- * This function will close our receiver's window so that we stop
- * receiving data for the current connection.
- */
-
-#define uip_stop(conn) ((conn)->tcpstateflags |= UIP_STOPPED)
-
-/* Find out if the current connection has been previously stopped with
- * uip_stop().
- */
-
-#define uip_stopped(conn) ((conn)->tcpstateflags & UIP_STOPPED)
-
-/* Restart the current connection, if is has previously been stopped
- * with uip_stop().
- *
- * This function will open the receiver's window again so that we
- * start receiving data for the current connection.
- */
-
-#define uip_restart(conn,f) \
- do { \
- (f) |= UIP_NEWDATA; \
- (conn)->tcpstateflags &= ~UIP_STOPPED; \
- } while(0)
-
-
/* uIP tests that can be made to determine in what state the current
* connection is, and what the application function should do.
*
@@ -710,54 +363,6 @@ extern void uip_tcpreadaheadrelease(struct uip_readahead_s *buf);
#define uip_poll_event(f) ((f) & UIP_POLL)
-/* Get the initial maxium segment size (MSS) of the current
- * connection.
- */
-
-#define uip_initialmss(conn) ((conn)->initialmss)
-
-/* Get the current maxium segment size that can be sent on the current
- * connection.
- *
- * The current maxiumum segment size that can be sent on the
- * connection is computed from the receiver's window and the MSS of
- * the connection (which also is available by calling
- * uip_initialmss()).
- */
-
-#define uip_mss(conn) ((conn)->mss)
-
-/* Bind a UDP connection to a local address */
-
-#ifdef CONFIG_NET_IPv6
-extern int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr);
-#else
-extern int uip_udpbind(struct uip_udp_conn *conn, const struct sockaddr_in *addr);
-#endif
-
-/* 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_udpbind() call, after the uip_udpconnect() function has been
- * called.
- *
- * This function is called as part of the implementation of sendto
- * and recvfrom.
- *
- * addr The address of the remote host.
- */
-
-#ifdef CONFIG_NET_IPv6
-extern int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr);
-#else
-extern int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr);
-#endif
-
-/* Enable/disable UDP callbacks on a connection */
-
-extern void uip_udpenable(struct uip_udp_conn *conn);
-extern void uip_udpdisable(struct uip_udp_conn *conn);
-
/* uIP convenience and converting functions.
*
* These functions can be used for converting between different data