From 50470d26f72a21786f23219f157a12aab64f2683 Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 6 Nov 2007 23:38:14 +0000 Subject: Breaking uip.c into smaller functions/files git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@374 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/net/net-sockets.c | 2 +- nuttx/net/send.c | 2 +- nuttx/net/uip/Make.defs | 20 ++- nuttx/net/uip/uip-chksum.c | 212 ++++++++++++++++++++++++ nuttx/net/uip/uip-initialize.c | 105 ++++++++++++ nuttx/net/uip/uip-internal.h | 46 +++++- nuttx/net/uip/uip-poll.c | 27 +-- nuttx/net/uip/uip-udpcallback.c | 90 ++++++++++ nuttx/net/uip/uip-udpinput.c | 156 +++++++++++++++++ nuttx/net/uip/uip-udppoll.c | 134 +++++++++++++++ nuttx/net/uip/uip-udpsend.c | 176 ++++++++++++++++++++ nuttx/net/uip/uip.c | 358 +++------------------------------------- 12 files changed, 963 insertions(+), 365 deletions(-) create mode 100644 nuttx/net/uip/uip-chksum.c create mode 100644 nuttx/net/uip/uip-initialize.c create mode 100644 nuttx/net/uip/uip-udpcallback.c create mode 100644 nuttx/net/uip/uip-udpinput.c create mode 100644 nuttx/net/uip/uip-udppoll.c create mode 100644 nuttx/net/uip/uip-udpsend.c (limited to 'nuttx/net') diff --git a/nuttx/net/net-sockets.c b/nuttx/net/net-sockets.c index 34a20a05a..98f9413bd 100644 --- a/nuttx/net/net-sockets.c +++ b/nuttx/net/net-sockets.c @@ -100,7 +100,7 @@ void net_initialize(void) { /* Initialize the uIP layer */ - uip_init(); + uip_initialize(); /* Initialize the socket layer */ diff --git a/nuttx/net/send.c b/nuttx/net/send.c index cfb56f1ca..84c6757b0 100644 --- a/nuttx/net/send.c +++ b/nuttx/net/send.c @@ -259,7 +259,7 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags) struct send_s state; irqstate_t save; int err; - int ret; + int ret = OK; /* Verify that the sockfd corresponds to valid, allocated socket */ diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs index c76f76299..d150e24fe 100644 --- a/nuttx/net/uip/Make.defs +++ b/nuttx/net/uip/Make.defs @@ -14,7 +14,7 @@ # 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 +# 3. Neither the name NuttX nor the names of its contributors may be # used to endorse or promote products derived from this software # without specific prior written permission. # @@ -34,6 +34,20 @@ ############################################################################ UIP_ASRCS = -UIP_CSRCS = uip-arp.c uip.c uip-send.c uip-fw.c uip-neighbor.c uip-split.c \ - uip-tcpconn.c uip-udpconn.c uip-listen.c uip-poll.c +UIP_CSRCS = + +ifeq ($(CONFIG_NET),y) + +UIP_CSRCS += uip-initialize.c uip-arp.c uip.c uip-send.c uip-fw.c \ + uip-neighbor.c uip-split.c uip-tcpconn.c uip-listen.c \ + uip-poll.c uip-chksum.c + +ifeq ($(CONFIG_NET_UDP),y) + +UIP_CSRCS += uip-udpconn.c uip-udppoll.c uip-udpsend.c uip-udpinput.c \ + uip-udpcallback.c + +endif +endif + diff --git a/nuttx/net/uip/uip-chksum.c b/nuttx/net/uip/uip-chksum.c new file mode 100644 index 000000000..ebf814e8b --- /dev/null +++ b/nuttx/net/uip/uip-chksum.c @@ -0,0 +1,212 @@ +/**************************************************************************** + * net/uip/uip-chksum.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#ifdef CONFIG_NET + +#include +#include + +#include +#include +#include + +#include "uip-internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN]) + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +#if !UIP_ARCH_CHKSUM +static uint16 chksum(uint16 sum, const uint8 *data, uint16 len) +{ + uint16 t; + const uint8 *dataptr; + const uint8 *last_byte; + + dataptr = data; + last_byte = data + len - 1; + + while(dataptr < last_byte) + { + /* At least two more bytes */ + + t = (dataptr[0] << 8) + dataptr[1]; + sum += t; + if (sum < t) + { + sum++; /* carry */ + } + dataptr += 2; + } + + if (dataptr == last_byte) + { + t = (dataptr[0] << 8) + 0; + sum += t; + if (sum < t) + { + sum++; /* carry */ + } + } + + /* Return sum in host byte order. */ + + return sum; +} + +static uint16 upper_layer_chksum(struct uip_driver_s *dev, uint8 proto) +{ + uint16 upper_layer_len; + uint16 sum; + +#ifdef CONFIG_NET_IPv6 + upper_layer_len = (((uint16)(BUF->len[0]) << 8) + BUF->len[1]); +#else /* CONFIG_NET_IPv6 */ + upper_layer_len = (((uint16)(BUF->len[0]) << 8) + BUF->len[1]) - UIP_IPH_LEN; +#endif /* CONFIG_NET_IPv6 */ + + /* First sum pseudoheader. */ + + /* IP protocol and length fields. This addition cannot carry. */ + sum = upper_layer_len + proto; + + /* Sum IP source and destination addresses. */ + sum = chksum(sum, (uint8 *)&BUF->srcipaddr, 2 * sizeof(uip_ipaddr_t)); + + /* Sum TCP header and data. */ + sum = chksum(sum, &dev->d_buf[UIP_IPH_LEN + UIP_LLH_LEN], upper_layer_len); + + return (sum == 0) ? 0xffff : htons(sum); +} + +#ifdef CONFIG_NET_IPv6 +static uint16 uip_icmp6chksum(struct uip_driver_s *dev) +{ + return upper_layer_chksum(dev, UIP_PROTO_ICMP6); +} +#endif /* CONFIG_NET_IPv6 */ + +#endif /* UIP_ARCH_CHKSUM */ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* 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) +{ + return htons(chksum(0, (uint8 *)data, len)); +} + +/* Calculate the IP header checksum of the packet header in d_buf. */ + +#ifndef UIP_ARCH_IPCHKSUM +uint16 uip_ipchksum(struct uip_driver_s *dev) +{ + uint16 sum; + + sum = chksum(0, &dev->d_buf[UIP_LLH_LEN], UIP_IPH_LEN); + return (sum == 0) ? 0xffff : htons(sum); +} +#endif + +/* Calculate the TCP checksum of the packet in d_buf and d_appdata. */ + +uint16 uip_tcpchksum(struct uip_driver_s *dev) +{ + return upper_layer_chksum(dev, UIP_PROTO_TCP); +} + +/* Calculate the UDP checksum of the packet in d_buf and d_appdata. */ + +#ifdef CONFIG_NET_UDP_CHECKSUMS +uint16 uip_udpchksum(struct uip_driver_s *dev) +{ + return upper_layer_chksum(dev, UIP_PROTO_UDP); +} +#endif /* UIP_UDP_CHECKSUMS */ +#endif /* UIP_ARCH_CHKSUM */ + +#endif /* CONFIG_NET */ diff --git a/nuttx/net/uip/uip-initialize.c b/nuttx/net/uip/uip-initialize.c new file mode 100644 index 000000000..dabcf64cc --- /dev/null +++ b/nuttx/net/uip/uip-initialize.c @@ -0,0 +1,105 @@ +/**************************************************************************** + * net/uip/uip-udppoll.c + * Poll for the availability of UDP TX data + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Adapted for NuttX from logic in uIP which also has a BSD-like license: + * + * Original author Adam Dunkels + * Copyright () 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#ifdef CONFIG_NET + +#include + +#include "uip-internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_initialize + * + * Description: + * Perform initialization of the uIP layer + * + * Parameters: + * None + * + * Return: + * None + * + ****************************************************************************/ + +void uip_initialize(void) +{ + /* Initialize the listening port structures */ + + uip_listeninit(); + + /* Initialize the TCP/IP connection structures */ + + uip_tcpinit(); + + /* Initialize the UDP connection structures */ + +#ifdef CONFIG_NET_UDP + uip_udpinit(); +#endif + + /* IPv4 initialization. */ +} +#endif /* CONFIG_NET */ + diff --git a/nuttx/net/uip/uip-internal.h b/nuttx/net/uip/uip-internal.h index 9b293abef..c8d1e10c4 100644 --- a/nuttx/net/uip/uip-internal.h +++ b/nuttx/net/uip/uip-internal.h @@ -43,6 +43,9 @@ * Included Files ****************************************************************************/ +#include +#ifdef CONFIG_NET + #include #include #include @@ -63,6 +66,10 @@ extern const uip_ipaddr_t all_ones_addr; extern const uip_ipaddr_t all_zeroes_addr; +/* Increasing number used for the IP ID field. */ + +extern uint16 g_ipid; + /**************************************************************************** * Public Function Prototypes ****************************************************************************/ @@ -83,21 +90,52 @@ EXTERN struct uip_conn *uip_tcplistener(uint16 portno); EXTERN struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf); EXTERN void uip_tcpnextsequence(void); +/* Defined in uip_listen.c **************************************************/ + +EXTERN void uip_listeninit(void); +EXTERN boolean uip_islistener(uint16 port); +EXTERN int uip_accept(struct uip_conn *conn, uint16 portno); + +#ifdef CONFIG_NET_UDP /* Defined in uip_udpconn.c *************************************************/ EXTERN void uip_udpinit(void); EXTERN struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf); EXTERN struct uip_udp_conn *uip_nextudpconn(struct uip_udp_conn *conn); -/* Defined in uip_listen.c **************************************************/ +/* Defined in uip-udppool.c *************************************************/ -EXTERN void uip_listeninit(void); -EXTERN boolean uip_islistener(uint16 port); -EXTERN int uip_accept(struct uip_conn *conn, uint16 portno); +EXTERN void uip_udppoll(struct uip_driver_s *dev, struct uip_udp_conn *conn); + +/* Defined in uip-udpsend.c *************************************************/ + +EXTERN void uip_udpsend(struct uip_driver_s *dev, struct uip_udp_conn *conn); + +/* Defined in uip-udpinput.c ************************************************/ + +EXTERN void uip_udpinput(struct uip_driver_s *dev); + +/* Defined in uip_uipcallback.c *********************************************/ + +EXTERN void uip_udpcallback(struct uip_driver_s *dev); +#endif /* CONFIG_NET_UDP */ + +/* UIP logging **************************************************************/ + +/* This function must be provided by the application if CONFIG_NET_LOGGING + * is defined. + */ + +#ifdef CONFIG_NET_LOGGING +EXTERN void uip_log(char *msg); +#else +# define uip_log(m) +#endif #undef EXTERN #ifdef __cplusplus } #endif +#endif /* CONFIG_NET */ #endif /* __UIP_INTERNAL_H */ diff --git a/nuttx/net/uip/uip-poll.c b/nuttx/net/uip/uip-poll.c index 22a641ce1..19dc16a5a 100644 --- a/nuttx/net/uip/uip-poll.c +++ b/nuttx/net/uip/uip-poll.c @@ -58,33 +58,12 @@ * Private Functions ****************************************************************************/ -/**************************************************************************** - * Name: uip_udppoll() - * - * Description: - * Periodic processing for a UDP 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. - * - ****************************************************************************/ - -static inline void uip_udppoll(struct uip_driver_s *dev, unsigned int conn) -{ -} - /**************************************************************************** * Public Functions ****************************************************************************/ /**************************************************************************** - * Function: uip-poll + * Function: uip_poll * * Description: * This function will traverse each active uIP connection structure and @@ -143,15 +122,13 @@ int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback, int event) udp_conn = NULL; while ((udp_conn = uip_nextudpconn(udp_conn))) { - uip_udp_conn = udp_conn; - uip_interrupt(dev, UIP_DRV_UDPPOLL); + uip_udppoll(dev, udp_conn); if (callback(dev)) { irqrestore(flags); return 1; } } - uip_udp_conn = NULL; #endif /* CONFIG_NET_UDP */ irqrestore(flags); diff --git a/nuttx/net/uip/uip-udpcallback.c b/nuttx/net/uip/uip-udpcallback.c new file mode 100644 index 000000000..ed283d193 --- /dev/null +++ b/nuttx/net/uip/uip-udpcallback.c @@ -0,0 +1,90 @@ +/**************************************************************************** + * net/uip/uip-udpcallback.c + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * + * 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 NuttX 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP) + +#include +#include + +#include +#include +#include + +#include "uip-internal.h" + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Function: uip_udpcallback + * + * Description: + * Inform the application holding the UDP socket of a change in state. + * + * Assumptions: + * This function is called at the interrupt level with interrupts disabled. + * + ****************************************************************************/ + +void uip_udpcallback(struct uip_driver_s *dev) +{ + vdbg("uip_flags: %02x\n", uip_flags); + + /* Some sanity checking */ + + if (uip_udp_conn && uip_udp_conn->event) + { + /* Perform the callback */ + + uip_udp_conn->event(dev, uip_udp_conn->private); + } +} + +#endif /* CONFIG_NET && CONFIG_NET_UDP */ diff --git a/nuttx/net/uip/uip-udpinput.c b/nuttx/net/uip/uip-udpinput.c new file mode 100644 index 000000000..d3b1aa2d8 --- /dev/null +++ b/nuttx/net/uip/uip-udpinput.c @@ -0,0 +1,156 @@ +/**************************************************************************** + * net/uip/uip-udpinput.c + * Handling incoming UDP input + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Adapted for NuttX from logic in uIP which also has a BSD-like license: + * + * Original author Adam Dunkels + * Copyright () 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP) + +#include +#include + +#include +#include +#include + +#include "uip-internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define UDPBUF ((struct uip_udpip_hdr *)&dev->d_buf[UIP_LLH_LEN]) + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_udpinput + * + * Description: + * Handle incoming UDP input + * + * Parameters: + * dev - The device driver structure containing the received UDP packet + * + * Return: + * None + * + * Assumptions: + * Called from the interrupt level or with interrupts disabled. + * + ****************************************************************************/ + +void uip_udpinput(struct uip_driver_s *dev) +{ + /* 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 d_sndlen, it has a packet to send. + */ + + dev->d_len -= UIP_IPUDPH_LEN; +#ifdef CONFIG_NET_UDP_CHECKSUMS + dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; + if (UDPBUF->udpchksum != 0 && uip_udpchksum(dev) != 0xffff) + { +#ifdef CONFIG_NET_STATISTICS + uip_stat.udp.drop++; + uip_stat.udp.chkerr++; +#endif + uip_log("udp: bad checksum."); + dev->d_len = 0; + } + else +#endif + { + /* Demultiplex this UDP packet between the UDP "connections". */ + + uip_udp_conn = uip_udpactive(UDPBUF); + if (uip_udp_conn) + { + /* Setup for the application callback */ + + uip_conn = NULL; + + dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; + dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; + dev->d_sndlen = 0; + + /* Perform the application callback */ + + uip_flags = UIP_NEWDATA; + uip_udpcallback(dev); + uip_flags = 0; + + /* If the application has data to send, setup the UDP/IP header */ + + if (dev->d_sndlen > 0) + { + uip_udpsend(dev, uip_udp_conn); + } + + uip_udp_conn = NULL; + } + else + { + uip_log("udp: no matching connection found"); + dev->d_len = 0; + } + } + + return; +} + +#endif /* CONFIG_NET && CONFIG_NET_UDP */ diff --git a/nuttx/net/uip/uip-udppoll.c b/nuttx/net/uip/uip-udppoll.c new file mode 100644 index 000000000..209d4e2ae --- /dev/null +++ b/nuttx/net/uip/uip-udppoll.c @@ -0,0 +1,134 @@ +/**************************************************************************** + * net/uip/uip-udppoll.c + * Poll for the availability of UDP TX data + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Adapted for NuttX from logic in uIP which also has a BSD-like license: + * + * Original author Adam Dunkels + * Copyright () 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP) + +#include +#include + +#include +#include +#include + +#include "uip-internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_udppoll + * + * Description: + * Poll a UDP "connection" structure for availability of TX data + * + * Parameters: + * dev - The device driver structure to use in the send operation + * conn - The UDP "connection" to poll for TX data + * + * Return: + * None + * + * Assumptions: + * Called from the interrupt level or with interrupts disabled. + * + ****************************************************************************/ + +void uip_udppoll(struct uip_driver_s *dev, struct uip_udp_conn *conn) +{ + /* Verify that the UDP connection is valid */ + + if (conn->lport != 0) + { + /* Setup for the application callback */ + + uip_conn = NULL; + uip_udp_conn = conn; + + dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; + dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; + dev->d_len = 0; + dev->d_sndlen = 0; + + /* Perform the application callback */ + + uip_flags = UIP_POLL; + uip_udpcallback(dev); + + /* If the application has data to send, setup the UDP/IP header */ + + if (dev->d_sndlen > 0) + { + uip_udpsend(dev, conn); + uip_udp_conn = NULL; + uip_flags = 0; + return; + } + } + + /* Make sure that d_len is zerp meaning that there is nothing to be sent */ + + dev->d_len = 0; + uip_udp_conn = NULL; + uip_flags = 0; +} + +#endif /* CONFIG_NET && CONFIG_NET_UDP */ diff --git a/nuttx/net/uip/uip-udpsend.c b/nuttx/net/uip/uip-udpsend.c new file mode 100644 index 000000000..207c0ea35 --- /dev/null +++ b/nuttx/net/uip/uip-udpsend.c @@ -0,0 +1,176 @@ +/**************************************************************************** + * net/uip/uip-udpsend.c + * Poll for the availability of UDP TX data + * + * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Adapted for NuttX from logic in uIP which also has a BSD-like license: + * + * Original author Adam Dunkels + * Copyright () 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP) + +#include +#include + +#include +#include +#include + +#include "uip-internal.h" + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define UDPBUF ((struct uip_udpip_hdr *)&dev->d_buf[UIP_LLH_LEN]) + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: uip_udpsend + * + * Description: + * Setup to send a UDP packet + * + * Parameters: + * dev - The device driver structure to use in the send operation + * conn - The UDP "connection" structure holding port information + * + * Return: + * None + * + * Assumptions: + * Called from the interrupt level or with interrupts disabled. + * + ****************************************************************************/ + +void uip_udpsend(struct uip_driver_s *dev, struct uip_udp_conn *conn) +{ + if (dev->d_sndlen == 0) + { + /* The total lenth to send is the size of the application data plus + * the IP and UDP headers (and, eventually, the ethernet header) + */ + + dev->d_len = dev->d_sndlen + UIP_IPUDPH_LEN; + + /* Initialize the IP header. Note that for IPv6, the IP length field + * does not include the IPv6 IP header length. + */ + +#ifdef CONFIG_NET_IPv6 + + UDPBUF->vtc = 0x60; + UDPBUF->tcf = 0x00; + UDPBUF->flow = 0x00; + UDPBUF->len[0] = (dev->d_sndlen >> 8); + UDPBUF->len[1] = (dev->d_sndlen & 0xff); + UDPBUF->proto = UIP_PROTO_UDP; + UDPBUF->ttl = conn->ttl; + + uip_ipaddr_copy(UDPBUF->srcipaddr, &dev->d_ipaddr); + uip_ipaddr_copy(UDPBUF->destipaddr, &conn->ripaddr); + +#else /* CONFIG_NET_IPv6 */ + + UDPBUF->vhl = 0x45; + UDPBUF->tos = 0; + UDPBUF->len[0] = (dev->d_len >> 8); + UDPBUF->len[1] = (dev->d_len & 0xff); + ++g_ipid; + UDPBUF->ipid[0] = g_ipid >> 8; + UDPBUF->ipid[1] = g_ipid & 0xff; + UDPBUF->ipoffset[0] = 0; + UDPBUF->ipoffset[1] = 0; + UDPBUF->ttl = conn->ttl; + UDPBUF->proto = UIP_PROTO_UDP; + + /* Calculate IP checksum. */ + + UDPBUF->ipchksum = 0; + UDPBUF->ipchksum = ~(uip_ipchksum(dev)); + + uiphdr_ipaddr_copy(UDPBUF->srcipaddr, &dev->d_ipaddr); + uiphdr_ipaddr_copy(UDPBUF->destipaddr, &conn->ripaddr); + +#endif /* CONFIG_NET_IPv6 */ + + /* Initialize the UDP header */ + + UDPBUF->srcport = conn->lport; + UDPBUF->destport = conn->rport; + UDPBUF->udplen = HTONS(dev->d_sndlen + UIP_UDPH_LEN); + +#ifdef CONFIG_NET_UDP_CHECKSUMS + /* Calculate UDP checksum. */ + + UDPBUF->udpchksum = ~(uip_udpchksum(dev)); + if (UDPBUF->udpchksum == 0) + { + UDPBUF->udpchksum = 0xffff; + } +#else + UDPBUF->udpchksum = 0; +#endif /* UIP_UDP_CHECKSUMS */ + + vdbg("Outgoing UDP packet length: %d (%d)\n", + dev->d_len, (UDPBUF->len[0] << 8) | UDPBUF->len[1]); + +#ifdef CONFIG_NET_STATISTICS + uip_stat.udp.sent++; + uip_stat.ip.sent++; +#endif + } +} + +#endif /* CONFIG_NET && CONFIG_NET_UDP */ diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c index bbe287d6c..7c9a997b6 100644 --- a/nuttx/net/uip/uip.c +++ b/nuttx/net/uip/uip.c @@ -89,21 +89,6 @@ # include "uip-neighbor.h" #endif /* CONFIG_NET_IPv6 */ -/* Check if logging of network events should be compiled in. - * - * This is useful mostly for debugging. The function uip_log() - * must be implemented to suit the architecture of the project, if - * logging is turned on. - */ - -#ifdef CONFIG_NET_LOGGING -# include -extern void uip_log(char *msg); -# define UIP_LOG(m) uip_log(m) -#else -# define UIP_LOG(m) -#endif - #include "uip-internal.h" /**************************************************************************** @@ -142,7 +127,6 @@ extern void uip_log(char *msg); #define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN]) #define FBUF ((struct uip_tcpip_hdr *)&uip_reassbuf[0]) #define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN]) -#define UDPBUF ((struct uip_udpip_hdr *)&dev->d_buf[UIP_LLH_LEN]) /**************************************************************************** * Public Variables @@ -171,12 +155,16 @@ struct uip_udp_conn *uip_udp_conn; uint8 uip_acc32[4]; -#if UIP_STATISTICS == 1 +#ifdef CONFIG_NET_STATISTICS struct uip_stats uip_stat; # define UIP_STAT(s) s #else # define UIP_STAT(s) -#endif /* UIP_STATISTICS == 1 */ +#endif + +/* Increasing number used for the IP ID field. */ + +uint16 g_ipid; const uip_ipaddr_t all_ones_addr = #ifdef CONFIG_NET_IPv6 @@ -196,84 +184,10 @@ const uip_ipaddr_t all_zeroes_addr = * Private Variables ****************************************************************************/ -static uint16 g_ipid; /* Increasing number used for the IP ID field. */ - /**************************************************************************** * Private Functions ****************************************************************************/ -#if !UIP_ARCH_CHKSUM -static uint16 chksum(uint16 sum, const uint8 *data, uint16 len) -{ - uint16 t; - const uint8 *dataptr; - const uint8 *last_byte; - - dataptr = data; - last_byte = data + len - 1; - - while(dataptr < last_byte) - { - /* At least two more bytes */ - - t = (dataptr[0] << 8) + dataptr[1]; - sum += t; - if (sum < t) - { - sum++; /* carry */ - } - dataptr += 2; - } - - if (dataptr == last_byte) - { - t = (dataptr[0] << 8) + 0; - sum += t; - if (sum < t) - { - sum++; /* carry */ - } - } - - /* Return sum in host byte order. */ - - return sum; -} - -static uint16 upper_layer_chksum(struct uip_driver_s *dev, uint8 proto) -{ - uint16 upper_layer_len; - uint16 sum; - -#ifdef CONFIG_NET_IPv6 - upper_layer_len = (((uint16)(BUF->len[0]) << 8) + BUF->len[1]); -#else /* CONFIG_NET_IPv6 */ - upper_layer_len = (((uint16)(BUF->len[0]) << 8) + BUF->len[1]) - UIP_IPH_LEN; -#endif /* CONFIG_NET_IPv6 */ - - /* First sum pseudoheader. */ - - /* IP protocol and length fields. This addition cannot carry. */ - sum = upper_layer_len + proto; - - /* Sum IP source and destination addresses. */ - sum = chksum(sum, (uint8 *)&BUF->srcipaddr, 2 * sizeof(uip_ipaddr_t)); - - /* Sum TCP header and data. */ - sum = chksum(sum, &dev->d_buf[UIP_IPH_LEN + UIP_LLH_LEN], upper_layer_len); - - return (sum == 0) ? 0xffff : htons(sum); -} - -#ifdef CONFIG_NET_IPv6 -static uint16 uip_icmp6chksum(struct uip_driver_s *dev) -{ - return upper_layer_chksum(dev, UIP_PROTO_ICMP6); -} -#endif /* CONFIG_NET_IPv6 */ - -#endif /* UIP_ARCH_CHKSUM */ - /**************************************************************************** * Public Functions ****************************************************************************/ @@ -285,94 +199,6 @@ void uip_setipid(uint16 id) g_ipid = 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) -{ - return htons(chksum(0, (uint8 *)data, len)); -} - -/* Calculate the IP header checksum of the packet header in d_buf. */ - -#ifndef UIP_ARCH_IPCHKSUM -uint16 uip_ipchksum(struct uip_driver_s *dev) -{ - uint16 sum; - - sum = chksum(0, &dev->d_buf[UIP_LLH_LEN], UIP_IPH_LEN); - return (sum == 0) ? 0xffff : htons(sum); -} -#endif - -/* Calculate the TCP checksum of the packet in d_buf and d_appdata. */ - -uint16 uip_tcpchksum(struct uip_driver_s *dev) -{ - return upper_layer_chksum(dev, UIP_PROTO_TCP); -} - -/* Calculate the UDP checksum of the packet in d_buf and d_appdata. */ - -#ifdef CONFIG_NET_UDP_CHECKSUMS -uint16 uip_udpchksum(struct uip_driver_s *dev) -{ - return upper_layer_chksum(dev, UIP_PROTO_UDP); -} -#endif /* UIP_UDP_CHECKSUMS */ -#endif /* UIP_ARCH_CHKSUM */ - -void uip_init(void) -{ - /* Initialize the listening port structures */ - - uip_listeninit(); - - /* Initialize the TCP/IP connection structures */ - - uip_tcpinit(); - - /* Initialize the UDP connection structures */ - -#ifdef CONFIG_NET_UDP - uip_udpinit(); -#endif - - /* IPv4 initialization. */ -} - /* IP fragment reassembly: not well-tested. */ #if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6) @@ -533,22 +359,6 @@ static void uip_add_rcv_nxt(uint16 n) uip_conn->rcv_nxt[3] = uip_acc32[3]; } -#ifdef CONFIG_NET_UDP -static void uip_udp_callback(struct uip_driver_s *dev) -{ - vdbg("uip_flags: %02x\n", uip_flags); - - /* Some sanity checking */ - - if (uip_udp_conn && uip_udp_conn->event) - { - /* Perform the callback */ - - uip_udp_conn->event(dev, uip_udp_conn->private); - } -} -#endif - static void uip_tcp_callback(struct uip_driver_s *dev) { vdbg("uip_flags: %02x\n", uip_flags); @@ -739,26 +549,6 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) goto drop; } -#ifdef CONFIG_NET_UDP - else if (event == UIP_DRV_UDPPOLL) - { - if (uip_udp_conn->lport != 0) - { - uip_conn = NULL; - dev->d_snddata = dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; - dev->d_len = 0; - dev->d_sndlen = 0; - uip_flags = UIP_POLL; - uip_udp_callback(dev); - goto udp_send; - } - else - { - goto drop; - } - } -#endif - /* This is where the input processing starts. */ UIP_STAT(++uip_stat.ip.recv); @@ -774,7 +564,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) UIP_STAT(++uip_stat.ip.drop); UIP_STAT(++uip_stat.ip.vhlerr); - UIP_LOG("ipv6: invalid version."); + uip_log("ipv6: invalid version."); goto drop; } #else /* CONFIG_NET_IPv6 */ @@ -786,7 +576,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) UIP_STAT(++uip_stat.ip.drop); UIP_STAT(++uip_stat.ip.vhlerr); - UIP_LOG("ip: invalid version or header length."); + uip_log("ip: invalid version or header length."); goto drop; } #endif /* CONFIG_NET_IPv6 */ @@ -815,7 +605,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) } else { - UIP_LOG("ip: packet shorter than reported in IP header."); + uip_log("ip: packet shorter than reported in IP header."); goto drop; } @@ -833,7 +623,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) #else /* UIP_REASSEMBLY */ UIP_STAT(++uip_stat.ip.drop); UIP_STAT(++uip_stat.ip.fragerr); - UIP_LOG("ip: fragment dropped."); + uip_log("ip: fragment dropped."); goto drop; #endif /* UIP_REASSEMBLY */ } @@ -849,12 +639,12 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) #if UIP_PINGADDRCONF && !CONFIG_NET_IPv6 if (BUF->proto == UIP_PROTO_ICMP) { - UIP_LOG("ip: possible ping config packet received."); + uip_log("ip: possible ping config packet received."); goto icmp_input; } else { - UIP_LOG("ip: packet dropped since no address assigned."); + uip_log("ip: packet dropped since no address assigned."); goto drop; } #endif /* UIP_PINGADDRCONF */ @@ -903,7 +693,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) UIP_STAT(++uip_stat.ip.drop); UIP_STAT(++uip_stat.ip.chkerr); - UIP_LOG("ip: bad checksum."); + uip_log("ip: bad checksum."); goto drop; } #endif /* CONFIG_NET_IPv6 */ @@ -918,9 +708,10 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) #ifdef CONFIG_NET_UDP if (BUF->proto == UIP_PROTO_UDP) { - goto udp_input; + uip_udpinput(dev); + return; } -#endif /* CONFIG_NET_UDP */ +#endif #ifndef CONFIG_NET_IPv6 /* ICMPv4 processing code follows. */ @@ -931,7 +722,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event) UIP_STAT(++uip_stat.ip.drop); UIP_STAT(++uip_stat.ip.protoerr); - UIP_LOG("ip: neither tcp nor icmp."); + uip_log("ip: neither tcp nor icmp."); goto drop; } @@ -949,7 +740,7 @@ icmp_input: { UIP_STAT(++uip_stat.icmp.drop); UIP_STAT(++uip_stat.icmp.typeerr); - UIP_LOG("icmp: not icmp echo."); + uip_log("icmp: not icmp echo."); goto drop; } @@ -993,7 +784,7 @@ icmp_input: UIP_STAT(++uip_stat.ip.drop); UIP_STAT(++uip_stat.ip.protoerr); - UIP_LOG("ip: neither tcp nor icmp6."); + uip_log("ip: neither tcp nor icmp6."); goto drop; } @@ -1055,102 +846,11 @@ icmp_input: { UIP_STAT(++uip_stat.icmp.drop); UIP_STAT(++uip_stat.icmp.typeerr); - UIP_LOG("icmp: unknown ICMP message."); + uip_log("icmp: unknown ICMP message."); goto drop; } #endif /* !CONFIG_NET_IPv6 */ -#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 d_sndlen, it has a packet to - * send. - */ - -#ifdef CONFIG_NET_UDP_CHECKSUMS - dev->d_len -= UIP_IPUDPH_LEN; - dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; - if (UDPBUF->udpchksum != 0 && uip_udpchksum(dev) != 0xffff) - { - UIP_STAT(++uip_stat.udp.drop); - UIP_STAT(++uip_stat.udp.chkerr); - UIP_LOG("udp: bad checksum."); - goto drop; - } -#else /* UIP_UDP_CHECKSUMS */ - dev->d_len -= UIP_IPUDPH_LEN; -#endif /* UIP_UDP_CHECKSUMS */ - - /* Demultiplex this UDP packet between the UDP "connections". */ - - uip_udp_conn = uip_udpactive(UDPBUF); - if (uip_udp_conn) - { - goto udp_found; - } - - UIP_LOG("udp: no matching connection found"); - goto drop; - -udp_found: - - uip_conn = NULL; - uip_flags = UIP_NEWDATA; - dev->d_snddata = dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN]; - dev->d_sndlen = 0; - uip_udp_callback(dev); - -udp_send: - - if (dev->d_sndlen == 0) - { - goto drop; - } - dev->d_len = dev->d_sndlen + UIP_IPUDPH_LEN; - -#ifdef CONFIG_NET_IPv6 - /* For IPv6, the IP length field does not include the IPv6 IP header - * length. - */ - - BUF->len[0] = ((dev->d_len - UIP_IPH_LEN) >> 8); - BUF->len[1] = ((dev->d_len - UIP_IPH_LEN) & 0xff); -#else /* CONFIG_NET_IPv6 */ - BUF->len[0] = (dev->d_len >> 8); - BUF->len[1] = (dev->d_len & 0xff); -#endif /* CONFIG_NET_IPv6 */ - - BUF->ttl = uip_udp_conn->ttl; - BUF->proto = UIP_PROTO_UDP; - - UDPBUF->udplen = HTONS(dev->d_sndlen + UIP_UDPH_LEN); - UDPBUF->udpchksum = 0; - - BUF->srcport = uip_udp_conn->lport; - BUF->destport = uip_udp_conn->rport; - - uiphdr_ipaddr_copy(BUF->srcipaddr, &dev->d_ipaddr); - uiphdr_ipaddr_copy(BUF->destipaddr, &uip_udp_conn->ripaddr); - - dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPTCPH_LEN]; - -#ifdef CONFIG_NET_UDP_CHECKSUMS - /* Calculate UDP checksum. */ - - UDPBUF->udpchksum = ~(uip_udpchksum(dev)); - if (UDPBUF->udpchksum == 0) - { - UDPBUF->udpchksum = 0xffff; - } -#endif /* UIP_UDP_CHECKSUMS */ - - goto ip_send_nolen; -#endif /* CONFIG_NET_UDP */ - /* TCP input processing. */ tcp_input: @@ -1165,7 +865,7 @@ tcp_input: UIP_STAT(++uip_stat.tcp.drop); UIP_STAT(++uip_stat.tcp.chkerr); - UIP_LOG("tcp: bad checksum."); + uip_log("tcp: bad checksum."); goto drop; } @@ -1239,13 +939,13 @@ reset: * to propagate the carry to the other bytes as well. */ - if (++BUF->ackno[3] == 0) + if (++(BUF->ackno[3]) == 0) { - if (++BUF->ackno[2] == 0) + if (++(BUF->ackno[2]) == 0) { - if (++BUF->ackno[1] == 0) + if (++(BUF->ackno[1]) == 0) { - ++BUF->ackno[0]; + ++(BUF->ackno[0]); } } } @@ -1302,7 +1002,7 @@ found_listen: */ UIP_STAT(++uip_stat.tcp.syndrop); - UIP_LOG("tcp: found no unused connections."); + uip_log("tcp: found no unused connections."); goto drop; } @@ -1396,7 +1096,7 @@ found: { uip_connr->tcpstateflags = UIP_CLOSED; vdbg("TCP state: UIP_CLOSED\n"); - UIP_LOG("tcp: got reset, aborting connection."); + uip_log("tcp: got reset, aborting connection."); uip_flags = UIP_ABORT; uip_tcp_callback(dev); @@ -2026,10 +1726,6 @@ tcp_send_noconn: BUF->tcpchksum = 0; BUF->tcpchksum = ~(uip_tcpchksum(dev)); -#ifdef CONFIG_NET_UDP -ip_send_nolen: -#endif /* CONFIG_NET_UDP */ - #ifdef CONFIG_NET_IPv6 BUF->vtc = 0x60; BUF->tcflow = 0x00; -- cgit v1.2.3