summaryrefslogtreecommitdiff
path: root/nuttx/include/net/uip
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-07 18:54:35 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-07 18:54:35 +0000
commita97e1cc4d1195f56bc10acbcd469bb71e016476c (patch)
treecf55edbd73ba0e05c79ccf087fc03d6e6fcfd1b4 /nuttx/include/net/uip
parent50470d26f72a21786f23219f157a12aab64f2683 (diff)
downloadpx4-nuttx-a97e1cc4d1195f56bc10acbcd469bb71e016476c.tar.gz
px4-nuttx-a97e1cc4d1195f56bc10acbcd469bb71e016476c.tar.bz2
px4-nuttx-a97e1cc4d1195f56bc10acbcd469bb71e016476c.zip
Finished partitioning uip.c (now system is broken)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@375 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include/net/uip')
-rw-r--r--nuttx/include/net/uip/uip-arch.h58
-rw-r--r--nuttx/include/net/uip/uip.h190
2 files changed, 114 insertions, 134 deletions
diff --git a/nuttx/include/net/uip/uip-arch.h b/nuttx/include/net/uip/uip-arch.h
index 8f1d6b41f..1d4337839 100644
--- a/nuttx/include/net/uip/uip-arch.h
+++ b/nuttx/include/net/uip/uip-arch.h
@@ -57,28 +57,20 @@
* Definitions
****************************************************************************/
-/* The following flags are passed as an argument to the uip_interrupt()
+/* The following flags are passed as an argument to the uip_poll()
* function. They are used to distinguish between the two cases where
- * uip_interrupt() is called. It can be called either because we have
+ * uip_poll() is called. It can be called either because we have
* incoming data that should be processed, or because the periodic
- * timer has fired. These values are never used directly, but only in
- * the macrose defined in this file.
+ * timer has fired.
*
- * UIP_DRV_RECEIVE - There is new incoming data from the driver in the d_buf
- * field of the uip_driver_s structure. The length of the
- * new data is provided in the d_len field of the
- * uip_driver_s structure.
* UIP_DRV_TIMER - Called periodically from driver to service timeout-
* related activities to and to get timeout-related
* responses (e.g., reset)
* UIP_DRV_POLL - Poll TCP for data to be transmitted
- * UIP_DRV_UDPPOLL - Poll for UDP data to be transmitted. This value is used
- * internally by the uip_poll logic.
*/
-#define UIP_DRV_RECEIVE 1
-#define UIP_DRV_TIMER 2
-#define UIP_DRV_POLL 3
+#define UIP_DRV_TIMER 1
+#define UIP_DRV_POLL 2
/****************************************************************************
* Public Types
@@ -214,7 +206,7 @@ struct uip_driver_s
*
* dev->d_len = devicedriver_poll();
* if(dev->d_len > 0) {
- * uip_input();
+ * uip_input(dev);
* if(dev->d_len > 0) {
* devicedriver_send();
* }
@@ -230,7 +222,7 @@ struct uip_driver_s
* if(dev->d_len > 0) {
* if(BUF->type == HTONS(UIP_ETHTYPE_IP)) {
* uip_arp_ipin();
- * uip_input();
+ * uip_input(dev);
* if(dev->d_len > 0) {
* uip_arp_out();
* devicedriver_send();
@@ -243,12 +235,12 @@ struct uip_driver_s
* }
*/
-#define uip_input(dev) uip_interrupt(dev, UIP_DRV_RECEIVE)
+extern void uip_input(struct uip_driver_s *dev);
/* Polling of connections.
*
* This function will traverse each active uIP connection structure and
- * perform uip_interrupt with the specified event. After each polling each
+ * perform uip_input with the specified event. After each polling each
* active uIP connection structure, this function will call the provided
* callback function if the poll resulted in new data to be send. The poll
* will continue until all connections have been polled or until the user-
@@ -305,37 +297,29 @@ extern int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback, int
#define uip_periodic(dev,cb) uip_poll(dev, db, UIP_DRV_TIMER);
-/* Architecure support
- *
- * The actual uIP function which does all the work. Called from the
- * interrupt level by a device driver.
- */
-
-extern void uip_interrupt(struct uip_driver_s *dev, uint8 event);
-
/* By defining UIP_ARCH_CHKSUM, the architecture can replace the following
* functions with hardware assisted solutions.
*/
/* Carry out a 32-bit addition.
*
- * Because not all architectures for which uIP is intended has native
- * 32-bit arithmetic, uIP uses an external C function for doing the
- * required 32-bit additions in the TCP protocol processing. This
- * function should add the two arguments and place the result in the
- * global variable uip_acc32.
+ * op32 - A pointer to a 4-byte array representing a 32-bit
+ * integer in network byte order (big endian). This value may not
+ * be word aligned.
*
- * Note: The 32-bit integer pointed to by the op32 parameter and the
- * result in the uip_acc32 variable are in network byte order (big
- * endian).
+ * For uip_incr32, the value pointed to by op32 is modified in place
+ * For uip_add32, the value pointed to by op32 is unmodified
+*
+ * op16 - A 16-bit integer in host byte order.
*
- * op32 A pointer to a 4-byte array representing a 32-bit
- * integer in network byte order (big endian).
+ * sum - The location to return the result (32-bit, network byte order,
+ * possibly unaligned).
*
- * op16 A 16-bit integer in host byte order.
+ * uip_add32 only.
*/
-extern void uip_add32(uint8 *op32, uint16 op16);
+extern void uip_add32(const uint8 *op32, uint16 op16, uint8 *sum);
+extern void uip_incr32(uint8 *op32, uint16 op16);
/* Calculate the Internet checksum over a buffer.
*
diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h
index 283891edb..ed8d85bed 100644
--- a/nuttx/include/net/uip/uip.h
+++ b/nuttx/include/net/uip/uip.h
@@ -222,55 +222,54 @@ 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. */
+ 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. */
+ 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 recived 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
- connections was avaliable. */
- uip_stats_t synrst; /* Number of SYNs for closed ports,
- triggering a RST. */
- } tcp; /* TCP statistics. */
+ 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. */
+ 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
+ connections was avaliable. */
+ 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. */
+ 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 */
};
@@ -282,28 +281,29 @@ struct uip_tcpip_hdr
/* IPv6 Ip header. */
- uint8 vtc;
- uint8 tcflow;
- uint16 flow;
- uint8 len[2];
- uint8 proto, ttl;
- uip_ip6addr_t srcipaddr;
- uip_ip6addr_t destipaddr;
+ 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 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 */
+ 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 */
@@ -327,31 +327,31 @@ struct uip_icmpip_hdr
{
#ifdef CONFIG_NET_IPv6
- /* IPv6 IP header. */
+ /* IPv6 Ip header. */
- uint8 vtc;
- uint8 tcf;
- uint16 flow;
- uint8 len[2];
- uint8 proto;
- uint8 ttl;
- uip_ip6addr_t srcipaddr;
- uip_ip6addr_t destipaddr;
+ 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 */
+ 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 */
@@ -384,31 +384,31 @@ struct uip_udpip_hdr
{
#ifdef CONFIG_NET_IPv6
- /* IPv6 IP header. */
+ /* IPv6 Ip header. */
- uint8 vtc;
- uint8 tcf;
- uint16 flow;
- uint8 len[2];
- uint8 proto;
- uint8 ttl;
- uip_ip6addr_t srcipaddr;
- uip_ip6addr_t destipaddr;
+ 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 */
+ 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 */
@@ -459,10 +459,6 @@ extern uint16 uip_urglen; /* Length of (received) urgent data */
extern struct uip_conn *uip_conn;
-/* 4-byte array used for the 32-bit sequence number calculations.*/
-
-extern uint8 uip_acc32[4];
-
/* The current UDP connection. */
#ifdef CONFIG_NET_UDP