aboutsummaryrefslogtreecommitdiff
path: root/nuttx/net/uip
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/net/uip')
-rw-r--r--nuttx/net/uip/Make.defs106
-rw-r--r--nuttx/net/uip/uip_arp.c431
-rw-r--r--nuttx/net/uip/uip_arptab.c257
-rw-r--r--nuttx/net/uip/uip_callback.c251
-rw-r--r--nuttx/net/uip/uip_chksum.c230
-rw-r--r--nuttx/net/uip/uip_icmpinput.c317
-rw-r--r--nuttx/net/uip/uip_icmpping.c388
-rw-r--r--nuttx/net/uip/uip_icmppoll.c103
-rw-r--r--nuttx/net/uip/uip_icmpsend.c168
-rw-r--r--nuttx/net/uip/uip_igmpgroup.c391
-rw-r--r--nuttx/net/uip/uip_igmpinit.c122
-rw-r--r--nuttx/net/uip/uip_igmpinput.c280
-rw-r--r--nuttx/net/uip/uip_igmpjoin.c160
-rw-r--r--nuttx/net/uip/uip_igmpleave.c182
-rw-r--r--nuttx/net/uip/uip_igmpmsg.c139
-rw-r--r--nuttx/net/uip/uip_igmppoll.c176
-rw-r--r--nuttx/net/uip/uip_igmpsend.c182
-rw-r--r--nuttx/net/uip/uip_igmptimer.c257
-rw-r--r--nuttx/net/uip/uip_initialize.c155
-rw-r--r--nuttx/net/uip/uip_input.c545
-rw-r--r--nuttx/net/uip/uip_internal.h272
-rw-r--r--nuttx/net/uip/uip_listen.c288
-rw-r--r--nuttx/net/uip/uip_lock.c219
-rw-r--r--nuttx/net/uip/uip_mcastmac.c132
-rw-r--r--nuttx/net/uip/uip_neighbor.c162
-rw-r--r--nuttx/net/uip/uip_neighbor.h61
-rw-r--r--nuttx/net/uip/uip_poll.c353
-rw-r--r--nuttx/net/uip/uip_send.c106
-rw-r--r--nuttx/net/uip/uip_setipid.c78
-rw-r--r--nuttx/net/uip/uip_tcpappsend.c215
-rw-r--r--nuttx/net/uip/uip_tcpbacklog.c403
-rw-r--r--nuttx/net/uip/uip_tcpcallback.c339
-rw-r--r--nuttx/net/uip/uip_tcpconn.c636
-rw-r--r--nuttx/net/uip/uip_tcpinput.c839
-rw-r--r--nuttx/net/uip/uip_tcppoll.c127
-rw-r--r--nuttx/net/uip/uip_tcpreadahead.c130
-rw-r--r--nuttx/net/uip/uip_tcpsend.c369
-rw-r--r--nuttx/net/uip/uip_tcpseqno.c173
-rw-r--r--nuttx/net/uip/uip_tcptimer.c250
-rw-r--r--nuttx/net/uip/uip_udpcallback.c90
-rw-r--r--nuttx/net/uip/uip_udpconn.c492
-rw-r--r--nuttx/net/uip/uip_udpinput.c156
-rw-r--r--nuttx/net/uip/uip_udppoll.c126
-rw-r--r--nuttx/net/uip/uip_udpsend.c177
44 files changed, 0 insertions, 11033 deletions
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
deleted file mode 100644
index c5d915e61..000000000
--- a/nuttx/net/uip/Make.defs
+++ /dev/null
@@ -1,106 +0,0 @@
-############################################################################
-# Make.defs
-#
-# Copyright (C) 2007, 2009-20010 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <gnutt@nuttx.org>
-#
-# 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.
-#
-############################################################################
-
-UIP_ASRCS =
-UIP_CSRCS =
-
-ifeq ($(CONFIG_NET),y)
-
-# Common IP source files
-
-UIP_CSRCS += uip_initialize.c uip_setipid.c uip_input.c uip_send.c \
- uip_poll.c uip_chksum.c uip_callback.c
-
-# Non-interrupt level support required?
-
-ifeq ($(CONFIG_NET_NOINTS),y)
-UIP_CSRCS += uip_lock.c
-endif
-
-# ARP supported is not provided for SLIP (Ethernet only)
-
-ifneq ($(CONFIG_NET_SLIP),y)
-UIP_CSRCS += uip_arp.c uip_arptab.c
-endif
-
-# IPv6-specific logic
-
-ifeq ($(CONFIG_NET_IPv6),y)
-UIP_CSRCS += uip_neighbor.c
-endif
-
-# TCP/IP source files
-
-ifeq ($(CONFIG_NET_TCP),y)
-
-UIP_CSRCS += uip_tcpconn.c uip_tcpseqno.c uip_tcppoll.c uip_tcptimer.c uip_tcpsend.c \
- uip_tcpinput.c uip_tcpappsend.c uip_listen.c uip_tcpcallback.c \
- uip_tcpreadahead.c uip_tcpbacklog.c
-
-endif
-
-# UDP source files
-
-ifeq ($(CONFIG_NET_UDP),y)
-
-UIP_CSRCS += uip_udpconn.c uip_udppoll.c uip_udpsend.c uip_udpinput.c \
- uip_udpcallback.c
-
-endif
-
-# ICMP source files
-
-ifeq ($(CONFIG_NET_ICMP),y)
-
-UIP_CSRCS += uip_icmpinput.c uip_igmppoll.c
-
-ifeq ($(CONFIG_NET_ICMP_PING),y)
-ifneq ($(CONFIG_DISABLE_CLOCK),y)
-UIP_CSRCS += uip_icmpping.c uip_icmppoll.c uip_icmpsend.c
-endif
-endif
-
-# IGMP source files
-
-ifeq ($(CONFIG_NET_IGMP),y)
-UIP_CSRCS += uip_igmpgroup.c uip_igmpinit.c uip_igmpinput.c uip_igmpjoin.c \
- uip_igmpleave.c uip_igmpmsg.c uip_igmpsend.c uip_igmptimer.c \
- uip_mcastmac.c
-endif
-
-endif
-endif
-
-
diff --git a/nuttx/net/uip/uip_arp.c b/nuttx/net/uip/uip_arp.c
deleted file mode 100644
index c731ff0de..000000000
--- a/nuttx/net/uip/uip_arp.c
+++ /dev/null
@@ -1,431 +0,0 @@
-/****************************************************************************
- * net/uip/uip_arp.c
- * Implementation of the ARP Address Resolution Protocol.
- *
- * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Based on 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.
- *
- ****************************************************************************/
-
-/* The Address Resolution Protocol ARP is used for mapping between IP
- * addresses and link level addresses such as the Ethernet MAC
- * addresses. ARP uses broadcast queries to ask for the link level
- * address of a known IP address and the host which is configured with
- * the IP address for which the query was meant, will respond with its
- * link level address.
- *
- * Note: This ARP implementation only supports Ethernet.
- */
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <sys/ioctl.h>
-#include <stdint.h>
-#include <string.h>
-#include <debug.h>
-
-#include <netinet/in.h>
-
-#include <net/ethernet.h>
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip-arch.h>
-#include <nuttx/net/uip/uip-arp.h>
-
-#ifdef CONFIG_NET_ARP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define ARP_REQUEST 1
-#define ARP_REPLY 2
-
-#define ARP_HWTYPE_ETH 1
-
-#define RASIZE 4 /* Size of ROUTER ALERT */
-
-#define ETHBUF ((struct uip_eth_hdr *)&dev->d_buf[0])
-#define ARPBUF ((struct arp_hdr_s *)&dev->d_buf[UIP_LLH_LEN])
-#define IPBUF ((struct arp_iphdr_s *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/* ARP header -- Size 28 bytes */
-
-struct arp_hdr_s
-{
- uint16_t ah_hwtype; /* 16-bit Hardware type (Ethernet=0x001) */
- uint16_t ah_protocol; /* 16-bit Protocol type (IP=0x0800) */
- uint8_t ah_hwlen; /* 8-bit Hardware address size (6) */
- uint8_t ah_protolen; /* 8-bit Procotol address size (4) */
- uint16_t ah_opcode; /* 16-bit Operation */
- uint8_t ah_shwaddr[6]; /* 48-bit Sender hardware address */
- uint16_t ah_sipaddr[2]; /* 32-bit Sender IP adress */
- uint8_t ah_dhwaddr[6]; /* 48-bit Target hardware address */
- uint16_t ah_dipaddr[2]; /* 32-bit Target IP address */
-};
-
-/* IP header -- Size 20 or 24 bytes */
-
-struct arp_iphdr_s
-{
- uint8_t eh_vhl; /* 8-bit Version (4) and header length (5 or 6) */
- uint8_t eh_tos; /* 8-bit Type of service (e.g., 6=TCP) */
- uint8_t eh_len[2]; /* 16-bit Total length */
- uint8_t eh_ipid[2]; /* 16-bit Identification */
- uint8_t eh_ipoffset[2]; /* 16-bit IP flags + fragment offset */
- uint8_t eh_ttl; /* 8-bit Time to Live */
- uint8_t eh_proto; /* 8-bit Protocol */
- uint16_t eh_ipchksum; /* 16-bit Header checksum */
- uint16_t eh_srcipaddr[2]; /* 32-bit Source IP address */
- uint16_t eh_destipaddr[2]; /* 32-bit Destination IP address */
- uint16_t eh_ipoption[2]; /* (optional) */
-};
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* Support for broadcast address */
-
-static const struct ether_addr g_broadcast_ethaddr =
- {{0xff, 0xff, 0xff, 0xff, 0xff, 0xff}};
-static const uint16_t g_broadcast_ipaddr[2] = {0xffff, 0xffff};
-
-/* Support for IGMP multicast addresses.
- *
- * Well-known ethernet multicast address:
- *
- * ADDRESS TYPE USAGE
- * 01-00-0c-cc-cc-cc 0x0802 CDP (Cisco Discovery Protocol), VTP (Virtual Trunking Protocol)
- * 01-00-0c-cc-cc-cd 0x0802 Cisco Shared Spanning Tree Protocol Address
- * 01-80-c2-00-00-00 0x0802 Spanning Tree Protocol (for bridges) IEEE 802.1D
- * 01-80-c2-00-00-02 0x0809 Ethernet OAM Protocol IEEE 802.3ah
- * 01-00-5e-xx-xx-xx 0x0800 IPv4 IGMP Multicast Address
- * 33-33-00-00-00-00 0x86DD IPv6 Neighbor Discovery
- * 33-33-xx-xx-xx-xx 0x86DD IPv6 Multicast Address (RFC3307)
- *
- * The following is the first three octects of the IGMP address:
- */
-
-#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
-static const uint8_t g_multicast_ethaddr[3] = {0x01, 0x00, 0x5e};
-#endif
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-#if defined(CONFIG_NET_DUMPARP) && defined(CONFIG_DEBUG)
-static void uip_arp_dump(struct arp_hdr_s *arp)
-{
- nlldbg(" HW type: %04x Protocol: %04x\n",
- arp->ah_hwtype, arp->ah_protocol);\
- nlldbg(" HW len: %02x Proto len: %02x Operation: %04x\n",
- arp->ah_hwlen, arp->ah_protolen, arp->ah_opcode);
- nlldbg(" Sender MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
- arp->ah_shwaddr[0], arp->ah_shwaddr[1], arp->ah_shwaddr[2],
- arp->ah_shwaddr[3], arp->ah_shwaddr[4], arp->ah_shwaddr[5],
- arp->ah_sipaddr[0] & 0xff, arp->ah_sipaddr[0] >> 8,
- arp->ah_sipaddr[1] & 0xff, arp->ah_sipaddr[1] >> 8);
- nlldbg(" Dest MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
- arp->ah_dhwaddr[0], arp->ah_dhwaddr[1], arp->ah_dhwaddr[2],
- arp->ah_dhwaddr[3], arp->ah_dhwaddr[4], arp->ah_dhwaddr[5],
- arp->ah_dipaddr[0] & 0xff, arp->ah_dipaddr[0] >> 8,
- arp->ah_dipaddr[1] & 0xff, arp->ah_dipaddr[1] >> 8);
-}
-#else
-# define uip_arp_dump(arp)
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/* ARP processing for incoming IP packets
- *
- * This function should be called by the device driver when an IP packet has
- * been received. The function will check if the address is in the ARP cache,
- * and if so the ARP cache entry will be refreshed. If no ARP cache entry was
- * found, a new one is created.
- *
- * This function expects an IP packet with a prepended Ethernet header in the
- * d_buf[] buffer, and the length of the packet in the variable d_len.
- */
-
-#ifdef CONFIG_NET_ARP_IPIN
-void uip_arp_ipin(struct uip_driver_s *dev)
-{
- in_addr_t srcipaddr;
-
- /* Only insert/update an entry if the source IP address of the incoming IP
- * packet comes from a host on the local network.
- */
-
- srcipaddr = uip_ip4addr_conv(IPBUF->eh_srcipaddr);
- if (!uip_ipaddr_maskcmp(srcipaddr, dev->d_ipaddr, dev->d_netmask))
- {
- uip_arp_update(IPBUF->eh_srcipaddr, ETHBUF->src);
- }
-}
-#endif /* CONFIG_NET_ARP_IPIN */
-
-/* ARP processing for incoming ARP packets.
- *
- * This function should be called by the device driver when an ARP
- * packet has been received. The function will act differently
- * depending on the ARP packet type: if it is a reply for a request
- * that we previously sent out, the ARP cache will be filled in with
- * the values from the ARP reply. If the incoming ARP packet is an ARP
- * request for our IP address, an ARP reply packet is created and put
- * into the d_buf[] buffer.
- *
- * When the function returns, the value of the field d_len
- * indicates whether the device driver should send out a packet or
- * not. If d_len is zero, no packet should be sent. If d_len is
- * non-zero, it contains the length of the outbound packet that is
- * present in the d_buf[] buffer.
- *
- * This function expects an ARP packet with a prepended Ethernet
- * header in the d_buf[] buffer, and the length of the packet in the
- * variable d_len.
- */
-
-void uip_arp_arpin(struct uip_driver_s *dev)
-{
- struct arp_hdr_s *parp = ARPBUF;
- in_addr_t ipaddr;
-
- if (dev->d_len < (sizeof(struct arp_hdr_s) + UIP_LLH_LEN))
- {
- nlldbg("Too small\n");
- dev->d_len = 0;
- return;
- }
- dev->d_len = 0;
-
- ipaddr = uip_ip4addr_conv(parp->ah_dipaddr);
- switch(parp->ah_opcode)
- {
- case HTONS(ARP_REQUEST):
- nllvdbg("ARP request for IP %04lx\n", (long)ipaddr);
-
- /* ARP request. If it asked for our address, we send out a reply. */
-
- if (uip_ipaddr_cmp(ipaddr, dev->d_ipaddr))
- {
- struct uip_eth_hdr *peth = ETHBUF;
-
- /* First, we register the one who made the request in our ARP
- * table, since it is likely that we will do more communication
- * with this host in the future.
- */
-
- uip_arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
-
- parp->ah_opcode = HTONS(ARP_REPLY);
- memcpy(parp->ah_dhwaddr, parp->ah_shwaddr, ETHER_ADDR_LEN);
- memcpy(parp->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
- memcpy(peth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
- memcpy(peth->dest, parp->ah_dhwaddr, ETHER_ADDR_LEN);
-
- parp->ah_dipaddr[0] = parp->ah_sipaddr[0];
- parp->ah_dipaddr[1] = parp->ah_sipaddr[1];
- uiphdr_ipaddr_copy(parp->ah_sipaddr, &dev->d_ipaddr);
- uip_arp_dump(parp);
-
- peth->type = HTONS(UIP_ETHTYPE_ARP);
- dev->d_len = sizeof(struct arp_hdr_s) + UIP_LLH_LEN;
- }
- break;
-
- case HTONS(ARP_REPLY):
- nllvdbg("ARP reply for IP %04lx\n", (long)ipaddr);
-
- /* ARP reply. We insert or update the ARP table if it was meant
- * for us.
- */
-
- if (uip_ipaddr_cmp(ipaddr, dev->d_ipaddr))
- {
- uip_arp_update(parp->ah_sipaddr, parp->ah_shwaddr);
- }
- break;
- }
-}
-
-/* Prepend Ethernet header to an outbound IP packet and see if we need
- * to send out an ARP request.
- *
- * This function should be called before sending out an IP packet. The
- * function checks the destination IP address of the IP packet to see
- * what Ethernet MAC address that should be used as a destination MAC
- * address on the Ethernet.
- *
- * If the destination IP address is in the local network (determined
- * by logical ANDing of netmask and our IP address), the function
- * checks the ARP cache to see if an entry for the destination IP
- * address is found. If so, an Ethernet header is prepended and the
- * function returns. If no ARP cache entry is found for the
- * destination IP address, the packet in the d_buf[] is replaced by
- * an ARP request packet for the IP address. The IP packet is dropped
- * and it is assumed that they higher level protocols (e.g., TCP)
- * eventually will retransmit the dropped packet.
- *
- * If the destination IP address is not on the local network, the IP
- * address of the default router is used instead.
- *
- * When the function returns, a packet is present in the d_buf[]
- * buffer, and the length of the packet is in the field d_len.
- */
-
-void uip_arp_out(struct uip_driver_s *dev)
-{
- const struct arp_entry *tabptr = NULL;
- struct arp_hdr_s *parp = ARPBUF;
- struct uip_eth_hdr *peth = ETHBUF;
- struct arp_iphdr_s *pip = IPBUF;
- in_addr_t ipaddr;
- in_addr_t destipaddr;
-
- /* Find the destination IP address in the ARP table and construct
- * the Ethernet header. If the destination IP addres isn't on the
- * local network, we use the default router's IP address instead.
- *
- * If not ARP table entry is found, we overwrite the original IP
- * packet with an ARP request for the IP address.
- */
-
- /* First check if destination is a local broadcast. */
-
- if (uiphdr_ipaddr_cmp(pip->eh_destipaddr, g_broadcast_ipaddr))
- {
- memcpy(peth->dest, g_broadcast_ethaddr.ether_addr_octet, ETHER_ADDR_LEN);
- }
-#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_IPv6)
- /* Check if the destination address is a multicast address
- *
- * - IPv4: multicast addresses lie in the class D group -- The address range
- * 224.0.0.0 to 239.255.255.255 (224.0.0.0/4)
- *
- * - IPv6 multicast addresses are have the high-order octet of the
- * addresses=0xff (ff00::/8.)
- */
-
- else if (NTOHS(pip->eh_destipaddr[0]) >= 0xe000 &&
- NTOHS(pip->eh_destipaddr[0]) <= 0xefff)
- {
- /* Build the well-known IPv4 IGMP ethernet address. The first
- * three bytes are fixed; the final three variable come from the
- * last three bytes of the IP address.
- */
-
- const uint8_t *ip = ((uint8_t*)pip->eh_destipaddr) + 1;
- memcpy(peth->dest, g_multicast_ethaddr, 3);
- memcpy(&peth->dest[3], ip, 3);
- }
-#endif
- else
- {
- /* Check if the destination address is on the local network. */
-
- destipaddr = uip_ip4addr_conv(pip->eh_destipaddr);
- if (!uip_ipaddr_maskcmp(destipaddr, dev->d_ipaddr, dev->d_netmask))
- {
- /* Destination address was not on the local network, so we need to
- * use the default router's IP address instead of the destination
- * address when determining the MAC address.
- */
-
- uip_ipaddr_copy(ipaddr, dev->d_draddr);
- }
- else
- {
- /* Else, we use the destination IP address. */
-
- uip_ipaddr_copy(ipaddr, destipaddr);
- }
-
- /* Check if we already have this destination address in the ARP table */
-
- tabptr = uip_arp_find(ipaddr);
- if (!tabptr)
- {
- nllvdbg("ARP request for IP %04lx\n", (long)ipaddr);
-
- /* The destination address was not in our ARP table, so we
- * overwrite the IP packet with an ARP request.
- */
-
- memset(peth->dest, 0xff, ETHER_ADDR_LEN);
- memset(parp->ah_dhwaddr, 0x00, ETHER_ADDR_LEN);
- memcpy(peth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
- memcpy(parp->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
-
- uiphdr_ipaddr_copy(parp->ah_dipaddr, &ipaddr);
- uiphdr_ipaddr_copy(parp->ah_sipaddr, &dev->d_ipaddr);
-
- parp->ah_opcode = HTONS(ARP_REQUEST);
- parp->ah_hwtype = HTONS(ARP_HWTYPE_ETH);
- parp->ah_protocol = HTONS(UIP_ETHTYPE_IP);
- parp->ah_hwlen = ETHER_ADDR_LEN;
- parp->ah_protolen = 4;
- uip_arp_dump(parp);
-
- peth->type = HTONS(UIP_ETHTYPE_ARP);
- dev->d_len = sizeof(struct arp_hdr_s) + UIP_LLH_LEN;
- return;
- }
-
- /* Build an ethernet header. */
-
- memcpy(peth->dest, tabptr->at_ethaddr.ether_addr_octet, ETHER_ADDR_LEN);
- }
-
- /* Finish populating the ethernet header */
-
- memcpy(peth->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
- peth->type = HTONS(UIP_ETHTYPE_IP);
- dev->d_len += UIP_LLH_LEN;
-}
-
-#endif /* CONFIG_NET_ARP */
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_arptab.c b/nuttx/net/uip/uip_arptab.c
deleted file mode 100644
index 3dff97070..000000000
--- a/nuttx/net/uip/uip_arptab.c
+++ /dev/null
@@ -1,257 +0,0 @@
-/****************************************************************************
- * net/uip/uip_arptab.c
- * Implementation of the ARP Address Resolution Protocol.
- *
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Based originally on 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <sys/ioctl.h>
-#include <stdint.h>
-#include <string.h>
-#include <debug.h>
-
-#include <netinet/in.h>
-
-#include <net/ethernet.h>
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip-arch.h>
-#include <nuttx/net/uip/uip-arp.h>
-
-#ifdef CONFIG_NET_ARP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* The table of known address mappings */
-
-static struct arp_entry g_arptable[CONFIG_NET_ARPTAB_SIZE];
-static uint8_t g_arptime;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_arp_init
- *
- * Description:
- * Initialize the ARP module. This function must be called before any of
- * the other ARP functions.
- *
- ****************************************************************************/
-
-void uip_arp_init(void)
-{
- int i;
- for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
- {
- memset(&g_arptable[i].at_ipaddr, 0, sizeof(in_addr_t));
- }
-}
-
-/****************************************************************************
- * Name: uip_arp_timer
- *
- * Description:
- * This function performs periodic timer processing in the ARP module
- * and should be called at regular intervals. The recommended interval
- * is 10 seconds between the calls. It is responsible for flushing old
- * entries in the ARP table.
- *
- ****************************************************************************/
-
-void uip_arp_timer(void)
-{
- struct arp_entry *tabptr;
- int i;
-
- ++g_arptime;
- for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
- {
- tabptr = &g_arptable[i];
- if (tabptr->at_ipaddr != 0 && g_arptime - tabptr->at_time >= UIP_ARP_MAXAGE)
- {
- tabptr->at_ipaddr = 0;
- }
- }
-}
-
-/****************************************************************************
- * Name: uip_arp_update
- *
- * Description:
- * Add the IP/HW address mapping to the ARP table -OR- change the IP
- * address of an existing association.
- *
- * Input parameters:
- * pipaddr - Refers to an IP address uint16_t[2]
- * ethaddr - Refers to a HW address uint8_t[IFHWADDRLEN]
- *
- * Assumptions
- * Interrupts are disabled
- *
- ****************************************************************************/
-
-void uip_arp_update(uint16_t *pipaddr, uint8_t *ethaddr)
-{
- struct arp_entry *tabptr = NULL;
- in_addr_t ipaddr = uip_ip4addr_conv(pipaddr);
- int i;
-
- /* Walk through the ARP mapping table and try to find an entry to
- * update. If none is found, the IP -> MAC address mapping is
- * inserted in the ARP table.
- */
-
- for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
- {
- tabptr = &g_arptable[i];
-
- /* Only check those entries that are actually in use. */
-
- if (tabptr->at_ipaddr != 0)
- {
- /* Check if the source IP address of the incoming packet matches
- * the IP address in this ARP table entry.
- */
-
- if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr))
- {
- /* An old entry found, update this and return. */
-
- memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN);
- tabptr->at_time = g_arptime;
- return;
- }
- }
- }
-
- /* If we get here, no existing ARP table entry was found, so we create one. */
-
- /* First, we try to find an unused entry in the ARP table. */
-
- for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
- {
- tabptr = &g_arptable[i];
- if (tabptr->at_ipaddr == 0)
- {
- break;
- }
- }
-
- /* If no unused entry is found, we try to find the oldest entry and
- * throw it away.
- */
-
- if (i == CONFIG_NET_ARPTAB_SIZE)
- {
- uint8_t tmpage = 0;
- int j = 0;
- for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
- {
- tabptr = &g_arptable[i];
- if (g_arptime - tabptr->at_time > tmpage)
- {
- tmpage = g_arptime - tabptr->at_time;
- j = i;
- }
- }
- i = j;
- tabptr = &g_arptable[i];
- }
-
- /* Now, i is the ARP table entry which we will fill with the new
- * information.
- */
-
- tabptr->at_ipaddr = ipaddr;
- memcpy(tabptr->at_ethaddr.ether_addr_octet, ethaddr, ETHER_ADDR_LEN);
- tabptr->at_time = g_arptime;
-}
-
-/****************************************************************************
- * Name: uip_arp_find
- *
- * Description:
- * Find the ARP entry corresponding to this IP address.
- *
- * Input parameters:
- * ipaddr - Refers to an IP addressin network order
- *
- * Assumptions
- * Interrupts are disabled; Returned value will become unstable when
- * interrupts are re-enabled or if any other uIP APIs are called.
- *
- ****************************************************************************/
-
-struct arp_entry *uip_arp_find(in_addr_t ipaddr)
-{
- struct arp_entry *tabptr;
- int i;
-
- for (i = 0; i < CONFIG_NET_ARPTAB_SIZE; ++i)
- {
- tabptr = &g_arptable[i];
- if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr))
- {
- return tabptr;
- }
- }
- return NULL;
-}
-
-#endif /* CONFIG_NET_ARP */
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_callback.c b/nuttx/net/uip/uip_callback.c
deleted file mode 100644
index 0c8c3aaa0..000000000
--- a/nuttx/net/uip/uip_callback.c
+++ /dev/null
@@ -1,251 +0,0 @@
-/****************************************************************************
- * net/uip/uip_callback.c
- *
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET)
-
-#include <stdint.h>
-#include <string.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static struct uip_callback_s g_cbprealloc[CONFIG_NET_NACTIVESOCKETS];
-static FAR struct uip_callback_s *g_cbfreelist = NULL;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_callbackinit
- *
- * Description:
- * Configure the pre-allocated callaback structures into a free list.
- * This is called internally as part of uIP initialization and should not
- * be accessed from the application or socket layer.
- *
- * Assumptions:
- * This function is called with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_callbackinit(void)
-{
- int i;
- for (i = 0; i < CONFIG_NET_NACTIVESOCKETS; i++)
- {
- g_cbprealloc[i].flink = g_cbfreelist;
- g_cbfreelist = &g_cbprealloc[i];
- }
-}
-
-/****************************************************************************
- * Function: uip_callbackalloc
- *
- * Description:
- * Allocate a callback container from the free list.
- * This is called internally as part of uIP initialization and should not
- * be accessed from the application or socket layer.
- *
- * Assumptions:
- * This function is called with interrupts disabled.
- *
- ****************************************************************************/
-
-FAR struct uip_callback_s *uip_callbackalloc(FAR struct uip_callback_s **list)
-{
- struct uip_callback_s *ret;
- uip_lock_t save;
-
- /* Check the head of the free list */
-
- save = uip_lock();
- ret = g_cbfreelist;
- if (ret)
- {
- /* Remove the next instance from the head of the free list */
-
- g_cbfreelist = ret->flink;
- memset(ret, 0, sizeof(struct uip_callback_s));
-
- /* Add the newly allocated instance to the head of the specified list */
-
- if (list)
- {
- ret->flink = *list;
- *list = ret;
- }
- else
- {
- ret->flink = NULL;
- }
- }
-#ifdef CONFIG_DEBUG
- else
- {
- nlldbg("Failed to allocate callback\n");
- }
-#endif
-
- uip_unlock(save);
- return ret;
-}
-
-/****************************************************************************
- * Function: uip_callbackfree
- *
- * Description:
- * Return a callback container to the free list.
- * This is called internally as part of uIP initialization and should not
- * be accessed from the application or socket layer.
- *
- * Assumptions:
- * This function is called with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_callbackfree(FAR struct uip_callback_s *cb, FAR struct uip_callback_s **list)
-{
- FAR struct uip_callback_s *prev;
- FAR struct uip_callback_s *curr;
- uip_lock_t save;
-
- if (cb)
- {
- /* Find the callback structure in the connection's list */
-
- save = uip_lock();
- if (list)
- {
- for (prev = NULL, curr = *list;
- curr && curr != cb;
- prev = curr, curr = curr->flink);
-
- /* Remove the structure from the connection's list */
-
- if (curr)
- {
- if (prev)
- {
- prev->flink = cb->flink;
- }
- else
- {
- *list = cb->flink;
- }
- }
- }
-
- /* Put the structure into the free list */
-
- cb->flink = g_cbfreelist;
- g_cbfreelist = cb;
- uip_unlock(save);
- }
-}
-
-/****************************************************************************
- * Function: uip_callbackexecute
- *
- * Description:
- * Execute a list of callbacks.
- * This is called internally as part of uIP initialization and should not
- * be accessed from the application or socket layer.
- *
- * Assumptions:
- * This function is called with interrupts disabled.
- *
- ****************************************************************************/
-
-uint16_t uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
- uint16_t flags, FAR struct uip_callback_s *list)
-{
- FAR struct uip_callback_s *next;
- uip_lock_t save;
-
- /* Loop for each callback in the list and while there are still events
- * set in the flags set.
- */
-
- save = uip_lock();
- while (list && flags)
- {
- /* Save the pointer to the next callback in the lists. This is done
- * because the callback action might delete the entry pointed to by
- * list.
- */
-
- next = list->flink;
-
- /* Check if this callback handles any of the events in the flag set */
-
- if (list->event && (flags & list->flags) != 0)
- {
- /* Yes.. perform the callback. Actions perform by the callback
- * may delete the current list entry or add a new list entry to
- * beginning of the list (which will be ignored on this pass)
- */
-
- nllvdbg("Call event=%p with flags=%04x\n", list->event, flags);
- flags = list->event(dev, pvconn, list->priv, flags);
- }
-
- /* Set up for the next time through the loop */
-
- list = next;
- }
-
- uip_unlock(save);
- return flags;
-}
-
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_chksum.c b/nuttx/net/uip/uip_chksum.c
deleted file mode 100644
index 7a4eee790..000000000
--- a/nuttx/net/uip/uip_chksum.c
+++ /dev/null
@@ -1,230 +0,0 @@
-/****************************************************************************
- * net/uip/uip_chksum.c
- *
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <stdint.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define BUF ((struct uip_ip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-#if !UIP_ARCH_CHKSUM
-static uint16_t chksum(uint16_t sum, const uint8_t *data, uint16_t len)
-{
- uint16_t t;
- const uint8_t *dataptr;
- const uint8_t *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_t upper_layer_chksum(struct uip_driver_s *dev, uint8_t proto)
-{
- struct uip_ip_hdr *pbuf = BUF;
- uint16_t upper_layer_len;
- uint16_t sum;
-
-#ifdef CONFIG_NET_IPv6
- upper_layer_len = (((uint16_t)(pbuf->len[0]) << 8) + pbuf->len[1]);
-#else /* CONFIG_NET_IPv6 */
- upper_layer_len = (((uint16_t)(pbuf->len[0]) << 8) + pbuf->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_t *)&pbuf->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_t 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
-static inline void uip_carry32(uint8_t *sum, uint16_t op16)
-{
- if (sum[2] < (op16 >> 8))
- {
- ++sum[1];
- if (sum[1] == 0)
- {
- ++sum[0];
- }
- }
-
- if (sum[3] < (op16 & 0xff))
- {
- ++sum[2];
- if (sum[2] == 0)
- {
- ++sum[1];
- if (sum[1] == 0)
- {
- ++sum[0];
- }
- }
- }
-}
-
-void uip_incr32(uint8_t *op32, uint16_t op16)
-{
- op32[3] += (op16 & 0xff);
- op32[2] += (op16 >> 8);
- uip_carry32(op32, op16);
-}
-
-#endif /* UIP_ARCH_ADD32 */
-
-#if !UIP_ARCH_CHKSUM
-uint16_t uip_chksum(uint16_t *data, uint16_t len)
-{
- return htons(chksum(0, (uint8_t *)data, len));
-}
-
-/* Calculate the IP header checksum of the packet header in d_buf. */
-
-#ifndef UIP_ARCH_IPCHKSUM
-uint16_t uip_ipchksum(struct uip_driver_s *dev)
-{
- uint16_t 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_t 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_t uip_udpchksum(struct uip_driver_s *dev)
-{
- return upper_layer_chksum(dev, UIP_PROTO_UDP);
-}
-#endif
-
-/* Calculate the checksum of the ICMP message */
-
-#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
-uint16_t uip_icmpchksum(struct uip_driver_s *dev, int len)
-{
- struct uip_icmpip_hdr *picmp = ICMPBUF;
- return uip_chksum((uint16_t*)&picmp->type, len);
-}
-#endif
-
-#endif /* UIP_ARCH_CHKSUM */
-
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_icmpinput.c b/nuttx/net/uip/uip_icmpinput.c
deleted file mode 100644
index cea2ae4fc..000000000
--- a/nuttx/net/uip/uip_icmpinput.c
+++ /dev/null
@@ -1,317 +0,0 @@
-/****************************************************************************
- * net/uip/uip_icmpinput.c
- * Handling incoming ICMP/ICMP6 input
- *
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <stdint.h>
-#include <debug.h>
-
-#include <net/if.h>
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_ICMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-#ifdef CONFIG_NET_ICMP_PING
-struct uip_callback_s *g_echocallback = NULL;
-#endif
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_icmpinput
- *
- * Description:
- * Handle incoming ICMP/ICMP6 input
- *
- * Parameters:
- * dev - The device driver structure containing the received ICMP/ICMP6
- * packet
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_icmpinput(struct uip_driver_s *dev)
-{
- struct uip_icmpip_hdr *picmp = ICMPBUF;
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.icmp.recv++;
-#endif
-
-#ifndef CONFIG_NET_IPv6
- /* ICMPv4 processing code follows. */
-
- /* ICMP echo (i.e., ping) processing. This is simple, we only change the
- * ICMP type from ECHO to ECHO_REPLY and adjust the ICMP checksum before
- * we return the packet.
- */
-
- if (picmp->type == ICMP_ECHO_REQUEST)
- {
- /* If we are configured to use ping IP address assignment, we use
- * the destination IP address of this ping packet and assign it to
- * ourself.
- */
-
-#ifdef CONFIG_NET_PINGADDRCONF
- if (dev->d_ipaddr == 0)
- {
- dev->d_ipaddr = picmp->destipaddr;
- }
-#endif
-
- /* Change the ICMP type */
-
- picmp->type = ICMP_ECHO_REPLY;
-
- /* Swap IP addresses. */
-
- uiphdr_ipaddr_copy(picmp->destipaddr, picmp->srcipaddr);
- uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
-
- /* Recalculate the ICMP checksum */
-
-#if 0
- /* The slow way... sum over the ICMP message */
-
- picmp->icmpchksum = 0;
- picmp->icmpchksum = ~uip_icmpchksum(dev, (((uint16_t)picmp->len[0] << 8) | (uint16_t)picmp->len[1]) - UIP_IPH_LEN);
- if (picmp->icmpchksum == 0)
- {
- picmp->icmpchksum = 0xffff;
- }
-#else
- /* The quick way -- Since only the type has changed, just adjust the
- * checksum for the change of type
- */
-
- if( picmp->icmpchksum >= HTONS(0xffff - (ICMP_ECHO_REQUEST << 8)))
- {
- picmp->icmpchksum += HTONS(ICMP_ECHO_REQUEST << 8) + 1;
- }
- else
- {
- picmp->icmpchksum += HTONS(ICMP_ECHO_REQUEST << 8);
- }
-#endif
-
- nllvdbg("Outgoing ICMP packet length: %d (%d)\n",
- dev->d_len, (picmp->len[0] << 8) | picmp->len[1]);
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.icmp.sent++;
- uip_stat.ip.sent++;
-#endif
- }
-
- /* If an ICMP echo reply is received then there should also be
- * a thread waiting to received the echo response.
- */
-
-#ifdef CONFIG_NET_ICMP_PING
- else if (picmp->type == ICMP_ECHO_REPLY && g_echocallback)
- {
- (void)uip_callbackexecute(dev, picmp, UIP_ECHOREPLY, g_echocallback);
- }
-#endif
-
- /* Otherwise the ICMP input was not processed */
-
- else
- {
- nlldbg("Unknown ICMP cmd: %d\n", picmp->type);
- goto typeerr;
- }
-
- return;
-
-typeerr:
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.icmp.typeerr++;
- uip_stat.icmp.drop++;
-#endif
- dev->d_len = 0;
-
-#else /* !CONFIG_NET_IPv6 */
-
- /* If we get a neighbor solicitation for our address we should send
- * a neighbor advertisement message back.
- */
-
- if (picmp->type == ICMP6_NEIGHBOR_SOLICITATION)
- {
- if (uip_ipaddr_cmp(picmp->icmp6data, dev->d_ipaddr))
- {
- if (picmp->options[0] == ICMP6_OPTION_SOURCE_LINK_ADDRESS)
- {
- /* Save the sender's address in our neighbor list. */
-
- uiphdr_neighbor_add(picmp->srcipaddr, &(picmp->options[2]));
- }
-
- /* We should now send a neighbor advertisement back to where the
- * neighbor solicication came from.
- */
-
- picmp->type = ICMP6_NEIGHBOR_ADVERTISEMENT;
- picmp->flags = ICMP6_FLAG_S; /* Solicited flag. */
-
- picmp->reserved1 = picmp->reserved2 = picmp->reserved3 = 0;
-
- uiphdr_ipaddr_copy(picmp->destipaddr, picmp->srcipaddr);
- uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
- picmp->options[0] = ICMP6_OPTION_TARGET_LINK_ADDRESS;
- picmp->options[1] = 1; /* Options length, 1 = 8 bytes. */
- memcpy(&(picmp->options[2]), &dev->d_mac, IFHWADDRLEN);
- picmp->icmpchksum = 0;
- picmp->icmpchksum = ~uip_icmp6chksum(dev);
- }
- else
- {
- goto drop;
- }
- }
- else if (picmp->type == ICMP6_ECHO_REQUEST)
- {
- /* ICMP echo (i.e., ping) processing. This is simple, we only
- * change the ICMP type from ECHO to ECHO_REPLY and update the
- * ICMP checksum before we return the packet.
- */
-
- picmp->type = ICMP6_ECHO_REPLY;
-
- uiphdr_ipaddr_copy(picmp->destipaddr, picmp->srcipaddr);
- uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
- picmp->icmpchksum = 0;
- picmp->icmpchksum = ~uip_icmp6chksum(dev);
- }
-
- /* If an ICMP echo reply is received then there should also be
- * a thread waiting to received the echo response.
- */
-
-#ifdef CONFIG_NET_ICMP_PING
- else if (picmp->type == ICMP6_ECHO_REPLY && g_echocallback)
- {
- uint16_t flags = UIP_ECHOREPLY;
-
- if (g_echocallback)
- {
- /* Dispatch the ECHO reply to the waiting thread */
-
- flags = uip_callbackexecute(dev, picmp, flags, g_echocallback);
- }
-
- /* If the ECHO reply was not handled, then drop the packet */
-
- if (flags == UIP_ECHOREPLY)
- {
- /* The ECHO reply was not handled */
-
- goto drop;
- }
- }
-#endif
-
- else
- {
- nlldbg("Unknown ICMP6 cmd: %d\n", picmp->type);
- goto typeerr;
- }
-
- nllvdbg("Outgoing ICMP6 packet length: %d (%d)\n",
- dev->d_len, (picmp->len[0] << 8) | picmp->len[1]);
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.icmp.sent++;
- uip_stat.ip.sent++;
-#endif
- return;
-
-typeerr:
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.icmp.typeerr++;
-#endif
-
-drop:
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.icmp.drop++;
-#endif
- dev->d_len = 0;
-
-#endif /* !CONFIG_NET_IPv6 */
-}
-
-#endif /* CONFIG_NET_ICMP */
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_icmpping.c b/nuttx/net/uip/uip_icmpping.c
deleted file mode 100644
index 36f6e892a..000000000
--- a/nuttx/net/uip/uip_icmpping.c
+++ /dev/null
@@ -1,388 +0,0 @@
-/****************************************************************************
- * net/uip/uip_icmpping.c
- *
- * Copyright (C) 2008-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMP) && \
- defined(CONFIG_NET_ICMP_PING) && !defined(CONFIG_DISABLE_CLOCK)
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <semaphore.h>
-#include <debug.h>
-
-#include <net/if.h>
-#include <nuttx/clock.h>
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-#include "../net_internal.h" /* Should not include this! */
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-#define ICMPDAT (&dev->d_buf[UIP_LLH_LEN + sizeof(struct uip_icmpip_hdr)])
-
-/* Allocate a new ICMP data callback */
-
-#define uip_icmpcallbackalloc() uip_callbackalloc(&g_echocallback)
-#define uip_icmpcallbackfree(cb) uip_callbackfree(cb, &g_echocallback)
-
-/****************************************************************************
- * Private Types
- ****************************************************************************/
-
-struct icmp_ping_s
-{
- FAR struct uip_callback_s *png_cb; /* Reference to callback instance */
-
- sem_t png_sem; /* Use to manage the wait for the response */
- uint32_t png_time; /* Start time for determining timeouts */
- uint32_t png_ticks; /* System clock ticks to wait */
- int png_result; /* 0: success; <0:negated errno on fail */
- uip_ipaddr_t png_addr; /* The peer to be ping'ed */
- uint16_t png_id; /* Used to match requests with replies */
- uint16_t png_seqno; /* IN: seqno to send; OUT: seqno recieved */
- uint16_t png_datlen; /* The length of data to send in the ECHO request */
- bool png_sent; /* true... the PING request has been sent */
-};
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: ping_timeout
- *
- * Description:
- * Check for send timeout.
- *
- * Parameters:
- * pstate - Ping state structure
- *
- * Returned Value:
- * TRUE:timeout FALSE:no timeout
- *
- * Assumptions:
- * Running at the interrupt level
- *
- ****************************************************************************/
-
-static inline int ping_timeout(struct icmp_ping_s *pstate)
-{
- uint32_t elapsed = clock_systimer() - pstate->png_time;
- if (elapsed >= pstate->png_ticks)
- {
- return TRUE;
- }
-
- return FALSE;
-}
-
-/****************************************************************************
- * Function: ping_interrupt
- *
- * Description:
- * This function is called from the interrupt level to perform the actual
- * ECHO request and/or ECHO reply actions when polled by the uIP layer.
- *
- * Parameters:
- * dev The structure of the network driver that caused the interrupt
- * conn The received packet, cast to void *
- * pvpriv An instance of struct icmp_ping_s cast to void*
- * flags Set of events describing why the callback was invoked
- *
- * Returned Value:
- * Modified value of the input flags
- *
- * Assumptions:
- * Running at the interrupt level
- *
- ****************************************************************************/
-
-static uint16_t ping_interrupt(struct uip_driver_s *dev, void *conn,
- void *pvpriv, uint16_t flags)
-{
- struct icmp_ping_s *pstate = (struct icmp_ping_s *)pvpriv;
- uint8_t *ptr;
- int i;
-
- nllvdbg("flags: %04x\n", flags);
- if (pstate)
- {
- /* Check if this is a ICMP ECHO reply. If so, return the sequence
- * number to the caller. NOTE: We may not even have sent the
- * requested ECHO request; this could have been the delayed ECHO
- * response from a previous ping.
- */
-
- if ((flags & UIP_ECHOREPLY) != 0 && conn != NULL)
- {
- struct uip_icmpip_hdr *icmp = (struct uip_icmpip_hdr *)conn;
- nlldbg("ECHO reply: id=%d seqno=%d\n",
- ntohs(icmp->id), ntohs(icmp->seqno));
-
- if (ntohs(icmp->id) == pstate->png_id)
- {
- /* Consume the ECHOREPLY */
-
- flags &= ~UIP_ECHOREPLY;
- dev->d_len = 0;
-
- /* Return the result to the caller */
-
- pstate->png_result = OK;
- pstate->png_seqno = ntohs(icmp->seqno);
- goto end_wait;
- }
- }
-
- /* Check:
- * If the outgoing packet is available (it may have been claimed
- * by a sendto interrupt serving a different thread)
- * -OR-
- * If the output buffer currently contains unprocessed incoming
- * data.
- * -OR-
- * If we have alread sent the ECHO request
- *
- * In the first two cases, we will just have to wait for the next
- * polling cycle.
- */
-
- if (dev->d_sndlen <= 0 && /* Packet available */
- (flags & UIP_NEWDATA) == 0 && /* No incoming data */
- !pstate->png_sent) /* Request not sent */
- {
- struct uip_icmpip_hdr *picmp = ICMPBUF;
-
- /* We can send the ECHO request now.
- *
- * Format the ICMP ECHO request packet
- */
-
- picmp->type = ICMP_ECHO_REQUEST;
- picmp->icode = 0;
-#ifndef CONFIG_NET_IPv6
- picmp->id = htons(pstate->png_id);
- picmp->seqno = htons(pstate->png_seqno);
-#else
-# error "IPv6 ECHO Request not implemented"
-#endif
- /* Add some easily verifiable data */
-
- for (i = 0, ptr = ICMPDAT; i < pstate->png_datlen; i++)
- {
- *ptr++ = i;
- }
-
- /* Send the ICMP echo request. Note that d_sndlen is set to
- * the size of the ICMP payload and does not include the size
- * of the ICMP header.
- */
-
- nlldbg("Send ECHO request: seqno=%d\n", pstate->png_seqno);
-
- dev->d_sndlen = pstate->png_datlen + 4;
- uip_icmpsend(dev, &pstate->png_addr);
- pstate->png_sent = true;
- return flags;
- }
-
- /* Check if the selected timeout has elapsed */
-
- if (ping_timeout(pstate))
- {
- int failcode;
-
- /* Check if this device is on the same network as the destination
- * device.
- */
-
- if (!uip_ipaddr_maskcmp(pstate->png_addr, dev->d_ipaddr, dev->d_netmask))
- {
- /* Destination address was not on the local network served by this
- * device. If a timeout occurs, then the most likely reason is
- * that the destination address is not reachable.
- */
-
- nlldbg("Not reachable\n");
- failcode = -ENETUNREACH;
- }
- else
- {
- nlldbg("Ping timeout\n");
- failcode = -ETIMEDOUT;
- }
-
- /* Report the failure */
-
- pstate->png_result = failcode;
- goto end_wait;
- }
-
- /* Continue waiting */
- }
-
- return flags;
-
-end_wait:
- nllvdbg("Resuming\n");
-
- /* Do not allow any further callbacks */
-
- pstate->png_cb->flags = 0;
- pstate->png_cb->priv = NULL;
- pstate->png_cb->event = NULL;
-
- /* Wake up the waiting thread */
-
- sem_post(&pstate->png_sem);
- return flags;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_ping
- *
- * Description:
- * Send a ECHO request and wait for the ECHO response
- *
- * Parameters:
- * addr - The IP address of the peer to send the ICMP ECHO request to
- * in network order.
- * id - The ID to use in the ICMP ECHO request. This number should be
- * unique; only ECHO responses with this matching ID will be
- * processed (host order)
- * seqno - The sequence number used in the ICMP ECHO request. NOT used
- * to match responses (host order)
- * dsecs - Wait up to this many deci-seconds for the ECHO response to be
- * returned (host order).
- *
- * Return:
- * seqno of received ICMP ECHO with matching ID (may be different
- * from the seqno argument (may be a delayed response from an earlier
- * ping with the same ID). Or a negated errno on any failure.
- *
- * Assumptions:
- * Called from the user level with interrupts enabled.
- *
- ****************************************************************************/
-
-int uip_ping(uip_ipaddr_t addr, uint16_t id, uint16_t seqno,
- uint16_t datalen, int dsecs)
-{
- struct icmp_ping_s state;
- uip_lock_t save;
-
- /* Initialize the state structure */
-
- sem_init(&state.png_sem, 0, 0);
- state.png_ticks = DSEC2TICK(dsecs); /* System ticks to wait */
- state.png_result = -ENOMEM; /* Assume allocation failure */
- state.png_addr = addr; /* Address of the peer to be ping'ed */
- state.png_id = id; /* The ID to use in the ECHO request */
- state.png_seqno = seqno; /* The seqno to use int the ECHO request */
- state.png_datlen = datalen; /* The length of data to send in the ECHO request */
- state.png_sent = false; /* ECHO request not yet sent */
-
- save = uip_lock();
- state.png_time = clock_systimer();
-
- /* Set up the callback */
-
- state.png_cb = uip_icmpcallbackalloc();
- if (state.png_cb)
- {
- state.png_cb->flags = UIP_POLL|UIP_ECHOREPLY;
- state.png_cb->priv = (void*)&state;
- state.png_cb->event = ping_interrupt;
- state.png_result = -EINTR; /* Assume sem-wait interrupted by signal */
-
- /* Notify the device driver of the availaibilty of TX data */
-
- netdev_txnotify(&state.png_addr);
-
- /* Wait for either the full round trip transfer to complete or
- * for timeout to occur. (1) uip_lockedwait will also terminate if a
- * signal is received, (2) interrupts may be disabled! They will
- * be re-enabled while the task sleeps and automatically
- * re-enabled when the task restarts.
- */
-
- nlldbg("Start time: 0x%08x seqno: %d\n", state.png_time, seqno);
- uip_lockedwait(&state.png_sem);
-
- uip_icmpcallbackfree(state.png_cb);
- }
-
- uip_unlock(save);
-
- /* Return the negated error number in the event of a failure, or the
- * sequence number of the ECHO reply on success.
- */
-
- if (!state.png_result)
- {
- nlldbg("Return seqno=%d\n", state.png_seqno);
- return (int)state.png_seqno;
- }
- else
- {
- nlldbg("Return error=%d\n", -state.png_result);
- return state.png_result;
- }
-}
-
-#endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING ... */
diff --git a/nuttx/net/uip/uip_icmppoll.c b/nuttx/net/uip/uip_icmppoll.c
deleted file mode 100644
index bcf7fe94b..000000000
--- a/nuttx/net/uip/uip_icmppoll.c
+++ /dev/null
@@ -1,103 +0,0 @@
-/****************************************************************************
- * net/uip/uip_icmppoll.c
- *
- * Copyright (C) 2008-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
-
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_icmppoll
- *
- * Description:
- * Poll a UDP "connection" structure for availability of TX data
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_icmppoll(struct uip_driver_s *dev)
-{
- /* Setup for the application callback */
-
- dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPICMPH_LEN];
- dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPICMPH_LEN];
-
- dev->d_len = 0;
- dev->d_sndlen = 0;
-
- /* Perform the application callback */
-
- (void)uip_callbackexecute(dev, NULL, UIP_POLL, g_echocallback);
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
diff --git a/nuttx/net/uip/uip_icmpsend.c b/nuttx/net/uip/uip_icmpsend.c
deleted file mode 100644
index 00c5bb9de..000000000
--- a/nuttx/net/uip/uip_icmpsend.c
+++ /dev/null
@@ -1,168 +0,0 @@
-/****************************************************************************
- * net/uip/uip_icmpsend.c
- *
- * Copyright (C) 2008-2010, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
-
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_icmpsend
- *
- * Description:
- * Setup to send an ICMP packet
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_icmpsend(struct uip_driver_s *dev, uip_ipaddr_t *destaddr)
-{
- struct uip_icmpip_hdr *picmp = ICMPBUF;
-
- if (dev->d_sndlen > 0)
- {
- /* The total length to send is the size of the application data plus
- * the IP and ICMP headers (and, eventually, the ethernet header)
- */
-
- dev->d_len = dev->d_sndlen + UIP_IPICMPH_LEN;
-
- /* The total size of the data (for ICMP checksum calculation) includes
- * the size of the ICMP header
- */
-
- dev->d_sndlen += UIP_ICMPH_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
-
- picmp->vtc = 0x60;
- picmp->tcf = 0x00;
- picmp->flow = 0x00;
- picmp->len[0] = (dev->d_sndlen >> 8);
- picmp->len[1] = (dev->d_sndlen & 0xff);
- picmp->nexthdr = UIP_PROTO_ICMP;
- picmp->hoplimit = UIP_TTL;
-
- uip_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
- uip_ipaddr_copy(picmp->destipaddr, destaddr);
-
-#else /* CONFIG_NET_IPv6 */
-
- picmp->vhl = 0x45;
- picmp->tos = 0;
- picmp->len[0] = (dev->d_len >> 8);
- picmp->len[1] = (dev->d_len & 0xff);
- ++g_ipid;
- picmp->ipid[0] = g_ipid >> 8;
- picmp->ipid[1] = g_ipid & 0xff;
- picmp->ipoffset[0] = UIP_TCPFLAG_DONTFRAG >> 8;
- picmp->ipoffset[1] = UIP_TCPFLAG_DONTFRAG & 0xff;
- picmp->ttl = UIP_TTL;
- picmp->proto = UIP_PROTO_ICMP;
-
- uiphdr_ipaddr_copy(picmp->srcipaddr, &dev->d_ipaddr);
- uiphdr_ipaddr_copy(picmp->destipaddr, destaddr);
-
- /* Calculate IP checksum. */
-
- picmp->ipchksum = 0;
- picmp->ipchksum = ~(uip_ipchksum(dev));
-
-#endif /* CONFIG_NET_IPv6 */
-
- /* Calculate the ICMP checksum. */
-
- picmp->icmpchksum = 0;
- picmp->icmpchksum = ~(uip_icmpchksum(dev, dev->d_sndlen));
- if (picmp->icmpchksum == 0)
- {
- picmp->icmpchksum = 0xffff;
- }
-
- nllvdbg("Outgoing ICMP packet length: %d (%d)\n",
- dev->d_len, (picmp->len[0] << 8) | picmp->len[1]);
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.icmp.sent++;
- uip_stat.ip.sent++;
-#endif
- }
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
diff --git a/nuttx/net/uip/uip_igmpgroup.c b/nuttx/net/uip/uip_igmpgroup.c
deleted file mode 100644
index b92db5476..000000000
--- a/nuttx/net/uip/uip_igmpgroup.c
+++ /dev/null
@@ -1,391 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmpgroup.c
- * IGMP group data structure management logic
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-#include <nuttx/compiler.h>
-
-#include <stdlib.h>
-#include <string.h>
-#include <wdog.h>
-#include <queue.h>
-#include <debug.h>
-
-#include <arch/irq.h>
-#include <nuttx/arch.h>
-#include <nuttx/kmalloc.h>
-
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* Configuration ************************************************************/
-
-#ifdef CONFIG_NET_IPv6
-# error "IGMP for IPv6 not supported"
-#endif
-
-#ifndef CONFIG_PREALLOC_IGMPGROUPS
-# define CONFIG_PREALLOC_IGMPGROUPS 4
-#endif
-
-/* Debug ********************************************************************/
-
-#undef IGMP_GRPDEBUG /* Define to enable detailed IGMP group debug */
-
-#ifndef CONFIG_NET_IGMP
-# undef IGMP_GRPDEBUG
-#endif
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-# ifdef IGMP_GRPDEBUG
-# define grpdbg(format, arg...) ndbg(format, ##arg)
-# define grplldbg(format, arg...) nlldbg(format, ##arg)
-# define grpvdbg(format, arg...) nvdbg(format, ##arg)
-# define grpllvdbg(format, arg...) nllvdbg(format, ##arg)
-# else
-# define grpdbg(x...)
-# define grplldbg(x...)
-# define grpvdbg(x...)
-# define grpllvdbg(x...)
-# endif
-#else
-# ifdef IGMP_GRPDEBUG
-# define grpdbg ndbg
-# define grplldbg nlldbg
-# define grpvdbg nvdbg
-# define grpllvdbg nllvdbg
-# else
-# define grpdbg (void)
-# define grplldbg (void)
-# define grpvdbg (void)
-# define grpllvdbg (void)
-# endif
-#endif
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* malloc() cannot be called from an interrupt handler. To work around this,
- * a small number of IGMP groups are preallocated just for use in interrupt
- * handling logic.
- */
-
-#if CONFIG_PREALLOC_IGMPGROUPS > 0
-static struct igmp_group_s g_preallocgrps[CONFIG_PREALLOC_IGMPGROUPS];
-static FAR sq_queue_t g_freelist;
-#endif
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_grpalloc
- *
- * Description:
- * Allocate a new group from heap memory.
- *
- * Assumptions:
- * Calls malloc and so cannot be called from an interrupt handler.
- *
- ****************************************************************************/
-
-static inline FAR struct igmp_group_s *uip_grpheapalloc(void)
-{
- return (FAR struct igmp_group_s *)zalloc(sizeof(struct igmp_group_s));
-}
-
-/****************************************************************************
- * Name: uip_grpprealloc
- *
- * Description:
- * Allocate a new group from the pre-allocated groups.
- *
- * Assumptions:
- * This function should only be called from an interrupt handler (or with
- * interrupts disabled).
- *
- ****************************************************************************/
-
-#if CONFIG_PREALLOC_IGMPGROUPS > 0
-static inline FAR struct igmp_group_s *uip_grpprealloc(void)
-{
- FAR struct igmp_group_s *group = (FAR struct igmp_group_s *)sq_remfirst(&g_freelist);
- if (group)
- {
- memset(group, 0, sizeof(struct igmp_group_s));
- group->flags = IGMP_PREALLOCATED;
- }
- return group;
-}
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_grpinit
- *
- * Description:
- * One-time initialization of group data.
- *
- * Assumptions:
- * Called only during early boot phases (pre-multitasking).
- *
- ****************************************************************************/
-
-void uip_grpinit(void)
-{
- FAR struct igmp_group_s *group;
- int i;
-
- grplldbg("Initializing\n");
-
-#if CONFIG_PREALLOC_IGMPGROUPS > 0
- for (i = 0; i < CONFIG_PREALLOC_IGMPGROUPS; i++)
- {
- group = &g_preallocgrps[i];
- sq_addfirst((FAR sq_entry_t *)group, &g_freelist);
- }
-#endif
-}
-
-/****************************************************************************
- * Name: uip_grpalloc
- *
- * Description:
- * Allocate a new group from heap memory.
- *
- * Assumptions:
- * May be called from either user or interrupt level processing.
- *
- ****************************************************************************/
-
-FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
- FAR const uip_ipaddr_t *addr)
-{
- FAR struct igmp_group_s *group;
- uip_lock_t flags;
-
- nllvdbg("addr: %08x dev: %p\n", *addr, dev);
- if (up_interrupt_context())
- {
-#if CONFIG_PREALLOC_IGMPGROUPS > 0
- grplldbg("Use a pre-allocated group entry\n");
- group = uip_grpprealloc();
-#else
- grplldbg("Cannot allocate from interrupt handler\n");
- group = NULL;
-#endif
- }
- else
- {
- grplldbg("Allocate from the heap\n");
- group = uip_grpheapalloc();
- }
- grplldbg("group: %p\n", group);
-
- /* Check if we succesfully allocated a group structure */
-
- if (group)
- {
- /* Initialize the non-zero elements of the group structure */
-
- uip_ipaddr_copy(group->grpaddr, *addr);
- sem_init(&group->sem, 0, 0);
-
- /* Initialize the group timer (but don't start it yet) */
-
- group->wdog = wd_create();
- DEBUGASSERT(group->wdog);
-
- /* Interrupts must be disabled in order to modify the group list */
-
- flags = uip_lock();
-
- /* Add the group structure to the list in the device structure */
-
- sq_addfirst((FAR sq_entry_t*)group, &dev->grplist);
- uip_unlock(flags);
- }
- return group;
-}
-
-/****************************************************************************
- * Name: uip_grpfind
- *
- * Description:
- * Find an existing group.
- *
- * Assumptions:
- * May be called from either user or interrupt level processing.
- *
- ****************************************************************************/
-
-FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
- FAR const uip_ipaddr_t *addr)
-{
- FAR struct igmp_group_s *group;
- uip_lock_t flags;
-
- grplldbg("Searching for addr %08x\n", (int)*addr);
-
- /* We must disable interrupts because we don't which context we were
- * called from.
- */
-
- flags = uip_lock();
- for (group = (FAR struct igmp_group_s *)dev->grplist.head;
- group;
- group = group->next)
- {
- grplldbg("Compare: %08x vs. %08x\n", group->grpaddr, *addr);
- if (uip_ipaddr_cmp(group->grpaddr, *addr))
- {
- grplldbg("Match!\n");
- break;
- }
- }
- uip_unlock(flags);
- return group;
-}
-
-/****************************************************************************
- * Name: uip_grpallocfind
- *
- * Description:
- * Find an existing group. If not found, create a new group for the
- * address.
- *
- * Assumptions:
- * May be called from either user or interrupt level processing.
- *
- ****************************************************************************/
-
-FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev,
- FAR const uip_ipaddr_t *addr)
-{
- FAR struct igmp_group_s *group = uip_grpfind(dev, addr);
-
- grplldbg("group: %p addr: %08x\n", group, (int)*addr);
- if (!group)
- {
- group = uip_grpalloc(dev, addr);
- }
- grplldbg("group: %p\n", group);
- return group;
-}
-
-/****************************************************************************
- * Name: uip_grpfree
- *
- * Description:
- * Release a previously allocated group.
- *
- * Assumptions:
- * May be called from either user or interrupt level processing.
- *
- ****************************************************************************/
-
-void uip_grpfree(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group)
-{
- uip_lock_t flags;
-
- grplldbg("Free: %p flags: %02x\n", group, group->flags);
-
- /* Cancel the wdog */
-
- flags = uip_lock();
- wd_cancel(group->wdog);
-
- /* Remove the group structure from the group list in the device structure */
-
- sq_rem((FAR sq_entry_t*)group, &dev->grplist);
-
- /* Destroy the wait semapore */
-
- (void)sem_destroy(&group->sem);
-
- /* Destroy the wdog */
-
- wd_delete(group->wdog);
-
- /* Then release the group structure resources. Check first if this is one
- * of the pre-allocated group structures that we will retain in a free list.
- */
-
-#if CONFIG_PREALLOC_IGMPGROUPS > 0
- if (IS_PREALLOCATED(group->flags))
- {
- grplldbg("Put back on free list\n");
- sq_addlast((FAR sq_entry_t*)group, &g_freelist);
- uip_unlock(flags);
- }
- else
-#endif
- {
- /* No.. deallocate the group structure. Use sched_free() just in case
- * this function is executing within an interrupt handler.
- */
-
- uip_unlock(flags);
- grplldbg("Call sched_free()\n");
- sched_free(group);
- }
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpinit.c b/nuttx/net/uip/uip_igmpinit.c
deleted file mode 100644
index 740ddf44b..000000000
--- a/nuttx/net/uip/uip_igmpinit.c
+++ /dev/null
@@ -1,122 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmpinit.c
- * IGMP initialization logic
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#ifdef CONFIG_NET_IPv6
-# error "IGMP for IPv6 not supported"
-#endif
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-uip_ipaddr_t g_allsystems;
-uip_ipaddr_t g_allrouters;
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_igmpinit
- *
- * Description:
- * Perform one-time IGMP initialization.
- *
- ****************************************************************************/
-
-void uip_igmpinit(void)
-{
- nvdbg("IGMP initializing\n");
-
- uip_ipaddr(g_allrouters, 224, 0, 0, 2);
- uip_ipaddr(g_allsystems, 224, 0, 0, 1);
-
- /* Initialize the group allocation logic */
-
- uip_grpinit();
-}
-
-/****************************************************************************
- * Name: uip_igmpdevinit
- *
- * Description:
- * Called when a new network device is registered to configure that device
- * for IGMP support.
- *
- ****************************************************************************/
-
-void uip_igmpdevinit(struct uip_driver_s *dev)
-{
- struct igmp_group_s *group;
-
- nvdbg("IGMP initializing dev %p\n", dev);
- DEBUGASSERT(dev->grplist.head == NULL);
-
- /* Add the all systems address to the group */
-
- group = uip_grpalloc(dev, &g_allsystems);
-
- /* Allow the IGMP messages at the MAC level */
-
- uip_addmcastmac(dev, &g_allrouters);
- uip_addmcastmac(dev, &g_allsystems);
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpinput.c b/nuttx/net/uip/uip_igmpinput.c
deleted file mode 100644
index 40c1cf3ba..000000000
--- a/nuttx/net/uip/uip_igmpinput.c
+++ /dev/null
@@ -1,280 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igminput.c
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-
-#include <wdog.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define IGMPBUF ((struct uip_igmphdr_s *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_igmpinput
- *
- * Description:
- * An IGMP packet has been received.
- *
- * ________________
- * | |
- * | |
- * | |
- * | |
- * +--------->| Non-Member |<---------+
- * | | | |
- * | | | |
- * | | | |
- * | |________________| |
- * | | |
- * | leave group | join group | leave group
- * | (stop timer, |(send report, | (send leave
- * | send leave if | set flag, | if flag set)
- * | flag set) | start timer) |
- * ________|________ | ________|________
- * | |<---------+ | |
- * | | | |
- * | |<-------------------| |
- * | | query received | |
- * | Delaying Member | (start timer) | Idle Member |
- * +---->| |------------------->| |
- * | | | report received | |
- * | | | (stop timer, | |
- * | | | clear flag) | |
- * | |_________________|------------------->|_________________|
- * | query received | timer expired
- * | (reset timer if | (send report,
- * | Max Resp Time | set flag)
- * | < current timer) |
- * +-------------------+
- *
- * NOTE: This is most likely executing from an interrupt handler.
- *
- ****************************************************************************/
-
-void uip_igmpinput(struct uip_driver_s *dev)
-{
- FAR struct igmp_group_s *group;
- uip_ipaddr_t destipaddr;
- uip_ipaddr_t grpaddr;
- unsigned int ticks;
-
- nllvdbg("IGMP message: %04x%04x\n", IGMPBUF->destipaddr[1], IGMPBUF->destipaddr[0]);
-
- /* Verify the message length */
-
- if (dev->d_len < UIP_LLH_LEN+UIP_IPIGMPH_LEN)
- {
- IGMP_STATINCR(uip_stat.igmp.length_errors);
- nlldbg("Length error\n");
- return;
- }
-
- /* Calculate and check the IGMP checksum */
-
- if (uip_chksum((uint16_t*)&IGMPBUF->type, UIP_IGMPH_LEN) != 0)
- {
- IGMP_STATINCR(uip_stat.igmp.chksum_errors);
- nlldbg("Checksum error\n");
- return;
- }
-
- /* Find the group (or create a new one) using the incoming IP address*/
-
- destipaddr = uip_ip4addr_conv(IGMPBUF->destipaddr);
- group = uip_grpallocfind(dev, &destipaddr);
- if (!group)
- {
- nlldbg("Failed to allocate/find group: %08x\n", destipaddr);
- return;
- }
-
- /* Now handle the message based on the IGMP message type */
-
- switch (IGMPBUF->type)
- {
- case IGMP_MEMBERSHIP_QUERY:
- /* RFC 2236, 2.2. ax Response Time
- * "The Max Response Time field is meaningful only in Membership Query
- * messages, and specifies the maximum allowed time before sending a
- * responding report in units of 1/10 second. In all other messages, it
- * is set to zero by the sender and ignored by receivers.
- */
-
- /* Check if the query was sent to all systems */
-
- if (uip_ipaddr_cmp(destipaddr, g_allsystems))
- {
- /* Yes... Now check the if this this is a general or a group
- * specific query.
- *
- * RFC 2236, 2.1. Type
- * There are two sub-types of Membership Query messages:
- * - General Query, used to learn which groups have members on an
- * attached network.
- * - Group-Specific Query, used to learn if a particular group
- * has any members on an attached network.
- *
- * RFC 2236, 2.4. Group Address
- * "In a Membership Query message, the group address field is
- * set to zero when sending a General Query, and set to the
- * group address being queried when sending a Group-Specific
- * Query."
- */
-
- if (IGMPBUF->grpaddr == 0)
- {
- FAR struct igmp_group_s *member;
-
- /* This is the general query */
-
- nllvdbg("General multicast query\n");
- if (IGMPBUF->maxresp == 0)
- {
- IGMP_STATINCR(uip_stat.igmp.v1_received);
- IGMPBUF->maxresp = 10;
-
- nlldbg("V1 not implemented\n");
- }
-
- IGMP_STATINCR(uip_stat.igmp.query_received);
- for (member = (FAR struct igmp_group_s *)dev->grplist.head;
- member;
- member = member->next)
- {
- /* Skip over the all systems group entry */
-
- if (!uip_ipaddr_cmp(member->grpaddr, g_allsystems))
- {
- ticks = uip_decisec2tick((int)IGMPBUF->maxresp);
- if (IS_IDLEMEMBER(member->flags) ||
- uip_igmpcmptimer(member, ticks))
- {
- uip_igmpstartticks(member, ticks);
- CLR_IDLEMEMBER(member->flags);
- }
- }
- }
- }
- else /* if (IGMPBUF->grpaddr != 0) */
- {
- nllvdbg("Group-specific multicast queury\n");
-
- /* We first need to re-lookup the group since we used dest last time.
- * Use the incoming IPaddress!
- */
-
- IGMP_STATINCR(uip_stat.igmp.ucast_query);
- grpaddr = uip_ip4addr_conv(IGMPBUF->grpaddr);
- group = uip_grpallocfind(dev, &grpaddr);
- ticks = uip_decisec2tick((int)IGMPBUF->maxresp);
- if (IS_IDLEMEMBER(group->flags) || uip_igmpcmptimer(group, ticks))
- {
- uip_igmpstartticks(group, ticks);
- CLR_IDLEMEMBER(group->flags);
- }
- }
- }
-
- /* Not sent to all systems -- Unicast query */
-
- else if (group->grpaddr != 0)
- {
- nllvdbg("Unitcast queury\n");
- IGMP_STATINCR(uip_stat.igmp.ucast_query);
-
- nlldbg("Query to a specific group with the group address as destination\n");
-
- ticks = uip_decisec2tick((int)IGMPBUF->maxresp);
- if (IS_IDLEMEMBER(group->flags) || uip_igmpcmptimer(group, ticks))
- {
- uip_igmpstartticks(group, ticks);
- CLR_IDLEMEMBER(group->flags);
- }
- }
- break;
-
- case IGMPv2_MEMBERSHIP_REPORT:
- {
- nllvdbg("Membership report\n");
-
- IGMP_STATINCR(uip_stat.igmp.report_received);
- if (!IS_IDLEMEMBER(group->flags))
- {
- /* This is on a specific group we have already looked up */
-
- wd_cancel(group->wdog);
- SET_IDLEMEMBER(group->flags);
- CLR_LASTREPORT(group->flags);
- }
- }
- break;
-
- default:
- {
- nlldbg("Unexpected msg %02x\n", IGMPBUF->type);
- }
- break;
- }
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpjoin.c b/nuttx/net/uip/uip_igmpjoin.c
deleted file mode 100644
index c02b0bb8f..000000000
--- a/nuttx/net/uip/uip_igmpjoin.c
+++ /dev/null
@@ -1,160 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmpjoin.c
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: igmp_joingroup
- *
- * Description:
- * Add the specified group address to the group.
- *
- * RFC 2236, 3. Protocol Description:
- *
- * "When a host joins a multicast group, it should immediately transmit
- * an unsolicited Version 2 Membership Report for that group, in case it
- * is the first member of that group on the network. To cover the
- * possibility of the initial Membership Report being lost or damaged,
- * it is recommended that it be repeated once or twice after short
- * delays [Unsolicited Report Interval]. (A simple way to accomplish
- * this is to send the initial Version 2 Membership Report and then act
- * as if a Group-Specific Query was received for that group, and set a
- * timer appropriately)."
- * ________________
- * | |
- * | |
- * | |
- * | |
- * +--------->| Non-Member |<---------+
- * | | | |
- * | | | |
- * | | | |
- * | |________________| |
- * | | |
- * | leave group | join group | leave group
- * | (stop timer, |(send report, | (send leave
- * | send leave if | set flag, | if flag set)
- * | flag set) | start timer) |
- * ________|________ | ________|________
- * | |<---------+ | |
- * | | | |
- * | |<-------------------| |
- * | | query received | |
- * | Delaying Member | (start timer) | Idle Member |
- * +---->| |------------------->| |
- * | | | report received | |
- * | | | (stop timer, | |
- * | | | clear flag) | |
- * | |_________________|------------------->|_________________|
- * | query received | timer expired
- * | (reset timer if | (send report,
- * | Max Resp Time | set flag)
- * | < current timer) |
- * +-------------------+
- *
- * Assumptions:
- * This function cannot be called from interrupt handling logic!
- *
- ****************************************************************************/
-
-int igmp_joingroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
-{
- struct igmp_group_s *group;
-
- DEBUGASSERT(dev && grpaddr);
-
- /* Check if a this address is already in the group */
-
- group = uip_grpfind(dev, &grpaddr->s_addr);
- if (!group)
- {
- /* No... allocate a new entry */
-
- nvdbg("Join to new group: %08x\n", grpaddr->s_addr);
- group = uip_grpalloc(dev, &grpaddr->s_addr);
- IGMP_STATINCR(uip_stat.igmp.joins);
-
- /* Send the Membership Report */
-
- IGMP_STATINCR(uip_stat.igmp.report_sched);
- uip_igmpwaitmsg(group, IGMPv2_MEMBERSHIP_REPORT);
-
- /* And start the timer at 10*100 msec */
-
- uip_igmpstarttimer(group, 10);
-
- /* Add the group (MAC) address to the ether drivers MAC filter list */
-
- uip_addmcastmac(dev, (FAR uip_ipaddr_t *)&grpaddr->s_addr);
- return OK;
- }
-
- /* Return EEXIST if the address is already a member of the group */
-
- return -EEXIST;
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpleave.c b/nuttx/net/uip/uip_igmpleave.c
deleted file mode 100644
index 4e08df576..000000000
--- a/nuttx/net/uip/uip_igmpleave.c
+++ /dev/null
@@ -1,182 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmpleave.c
- *
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-
-#include <wdog.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: igmp_leavegroup
- *
- * Description:
- * Remove the specified group address to the group.
- *
- * RFC 2236, 3. Protocol Description:
- *
- * "When a host leaves a multicast group, if it was the last host to
- * reply to a Query with a Membership Report for that group, it SHOULD
- * send a Leave Group message to the all-routers multicast group
- * (224.0.0.2). If it was not the last host to reply to a Query, it MAY
- * send nothing as there must be another member on the subnet. This is
- * an optimization to reduce traffic; a host without sufficient storage
- * to remember whether or not it was the last host to reply MAY always
- * send a Leave Group message when it leaves a group. Routers SHOULD
- * accept a Leave Group message addressed to the group being left, in
- * order to accommodate implementations of an earlier version of this
- * standard. Leave Group messages are addressed to the all-routers
- * group because other group members have no need to know that a host
- * has left the group, but it does no harm to address the message to the
- * group."
- *
- * ________________
- * | |
- * | |
- * | |
- * | |
- * +--------->| Non-Member |<---------+
- * | | | |
- * | | | |
- * | | | |
- * | |________________| |
- * | | |
- * | leave group | join group | leave group
- * | (stop timer, |(send report, | (send leave
- * | send leave if | set flag, | if flag set)
- * | flag set) | start timer) |
- * ________|________ | ________|________
- * | |<---------+ | |
- * | | | |
- * | |<-------------------| |
- * | | query received | |
- * | Delaying Member | (start timer) | Idle Member |
- * +---->| |------------------->| |
- * | | | report received | |
- * | | | (stop timer, | |
- * | | | clear flag) | |
- * | |_________________|------------------->|_________________|
- * | query received | timer expired
- * | (reset timer if | (send report,
- * | Max Resp Time | set flag)
- * | < current timer) |
- * +-------------------+
- *
- * Assumptions:
- * This function cannot be called from interrupt handling logic!
- *
- ****************************************************************************/
-
-int igmp_leavegroup(struct uip_driver_s *dev, FAR const struct in_addr *grpaddr)
-{
- struct igmp_group_s *group;
- uip_lock_t flags;
-
- DEBUGASSERT(dev && grpaddr);
-
- /* Find the entry corresponding to the address leaving the group */
-
- group = uip_grpfind(dev, &grpaddr->s_addr);
- ndbg("Leaving group: %p\n", group);
- if (group)
- {
- /* Cancel the timer and discard any queued Membership Reports. Canceling
- * the timer will prevent any new Membership Reports from being sent;
- * clearing the flags will discard any pending Membership Reports that
- * could interfere with the Leave Group.
- */
-
- flags = uip_lock();
- wd_cancel(group->wdog);
- CLR_SCHEDMSG(group->flags);
- CLR_WAITMSG(group->flags);
- uip_unlock(flags);
-
- IGMP_STATINCR(uip_stat.igmp.leaves);
-
- /* Send a leave if the flag is set according to the state diagram */
-
- if (IS_LASTREPORT(group->flags))
- {
- ndbg("Schedule Leave Group message\n");
- IGMP_STATINCR(uip_stat.igmp.leave_sched);
- uip_igmpwaitmsg(group, IGMP_LEAVE_GROUP);
- }
-
- /* Free the group structure (state is now Non-Member */
-
- uip_grpfree(dev, group);
-
- /* And remove the group address from the ethernet drivers MAC filter set */
-
- uip_removemcastmac(dev, (FAR uip_ipaddr_t *)&grpaddr->s_addr);
- return OK;
- }
-
- /* Return ENOENT if the address is not a member of the group */
-
- nvdbg("Return -ENOENT\n");
- return -ENOENT;
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpmsg.c b/nuttx/net/uip/uip_igmpmsg.c
deleted file mode 100644
index 5209eaf7a..000000000
--- a/nuttx/net/uip/uip_igmpmsg.c
+++ /dev/null
@@ -1,139 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmpmgs.c
- *
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_igmpschedmsg
- *
- * Description:
- * Schedule a message to be send at the next driver polling interval.
- *
- * Assumptions:
- * This function may be called in most any context.
- *
- ****************************************************************************/
-
-void uip_igmpschedmsg(FAR struct igmp_group_s *group, uint8_t msgid)
-{
- uip_lock_t flags;
-
- /* The following should be atomic */
-
- flags = uip_lock();
- DEBUGASSERT(!IS_SCHEDMSG(group->flags));
- group->msgid = msgid;
- SET_SCHEDMSG(group->flags);
- uip_unlock(flags);
-}
-
-/****************************************************************************
- * Name: uip_igmpwaitmsg
- *
- * Description:
- * Schedule a message to be send at the next driver polling interval and
- * block, waiting for the message to be sent.
- *
- * Assumptions:
- * This function cannot be called from an interrupt handler (if you try it,
- * uip_lockedwait will assert).
- *
- ****************************************************************************/
-
-void uip_igmpwaitmsg(FAR struct igmp_group_s *group, uint8_t msgid)
-{
- uip_lock_t flags;
-
- /* Schedule to send the message */
-
- flags = uip_lock();
- DEBUGASSERT(!IS_WAITMSG(group->flags));
- SET_WAITMSG(group->flags);
- uip_igmpschedmsg(group, msgid);
-
- /* Then wait for the message to be sent */
-
- while (IS_SCHEDMSG(group->flags))
- {
- /* Wait for the semaphore to be posted */
-
- while (uip_lockedwait(&group->sem) != 0)
- {
- /* The only error that should occur from uip_lockedwait() is if
- * the wait is awakened by a signal.
- */
-
- ASSERT(errno == EINTR);
- }
- }
-
- /* The message has been sent and we are no longer waiting */
-
- CLR_WAITMSG(group->flags);
- uip_unlock(flags);
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmppoll.c b/nuttx/net/uip/uip_igmppoll.c
deleted file mode 100644
index e86eb687b..000000000
--- a/nuttx/net/uip/uip_igmppoll.c
+++ /dev/null
@@ -1,176 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmppoll.c
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_schedsend
- *
- * Description:
- * Construct the .
- *
- * Returned Value:
- * Returns a non-zero value if a IGP message is sent.
- *
- * Assumptions:
- * This function is called from the driver polling logic... probably within
- * an interrupt handler.
- *
- ****************************************************************************/
-
-static inline void uip_schedsend(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group)
-{
- uip_ipaddr_t *dest;
-
- /* Check what kind of messsage we need to send. There are only two
- * possibilities:
- */
-
- if (group->msgid == IGMPv2_MEMBERSHIP_REPORT)
- {
- dest = &group->grpaddr;
- nllvdbg("Send IGMPv2_MEMBERSHIP_REPORT, dest=%08x flags=%02x\n",
- *dest, group->flags);
- IGMP_STATINCR(uip_stat.igmp.report_sched);
- SET_LASTREPORT(group->flags); /* Remember we were the last to report */
- }
- else
- {
- DEBUGASSERT(group->msgid == IGMP_LEAVE_GROUP);
- dest = &g_allrouters;
- nllvdbg("Send IGMP_LEAVE_GROUP, dest=%08x flags=%02x\n",
- *dest, group->flags);
- IGMP_STATINCR(uip_stat.igmp.leave_sched);
- }
-
- /* Send the message */
-
- uip_igmpsend(dev, group, dest);
-
- /* Indicate that the message has been sent */
-
- CLR_SCHEDMSG(group->flags);
- group->msgid = 0;
-
- /* If there is a thread waiting fore the message to be sent, wake it up */
-
- if (IS_WAITMSG(group->flags))
- {
- nllvdbg("Awakening waiter\n");
- sem_post(&group->sem);
- }
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_igmppoll
- *
- * Description:
- * Poll the groups associated with the device to see if any IGMP messages
- * are pending transfer.
- *
- * Returned Value:
- * Returns a non-zero value if a IGP message is sent.
- *
- * Assumptions:
- * This function is called from the driver polling logic... probably within
- * an interrupt handler.
- *
- ****************************************************************************/
-
-void uip_igmppoll(FAR struct uip_driver_s *dev)
-{
- FAR struct igmp_group_s *group;
-
- nllvdbg("Entry\n");
-
- /* Setup the poll operation */
-
- dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPIGMPH_LEN];
- dev->d_snddata = &dev->d_buf[UIP_LLH_LEN + UIP_IPIGMPH_LEN];
-
- dev->d_len = 0;
- dev->d_sndlen = 0;
-
- /* Check each member of the group */
-
- for (group = (FAR struct igmp_group_s *)dev->grplist.head; group; group = group->next)
- {
- /* Does this member have a pending outgoing message? */
-
- if (IS_SCHEDMSG(group->flags))
- {
- /* Yes, create the IGMP message in the driver buffer */
-
- uip_schedsend(dev, group);
-
- /* Mark the message as sent and break out */
-
- CLR_SCHEDMSG(group->flags);
- break;
- }
- }
-}
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmpsend.c b/nuttx/net/uip/uip_igmpsend.c
deleted file mode 100644
index f22282b62..000000000
--- a/nuttx/net/uip/uip_igmpsend.c
+++ /dev/null
@@ -1,182 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmpsend.c
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-
-#include <debug.h>
-#include <arpa/inet.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-#include <nuttx/net/uip/uip-ipopt.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* Debug */
-
-#undef IGMP_DUMPPKT /* Define to enable packet dump */
-
-#ifndef CONFIG_DEBUG_NET
-# undef IGMP_DUMPPKT
-#endif
-
-#ifdef IGMP_DUMPPKT
-# define igmp_dumppkt(b,n) lib_dumpbuffer("IGMP", (FAR const uint8_t*)(b), (n))
-#else
-# define igmp_dumppkt(b,n)
-#endif
-
-/* Buffer layout */
-
-#define RASIZE (4)
-#define IGMPBUF ((struct uip_igmphdr_s *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-static uint16_t uip_igmpchksum(FAR uint8_t *buffer, int buflen)
-{
- uint16_t sum = uip_chksum((FAR uint16_t*)buffer, buflen);
- return sum ? sum : 0xffff;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_igmpsend
- *
- * Description:
- * Sends an IGMP IP packet on a network interface. This function constructs
- * the IP header and calculates the IP header checksum.
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation.
- * group - Describes the multicast group member and identifies the message
- * to be sent.
- * destipaddr - The IP address of the recipient of the message
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_igmpsend(FAR struct uip_driver_s *dev, FAR struct igmp_group_s *group,
- FAR uip_ipaddr_t *destipaddr)
-{
- nllvdbg("msgid: %02x destipaddr: %08x\n", group->msgid, (int)*destipaddr);
-
- /* The total length to send is the size of the IP and IGMP headers and 4
- * bytes for the ROUTER ALERT (and, eventually, the ethernet header)
- */
-
- dev->d_len = UIP_IPIGMPH_LEN;
-
- /* The total size of the data is the size of the IGMP header */
-
- dev->d_sndlen = UIP_IGMPH_LEN;
-
- /* Add the router alert option */
-
- IGMPBUF->ra[0] = HTONS(IPOPT_RA >> 16);
- IGMPBUF->ra[1] = HTONS(IPOPT_RA & 0xffff);
-
- /* Initialize the IPv4 header */
-
- IGMPBUF->vhl = 0x46; /* 4->IP; 6->24 bytes */
- IGMPBUF->tos = 0;
- IGMPBUF->len[0] = (dev->d_len >> 8);
- IGMPBUF->len[1] = (dev->d_len & 0xff);
- ++g_ipid;
- IGMPBUF->ipid[0] = g_ipid >> 8;
- IGMPBUF->ipid[1] = g_ipid & 0xff;
- IGMPBUF->ipoffset[0] = UIP_TCPFLAG_DONTFRAG >> 8;
- IGMPBUF->ipoffset[1] = UIP_TCPFLAG_DONTFRAG & 0xff;
- IGMPBUF->ttl = IGMP_TTL;
- IGMPBUF->proto = UIP_PROTO_IGMP;
-
- uiphdr_ipaddr_copy(IGMPBUF->srcipaddr, &dev->d_ipaddr);
- uiphdr_ipaddr_copy(IGMPBUF->destipaddr, destipaddr);
-
- /* Calculate IP checksum. */
-
- IGMPBUF->ipchksum = 0;
- IGMPBUF->ipchksum = ~uip_igmpchksum((FAR uint8_t *)IGMPBUF, UIP_IPH_LEN + RASIZE);
-
- /* Set up the IGMP message */
-
- IGMPBUF->type = group->msgid;
- IGMPBUF->maxresp = 0;
- uiphdr_ipaddr_copy(IGMPBUF->grpaddr, &group->grpaddr);
-
- /* Calculate the IGMP checksum. */
-
- IGMPBUF->chksum = 0;
- IGMPBUF->chksum = ~uip_igmpchksum(&IGMPBUF->type, UIP_IPIGMPH_LEN);
-
- IGMP_STATINCR(uip_stat.igmp.poll_send);
- IGMP_STATINCR(uip_stat.ip.sent);
-
- nllvdbg("Outgoing IGMP packet length: %d (%d)\n",
- dev->d_len, (IGMPBUF->len[0] << 8) | IGMPBUF->len[1]);
- igmp_dumppkt(RA, UIP_IPIGMPH_LEN + RASIZE);
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_igmptimer.c b/nuttx/net/uip/uip_igmptimer.c
deleted file mode 100644
index 4655f3a2f..000000000
--- a/nuttx/net/uip/uip_igmptimer.c
+++ /dev/null
@@ -1,257 +0,0 @@
-/****************************************************************************
- * net/uip/uip_igmptimer.c
- *
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-#include <nuttx/compiler.h>
-
-#include <wdog.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-igmp.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* Debug ********************************************************************/
-
-#undef IGMP_GTMRDEBUG /* Define to enable detailed IGMP group debug */
-
-#ifndef CONFIG_NET_IGMP
-# undef IGMP_GTMRDEBUG
-#endif
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-# ifdef IGMP_GTMRDEBUG
-# define gtmrdbg(format, arg...) ndbg(format, ##arg)
-# define gtmrlldbg(format, arg...) nlldbg(format, ##arg)
-# define gtmrvdbg(format, arg...) nvdbg(format, ##arg)
-# define gtmrllvdbg(format, arg...) nllvdbg(format, ##arg)
-# else
-# define gtmrdbg(x...)
-# define gtmrlldbg(x...)
-# define gtmrvdbg(x...)
-# define gtmrllvdbg(x...)
-# endif
-#else
-# ifdef IGMP_GTMRDEBUG
-# define gtmrdbg ndbg
-# define gtmrlldbg nlldbg
-# define gtmrvdbg nvdbg
-# define gtmrllvdbg nllvdbg
-# else
-# define gtmrdbg (void)
-# define gtmrlldbg (void)
-# define gtmrvdbg (void)
-# define gtmrllvdbg (void)
-# endif
-#endif
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_igmptimeout
- *
- * Description:
- * Timeout watchdog handler.
- *
- * Assumptions:
- * This function is called from the wdog timer handler which runs in the
- * context of the timer interrupt handler.
- *
- ****************************************************************************/
-
-static void uip_igmptimeout(int argc, uint32_t arg, ...)
-{
- FAR struct igmp_group_s *group;
-
- /* If the state is DELAYING_MEMBER then we send a report for this group */
-
- nllvdbg("Timeout!\n");
- group = (FAR struct igmp_group_s *)arg;
- DEBUGASSERT(argc == 1 && group);
-
- /* If the group exists and is no an IDLE MEMBER, then it must be a DELAYING
- * member. Race conditions are avoided because (1) the timer is not started
- * until after the first IGMPv2_MEMBERSHIP_REPORT during the join, and (2)
- * the timer is canceled before sending the IGMP_LEAVE_GROUP during a leave.
- */
-
- if (!IS_IDLEMEMBER(group->flags))
- {
- /* Schedule (and forget) the Membership Report. NOTE:
- * Since we are executing from a timer interrupt, we cannot wait
- * for the message to be sent.
- */
-
- IGMP_STATINCR(uip_stat.igmp.report_sched);
- uip_igmpschedmsg(group, IGMPv2_MEMBERSHIP_REPORT);
-
- /* Also note: The Membership Report is sent at most two times becasue
- * the timer is not reset here. Hmm.. does this mean that the group
- * is stranded if both reports were lost? This is consistent with the
- * RFC that states: "To cover the possibility of the initial Membership
- * Report being lost or damaged, it is recommended that it be repeated
- * once or twice after shortdelays [Unsolicited Report Interval]..."
- */
- }
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_igmpstarttimer
- *
- * Description:
- * Start the IGMP timer.
- *
- * Assumptions:
- * This function may be called from most any context.
- *
- ****************************************************************************/
-
-int uip_decisec2tick(int decisecs)
-{
- /* Convert the deci-second comparison value to clock ticks. The CLK_TCK
- * value is the number of clock ticks per second; decisecs argument is the
- * maximum delay in 100's of milliseconds. CLK_TCK/10 is then the number
- * of clock ticks in 100 milliseconds.
- */
-
- return CLK_TCK * decisecs / 10;
-}
-
-/****************************************************************************
- * Name: uip_igmpstartticks and uip_igmpstarttimer
- *
- * Description:
- * Start the IGMP timer with differing time units (ticks or deciseconds).
- *
- * Assumptions:
- * This function may be called from most any context.
- *
- ****************************************************************************/
-
-void uip_igmpstartticks(FAR struct igmp_group_s *group, int ticks)
-{
- int ret;
-
- /* Start the timer */
-
- gtmrlldbg("ticks: %d\n", ticks);
- ret = wd_start(group->wdog, ticks, uip_igmptimeout, 1, (uint32_t)group);
- DEBUGASSERT(ret == OK);
-}
-
-void uip_igmpstarttimer(FAR struct igmp_group_s *group, uint8_t decisecs)
-{
- /* Convert the decisec value to system clock ticks and start the timer.
- * Important!! this should be a random timer from 0 to decisecs
- */
-
- gtmrdbg("decisecs: %d\n", decisecs);
- uip_igmpstartticks(group, uip_decisec2tick(decisecs));
-}
-
-/****************************************************************************
- * Name: uip_igmpcmptimer
- *
- * Description:
- * Compare the timer remaining on the watching timer to the deci-second
- * value. If maxticks > ticks-remaining, then (1) cancel the timer (to
- * avoid race conditions) and return true.
- *
- * Assumptions:
- * This function may be called from most any context. If true is retuend
- * then the caller must call uip_igmpstartticks() to restart the timer
- *
- ****************************************************************************/
-
-bool uip_igmpcmptimer(FAR struct igmp_group_s *group, int maxticks)
-{
- uip_lock_t flags;
- int remaining;
-
- /* Disable interrupts so that there is no race condition with the actual
- * timer expiration.
- */
-
- flags = uip_lock();
-
- /* Get the timer remaining on the watchdog. A time of <= zero means that
- * the watchdog was never started.
- */
-
- remaining = wd_gettime(group->wdog);
-
- /* A remaining time of zero means that the watchdog was never started
- * or has already expired. That case should be covered in the following
- * test as well.
- */
-
- gtmrdbg("maxticks: %d remaining: %d\n", maxticks, remaining);
- if (maxticks > remaining)
- {
- /* Cancel the watchdog timer and return true */
-
- wd_cancel(group->wdog);
- uip_unlock(flags);
- return true;
- }
-
- uip_unlock(flags);
- return false;
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_initialize.c b/nuttx/net/uip/uip_initialize.c
deleted file mode 100644
index e737d646e..000000000
--- a/nuttx/net/uip/uip_initialize.c
+++ /dev/null
@@ -1,155 +0,0 @@
-/****************************************************************************
- * net/uip/uip_initialize.c
- *
- * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <stdint.h>
-#include <nuttx/net/uip/uip.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/* IP/TCP/UDP/ICMP statistics for all network interfaces */
-
-#ifdef CONFIG_NET_STATISTICS
-struct uip_stats uip_stat;
-#endif
-
-/* Increasing number used for the IP ID field. */
-
-uint16_t g_ipid;
-
-const uip_ipaddr_t g_alloneaddr =
-#ifdef CONFIG_NET_IPv6
- {0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff, 0xffff};
-#else
- 0xffffffff;
-#endif
-
-const uip_ipaddr_t g_allzeroaddr =
-#ifdef CONFIG_NET_IPv6
- {0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000, 0x0000};
-#else
- 0x00000000;
-#endif
-
-/* Reassembly timer (units: deci-seconds) */
-
-#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
-uint8_t uip_reasstmr;
-#endif
-
-/****************************************************************************
- * 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 locking facility */
-
- uip_lockinit();
-
- /* Initialize callback support */
-
- uip_callbackinit();
-
- /* Initialize the listening port structures */
-
-#ifdef CONFIG_NET_TCP
- uip_listeninit();
-
- /* Initialize the TCP/IP connection structures */
-
- uip_tcpinit();
-
- /* Initialize the TCP/IP read-ahead buffering */
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- uip_tcpreadaheadinit();
-#endif
-#endif /* CONFIG_NET_TCP */
-
- /* Initialize the UDP connection structures */
-
-#ifdef CONFIG_NET_UDP
- uip_udpinit();
-#endif
-
- /* Initialize IGMP support */
-
-#ifdef CONFIG_NET_IGMP
- uip_igmpinit();
-#endif
-}
-#endif /* CONFIG_NET */
-
diff --git a/nuttx/net/uip/uip_input.c b/nuttx/net/uip/uip_input.c
deleted file mode 100644
index 878b351a7..000000000
--- a/nuttx/net/uip/uip_input.c
+++ /dev/null
@@ -1,545 +0,0 @@
-/****************************************************************************
- * netuip/uip_input.c
- * The uIP TCP/IP stack code.
- *
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * uIP is an implementation of the TCP/IP protocol stack intended for
- * small 8-bit and 16-bit microcontrollers.
- *
- * uIP provides the necessary protocols for Internet communication,
- * with a very small code footprint and RAM requirements - the uIP
- * code size is on the order of a few kilobytes and RAM usage is on
- * the order of a few hundred bytes.
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * uIP is a small implementation of the IP, UDP and TCP protocols (as
- * well as some basic ICMP stuff). The implementation couples the IP,
- * UDP, TCP and the application layers very tightly. To keep the size
- * of the compiled code down, this code frequently uses the goto
- * statement. While it would be possible to break the uip_input()
- * function into many smaller functions, this would increase the code
- * size because of the overhead of parameter passing and the fact that
- * the optimier would not be as efficient.
- *
- * The principle is that we have a small buffer, called the d_buf,
- * in which the device driver puts an incoming packet. The TCP/IP
- * stack parses the headers in the packet, and calls the
- * application. If the remote host has sent data to the application,
- * this data is present in the d_buf and the application read the
- * data from there. It is up to the application to put this data into
- * a byte stream if needed. The application will not be fed with data
- * that is out of sequence.
- *
- * If the application whishes to send data to the peer, it should put
- * its data into the d_buf. The d_appdata pointer points to the
- * first available byte. The TCP/IP stack will calculate the
- * checksums, and fill in the necessary header fields and finally send
- * the packet back to the peer.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <sys/ioctl.h>
-#include <stdint.h>
-#include <debug.h>
-#include <string.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#ifdef CONFIG_NET_IPv6
-# include "uip_neighbor.h"
-#endif /* CONFIG_NET_IPv6 */
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/* Macros. */
-
-#define BUF ((struct uip_ip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-#define FBUF ((struct uip_ip_hdr *)&uip_reassbuf[0])
-
-/* IP fragment re-assembly */
-
-#define IP_MF 0x20
-#define UIP_REASS_BUFSIZE (CONFIG_NET_BUFSIZE - UIP_LLH_LEN)
-#define UIP_REASS_FLAG_LASTFRAG 0x01
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
-static uint8_t uip_reassbuf[UIP_REASS_BUFSIZE];
-static uint8_t uip_reassbitmap[UIP_REASS_BUFSIZE / (8 * 8)];
-static const uint8_t bitmap_bits[8] = {0xff, 0x7f, 0x3f, 0x1f, 0x0f, 0x07, 0x03, 0x01};
-static uint16_t uip_reasslen;
-static uint8_t uip_reassflags;
-#endif /* UIP_REASSEMBLY */
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_reass
- *
- * Description:
- * IP fragment reassembly: not well-tested.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
-static uint8_t uip_reass(void)
-{
- struct uip_ip_hdr *pbuf = BUF;
- struct uip_ip_hdr *pfbuf = FBUF;
- uint16_t offset;
- uint16_t len;
- uint16_t i;
-
- /* If uip_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)
- {
- memcpy(uip_reassbuf, &pbuf->vhl, UIP_IPH_LEN);
- uip_reasstmr = UIP_REASS_MAXAGE;
- uip_reassflags = 0;
-
- /* Clear the bitmap. */
-
- memset(uip_reassbitmap, 0, sizeof(uip_reassbitmap));
- }
-
- /* 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 (uiphdr_addr_cmp(pbuf->srcipaddr, pfbuf->srcipaddr) &&
- uiphdr_addr_cmp(pbuf->destipaddr == pfbuf->destipaddr) &&
- pbuf->g_ipid[0] == pfbuf->g_ipid[0] && pbuf->g_ipid[1] == pfbuf->g_ipid[1])
- {
- len = (pbuf->len[0] << 8) + pbuf->len[1] - (pbuf->vhl & 0x0f) * 4;
- offset = (((pbuf->ipoffset[0] & 0x3f) << 8) + pbuf->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 *)pbuf + (int)((pbuf->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 ((pbuf->ipoffset[0] & IP_MF) == 0)
- {
- uip_reassflags |= UIP_REASS_FLAG_LASTFRAG;
- uip_reasslen = offset + len;
- }
-
- /* 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_t)~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(pbuf, pfbuf, uip_reasslen);
-
- /* Pretend to be a "normal" (i.e., not fragmented) IP packet from
- * now on.
- */
-
- pbuf->ipoffset[0] = pbuf->ipoffset[1] = 0;
- pbuf->len[0] = uip_reasslen >> 8;
- pbuf->len[1] = uip_reasslen & 0xff;
- pbuf->ipchksum = 0;
- pbuf->ipchksum = ~(uip_ipchksum(dev));
-
- return uip_reasslen;
- }
- }
-
-nullreturn:
- return 0;
-}
-#endif /* UIP_REASSEMBLY */
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_input
- *
- * Description:
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-void uip_input(struct uip_driver_s *dev)
-{
- struct uip_ip_hdr *pbuf = BUF;
- uint16_t iplen;
-
- /* This is where the input processing starts. */
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.recv++;
-#endif
-
- /* Start of IP input header processing code. */
-
-#ifdef CONFIG_NET_IPv6
- /* Check validity of the IP header. */
-
- if ((pbuf->vtc & 0xf0) != 0x60)
- {
- /* IP version and header length. */
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.drop++;
- uip_stat.ip.vhlerr++;
-#endif
- nlldbg("Invalid IPv6 version: %d\n", pbuf->vtc >> 4);
- goto drop;
- }
-#else /* CONFIG_NET_IPv6 */
- /* Check validity of the IP header. */
-
- if (pbuf->vhl != 0x45)
- {
- /* IP version and header length. */
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.drop++;
- uip_stat.ip.vhlerr++;
-#endif
- nlldbg("Invalid IP version or header length: %02x\n", pbuf->vhl);
- goto drop;
- }
-#endif /* CONFIG_NET_IPv6 */
-
- /* Check the size of the packet. If the size reported to us in d_len is
- * smaller the size reported in the IP header, we assume that the packet
- * has been corrupted in transit. If the size of d_len is larger than the
- * size reported in the IP packet header, the packet has been padded and
- * we set d_len to the correct value.
- */
-
-#ifdef CONFIG_NET_IPv6
- /* The length reported in the IPv6 header is the length of the payload
- * that follows the header. However, uIP uses the d_len variable for
- * holding the size of the entire packet, including the IP header. For
- * IPv4 this is not a problem as the length field in the IPv4 header
- * contains the length of the entire packet. But for IPv6 we need to add
- * the size of the IPv6 header (40 bytes).
- */
-
- iplen = (pbuf->len[0] << 8) + pbuf->len[1] + UIP_IPH_LEN;
-#else
- iplen = (pbuf->len[0] << 8) + pbuf->len[1];
-#endif /* CONFIG_NET_IPv6 */
-
- if (iplen <= dev->d_len)
- {
- dev->d_len = iplen;
- }
- else
- {
- nlldbg("IP packet shorter than length in IP header\n");
- goto drop;
- }
-
-#ifndef CONFIG_NET_IPv6
- /* Check the fragment flag. */
-
- if ((pbuf->ipoffset[0] & 0x3f) != 0 || pbuf->ipoffset[1] != 0)
- {
-#if UIP_REASSEMBLY
- dev->d_len = uip_reass();
- if (dev->d_len == 0)
- {
- goto drop;
- }
-#else /* UIP_REASSEMBLY */
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.drop++;
- uip_stat.ip.fragerr++;
-#endif
- nlldbg("IP fragment dropped\n");
- goto drop;
-#endif /* UIP_REASSEMBLY */
- }
-#endif /* CONFIG_NET_IPv6 */
-
- /* If IP broadcast support is configured, we check for a broadcast
- * UDP packet, which may be destined to us (even if there is no IP
- * address yet assigned to the device as is the case when we are
- * negotiating over DHCP for an address).
- */
-
-#if defined(CONFIG_NET_BROADCAST) && defined(CONFIG_NET_UDP)
- if (pbuf->proto == UIP_PROTO_UDP &&
-#ifndef CONFIG_NET_IPv6
- uip_ipaddr_cmp(uip_ip4addr_conv(pbuf->destipaddr), g_alloneaddr))
-#else
- uip_ipaddr_cmp(pbuf->destipaddr, g_alloneaddr))
-#endif
- {
- uip_udpinput(dev);
- return;
- }
-
- /* In most other cases, the device must be assigned a non-zero IP
- * address. Another exception is when CONFIG_NET_PINGADDRCONF is
- * enabled...
- */
-
- else
-#endif
-#ifdef CONFIG_NET_ICMP
- if (uip_ipaddr_cmp(dev->d_ipaddr, g_allzeroaddr))
- {
- /* If we are configured to use ping IP address configuration and
- * hasn't been assigned an IP address yet, we accept all ICMP
- * packets.
- */
-
-#if defined(CONFIG_NET_PINGADDRCONF) && !defined(CONFIG_NET_IPv6)
- if (pbuf->proto == UIP_PROTO_ICMP)
- {
- nlldbg("Possible ping config packet received\n");
- uip_icmpinput(dev);
- goto done;
- }
- else
-#endif
- {
- nlldbg("No IP address assigned\n");
- goto drop;
- }
- }
-
- /* Check if the packet is destined for out IP address */
- else
-#endif
- {
- /* Check if the packet is destined for our IP address. */
-#ifndef CONFIG_NET_IPv6
- if (!uip_ipaddr_cmp(uip_ip4addr_conv(pbuf->destipaddr), dev->d_ipaddr))
- {
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.drop++;
-#endif
- goto drop;
- }
-#else /* CONFIG_NET_IPv6 */
- /* For IPv6, packet reception is a little trickier as we need to
- * make sure that we listen to certain multicast addresses (all
- * hosts multicast address, and the solicited-node multicast
- * address) as well. However, we will cheat here and accept all
- * multicast packets that are sent to the ff02::/16 addresses.
- */
-
- if (!uip_ipaddr_cmp(pbuf->destipaddr, dev->d_ipaddr) &&
- pbuf->destipaddr[0] != 0xff02)
- {
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.drop++;
-#endif
- goto drop;
- }
-#endif /* CONFIG_NET_IPv6 */
- }
-
-#ifndef CONFIG_NET_IPv6
- if (uip_ipchksum(dev) != 0xffff)
- {
- /* Compute and check the IP header checksum. */
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.drop++;
- uip_stat.ip.chkerr++;
-#endif
- nlldbg("Bad IP checksum\n");
- goto drop;
- }
-#endif /* CONFIG_NET_IPv6 */
-
- /* Everything looks good so far. Now process the incoming packet
- * according to the protocol.
- */
-
- switch (pbuf->proto)
- {
-#ifdef CONFIG_NET_TCP
- case UIP_PROTO_TCP: /* TCP input */
- uip_tcpinput(dev);
- break;
-#endif
-
-#ifdef CONFIG_NET_UDP
- case UIP_PROTO_UDP: /* UDP input */
- uip_udpinput(dev);
- break;
-#endif
-
- /* Check for ICMP input */
-
-#ifdef CONFIG_NET_ICMP
-#ifndef CONFIG_NET_IPv6
- case UIP_PROTO_ICMP: /* ICMP input */
-#else
- case UIP_PROTO_ICMP6: /* ICMP6 input */
-#endif
- uip_icmpinput(dev);
- break;
-#endif
-
- /* Check for ICMP input */
-
-#ifdef CONFIG_NET_IGMP
-#ifndef CONFIG_NET_IPv6
- case UIP_PROTO_IGMP: /* IGMP input */
- uip_igmpinput(dev);
- break;
-#endif
-#endif
-
- default: /* Unrecognized/unsupported protocol */
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.ip.drop++;
- uip_stat.ip.protoerr++;
-#endif
-
- nlldbg("Unrecognized IP protocol\n");
- goto drop;
- }
-
- /* Return and let the caller do any actual transmission. */
-
- return;
-
-drop:
- dev->d_len = 0;
-}
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_internal.h b/nuttx/net/uip/uip_internal.h
deleted file mode 100644
index eee99a222..000000000
--- a/nuttx/net/uip/uip_internal.h
+++ /dev/null
@@ -1,272 +0,0 @@
-/****************************************************************************
- * net/uip/uip_internal.h
- *
- * Copyright (C) 2007-2009, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <errno.h>
-#include <arch/irq.h>
-#include <nuttx/net/uip/uip.h>
-
-/****************************************************************************
- * Public Macro Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-extern const uip_ipaddr_t g_alloneaddr;
-extern const uip_ipaddr_t g_allzeroaddr;
-
-/* Increasing number used for the IP ID field. */
-
-extern uint16_t g_ipid;
-
-/* Reassembly timer (units: deci-seconds) */
-
-#if UIP_REASSEMBLY && !defined(CONFIG_NET_IPv6)
-extern uint8_t uip_reasstmr;
-#endif
-
-/* List of applications waiting for ICMP ECHO REPLY */
-
-#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
-extern struct uip_callback_s *g_echocallback;
-#endif
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#ifdef __cplusplus
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/* Defined in uip_callback.c ************************************************/
-
-EXTERN void uip_callbackinit(void);
-EXTERN FAR struct uip_callback_s *uip_callbackalloc(struct uip_callback_s **list);
-EXTERN void uip_callbackfree(FAR struct uip_callback_s *cb, struct uip_callback_s **list);
-EXTERN uint16_t uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn,
- uint16_t flags, FAR struct uip_callback_s *list);
-
-#ifdef CONFIG_NET_TCP
-/* Defined in uip_tcpconn.c *************************************************/
-
-EXTERN void uip_tcpinit(void);
-EXTERN struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf);
-EXTERN struct uip_conn *uip_nexttcpconn(struct uip_conn *conn);
-EXTERN struct uip_conn *uip_tcplistener(uint16_t portno);
-EXTERN struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf);
-
-/* Defined in uip_tcpseqno.c ************************************************/
-
-EXTERN void uip_tcpsetsequence(FAR uint8_t *seqno, uint32_t value);
-EXTERN uint32_t uip_tcpgetsequence(FAR uint8_t *seqno);
-EXTERN uint32_t uip_tcpaddsequence(FAR uint8_t *seqno, uint16_t len);
-EXTERN void uip_tcpinitsequence(FAR uint8_t *seqno);
-EXTERN void uip_tcpnextsequence(void);
-
-/* Defined in uip_tcppoll.c *************************************************/
-
-EXTERN void uip_tcppoll(struct uip_driver_s *dev, struct uip_conn *conn);
-
-/* Defined in uip_udptimer.c ************************************************/
-
-EXTERN void uip_tcptimer(struct uip_driver_s *dev, struct uip_conn *conn, int hsec);
-
-/* Defined in uip_listen.c **************************************************/
-
-EXTERN void uip_listeninit(void);
-EXTERN bool uip_islistener(uint16_t port);
-EXTERN int uip_accept(struct uip_driver_s *dev, struct uip_conn *conn, uint16_t portno);
-
-/* Defined in uip_tcpsend.c *************************************************/
-
-EXTERN void uip_tcpsend(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t flags, uint16_t len);
-EXTERN void uip_tcpreset(struct uip_driver_s *dev);
-EXTERN void uip_tcpack(struct uip_driver_s *dev, struct uip_conn *conn,
- uint8_t ack);
-
-/* Defined in uip_tcpappsend.c **********************************************/
-
-EXTERN void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t result);
-EXTERN void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t result);
-
-/* Defined in uip_tcpinput.c ************************************************/
-
-EXTERN void uip_tcpinput(struct uip_driver_s *dev);
-
-/* Defined in uip_tcpcallback.c *********************************************/
-
-EXTERN uint16_t uip_tcpcallback(FAR struct uip_driver_s *dev,
- FAR struct uip_conn *conn, uint16_t flags);
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
-EXTERN uint16_t uip_datahandler(FAR struct uip_conn *conn,
- FAR uint8_t *buffer, uint16_t nbytes);
-#endif
-
-/* Defined in uip_tcpreadahead.c ********************************************/
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
-EXTERN void uip_tcpreadaheadinit(void);
-EXTERN struct uip_readahead_s *uip_tcpreadaheadalloc(void);
-EXTERN void uip_tcpreadaheadrelease(struct uip_readahead_s *buf);
-#endif /* CONFIG_NET_NTCP_READAHEAD_BUFFERS */
-
-#endif /* CONFIG_NET_TCP */
-
-#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_udppoll.c *************************************************/
-
-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_udpcallback.c *********************************************/
-
-EXTERN void uip_udpcallback(struct uip_driver_s *dev,
- struct uip_udp_conn *conn, uint16_t flags);
-#endif /* CONFIG_NET_UDP */
-
-#ifdef CONFIG_NET_ICMP
-/* Defined in uip_icmpinput.c ***********************************************/
-
-EXTERN void uip_icmpinput(struct uip_driver_s *dev);
-
-#ifdef CONFIG_NET_ICMP_PING
-/* Defined in uip_icmpoll.c *************************************************/
-
-EXTERN void uip_icmppoll(struct uip_driver_s *dev);
-
-/* Defined in uip_icmsend.c *************************************************/
-
-EXTERN void uip_icmpsend(struct uip_driver_s *dev, uip_ipaddr_t *destaddr);
-
-#endif /* CONFIG_NET_ICMP_PING */
-#endif /* CONFIG_NET_ICMP */
-
-#ifdef CONFIG_NET_IGMP
-/* Defined in uip_igmpinit.c ************************************************/
-
-EXTERN void uip_igmpinit(void);
-
-/* Defined in uip_igmpinput.c ***********************************************/
-
-EXTERN void uip_igmpinput(struct uip_driver_s *dev);
-
-/* Defined in uip_igmpgroup.c ***********************************************/
-
-EXTERN void uip_grpinit(void);
-EXTERN FAR struct igmp_group_s *uip_grpalloc(FAR struct uip_driver_s *dev,
- FAR const uip_ipaddr_t *addr);
-EXTERN FAR struct igmp_group_s *uip_grpfind(FAR struct uip_driver_s *dev,
- FAR const uip_ipaddr_t *addr);
-EXTERN FAR struct igmp_group_s *uip_grpallocfind(FAR struct uip_driver_s *dev,
- FAR const uip_ipaddr_t *addr);
-EXTERN void uip_grpfree(FAR struct uip_driver_s *dev,
- FAR struct igmp_group_s *group);
-
-/* Defined in uip_igmpmsg.c **************************************************/
-
-EXTERN void uip_igmpschedmsg(FAR struct igmp_group_s *group, uint8_t msgid);
-EXTERN void uip_igmpwaitmsg(FAR struct igmp_group_s *group, uint8_t msgid);
-
-/* Defined in uip_igmppoll.c *************************************************/
-
-EXTERN void uip_igmppoll(FAR struct uip_driver_s *dev);
-
-/* Defined in up_igmpsend.c **************************************************/
-
-EXTERN void uip_igmpsend(FAR struct uip_driver_s *dev,
- FAR struct igmp_group_s *group,
- FAR uip_ipaddr_t *dest);
-
-/* Defined in uip_igmptimer.c ************************************************/
-
-EXTERN int uip_decisec2tick(int decisecs);
-EXTERN void uip_igmpstartticks(FAR struct igmp_group_s *group, int ticks);
-EXTERN void uip_igmpstarttimer(FAR struct igmp_group_s *group, uint8_t decisecs);
-EXTERN bool uip_igmpcmptimer(FAR struct igmp_group_s *group, int maxticks);
-
-/* Defined in uip_mcastmac ***************************************************/
-
-EXTERN void uip_addmcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip);
-EXTERN void uip_removemcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip);
-
-#endif /* CONFIG_NET_IGMP */
-
-#undef EXTERN
-#ifdef __cplusplus
-}
-#endif
-
-#endif /* CONFIG_NET */
-#endif /* __UIP_INTERNAL_H */
diff --git a/nuttx/net/uip/uip_listen.c b/nuttx/net/uip/uip_listen.c
deleted file mode 100644
index 420fbb070..000000000
--- a/nuttx/net/uip/uip_listen.c
+++ /dev/null
@@ -1,288 +0,0 @@
-/****************************************************************************
- * net/uip/uip_listen.c
- *
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * A direct leverage of logic from uIP which also has b 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* The uip_listenports list all currently listening ports. */
-
-static struct uip_conn *uip_listenports[CONFIG_NET_MAX_LISTENPORTS];
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_findlistener
- *
- * Description:
- * Return the connection listener for connections on this port (if any)
- *
- * Assumptions:
- * Called at interrupt level
- *
- ****************************************************************************/
-
-struct uip_conn *uip_findlistener(uint16_t portno)
-{
- int ndx;
-
- /* Examine each connection structure in each slot of the listener list */
-
- for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
- {
- /* Is this slot assigned? If so, does the connection have the same
- * local port number?
- */
-
- struct uip_conn *conn = uip_listenports[ndx];
- if (conn && conn->lport == portno)
- {
- /* Yes.. we found a listener on this port */
-
- return conn;
- }
- }
-
- /* No listener for this port */
-
- return NULL;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_listeninit
- *
- * Description:
- * Setup the listening data structures
- *
- * Assumptions:
- * Called early in the inialization phase while the system is still
- * single-threaded.
- *
- ****************************************************************************/
-
-void uip_listeninit(void)
-{
- int ndx;
- for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
- {
- uip_listenports[ndx] = NULL;
- }
-}
-
-/****************************************************************************
- * Function: uip_unlisten
- *
- * Description:
- * Stop listening to the port bound to the specified TCP connection
- *
- * Assumptions:
- * Called from normal user code.
- *
- ****************************************************************************/
-
-int uip_unlisten(struct uip_conn *conn)
-{
- uip_lock_t flags;
- int ndx;
- int ret = -EINVAL;
-
- flags = uip_lock();
- for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
- {
- if (uip_listenports[ndx] == conn)
- {
- uip_listenports[ndx] = NULL;
- ret = OK;
- break;
- }
- }
-
- uip_unlock(flags);
- return ret;
-}
-
-/****************************************************************************
- * Function: uip_listen
- *
- * Description:
- * Start listening to the port bound to the specified TCP connection
- *
- * Assumptions:
- * Called from normal user code.
- *
- ****************************************************************************/
-
-int uip_listen(struct uip_conn *conn)
-{
- uip_lock_t flags;
- int ndx;
- int ret;
-
- /* This must be done with interrupts disabled because the listener table
- * is accessed from interrupt level as well.
- */
-
- flags = uip_lock();
-
- /* First, check if there is already a socket listening on this port */
-
- if (uip_islistener(conn->lport))
- {
- /* Yes, then we must refuse this request */
-
- ret = -EADDRINUSE;
- }
- else
- {
- /* Otherwise, save a reference to the connection structure in the
- * "listener" list.
- */
-
- ret = -ENOBUFS; /* Assume failure */
-
- /* Search all slots until an available slot is found */
-
- for (ndx = 0; ndx < CONFIG_NET_MAX_LISTENPORTS; ndx++)
- {
- /* Is the next slot available? */
-
- if (!uip_listenports[ndx])
- {
- /* Yes.. we found it */
-
- uip_listenports[ndx] = conn;
- ret = OK;
- break;
- }
- }
- }
-
- uip_unlock(flags);
- return ret;
-}
-
-/****************************************************************************
- * Function: uip_islistener
- *
- * Description:
- * Return true is there is a listener for the specified port
- *
- * Assumptions:
- * Called at interrupt level
- *
- ****************************************************************************/
-
-bool uip_islistener(uint16_t portno)
-{
- return uip_findlistener(portno) != NULL;
-}
-
-/****************************************************************************
- * Function: uip_accept
- *
- * Description:
- * Accept the new connection for the specified listening port.
- *
- * Assumptions:
- * Called at interrupt level
- *
- ****************************************************************************/
-
-int uip_accept(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t portno)
-{
- struct uip_conn *listener;
- int ret = ERROR;
-
- /* The interrupt logic has already allocated and initialized a TCP
- * connection -- now check there if is an application in place to accept the
- * connection.
- */
-
- listener = uip_findlistener(portno);
- if (listener)
- {
- /* Yes, there is a listener. Is it accepting connections now? */
-
- if (listener->accept)
- {
- /* Yes.. accept the connection */
-
- ret = listener->accept(listener, conn);
- }
-#ifdef CONFIG_NET_TCPBACKLOG
- else
- {
- /* Add the connection to the backlog and notify any threads that
- * may be waiting on poll()/select() that the connection is available.
- */
-
- ret = uip_backlogadd(listener, conn);
- if (ret == OK)
- {
- (void)uip_tcpcallback(dev, listener, UIP_BACKLOG);
- }
- }
-#endif
- }
- return ret;
-}
-
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_lock.c b/nuttx/net/uip/uip_lock.c
deleted file mode 100644
index 5abcda269..000000000
--- a/nuttx/net/uip/uip_lock.c
+++ /dev/null
@@ -1,219 +0,0 @@
-/****************************************************************************
- * net/uip/uip_lock.c
- *
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-
-#include <unistd.h>
-#include <semaphore.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <nuttx/arch.h>
-#include <nuttx/net/uip/uip.h>
-
-#if defined(CONFIG_NET) && defined(CONFIG_NET_NOINTS)
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define NO_HOLDER (pid_t)-1
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-static sem_t g_uipsem;
-static pid_t g_holder = NO_HOLDER;
-static unsigned int g_count = 0;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_takesem
- *
- * Description:
- * Take the semaphore
- *
- ****************************************************************************/
-
-static void uip_takesem(void)
-{
- while (sem_wait(&g_uipsem) != 0)
- {
- /* The only case that an error should occur here is if the wait was
- * awakened by a signal.
- */
-
- ASSERT(errno == EINTR);
- }
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_lockinit
- *
- * Description:
- * Initialize the locking facility
- *
- ****************************************************************************/
-
-void uip_lockinit(void)
-{
- sem_init(&g_uipsem, 0, 1);
-}
-
-/****************************************************************************
- * Function: uip_lock
- *
- * Description:
- * Take the lock
- *
- ****************************************************************************/
-
-uip_lock_t uip_lock(void)
-{
- pid_t me = getpid();
-
- /* Does this thread already hold the semaphore? */
-
- if (g_holder == me)
- {
- /* Yes.. just increment the reference count */
-
- g_count++;
- }
- else
- {
- /* No.. take the semaphore (perhaps waiting) */
-
- uip_takesem();
-
- /* Now this thread holds the semaphore */
-
- g_holder = me;
- g_count = 1;
- }
-
- return 0;
-}
-
-/****************************************************************************
- * Function: uip_unlock
- *
- * Description:
- * Release the lock.
- *
- ****************************************************************************/
-
-void uip_unlock(uip_lock_t flags)
-{
- DEBUGASSERT(g_holder == getpid() && g_count > 0);
-
- /* If the count would go to zero, then release the semaphore */
-
- if (g_count == 1)
- {
- /* We no longer hold the semaphore */
-
- g_holder = NO_HOLDER;
- g_count = 0;
- sem_post(&g_uipsem);
- }
- else
- {
- /* We still hold the semaphore. Just decrement the count */
-
- g_count--;
- }
-}
-
-/****************************************************************************
- * Function: uip_lockedwait
- *
- * Description:
- * Atomically wait for sem while temporarily releasing g_uipsem.
- *
- ****************************************************************************/
-
-int uip_lockedwait(sem_t *sem)
-{
- pid_t me = getpid();
- unsigned int count;
- irqstate_t flags;
- int ret;
-
- flags = irqsave(); /* No interrupts */
- sched_lock(); /* No context switches */
- if (g_holder == me)
- {
- /* Release the uIP semaphore, remembering the count */
-
- count = g_count;
- g_holder = NO_HOLDER;
- g_count = 0;
- sem_post(&g_uipsem);
-
- /* Now take the semaphore */
-
- ret = sem_wait(sem);
-
- /* Recover the uIP semaphore at the proper count */
-
- uip_takesem();
- g_holder = me;
- g_count = count;
- }
- else
- {
- ret = sem_wait(sem);
- }
-
- sched_unlock();
- irqrestore(flags);
- return ret;
- }
-
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_mcastmac.c b/nuttx/net/uip/uip_mcastmac.c
deleted file mode 100644
index 9bd146198..000000000
--- a/nuttx/net/uip/uip_mcastmac.c
+++ /dev/null
@@ -1,132 +0,0 @@
-/****************************************************************************
- * net/uip/uip_mcastmac.c
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * The NuttX implementation of IGMP was inspired by the IGMP add-on for the
- * lwIP TCP/IP stack by Steve Reynolds:
- *
- * Copyright (c) 2002 CITEL Technologies Ltd.
- * 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. Neither the name of CITEL Technologies Ltd 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 CITEL TECHNOLOGIES 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 CITEL TECHNOLOGIES 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 <nuttx/config.h>
-
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-
-#include "uip_internal.h"
-
-#ifdef CONFIG_NET_IGMP
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_mcastmac
- *
- * Description:
- * Given an IP address (in network order), create a IGMP multicast MAC
- * address.
- *
- ****************************************************************************/
-
-static void uip_mcastmac(uip_ipaddr_t *ip, FAR uint8_t *mac)
-{
- /* This mapping is from the IETF IN RFC 1700 */
-
- mac[0] = 0x01;
- mac[1] = 0x00;
- mac[2] = 0x5e;
- mac[3] = ip4_addr2(*ip) & 0x7f;
- mac[4] = ip4_addr3(*ip);
- mac[5] = ip4_addr4(*ip);
-
- nvdbg("IP: %08x -> MAC: %02x%02x%02x%02x%02x%02x\n",
- *ip, mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]);
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_addmcastmac
- *
- * Description:
- * Add an IGMP MAC address to the device's MAC filter table.
- *
- ****************************************************************************/
-
-void uip_addmcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip)
-{
- uint8_t mcastmac[6];
-
- nvdbg("Adding: IP %08x\n", *ip);
- if (dev->d_addmac)
- {
- uip_mcastmac(ip, mcastmac);
- dev->d_addmac(dev, mcastmac);
- }
-}
-
-/****************************************************************************
- * Name: uip_removemcastmac
- *
- * Description:
- * Remove an IGMP MAC address from the device's MAC filter table.
- *
- ****************************************************************************/
-
-void uip_removemcastmac(FAR struct uip_driver_s *dev, FAR uip_ipaddr_t *ip)
-{
- uint8_t mcastmac[6];
-
- nvdbg("Removing: IP %08x\n", *ip);
- if (dev->d_rmmac)
- {
- uip_mcastmac(ip, mcastmac);
- dev->d_rmmac(dev, mcastmac);
- }
-}
-
-#endif /* CONFIG_NET_IGMP */
diff --git a/nuttx/net/uip/uip_neighbor.c b/nuttx/net/uip/uip_neighbor.c
deleted file mode 100644
index 82fb9a845..000000000
--- a/nuttx/net/uip/uip_neighbor.c
+++ /dev/null
@@ -1,162 +0,0 @@
-/*
- * uip_neighbor.c
- * Database of link-local neighbors, used by IPv6 code and to be used by
- * a future ARP code rewrite.
- *
- * Author: Adam Dunkels <adam@sics.se>
- * Copyright (c) 2006, Swedish Institute of Computer Science.
- * 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. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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.
- */
-
-#include <string.h>
-#include <debug.h>
-
-#include "uip_neighbor.h"
-
-#define MAX_TIME 128
-
-#ifdef UIP_NEIGHBOR_CONF_ENTRIES
-#define ENTRIES UIP_NEIGHBOR_CONF_ENTRIES
-#else /* UIP_NEIGHBOR_CONF_ENTRIES */
-#define ENTRIES 8
-#endif /* UIP_NEIGHBOR_CONF_ENTRIES */
-
-struct neighbor_entry
-{
- uip_ipaddr_t ipaddr;
- struct uip_neighbor_addr addr;
- uint8_t time;
-};
-static struct neighbor_entry entries[ENTRIES];
-
-void uip_neighbor_init(void)
-{
- int i;
-
- for(i = 0; i < ENTRIES; ++i)
- {
- entries[i].time = MAX_TIME;
- }
-}
-
-void uip_neighbor_periodic(void)
-{
- int i;
-
- for(i = 0; i < ENTRIES; ++i)
- {
- if (entries[i].time < MAX_TIME)
- {
- entries[i].time++;
- }
- }
-}
-
-void uip_neighbor_add(uip_ipaddr_t ipaddr, struct uip_neighbor_addr *addr)
-{
- uint8_t oldest_time;
- int oldest;
- int i;
-
- nlldbg("Add neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
- addr->addr.ether_addr_octet[0], addr->addr.ether_addr_octet[1],
- addr->addr.ether_addr_octet[2], addr->addr.ether_addr_octet[3],
- addr->addr.ether_addr_octet[4], addr->addr.ether_addr_octet[5]);
-
- /* Find the first unused entry or the oldest used entry. */
-
- oldest_time = 0;
- oldest = 0;
- for (i = 0; i < ENTRIES; ++i)
- {
- if (entries[i].time == MAX_TIME)
- {
- oldest = i;
- break;
- }
- if (uip_ipaddr_cmp(entries[i].ipaddr, addr))
- {
- oldest = i;
- break;
- }
- if (entries[i].time > oldest_time)
- {
- oldest = i;
- oldest_time = entries[i].time;
- }
- }
-
- /* Use the oldest or first free entry (either pointed to by the
- * "oldest" variable).
- */
-
- entries[oldest].time = 0;
- uip_ipaddr_copy(entries[oldest].ipaddr, ipaddr);
- memcpy(&entries[oldest].addr, addr, sizeof(struct uip_neighbor_addr));
-}
-
-static struct neighbor_entry *find_entry(uip_ipaddr_t ipaddr)
-{
- int i;
-
- for(i = 0; i < ENTRIES; ++i)
- {
- if (uip_ipaddr_cmp(entries[i].ipaddr, ipaddr))
- {
- return &entries[i];
- }
- }
- return NULL;
-}
-
-void uip_neighbor_update(uip_ipaddr_t ipaddr)
-{
- struct neighbor_entry *e;
-
- e = find_entry(ipaddr);
- if (e != NULL)
- {
- e->time = 0;
- }
-}
-
-struct uip_neighbor_addr *uip_neighbor_lookup(uip_ipaddr_t ipaddr)
-{
- struct neighbor_entry *e;
-
- e = find_entry(ipaddr);
- if (e != NULL)
- {
- nlldbg("Lookup neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
- e->addr.addr.ether_addr_octet[0], e->addr.addr.ether_addr_octet[1],
- e->addr.addr.ether_addr_octet[2], e->addr.addr.ether_addr_octet[3],
- e->addr.addr.ether_addr_octet[4], e->addr.addr.ether_addr_octet[5]);
-
- return &e->addr;
- }
- return NULL;
-}
diff --git a/nuttx/net/uip/uip_neighbor.h b/nuttx/net/uip/uip_neighbor.h
deleted file mode 100644
index b55835b74..000000000
--- a/nuttx/net/uip/uip_neighbor.h
+++ /dev/null
@@ -1,61 +0,0 @@
-/* net/uip/uip_neighbor.h
- * Header file for database of link-local neighbors, used by IPv6 code and
- * to be used by future ARP code.
- *
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * A direct leverage of logic from uIP which also has b BSD style license
- *
- * Author: Adam Dunkels <adam@sics.se>
- * Copyright (c) 2006, Swedish Institute of Computer Science.
- * 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. Neither the name of the Institute 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 INSTITUTE 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 INSTITUTE 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 __UIP_NEIGHBOR_H__
-#define __UIP_NEIGHBOR_H__
-
-#include <stdint.h>
-#include <nuttx/net/uip/uip.h>
-#include <net/ethernet.h>
-
-struct uip_neighbor_addr
-{
-#if UIP_NEIGHBOR_CONF_ADDRTYPE
- UIP_NEIGHBOR_CONF_ADDRTYPE addr;
-#else
- struct ether_addr addr;
-#endif
-};
-
-void uip_neighbor_init(void);
-void uip_neighbor_add(uip_ipaddr_t ipaddr, struct uip_neighbor_addr *addr);
-void uip_neighbor_update(uip_ipaddr_t ipaddr);
-struct uip_neighbor_addr *uip_neighbor_lookup(uip_ipaddr_t ipaddr);
-void uip_neighbor_periodic(void);
-
-#endif /* __UIP-NEIGHBOR_H__ */
diff --git a/nuttx/net/uip/uip_poll.c b/nuttx/net/uip/uip_poll.c
deleted file mode 100644
index 8c56e7bf6..000000000
--- a/nuttx/net/uip/uip_poll.c
+++ /dev/null
@@ -1,353 +0,0 @@
-/****************************************************************************
- * net/uip/uip_poll.c
- *
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_pollicmp
- *
- * Description:
- * Poll all UDP connections for available packets to send.
- *
- * Assumptions:
- * This function is called from the CAN device driver and may be called from
- * the timer interrupt/watchdog handle level.
- *
- ****************************************************************************/
-
-#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
-static inline int uip_pollicmp(struct uip_driver_s *dev, uip_poll_callback_t callback)
-{
- /* Perform the UDP TX poll */
-
- uip_icmppoll(dev);
-
- /* Call back into the driver */
-
- return callback(dev);
-}
-#endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
-
-/****************************************************************************
- * Function: uip_polligmp
- *
- * Description:
- * Poll all UDP connections for available packets to send.
- *
- * Assumptions:
- * This function is called from the CAN device driver and may be called from
- * the timer interrupt/watchdog handle level.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_NET_IGMP
-static inline int uip_polligmp(struct uip_driver_s *dev, uip_poll_callback_t callback)
-{
- /* Perform the UDP TX poll */
-
- uip_igmppoll(dev);
-
- /* Call back into the driver */
-
- return callback(dev);
-}
-#endif /* CONFIG_NET_IGMP */
-
-/****************************************************************************
- * Function: uip_polludpconnections
- *
- * Description:
- * Poll all UDP connections for available packets to send.
- *
- * Assumptions:
- * This function is called from the CAN device driver and may be called from
- * the timer interrupt/watchdog handle level.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_NET_UDP
-static int uip_polludpconnections(struct uip_driver_s *dev,
- uip_poll_callback_t callback)
-{
- struct uip_udp_conn *udp_conn = NULL;
- int bstop = 0;
-
- /* Traverse all of the allocated UDP connections and perform the poll action */
-
- while (!bstop && (udp_conn = uip_nextudpconn(udp_conn)))
- {
- /* Perform the UDP TX poll */
-
- uip_udppoll(dev, udp_conn);
-
- /* Call back into the driver */
-
- bstop = callback(dev);
- }
-
- return bstop;
-}
-#endif /* CONFIG_NET_UDP */
-
-/****************************************************************************
- * Function: uip_polltcpconnections
- *
- * Description:
- * Poll all UDP connections for available packets to send.
- *
- * Assumptions:
- * This function is called from the CAN device driver and may be called from
- * the timer interrupt/watchdog handle level.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_NET_TCP
-static inline int uip_polltcpconnections(struct uip_driver_s *dev,
- uip_poll_callback_t callback)
-{
- struct uip_conn *conn = NULL;
- int bstop = 0;
-
- /* Traverse all of the active TCP connections and perform the poll action */
-
- while (!bstop && (conn = uip_nexttcpconn(conn)))
- {
- /* Perform the TCP TX poll */
-
- uip_tcppoll(dev, conn);
-
- /* Call back into the driver */
-
- bstop = callback(dev);
- }
-
- return bstop;
-}
-#else
-# define uip_polltcpconnections(dev, callback) (0)
-#endif
-
-/****************************************************************************
- * Function: uip_polltcptimer
- *
- * Description:
- * The TCP timer has expired. Update TCP timing state in each active,
- * TCP connection.
- *
- * Assumptions:
- * This function is called from the CAN device driver and may be called from
- * the timer interrupt/watchdog handle level.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_NET_TCP
-static inline int uip_polltcptimer(struct uip_driver_s *dev,
- uip_poll_callback_t callback, int hsec)
-{
- struct uip_conn *conn = NULL;
- int bstop = 0;
-
- /* Traverse all of the active TCP connections and perform the poll action */
-
- while (!bstop && (conn = uip_nexttcpconn(conn)))
- {
- /* Perform the TCP timer poll */
-
- uip_tcptimer(dev, conn, hsec);
-
- /* Call back into the driver */
-
- bstop = callback(dev);
- }
-
- return bstop;
-}
-#else
-# define uip_polltcptimer(dev, callback, hsec) (0)
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_poll
- *
- * Description:
- * This function will traverse each active uIP connection structure and
- * will perform TCP and UDP polling operations. uip_poll() may be called
- * asychronously with the network drvier can accept another outgoing packet.
- *
- * This function will call the provided callback function for every active
- * connection. Polling will continue until all connections have been polled
- * or until the user-suplied function returns a non-zero value (which it
- * should do only if it cannot accept further write data).
- *
- * When the callback function is called, there may be an outbound packet
- * waiting for service in the uIP packet buffer, and if so the d_len field
- * is set to a value larger than zero. The device driver should then send
- * out the packet.
- *
- * Assumptions:
- * This function is called from the CAN device driver and may be called from
- * the timer interrupt/watchdog handle level.
- *
- ****************************************************************************/
-
-int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback)
-{
- int bstop;
-
- /* Check for pendig IGMP messages */
-
-#ifdef CONFIG_NET_IGMP
- bstop = uip_polligmp(dev, callback);
- if (!bstop)
-#endif
- {
- /* Traverse all of the active TCP connections and perform the poll action */
-
- bstop = uip_polltcpconnections(dev, callback);
- if (!bstop)
- {
-#ifdef CONFIG_NET_UDP
- /* Traverse all of the allocated UDP connections and perform the poll action */
-
- bstop = uip_polludpconnections(dev, callback);
- if (!bstop)
-#endif
- {
-#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
- /* Traverse all of the tasks waiting to send an ICMP ECHO request */
-
- bstop = uip_pollicmp(dev, callback);
-#endif
- }
- }
- }
-
- return bstop;
-}
-
-/****************************************************************************
- * Function: uip_timer
- *
- * Description:
- * These function will traverse each active uIP connection structure and
- * perform TCP timer operations (and UDP polling operations). The Ethernet
- * driver MUST implement logic to periodically call uip_timer().
- *
- * This function will call the provided callback function for every active
- * connection. Polling will continue until all connections have been polled
- * or until the user-suplied function returns a non-zero value (which it
- * should do only if it cannot accept further write data).
- *
- * When the callback function is called, there may be an outbound packet
- * waiting for service in the uIP packet buffer, and if so the d_len field
- * is set to a value larger than zero. The device driver should then send
- * out the packet.
- *
- * Assumptions:
- * This function is called from the CAN device driver and may be called from
- * the timer interrupt/watchdog handle level.
- *
- ****************************************************************************/
-
-int uip_timer(struct uip_driver_s *dev, uip_poll_callback_t callback, int hsec)
-{
- int bstop;
-
- /* Increment the timer used by the IP reassembly logic */
-
-#if UIP_REASSEMBLY
- if (uip_reasstmr != 0 && uip_reasstmr < UIP_REASS_MAXAGE)
- {
- uip_reasstmr += hsec;
- }
-#endif /* UIP_REASSEMBLY */
-
- /* Check for pendig IGMP messages */
-
-#ifdef CONFIG_NET_IGMP
- bstop = uip_polligmp(dev, callback);
- if (!bstop)
-#endif
- {
- /* Traverse all of the active TCP connections and perform the timer action */
-
- bstop = uip_polltcptimer(dev, callback, hsec);
- if (!bstop)
- {
- /* Traverse all of the allocated UDP connections and perform the poll action */
-
-#ifdef CONFIG_NET_UDP
- bstop = uip_polludpconnections(dev, callback);
- if (!bstop)
-#endif
- {
-#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
- /* Traverse all of the tasks waiting to send an ICMP ECHO request */
-
- bstop = uip_pollicmp(dev, callback);
-#endif
- }
- }
- }
-
- return bstop;
-}
-
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_send.c b/nuttx/net/uip/uip_send.c
deleted file mode 100644
index b26c799a0..000000000
--- a/nuttx/net/uip/uip_send.c
+++ /dev/null
@@ -1,106 +0,0 @@
-/****************************************************************************
- * net/uip/uip_send.c
- *
- * Copyright (C) 2007i, 2008 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Based in part on uIP which also has a BSD stylie 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <string.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Private Type Declarations
- ****************************************************************************/
-
-/****************************************************************************
- * Private Function Prototypes
- ****************************************************************************/
-
-/****************************************************************************
- * Global Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Global Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Constant Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Global Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_send
- *
- * Description:
- * Called from socket logic in response to a xmit or poll request from the
- * the network interface driver.
- *
- * Assumptions:
- * Called from the interrupt level or, at a mimimum, with interrupts
- * disabled.
- *
- ****************************************************************************/
-
-void uip_send(struct uip_driver_s *dev, const void *buf, int len)
-{
- /* Some sanity checks -- note that the actually available length in the
- * buffer is considerably less than CONFIG_NET_BUFSIZE.
- */
-
- if (dev && len > 0 && len < CONFIG_NET_BUFSIZE)
- {
- memcpy(dev->d_snddata, buf, len);
- dev->d_sndlen = len;
- }
-}
diff --git a/nuttx/net/uip/uip_setipid.c b/nuttx/net/uip/uip_setipid.c
deleted file mode 100644
index 12a94860b..000000000
--- a/nuttx/net/uip/uip_setipid.c
+++ /dev/null
@@ -1,78 +0,0 @@
-/****************************************************************************
- * net/uip/uip_setipid.c
- *
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- *
- * 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 <nuttx/config.h>
-#ifdef CONFIG_NET
-
-#include <stdint.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uip.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_setipid
- *
- * Description:
- * This function may be used at boot time to set the initial ip_id.
- *
- * Assumptions:
- *
- ****************************************************************************/
-
-void uip_setipid(uint16_t id)
-{
- g_ipid = id;
-}
-
-#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip_tcpappsend.c b/nuttx/net/uip/uip_tcpappsend.c
deleted file mode 100644
index dfddbcff9..000000000
--- a/nuttx/net/uip/uip_tcpappsend.c
+++ /dev/null
@@ -1,215 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpappsend.c
- *
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <assert.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcpappsend
- *
- * Description:
- * Handle application or TCP protocol response. If this function is called
- * with dev->d_sndlen > 0, then this is an application attempting to send
- * packet.
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- * conn - The TCP connection structure holding connection information
- * result - App result event sent
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcpappsend(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t result)
-{
- /* Handle the result based on the application response */
-
- nllvdbg("result: %04x d_sndlen: %d conn->unacked: %d\n",
- result, dev->d_sndlen, conn->unacked);
-
- /* Check for connection aborted */
-
- if ((result & UIP_ABORT) != 0)
- {
- dev->d_sndlen = 0;
- conn->tcpstateflags = UIP_CLOSED;
- nllvdbg("TCP state: UIP_CLOSED\n");
-
- uip_tcpsend(dev, conn, TCP_RST | TCP_ACK, UIP_IPTCPH_LEN);
- }
-
- /* Check for connection closed */
-
- else if ((result & UIP_CLOSE) != 0)
- {
- conn->tcpstateflags = UIP_FIN_WAIT_1;
- conn->unacked = 1;
- conn->nrtx = 0;
- nllvdbg("TCP state: UIP_FIN_WAIT_1\n");
-
- dev->d_sndlen = 0;
- uip_tcpsend(dev, conn, TCP_FIN | TCP_ACK, UIP_IPTCPH_LEN);
- }
-
- /* None of the above */
-
- else
- {
- /* If d_sndlen > 0, the application has data to be sent. */
-
- if (dev->d_sndlen > 0)
- {
- /* Remember how much data we send out now so that we know
- * when everything has been acknowledged. Just increment the amount
- * of data sent. This will be needed in sequence number calculations
- * and we know that this is not a re-tranmission. Retransmissions
- * do not go through this path.
- */
-
- conn->unacked += dev->d_sndlen;
-
- /* The application cannot send more than what is allowed by the
- * MSS (the minumum of the MSS and the available window).
- */
-
- DEBUGASSERT(dev->d_sndlen <= conn->mss);
- }
-
- /* Then handle the rest of the operation just as for the rexmit case */
-
- conn->nrtx = 0;
- uip_tcprexmit(dev, conn, result);
- }
-}
-
-/****************************************************************************
- * Name: uip_tcprexmit
- *
- * Description:
- * Handle application retransmission
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- * conn - The TCP connection structure holding connection information
- * result - App result event sent
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcprexmit(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t result)
-{
- nllvdbg("result: %04x d_sndlen: %d conn->unacked: %d\n",
- result, dev->d_sndlen, conn->unacked);
-
- dev->d_appdata = dev->d_snddata;
-
- /* If the application has data to be sent, or if the incoming packet had
- * new data in it, we must send out a packet.
- */
-
- if (dev->d_sndlen > 0 && conn->unacked > 0)
- {
- /* We always set the ACK flag in response packets adding the length of
- * the IP and TCP headers.
- */
-
- uip_tcpsend(dev, conn, TCP_ACK | TCP_PSH, dev->d_sndlen + UIP_TCPIP_HLEN);
- }
-
- /* If there is no data to send, just send out a pure ACK if one is requested`. */
-
- else if ((result & UIP_SNDACK) != 0)
- {
- uip_tcpsend(dev, conn, TCP_ACK, UIP_TCPIP_HLEN);
- }
-
- /* There is nothing to do -- drop the packet */
-
- else
- {
- dev->d_len = 0;
- }
-}
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpbacklog.c b/nuttx/net/uip/uip_tcpbacklog.c
deleted file mode 100644
index 459d54312..000000000
--- a/nuttx/net/uip/uip_tcpbacklog.c
+++ /dev/null
@@ -1,403 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpbacklog.c
- *
- * Copyright (C) 2008-2009, 2011-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/net/uip/uipopt.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) && defined(CONFIG_NET_TCPBACKLOG)
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <stdlib.h>
-#include <queue.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-tcp.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_backlogcreate
- *
- * Description:
- * Called from the listen() logic to setup the backlog as specified in the
- * the listen arguments.
- *
- * Assumptions:
- * Called from normal user code. Interrupts may be disabled.
- *
- ****************************************************************************/
-
-int uip_backlogcreate(FAR struct uip_conn *conn, int nblg)
-{
- FAR struct uip_backlog_s *bls = NULL;
- FAR struct uip_blcontainer_s *blc;
- uip_lock_t flags;
- int size;
- int offset;
- int i;
-
- nllvdbg("conn=%p nblg=%d\n", conn, nblg);
-
-#ifdef CONFIG_DEBUG
- if (!conn)
- {
- return -EINVAL;
- }
-#endif
-
- /* Then allocate the backlog as requested */
-
- if (nblg > 0)
- {
- /* Align the list of backlog structures to 32-bit boundaries. This
- * may be excessive on 24-16-bit address machines; and insufficient
- * on 64-bit address machines -- REVISIT
- */
-
- offset = (sizeof(struct uip_backlog_s) + 3) & ~3;
-
- /* Then determine the full size of the allocation include the
- * uip_backlog_s, a pre-allocated array of struct uip_blcontainer_s
- * and alignement padding
- */
-
- size = offset + nblg * sizeof(struct uip_blcontainer_s);
-
- /* Then allocate that much */
-
- bls = (FAR struct uip_backlog_s *)zalloc(size);
- if (!bls)
- {
- nlldbg("Failed to allocate backlog\n");
- return -ENOMEM;
- }
-
- /* Then add all of the pre-allocated containers to the free list */
-
- blc = (FAR struct uip_blcontainer_s*)(((FAR uint8_t*)bls) + offset);
- for (i = 0; i < nblg; i++)
- {
- sq_addfirst(&blc->bc_node, &bls->bl_free);
- }
- }
-
- /* Destroy any existing backlog (shouldn't be any) */
-
- flags = uip_lock();
- uip_backlogdestroy(conn);
-
- /* Now install the backlog tear-off in the connection. NOTE that bls may
- * actually be NULL if nblg is <= 0; In that case, we are disabling backlog
- * support. Since interrupts are disabled, destroying the old backlog and
- * replace it with the new is an atomic operation
- */
-
- conn->backlog = bls;
- uip_unlock(flags);
- return OK;
-}
-
-/****************************************************************************
- * Function: uip_backlogdestroy
- *
- * Description:
- * (1) Called from uip_tcpfree() whenever a connection is freed.
- * (2) Called from uip_backlogcreate() to destroy any old backlog
- *
- * NOTE: This function may re-enter uip_tcpfree when a connection that
- * is freed that has pending connections.
- *
- * Assumptions:
- * The caller has disabled interrupts so that there can be no conflict
- * with ongoing, interrupt driven activity
- *
- ****************************************************************************/
-
-int uip_backlogdestroy(FAR struct uip_conn *conn)
-{
- FAR struct uip_backlog_s *blg;
- FAR struct uip_blcontainer_s *blc;
- FAR struct uip_conn *blconn;
-
- nllvdbg("conn=%p\n", conn);
-
-#ifdef CONFIG_DEBUG
- if (!conn)
- {
- return -EINVAL;
- }
-#endif
-
- /* Make sure that the connection has a backlog to be destroyed */
-
- if (conn->backlog)
- {
- /* Remove the backlog structure reference from the connection */
-
- blg = conn->backlog;
- conn->backlog = NULL;
-
- /* Handle any pending connections in the backlog */
-
- while ((blc = (FAR struct uip_blcontainer_s*)sq_remfirst(&blg->bl_pending)) != NULL)
- {
- blconn = blc->bc_conn;
- if (blconn)
- {
- /* REVISIT -- such connections really need to be gracefully closed */
-
- blconn->blparent = NULL;
- blconn->backlog = NULL;
- blconn->crefs = 0;
- uip_tcpfree(blconn);
- }
- }
-
- /* Then free the entire backlog structure */
-
- free(blg);
- }
-
- return OK;
-}
-
-/****************************************************************************
- * Function: uip_backlogadd
- *
- * Description:
- * Called uip_listen when a new connection is made with a listener socket
- * but when there is no accept() in place to receive the connection. This
- * function adds the new connection to the backlog.
- *
- * Assumptions:
- * Called from the interrupt level with interrupts disabled
- *
- ****************************************************************************/
-
-int uip_backlogadd(FAR struct uip_conn *conn, FAR struct uip_conn *blconn)
-{
- FAR struct uip_backlog_s *bls;
- FAR struct uip_blcontainer_s *blc;
- int ret = -EINVAL;
-
- nllvdbg("conn=%p blconn=%p\n", conn, blconn);
-
-#ifdef CONFIG_DEBUG
- if (!conn)
- {
- return -EINVAL;
- }
-#endif
-
- bls = conn->backlog;
- if (bls && blconn)
- {
- /* Allocate a container for the connection from the free list */
-
- blc = (FAR struct uip_blcontainer_s *)sq_remfirst(&bls->bl_free);
- if (!blc)
- {
- nlldbg("Failed to allocate container\n");
- ret = -ENOMEM;
- }
- else
- {
- /* Save the connection reference in the container and put the
- * container at the end of the pending connection list (FIFO).
- */
-
- blc->bc_conn = blconn;
- sq_addlast(&blc->bc_node, &bls->bl_pending);
- ret = OK;
- }
- }
- return ret;
-}
-
-/****************************************************************************
- * Function: uip_backlogremove
- *
- * Description:
- * Called from poll(). Before waiting for a new connection, poll will
- * call this API to see if there are pending connections in the backlog.
- *
- * Assumptions:
- * Called from normal user code, but with interrupts disabled,
- *
- ****************************************************************************/
-
-#ifndef CONFIG_DISABLE_POLL
-bool uip_backlogavailable(FAR struct uip_conn *conn)
-{
- return (conn && conn->backlog && !sq_empty(&conn->backlog->bl_pending));
-}
-#endif
-
-/****************************************************************************
- * Function: uip_backlogremove
- *
- * Description:
- * Called from accept(). Before waiting for a new connection, accept will
- * call this API to see if there are pending connections in the backlog.
- *
- * Assumptions:
- * Called from normal user code, but with interrupts disabled,
- *
- ****************************************************************************/
-
-struct uip_conn *uip_backlogremove(FAR struct uip_conn *conn)
-{
- FAR struct uip_backlog_s *bls;
- FAR struct uip_blcontainer_s *blc;
- FAR struct uip_conn *blconn = NULL;
-
-#ifdef CONFIG_DEBUG
- if (!conn)
- {
- return NULL;
- }
-#endif
-
- bls = conn->backlog;
- if (bls)
- {
- /* Remove the a container at the head of the pending connection list
- * (FIFO)
- */
-
- blc = (FAR struct uip_blcontainer_s *)sq_remfirst(&bls->bl_pending);
- if (blc)
- {
- /* Extract the connection reference from the container and put
- * container in the free list
- */
-
- blconn = blc->bc_conn;
- blc->bc_conn = NULL;
- sq_addlast(&blc->bc_node, &bls->bl_free);
- }
- }
-
- nllvdbg("conn=%p, returning %p\n", conn, blconn);
- return blconn;
-}
-
-/****************************************************************************
- * Function: uip_backlogdelete
- *
- * Description:
- * Called from uip_tcpfree() when a connection is freed that this also
- * retained in the pending connectino list of a listener. We simply need
- * to remove the defunct connecton from the list.
- *
- * Assumptions:
- * Called from the interrupt level with interrupts disabled
- *
- ****************************************************************************/
-
-int uip_backlogdelete(FAR struct uip_conn *conn, FAR struct uip_conn *blconn)
-{
- FAR struct uip_backlog_s *bls;
- FAR struct uip_blcontainer_s *blc;
- FAR struct uip_blcontainer_s *prev;
-
- nllvdbg("conn=%p blconn=%p\n", conn, blconn);
-
-#ifdef CONFIG_DEBUG
- if (!conn)
- {
- return -EINVAL;
- }
-#endif
-
- bls = conn->backlog;
- if (bls)
- {
- /* Find the container hold the connection */
-
- for (blc = (FAR struct uip_blcontainer_s *)sq_peek(&bls->bl_pending), prev = NULL;
- blc;
- prev = blc, blc = (FAR struct uip_blcontainer_s *)sq_next(&blc->bc_node))
- {
- if (blc->bc_conn == blconn)
- {
- if (prev)
- {
- /* Remove the a container from the middle of the list of
- * pending connections
- */
-
- (void)sq_remafter(&prev->bc_node, &bls->bl_pending);
- }
- else
- {
- /* Remove the a container from the head of the list of
- * pending connections
- */
-
- (void)sq_remfirst(&bls->bl_pending);
- }
-
- /* Put container in the free list */
-
- blc->bc_conn = NULL;
- sq_addlast(&blc->bc_node, &bls->bl_free);
- return OK;
- }
- }
-
- nlldbg("Failed to find pending connection\n");
- return -EINVAL;
- }
- return OK;
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP && CONFIG_NET_TCPBACKLOG */
diff --git a/nuttx/net/uip/uip_tcpcallback.c b/nuttx/net/uip/uip_tcpcallback.c
deleted file mode 100644
index 8ac1351f7..000000000
--- a/nuttx/net/uip/uip_tcpcallback.c
+++ /dev/null
@@ -1,339 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpcallback.c
- *
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <string.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_readahead
- *
- * Description:
- * Copy as much received data as possible into the readahead buffer
- *
- * Assumptions:
- * This function is called at the interrupt level with interrupts disabled.
- *
- ****************************************************************************/
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
-static int uip_readahead(struct uip_readahead_s *readahead, uint8_t *buf,
- int len)
-{
- int available = CONFIG_NET_TCP_READAHEAD_BUFSIZE - readahead->rh_nbytes;
- int recvlen = 0;
-
- if (len > 0 && available > 0)
- {
- /* Get the length of the data to buffer. */
-
- if (len > available)
- {
- recvlen = available;
- }
- else
- {
- recvlen = len;
- }
-
- /* Copy the new appdata into the read-ahead buffer */
-
- memcpy(&readahead->rh_buffer[readahead->rh_nbytes], buf, recvlen);
- readahead->rh_nbytes += recvlen;
- }
- return recvlen;
-}
-#endif
-
-/****************************************************************************
- * Function: uip_dataevent
- *
- * Description:
- * Handle data that is not accepted by the application because there is no
- * listener in place ready to receive the data.
- *
- * Assumptions:
- * - The caller has checked that UIP_NEWDATA is set in flags and that is no
- * other handler available to process the incoming data.
- * - This function is called at the interrupt level with interrupts disabled.
- *
- ****************************************************************************/
-
-static inline uint16_t
-uip_dataevent(FAR struct uip_driver_s *dev, FAR struct uip_conn *conn,
- uint16_t flags)
-{
- uint16_t ret;
-
- /* Assume that we will ACK the data. The data will be ACKed if it is
- * placed in the read-ahead buffer -OR- if it zero length
- */
-
- ret = (flags & ~UIP_NEWDATA) | UIP_SNDACK;
-
- /* Is there new data? With non-zero length? (Certain connection events
- * can have zero-length with UIP_NEWDATA set just to cause an ACK).
- */
-
- if (dev->d_len > 0)
- {
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- uint8_t *buffer = dev->d_appdata;
- int buflen = dev->d_len;
- uint16_t recvlen;
-#endif
-
- nllvdbg("No listener on connection\n");
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- /* Save as much data as possible in the read-ahead buffers */
-
- recvlen = uip_datahandler(conn, buffer, buflen);
-
- /* There are several complicated buffering issues that are not addressed
- * properly here. For example, what if we cannot buffer the entire
- * packet? In that case, some data will be accepted but not ACKed.
- * Therefore it will be resent and duplicated. Fixing this could be tricky.
- */
-
- if (recvlen < buflen)
-#endif
- {
- /* There is no handler to receive new data and there are no free
- * read-ahead buffers to retain the data -- drop the packet.
- */
-
- nllvdbg("Dropped %d bytes\n", dev->d_len);
-
- #ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.syndrop++;
- uip_stat.tcp.drop++;
-#endif
- /* Clear the UIP_SNDACK bit so that no ACK will be sent */
-
- ret &= ~UIP_SNDACK;
- }
- }
-
- /* In any event, the new data has now been handled */
-
- dev->d_len = 0;
- return ret;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_tcpcallback
- *
- * Description:
- * Inform the application holding the TCP socket of a change in state.
- *
- * Assumptions:
- * This function is called at the interrupt level with interrupts disabled.
- *
- ****************************************************************************/
-
-uint16_t uip_tcpcallback(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t flags)
-{
- /* Preserve the UIP_ACKDATA, UIP_CLOSE, and UIP_ABORT in the response.
- * These is needed by uIP to handle responses and buffer state. The
- * UIP_NEWDATA indication will trigger the ACK response, but must be
- * explicitly set in the callback.
- */
-
- uint16_t ret = flags;
-
- nllvdbg("flags: %04x\n", flags);
-
- /* Perform the data callback. When a data callback is executed from 'list',
- * the input flags are normally returned, however, the implementation
- * 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.
- *
- * And/Or set/clear the following:
- *
- * UIP_NEWDATA - May be cleared to indicate that the data was consumed
- * and that no further process of the new data should be
- * attempted.
- * UIP_SNDACK - If UIP_NEWDATA is cleared, then UIP_SNDACK may be set
- * to indicate that an ACK should be included in the response.
- * (In UIP_NEWDATA is cleared bu UIP_SNDACK is not set, then
- * dev->d_len should also be cleared).
- */
-
- ret = uip_callbackexecute(dev, conn, flags, conn->list);
-
- /* There may be no new data handler in place at them moment that the new
- * incoming data is received. If the new incoming data was not handled, then
- * either (1) put the unhandled incoming data in the read-ahead buffer (if
- * enabled) or (2) suppress the ACK to the data in the hope that it will
- * be re-transmitted at a better time.
- */
-
- if ((ret & UIP_NEWDATA) != 0)
- {
- /* Data was not handled.. dispose of it appropriately */
-
- ret = uip_dataevent(dev, conn, ret);
- }
-
- /* Check if there is a connection-related event and a connection
- * callback.
- */
-
- if (((flags & UIP_CONN_EVENTS) != 0) && conn->connection_event)
- {
- /* Perform the callback */
-
- conn->connection_event(conn, flags);
- }
-
- return ret;
-}
-
-/****************************************************************************
- * Function: uip_datahandler
- *
- * Description:
- * Handle data that is not accepted by the application. This may be called
- * either (1) from the data receive logic if it cannot buffer the data, or
- * (2) from the TCP event logic is there is no listener in place ready to
- * receive the data.
- *
- * Input Parmeters:
- * conn - A pointer to the TCP connection structure
- * buffer - A pointer to the buffer to be copied to the read-ahead
- * buffers
- * buflen - The number of bytes to copy to the read-ahead buffer.
- *
- * Returned value:
- * The number of bytes actually buffered. This could be less than 'nbytes'
- * if there is insufficient buffering available.
- *
- * Assumptions:
- * - The caller has checked that UIP_NEWDATA is set in flags and that is no
- * other handler available to process the incoming data.
- * - This function is called at the interrupt level with interrupts disabled.
- *
- ****************************************************************************/
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
-uint16_t uip_datahandler(FAR struct uip_conn *conn, FAR uint8_t *buffer,
- uint16_t buflen)
-{
- FAR struct uip_readahead_s *readahead1;
- FAR struct uip_readahead_s *readahead2 = NULL;
- uint16_t remaining;
- uint16_t recvlen = 0;
-
- /* First, we need to determine if we have space to buffer the data. This
- * needs to be verified before we actually begin buffering the data. We
- * will use any remaining space in the last allocated readahead buffer
- * plus as much one additional buffer. It is expected that the size of
- * readahead buffers are tuned so that one full packet will always fit
- * into one readahead buffer (for example if the buffer size is 420, then
- * a readahead buffer of 366 will hold a full packet of TCP data).
- */
-
- readahead1 = (FAR struct uip_readahead_s*)conn->readahead.tail;
- if ((readahead1 &&
- (CONFIG_NET_TCP_READAHEAD_BUFSIZE - readahead1->rh_nbytes) > buflen) ||
- (readahead2 = uip_tcpreadaheadalloc()) != NULL)
- {
- /* We have buffer space. Now try to append add as much data as possible
- * to the last readahead buffer attached to this connection.
- */
-
- remaining = buflen;
- if (readahead1)
- {
- recvlen = uip_readahead(readahead1, buffer, remaining);
- if (recvlen > 0)
- {
- buffer += recvlen;
- remaining -= recvlen;
- }
- }
-
- /* Do we need to buffer into the newly allocated buffer as well? */
-
- if (readahead2)
- {
- readahead2->rh_nbytes = 0;
- recvlen += uip_readahead(readahead2, buffer, remaining);
-
- /* Save the readahead buffer in the connection structure where
- * it can be found with recv() is called.
- */
-
- sq_addlast(&readahead2->rh_node, &conn->readahead);
- }
- }
-
- nllvdbg("Buffered %d bytes (of %d)\n", recvlen, buflen);
- return recvlen;
-}
-#endif /* CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0 */
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpconn.c b/nuttx/net/uip/uip_tcpconn.c
deleted file mode 100644
index 31e020f63..000000000
--- a/nuttx/net/uip/uip_tcpconn.c
+++ /dev/null
@@ -1,636 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpconn.c
- *
- * Copyright (C) 2007-2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Large parts of this file were leveraged from uIP logic:
- *
- * 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Compilation Switches
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <string.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <arch/irq.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* The array containing all uIP TCP connections. */
-
-static struct uip_conn g_tcp_connections[CONFIG_NET_TCP_CONNS];
-
-/* A list of all free TCP connections */
-
-static dq_queue_t g_free_tcp_connections;
-
-/* A list of all connected TCP connections */
-
-static dq_queue_t g_active_tcp_connections;
-
-/* Last port used by a TCP connection connection. */
-
-static uint16_t g_last_tcp_port;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_selectport()
- *
- * Description:
- * If the portnumber is zero; select an unused port for the connection.
- * If the portnumber is non-zero, verify that no other connection has
- * been created with this port number.
- *
- * Input Parameters:
- * portno -- the selected port number in host order. Zero means no port
- * selected.
- *
- * Return:
- * 0 on success, negated errno on failure:
- *
- * EADDRINUSE
- * The given address is already in use.
- * EADDRNOTAVAIL
- * Cannot assign requested address (unlikely)
- *
- * Assumptions:
- * Interrupts are disabled
- *
- ****************************************************************************/
-
-static int uip_selectport(uint16_t portno)
-{
- if (portno == 0)
- {
- /* No local port assigned. Loop until we find a valid listen port number
- * that is not being used by any other connection. NOTE the following loop
- * is assumed to terminate but could not if all 32000-4096+1 ports are
- * in used (unlikely).
- */
-
- do
- {
- /* Guess that the next available port number will be the one after
- * the last port number assigned.
- */
- portno = ++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_tcplistener(htons(g_last_tcp_port)));
- }
- else
- {
- /* A port number has been supplied. Verify that no other TCP/IP
- * connection is using this local port.
- */
-
- if (uip_tcplistener(portno))
- {
- /* It is in use... return EADDRINUSE */
-
- return -EADDRINUSE;
- }
- }
-
- /* Return the selected or verified port number */
-
- return portno;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcpinit()
- *
- * Description:
- * Initialize the TCP/IP connection structures. Called only once and only
- * from the UIP layer at startup in normal user mode.
- *
- ****************************************************************************/
-
-void uip_tcpinit(void)
-{
- int i;
-
- /* Initialize the queues */
-
- dq_init(&g_free_tcp_connections);
- dq_init(&g_active_tcp_connections);
-
- /* Now initialize each connection structure */
-
- for (i = 0; i < CONFIG_NET_TCP_CONNS; i++)
- {
- /* Mark the connection closed and move it to the free list */
-
- g_tcp_connections[i].tcpstateflags = UIP_CLOSED;
- dq_addlast(&g_tcp_connections[i].node, &g_free_tcp_connections);
- }
-
- 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)
-{
- struct uip_conn *conn;
- uip_lock_t flags;
-
- /* 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_free_tcp_connections[];
- */
-
- flags = uip_lock();
-
- /* Return the entry from the head of the free list */
-
- conn = (struct uip_conn *)dq_remfirst(&g_free_tcp_connections);
-
-#if 0 /* Revisit */
- /* Is the free list empty? */
-
- if (!conn)
- {
- /* As a fallback, check for connection structures in the TIME_WAIT
- * state. If no CLOSED connections are found, then take the oldest
- */
-
- struct uip_conn *tmp = g_active_tcp_connections.head;
- while (tmp)
- {
- /* Is this connectin in the UIP_TIME_WAIT state? */
-
- if (tmp->tcpstateflags == UIP_TIME_WAIT)
- {
- /* Is it the oldest one we have seen so far? */
-
- if (!conn || tmp->timer > conn->timer)
- {
- /* Yes.. remember it */
-
- conn = tmp;
- }
- }
-
- /* Look at the next active connection */
-
- tmp = tmp->node.flink;
- }
-
- /* If we found one, remove it from the active connection list */
-
- dq_rem(&conn->node, &g_active_tcp_connections);
- }
-#endif
-
- uip_unlock(flags);
-
- /* Mark the connection allocated */
-
- if (conn)
- {
- conn->tcpstateflags = UIP_ALLOCATED;
- }
-
- return conn;
-}
-
-/****************************************************************************
- * 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)
-{
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- struct uip_readahead_s *readahead;
-#endif
- uip_lock_t flags;
-
- /* Because g_free_tcp_connections is accessed from user level and interrupt
- * level, code, it is necessary to keep interrupts disabled during this
- * operation.
- */
-
- DEBUGASSERT(conn->crefs == 0);
- flags = uip_lock();
-
- /* UIP_ALLOCATED means that that the connection is not in the active list
- * yet.
- */
-
- if (conn->tcpstateflags != UIP_ALLOCATED)
- {
- /* Remove the connection from the active list */
-
- dq_rem(&conn->node, &g_active_tcp_connections);
- }
-
- /* Release any read-ahead buffers attached to the connection */
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- while ((readahead = (struct uip_readahead_s *)sq_remfirst(&conn->readahead)) != NULL)
- {
- uip_tcpreadaheadrelease(readahead);
- }
-#endif
-
- /* Remove any backlog attached to this connection */
-
-#ifdef CONFIG_NET_TCPBACKLOG
- if (conn->backlog)
- {
- uip_backlogdestroy(conn);
- }
-
- /* If this connection is, itself, backlogged, then remove it from the
- * parent connection's backlog list.
- */
-
- if (conn->blparent)
- {
- uip_backlogdelete(conn->blparent, conn);
- }
-#endif
-
- /* Mark the connection available and put it into the free list */
-
- conn->tcpstateflags = UIP_CLOSED;
- dq_addlast(&conn->node, &g_free_tcp_connections);
- uip_unlock(flags);
-}
-
-/****************************************************************************
- * Name: uip_tcpactive()
- *
- * Description:
- * Find a connection structure that is the appropriate
- * connection to be used with 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 = (struct uip_conn *)g_active_tcp_connections.head;
- in_addr_t srcipaddr = uip_ip4addr_conv(buf->srcipaddr);
-
- while (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(srcipaddr, conn->ripaddr))
- {
- /* Matching connection found.. break out of the loop and return a
- * reference to it.
- */
-
- break;
- }
-
- /* Look at the next active connection */
-
- conn = (struct uip_conn *)conn->node.flink;
- }
-
- return conn;
-}
-
-/****************************************************************************
- * Name: uip_nexttcpconn()
- *
- * Description:
- * Traverse the list of active TCP connections
- *
- * Assumptions:
- * This function is called from UIP logic at interrupt level (or with
- * interrupts disabled).
- *
- ****************************************************************************/
-
-struct uip_conn *uip_nexttcpconn(struct uip_conn *conn)
-{
- if (!conn)
- {
- return (struct uip_conn *)g_active_tcp_connections.head;
- }
- else
- {
- return (struct uip_conn *)conn->node.flink;
- }
-}
-
-/****************************************************************************
- * Name: uip_tcplistener()
- *
- * Description:
- * Given a local port number (in network byte order), find the TCP
- * connection that listens on this this port.
- *
- * Primary uses: (1) to determine if a port number is available, (2) to
- * To idenfity the socket that will accept new connections on a local port.
- *
- ****************************************************************************/
-
-struct uip_conn *uip_tcplistener(uint16_t portno)
-{
- struct uip_conn *conn;
- int i;
-
- /* Check if this port number is in use by any active UIP TCP connection */
-
- for (i = 0; i < CONFIG_NET_TCP_CONNS; i++)
- {
- conn = &g_tcp_connections[i];
- if (conn->tcpstateflags != UIP_CLOSED && conn->lport == portno)
- {
- /* The portnumber is in use, return the connection */
-
- return conn;
- }
- }
- return NULL;
-}
-
-/****************************************************************************
- * Name: uip_tcpaccept()
- *
- * Description:
- * Called when uip_interupt matches the incoming packet with a connection
- * in LISTEN. In that case, this function will create a new connection and
- * initialize it to send a SYNACK in return.
- *
- * Assumptions:
- * This function is called from UIP logic at interrupt level
- *
- ****************************************************************************/
-
-struct uip_conn *uip_tcpaccept(struct uip_tcpip_hdr *buf)
-{
- struct uip_conn *conn = uip_tcpalloc();
- if (conn)
- {
- /* Fill in the necessary fields for the new connection. */
-
- conn->rto = UIP_RTO;
- conn->timer = UIP_RTO;
- conn->sa = 0;
- conn->sv = 4;
- conn->nrtx = 0;
- conn->lport = buf->destport;
- conn->rport = buf->srcport;
- uip_ipaddr_copy(conn->ripaddr, uip_ip4addr_conv(buf->srcipaddr));
- conn->tcpstateflags = UIP_SYN_RCVD;
-
- uip_tcpinitsequence(conn->sndseq);
- conn->unacked = 1;
-
- /* rcvseq should be the seqno from the incoming packet + 1. */
-
- memcpy(conn->rcvseq, buf->seqno, 4);
-
- /* Initialize the list of TCP read-ahead buffers */
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- sq_init(&conn->readahead);
-#endif
-
- /* And, finally, put the connection structure into the active list.
- * Interrupts should already be disabled in this context.
- */
-
- dq_addlast(&conn->node, &g_active_tcp_connections);
- }
- return conn;
-}
-
-/****************************************************************************
- * Name: uip_tcpbind()
- *
- * Description:
- * This function implements the UIP specific parts of the standard TCP
- * bind() operation.
- *
- * Return:
- * 0 on success or -EADDRINUSE on failure
- *
- * 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
-{
- uip_lock_t flags;
- int port;
-
- /* Verify or select a local port */
-
- flags = uip_lock();
- port = uip_selectport(ntohs(addr->sin_port));
- uip_unlock(flags);
-
- if (port < 0)
- {
- return port;
- }
-
- /* Save the local address in the connection structure. Note that the requested
- * local IP address is saved but not used. At present, only a single network
- * interface is supported, the IP address is not of importance.
- */
-
- conn->lport = addr->sin_port;
-
-#if 0 /* Not used */
-#ifdef CONFIG_NET_IPv6
- uip_ipaddr_copy(conn->lipaddr, addr->sin6_addr.in6_u.u6_addr16);
-#else
- uip_ipaddr_copy(conn->lipaddr, addr->sin_addr.s_addr);
-#endif
-#endif
-
- return OK;
-}
-
-/****************************************************************************
- * Name: uip_tcpconnect()
- *
- * 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
-{
- uip_lock_t flags;
- int port;
-
- /* The connection is expected to be in the UIP_ALLOCATED state.. i.e.,
- * allocated via up_tcpalloc(), but not yet put into the active connections
- * list.
- */
-
- if (!conn || conn->tcpstateflags != UIP_ALLOCATED)
- {
- return -EISCONN;
- }
-
- /* If the TCP port has not alread been bound to a local port, then select
- * one now.
- */
-
- flags = uip_lock();
- port = uip_selectport(ntohs(conn->lport));
- uip_unlock(flags);
-
- if (port < 0)
- {
- return port;
- }
-
- /* Initialize and return the connection structure, bind it to the port number */
-
- conn->tcpstateflags = UIP_SYN_SENT;
- uip_tcpinitsequence(conn->sndseq);
-
- conn->initialmss = conn->mss = UIP_TCP_MSS;
- conn->unacked = 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((uint16_t)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);
-
- /* Initialize the list of TCP read-ahead buffers */
-
-#if CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0
- sq_init(&conn->readahead);
-#endif
-
- /* And, finally, put the connection structure into the active
- * list. Because g_active_tcp_connections is accessed from user level and
- * interrupt level, code, it is necessary to keep interrupts disabled during
- * this operation.
- */
-
- flags = uip_lock();
- dq_addlast(&conn->node, &g_active_tcp_connections);
- uip_unlock(flags);
-
- return OK;
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpinput.c b/nuttx/net/uip/uip_tcpinput.c
deleted file mode 100644
index 5b40963b6..000000000
--- a/nuttx/net/uip/uip_tcpinput.c
+++ /dev/null
@@ -1,839 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpinput.c
- * Handling incoming TCP input
- *
- * Copyright (C) 2007-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <string.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcpinput
- *
- * Description:
- * Handle incoming TCP input
- *
- * Parameters:
- * dev - The device driver structure containing the received TCP packet.
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcpinput(struct uip_driver_s *dev)
-{
- struct uip_conn *conn = NULL;
- struct uip_tcpip_hdr *pbuf = BUF;
- uint16_t tmp16;
- uint16_t flags;
- uint8_t opt;
- uint8_t result;
- int len;
- int i;
-
- dev->d_snddata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
- dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.recv++;
-#endif
-
- /* Start of TCP input header processing code. */
-
- if (uip_tcpchksum(dev) != 0xffff)
- {
- /* Compute and check the TCP checksum. */
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.drop++;
- uip_stat.tcp.chkerr++;
-#endif
- nlldbg("Bad TCP checksum\n");
- goto drop;
- }
-
- /* Demultiplex this segment. First check any active connections. */
-
- conn = uip_tcpactive(pbuf);
- if (conn)
- {
- /* We found an active connection.. Check for the subsequent SYN
- * arriving in UIP_SYN_RCVD state after the SYNACK packet was
- * lost. To avoid other issues, reset any active connection
- * where a SYN arrives in a state != UIP_SYN_RCVD.
- */
-
- if ((conn->tcpstateflags & UIP_TS_MASK) != UIP_SYN_RCVD &&
- (BUF->flags & TCP_CTL) == TCP_SYN)
- {
- goto reset;
- }
- else
- {
- goto found;
- }
- }
-
- /* If we didn't find and active connection that expected the packet,
- * either (1) this packet is an old duplicate, or (2) 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 ((pbuf->flags & TCP_CTL) == TCP_SYN)
- {
- /* This is a SYN packet for a connection. Find the connection
- * listening on this port.
- */
-
- tmp16 = pbuf->destport;
- if (uip_islistener(tmp16))
- {
- /* We matched the incoming packet with a connection in LISTEN.
- * We now need to create a new connection and send a SYNACK in
- * response.
- */
-
- /* First allocate a new connection structure and see if there is any
- * user application to accept it.
- */
-
- conn = uip_tcpaccept(pbuf);
- if (conn)
- {
- /* The connection structure was successfully allocated. Now see if
- * there is an application waiting to accept the connection (or at
- * least queue it it for acceptance).
- */
-
- conn->crefs = 1;
- if (uip_accept(dev, conn, tmp16) != OK)
- {
- /* No, then we have to give the connection back and drop the packet */
-
- conn->crefs = 0;
- uip_tcpfree(conn);
- conn = NULL;
- }
- else
- {
- /* TCP state machine should move to the ESTABLISHED state only after
- * it has received ACK from the host. This needs to be investigated
- * further.
- */
-
- conn->tcpstateflags = UIP_ESTABLISHED;
- }
- }
-
- if (!conn)
- {
- /* Either (1) all available connections are in use, or (2) there is no
- * application in place to accept the connection. We drop packet and hope that
- * the remote end will retransmit the packet at a time when we
- * have more spare connections or someone waiting to accept the connection.
- */
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.syndrop++;
-#endif
- nlldbg("No free TCP connections\n");
- goto drop;
- }
-
- uip_incr32(conn->rcvseq, 1);
-
- /* Parse the TCP MSS option, if present. */
-
- if ((pbuf->tcpoffset & 0xf0) > 0x50)
- {
- for (i = 0; i < ((pbuf->tcpoffset >> 4) - 5) << 2 ;)
- {
- opt = dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + i];
- if (opt == TCP_OPT_END)
- {
- /* End of options. */
-
- break;
- }
- else if (opt == TCP_OPT_NOOP)
- {
- /* NOP option. */
-
- ++i;
- }
- else if (opt == TCP_OPT_MSS &&
- dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == TCP_OPT_MSS_LEN)
- {
- /* An MSS option with the right option length. */
-
- tmp16 = ((uint16_t)dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + i] << 8) |
- (uint16_t)dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + 3 + i];
- conn->initialmss = conn->mss =
- tmp16 > UIP_TCP_MSS? UIP_TCP_MSS: tmp16;
-
- /* And we are done processing options. */
-
- break;
- }
- else
- {
- /* All other options have a length field, so that we easily
- * can skip past them.
- */
-
- if (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == 0)
- {
- /* If the length field is zero, the options are malformed
- * and we don't process them further.
- */
-
- break;
- }
- i += dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i];
- }
- }
- }
-
- /* Our response will be a SYNACK. */
-
- uip_tcpack(dev, conn, TCP_ACK | TCP_SYN);
- return;
- }
- }
-
- /* This is (1) an old duplicate packet or (2) a SYN packet but with
- * no matching listener found. Send RST packet in either case.
- */
-
-reset:
-
- /* We do not send resets in response to resets. */
-
- if ((pbuf->flags & TCP_RST) != 0)
- {
- goto drop;
- }
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.synrst++;
-#endif
- uip_tcpreset(dev);
- return;
-
-found:
-
- flags = 0;
-
- /* We do a very naive form of TCP reset processing; we just accept
- * any RST and kill our connection. We should in fact check if the
- * sequence number of this reset is within our advertised window
- * before we accept the reset.
- */
-
- if ((pbuf->flags & TCP_RST) != 0)
- {
- conn->tcpstateflags = UIP_CLOSED;
- nlldbg("RESET - TCP state: UIP_CLOSED\n");
-
- (void)uip_tcpcallback(dev, conn, UIP_ABORT);
- goto drop;
- }
-
- /* Calculated the length of the data, if the application has sent
- * any data to us.
- */
-
- len = (pbuf->tcpoffset >> 4) << 2;
-
- /* d_len will contain the length of the actual TCP data. This is
- * calculated by subtracting the length of the TCP header (in
- * len) and the length of the IP header (20 bytes).
- */
-
- dev->d_len -= (len + UIP_IPH_LEN);
-
- /* First, check if the sequence number of the incoming packet is
- * what we're expecting next. If not, we send out an ACK with the
- * correct numbers in, unless we are in the SYN_RCVD state and
- * receive a SYN, in which case we should retransmit our SYNACK
- * (which is done further down).
- */
-
- if (!((((conn->tcpstateflags & UIP_TS_MASK) == UIP_SYN_SENT) &&
- ((pbuf->flags & TCP_CTL) == (TCP_SYN | TCP_ACK))) ||
- (((conn->tcpstateflags & UIP_TS_MASK) == UIP_SYN_RCVD) &&
- ((pbuf->flags & TCP_CTL) == TCP_SYN))))
- {
- if ((dev->d_len > 0 || ((pbuf->flags & (TCP_SYN | TCP_FIN)) != 0)) &&
- memcmp(pbuf->seqno, conn->rcvseq, 4) != 0)
- {
- uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
- return;
- }
- }
-
- /* Next, check if the incoming segment acknowledges any outstanding
- * data. If so, we update the sequence number, reset the length of
- * the outstanding data, calculate RTT estimations, and reset the
- * retransmission timer.
- */
-
- if ((pbuf->flags & TCP_ACK) != 0 && conn->unacked > 0)
- {
- uint32_t unackseq;
- uint32_t ackseq;
-
- /* The next sequence number is equal to the current sequence
- * number (sndseq) plus the size of the oustanding, unacknowledged
- * data (unacked).
- */
-
- unackseq = uip_tcpaddsequence(conn->sndseq, conn->unacked);
-
- /* Get the sequence number of that has just been acknowledged by this
- * incoming packet.
- */
-
- ackseq = uip_tcpgetsequence(pbuf->ackno);
-
- /* Check how many of the outstanding bytes have been acknowledged. For
- * a most uIP send operation, this should always be true. However,
- * the send() API sends data ahead when it can without waiting for
- * the ACK. In this case, the 'ackseq' could be less than then the
- * new sequence number.
- */
-
- if (ackseq <= unackseq)
- {
- /* Calculate the new number of oustanding, unacknowledged bytes */
-
- conn->unacked = unackseq - ackseq;
- }
- else
- {
- /* What would it mean if ackseq > unackseq? The peer has ACKed
- * more bytes than we think we have sent? Someone has lost it.
- * Complain and reset the number of outstanding, unackowledged
- * bytes
- */
-
- nlldbg("ERROR: ackseq[%08x] > unackseq[%08x]\n", ackseq, unackseq);
- conn->unacked = 0;
- }
-
- /* Update sequence number to the unacknowledge sequence number. If
- * there is still outstanding, unacknowledged data, then this will
- * be beyond ackseq.
- */
-
- nllvdbg("sndseq: %08x->%08x unackseq: %08x new unacked: %d\n",
- conn->sndseq, ackseq, unackseq, conn->unacked);
- uip_tcpsetsequence(conn->sndseq, ackseq);
-
- /* Do RTT estimation, unless we have done retransmissions. */
-
- if (conn->nrtx == 0)
- {
- signed char m;
- m = conn->rto - conn->timer;
-
- /* This is taken directly from VJs original code in his paper */
-
- m = m - (conn->sa >> 3);
- conn->sa += m;
- if (m < 0)
- {
- m = -m;
- }
-
- m = m - (conn->sv >> 2);
- conn->sv += m;
- conn->rto = (conn->sa >> 3) + conn->sv;
- }
-
- /* Set the acknowledged flag. */
-
- flags |= UIP_ACKDATA;
-
- /* Reset the retransmission timer. */
-
- conn->timer = conn->rto;
- }
-
- /* Do different things depending on in what state the connection is. */
-
- switch (conn->tcpstateflags & UIP_TS_MASK)
- {
- /* CLOSED and LISTEN are not handled here. CLOSE_WAIT is not
- * implemented, since we force the application to close when the
- * peer sends a FIN (hence the application goes directly from
- * ESTABLISHED to LAST_ACK).
- */
-
- case UIP_SYN_RCVD:
- /* In SYN_RCVD we have sent out a SYNACK in response to a SYN, and
- * we are waiting for an ACK that acknowledges the data we sent
- * out the last time. Therefore, we want to have the UIP_ACKDATA
- * flag set. If so, we enter the ESTABLISHED state.
- */
-
- if ((flags & UIP_ACKDATA) != 0)
- {
- conn->tcpstateflags = UIP_ESTABLISHED;
- conn->unacked = 0;
- nllvdbg("TCP state: UIP_ESTABLISHED\n");
-
- flags = UIP_CONNECTED;
-
- if (dev->d_len > 0)
- {
- flags |= UIP_NEWDATA;
- uip_incr32(conn->rcvseq, dev->d_len);
- }
-
- dev->d_sndlen = 0;
- result = uip_tcpcallback(dev, conn, flags);
- uip_tcpappsend(dev, conn, result);
- return;
- }
-
- /* We need to retransmit the SYNACK */
-
- if ((pbuf->flags & TCP_CTL) == TCP_SYN)
- {
- uip_tcpack(dev, conn, TCP_ACK | TCP_SYN);
- return;
- }
- goto drop;
-
- case UIP_SYN_SENT:
- /* In SYN_SENT, we wait for a SYNACK that is sent in response to
- * our SYN. The rcvseq is set to sequence number in the SYNACK
- * plus one, and we send an ACK. We move into the ESTABLISHED
- * state.
- */
-
- if ((flags & UIP_ACKDATA) != 0 && (pbuf->flags & TCP_CTL) == (TCP_SYN | TCP_ACK))
- {
- /* Parse the TCP MSS option, if present. */
-
- if ((pbuf->tcpoffset & 0xf0) > 0x50)
- {
- for (i = 0; i < ((pbuf->tcpoffset >> 4) - 5) << 2 ;)
- {
- opt = dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + i];
- if (opt == TCP_OPT_END)
- {
- /* End of options. */
-
- break;
- }
- else if (opt == TCP_OPT_NOOP)
- {
- /* NOP option. */
-
- ++i;
- }
- else if (opt == TCP_OPT_MSS &&
- dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == TCP_OPT_MSS_LEN)
- {
- /* An MSS option with the right option length. */
-
- tmp16 =
- (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + i] << 8) |
- dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 3 + i];
- conn->initialmss =
- conn->mss =
- tmp16 > UIP_TCP_MSS? UIP_TCP_MSS: tmp16;
-
- /* And we are done processing options. */
-
- break;
- }
- else
- {
- /* All other options have a length field, so that we
- * easily can skip past them.
- */
-
- if (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i] == 0)
- {
- /* If the length field is zero, the options are
- * malformed and we don't process them further.
- */
-
- break;
- }
- i += dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + i];
- }
- }
- }
-
- conn->tcpstateflags = UIP_ESTABLISHED;
- memcpy(conn->rcvseq, pbuf->seqno, 4);
- nllvdbg("TCP state: UIP_ESTABLISHED\n");
-
- uip_incr32(conn->rcvseq, 1);
- conn->unacked = 0;
- dev->d_len = 0;
- dev->d_sndlen = 0;
- result = uip_tcpcallback(dev, conn, UIP_CONNECTED | UIP_NEWDATA);
- uip_tcpappsend(dev, conn, result);
- return;
- }
-
- /* Inform the application that the connection failed */
-
- (void)uip_tcpcallback(dev, conn, UIP_ABORT);
-
- /* The connection is closed after we send the RST */
-
- conn->tcpstateflags = UIP_CLOSED;
- nllvdbg("Connection failed - TCP state: UIP_CLOSED\n");
-
- /* We do not send resets in response to resets. */
-
- if ((pbuf->flags & TCP_RST) != 0)
- {
- goto drop;
- }
- uip_tcpreset(dev);
- return;
-
- case UIP_ESTABLISHED:
- /* In the ESTABLISHED state, we call upon the application to feed
- * data into the d_buf. If the UIP_ACKDATA flag is set, the
- * application should put new data into the buffer, otherwise we are
- * retransmitting an old segment, and the application should put that
- * data into the buffer.
- *
- * If the incoming packet is a FIN, we should close the connection on
- * this side as well, and we send out a FIN and enter the LAST_ACK
- * state. We require that there is no outstanding data; otherwise the
- * sequence numbers will be screwed up.
- */
-
- if ((pbuf->flags & TCP_FIN) != 0 && (conn->tcpstateflags & UIP_STOPPED) == 0)
- {
- if (conn->unacked > 0)
- {
- goto drop;
- }
-
- /* Update the sequence number and indicate that the connection has
- * been closed.
- */
-
- uip_incr32(conn->rcvseq, dev->d_len + 1);
- flags |= UIP_CLOSE;
-
- if (dev->d_len > 0)
- {
- flags |= UIP_NEWDATA;
- }
-
- (void)uip_tcpcallback(dev, conn, flags);
-
- conn->tcpstateflags = UIP_LAST_ACK;
- conn->unacked = 1;
- conn->nrtx = 0;
- nllvdbg("TCP state: UIP_LAST_ACK\n");
-
- uip_tcpsend(dev, conn, TCP_FIN | TCP_ACK, UIP_IPTCPH_LEN);
- return;
- }
-
- /* Check the URG flag. If this is set, the segment carries urgent
- * data that we must pass to the application.
- */
-
- if ((pbuf->flags & TCP_URG) != 0)
- {
-#ifdef CONFIG_NET_TCPURGDATA
- dev->d_urglen = (pbuf->urgp[0] << 8) | pbuf->urgp[1];
- if (dev->d_urglen > dev->d_len)
- {
- /* There is more urgent data in the next segment to come. */
-
- dev->d_urglen = dev->d_len;
- }
-
- uip_incr32(conn->rcvseq, dev->d_urglen);
- dev->d_len -= dev->d_urglen;
- dev->d_urgdata = dev->d_appdata;
- dev->d_appdata += dev->d_urglen;
- }
- else
- {
- dev->d_urglen = 0;
-#else /* CONFIG_NET_TCPURGDATA */
- dev->d_appdata = ((uint8_t*)dev->d_appdata) + ((pbuf->urgp[0] << 8) | pbuf->urgp[1]);
- dev->d_len -= (pbuf->urgp[0] << 8) | pbuf->urgp[1];
-#endif /* CONFIG_NET_TCPURGDATA */
- }
-
- /* If d_len > 0 we have TCP data in the packet, and we flag this
- * by setting the UIP_NEWDATA flag. If the application has stopped
- * the dataflow using uip_stop(), we must not accept any data
- * packets from the remote host.
- */
-
- if (dev->d_len > 0 && (conn->tcpstateflags & UIP_STOPPED) == 0)
- {
- flags |= UIP_NEWDATA;
- }
-
- /* Check if the available buffer space advertised by the other end
- * is smaller than the initial MSS for this connection. If so, we
- * set the current MSS to the window size to ensure that the
- * application does not send more data than the other end can
- * handle.
- *
- * If the remote host advertises a zero window, we set the MSS to
- * the initial MSS so that the application will send an entire MSS
- * of data. This data will not be acknowledged by the receiver,
- * and the application will retransmit it. This is called the
- * "persistent timer" and uses the retransmission mechanim.
- */
-
- tmp16 = ((uint16_t)pbuf->wnd[0] << 8) + (uint16_t)pbuf->wnd[1];
- if (tmp16 > conn->initialmss || tmp16 == 0)
- {
- tmp16 = conn->initialmss;
- }
- conn->mss = tmp16;
-
- /* If this packet constitutes an ACK for outstanding data (flagged
- * by the UIP_ACKDATA flag), we should call the application since it
- * might want to send more data. If the incoming packet had data
- * from the peer (as flagged by the UIP_NEWDATA flag), the
- * application must also be notified.
- *
- * When the application is called, the d_len field
- * contains the length of the incoming data. The application can
- * access the incoming data through the global pointer
- * d_appdata, which usually points UIP_IPTCPH_LEN + UIP_LLH_LEN
- * bytes into the d_buf array.
- *
- * If the application wishes to send any data, this data should be
- * put into the d_appdata and the length of the data should be
- * put into d_len. If the application don't have any data to
- * send, d_len must be set to 0.
- */
-
- if ((flags & (UIP_NEWDATA | UIP_ACKDATA)) != 0)
- {
- /* Clear sndlen and remember the size in d_len. The application
- * may modify d_len and we will need this value later when we
- * update the sequence number.
- */
-
- dev->d_sndlen = 0;
- len = dev->d_len;
-
- /* Provide the packet to the application */
-
- result = uip_tcpcallback(dev, conn, flags);
-
- /* If the application successfully handled the incoming data,
- * then UIP_SNDACK will be set in the result. In this case,
- * we need to update the sequence number. The ACK will be
- * send by uip_tcpappsend().
- */
-
- if ((result & UIP_SNDACK) != 0)
- {
- /* Update the sequence number using the saved length */
-
- uip_incr32(conn->rcvseq, len);
- }
-
- /* Send the response, ACKing the data or not, as appropriate */
-
- uip_tcpappsend(dev, conn, result);
- return;
- }
- goto drop;
-
- case UIP_LAST_ACK:
- /* We can close this connection if the peer has acknowledged our
- * FIN. This is indicated by the UIP_ACKDATA flag.
- */
-
- if ((flags & UIP_ACKDATA) != 0)
- {
- conn->tcpstateflags = UIP_CLOSED;
- nllvdbg("UIP_LAST_ACK TCP state: UIP_CLOSED\n");
-
- (void)uip_tcpcallback(dev, conn, UIP_CLOSE);
- }
- break;
-
- case UIP_FIN_WAIT_1:
- /* The application has closed the connection, but the remote host
- * hasn't closed its end yet. Thus we do nothing but wait for a
- * FIN from the other side.
- */
-
- if (dev->d_len > 0)
- {
- uip_incr32(conn->rcvseq, dev->d_len);
- }
-
- if ((pbuf->flags & TCP_FIN) != 0)
- {
- if ((flags & UIP_ACKDATA) != 0)
- {
- conn->tcpstateflags = UIP_TIME_WAIT;
- conn->timer = 0;
- conn->unacked = 0;
- nllvdbg("TCP state: UIP_TIME_WAIT\n");
- }
- else
- {
- conn->tcpstateflags = UIP_CLOSING;
- nllvdbg("TCP state: UIP_CLOSING\n");
- }
-
- uip_incr32(conn->rcvseq, 1);
- (void)uip_tcpcallback(dev, conn, UIP_CLOSE);
- uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
- return;
- }
- else if ((flags & UIP_ACKDATA) != 0)
- {
- conn->tcpstateflags = UIP_FIN_WAIT_2;
- conn->unacked = 0;
- nllvdbg("TCP state: UIP_FIN_WAIT_2\n");
- goto drop;
- }
-
- if (dev->d_len > 0)
- {
- uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
- return;
- }
- goto drop;
-
- case UIP_FIN_WAIT_2:
- if (dev->d_len > 0)
- {
- uip_incr32(conn->rcvseq, dev->d_len);
- }
-
- if ((pbuf->flags & TCP_FIN) != 0)
- {
- conn->tcpstateflags = UIP_TIME_WAIT;
- conn->timer = 0;
- nllvdbg("TCP state: UIP_TIME_WAIT\n");
-
- uip_incr32(conn->rcvseq, 1);
- (void)uip_tcpcallback(dev, conn, UIP_CLOSE);
- uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
- return;
- }
-
- if (dev->d_len > 0)
- {
- uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
- return;
- }
- goto drop;
-
- case UIP_TIME_WAIT:
- uip_tcpsend(dev, conn, TCP_ACK, UIP_IPTCPH_LEN);
- return;
-
- case UIP_CLOSING:
- if ((flags & UIP_ACKDATA) != 0)
- {
- conn->tcpstateflags = UIP_TIME_WAIT;
- conn->timer = 0;
- nllvdbg("TCP state: UIP_TIME_WAIT\n");
- }
-
- default:
- break;
- }
-
-drop:
- dev->d_len = 0;
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcppoll.c b/nuttx/net/uip/uip_tcppoll.c
deleted file mode 100644
index ddc8ab029..000000000
--- a/nuttx/net/uip/uip_tcppoll.c
+++ /dev/null
@@ -1,127 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcppoll.c
- * Poll for the availability of TCP TX data
- *
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcppoll
- *
- * Description:
- * Poll a TCP connection structure for availability of TX data
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- * conn - The TCP "connection" to poll for TX data
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcppoll(struct uip_driver_s *dev, struct uip_conn *conn)
-{
- uint8_t result;
-
- /* Verify that the connection is established */
-
- if ((conn->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED)
- {
- /* Set up for the callback */
-
- dev->d_snddata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
- dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
-
- dev->d_len = 0;
- dev->d_sndlen = 0;
-
- /* Perfom the callback */
-
- result = uip_tcpcallback(dev, conn, UIP_POLL);
-
- /* Handle the callback response */
-
- uip_tcpappsend(dev, conn, result);
- }
- else
- {
- /* Nothing to do for this connection */
-
- dev->d_len = 0;
- }
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpreadahead.c b/nuttx/net/uip/uip_tcpreadahead.c
deleted file mode 100644
index a304925a8..000000000
--- a/nuttx/net/uip/uip_tcpreadahead.c
+++ /dev/null
@@ -1,130 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpreadahead.c
- *
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/net/uip/uipopt.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP) && (CONFIG_NET_NTCP_READAHEAD_BUFFERS > 0)
-
-#include <queue.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uip.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* These are the pre-allocated read-ahead buffers */
-
-static struct uip_readahead_s g_buffers[CONFIG_NET_NTCP_READAHEAD_BUFFERS];
-
-/* This is the list of available read-ahead buffers */
-
-static sq_queue_t g_freebuffers;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Function: uip_tcpreadaheadinit
- *
- * Description:
- * Initialize the list of free read-ahead buffers
- *
- * Assumptions:
- * Called once early initialization.
- *
- ****************************************************************************/
-
-void uip_tcpreadaheadinit(void)
-{
- int i;
-
- sq_init(&g_freebuffers);
- for (i = 0; i < CONFIG_NET_NTCP_READAHEAD_BUFFERS; i++)
- {
- sq_addfirst(&g_buffers[i].rh_node, &g_freebuffers);
- }
-}
-
-/****************************************************************************
- * Function: uip_tcpreadaheadalloc
- *
- * Description:
- * Allocate a TCP read-ahead buffer by taking a pre-allocated buffer from
- * the free list. This function is called from TCP logic when new,
- * incoming TCP data is received but there is no user logic recving the
- * the data. Note: malloc() cannot be used because this function is
- * called from interrupt level.
- *
- * Assumptions:
- * Called from interrupt level with interrupts disabled.
- *
- ****************************************************************************/
-
-struct uip_readahead_s *uip_tcpreadaheadalloc(void)
-{
- return (struct uip_readahead_s*)sq_remfirst(&g_freebuffers);
-}
-
-/****************************************************************************
- * Function: uip_tcpreadaheadrelease
- *
- * Description:
- * Release a TCP read-ahead buffer by returning the buffer to the free list.
- * This function is called from user logic after it is consumed the buffered
- * data.
- *
- * Assumptions:
- * Called from user logic BUT with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcpreadaheadrelease(struct uip_readahead_s *buf)
-{
- sq_addfirst(&buf->rh_node, &g_freebuffers);
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP && CONFIG_NET_NTCP_READAHEAD_BUFFERS*/
diff --git a/nuttx/net/uip/uip_tcpsend.c b/nuttx/net/uip/uip_tcpsend.c
deleted file mode 100644
index 7051d7621..000000000
--- a/nuttx/net/uip/uip_tcpsend.c
+++ /dev/null
@@ -1,369 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpsend.c
- *
- * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <string.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-#define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcpsendcomplete
- *
- * Description:
- * Complete the final portions of the send operation. This function sets
- * up IP header and computes the TCP checksum
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-static void uip_tcpsendcomplete(struct uip_driver_s *dev)
-{
- struct uip_tcpip_hdr *pbuf = BUF;
-
- pbuf->ttl = UIP_TTL;
-
-#ifdef CONFIG_NET_IPv6
-
- /* For IPv6, the IP length field does not include the IPv6 IP header
- * length.
- */
-
- pbuf->len[0] = ((dev->d_len - UIP_IPH_LEN) >> 8);
- pbuf->len[1] = ((dev->d_len - UIP_IPH_LEN) & 0xff);
-
-#else /* CONFIG_NET_IPv6 */
-
- pbuf->len[0] = (dev->d_len >> 8);
- pbuf->len[1] = (dev->d_len & 0xff);
-
-#endif /* CONFIG_NET_IPv6 */
-
- pbuf->urgp[0] = pbuf->urgp[1] = 0;
-
- /* Calculate TCP checksum. */
-
- pbuf->tcpchksum = 0;
- pbuf->tcpchksum = ~(uip_tcpchksum(dev));
-
-#ifdef CONFIG_NET_IPv6
-
- pbuf->vtc = 0x60;
- pbuf->tcf = 0x00;
- pbuf->flow = 0x00;
-
-#else /* CONFIG_NET_IPv6 */
-
- pbuf->vhl = 0x45;
- pbuf->tos = 0;
- pbuf->ipoffset[0] = 0;
- pbuf->ipoffset[1] = 0;
- ++g_ipid;
- pbuf->ipid[0] = g_ipid >> 8;
- pbuf->ipid[1] = g_ipid & 0xff;
-
- /* Calculate IP checksum. */
-
- pbuf->ipchksum = 0;
- pbuf->ipchksum = ~(uip_ipchksum(dev));
-
-#endif /* CONFIG_NET_IPv6 */
-
- nllvdbg("Outgoing TCP packet length: %d (%d)\n",
- dev->d_len, (pbuf->len[0] << 8) | pbuf->len[1]);
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.sent++;
- uip_stat.ip.sent++;
-#endif
-}
-
-/****************************************************************************
- * Name: uip_tcpsendcommon
- *
- * Description:
- * We're done with the input processing. We are now ready to send a reply
- * Our job is to fill in all the fields of the TCP and IP headers before
- * calculating the checksum and finally send the packet.
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- * conn - The TCP connection structure holding connection information
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-static void uip_tcpsendcommon(struct uip_driver_s *dev, struct uip_conn *conn)
-{
- struct uip_tcpip_hdr *pbuf = BUF;
-
- memcpy(pbuf->ackno, conn->rcvseq, 4);
- memcpy(pbuf->seqno, conn->sndseq, 4);
-
- pbuf->proto = UIP_PROTO_TCP;
- pbuf->srcport = conn->lport;
- pbuf->destport = conn->rport;
-
- uiphdr_ipaddr_copy(pbuf->srcipaddr, &dev->d_ipaddr);
- uiphdr_ipaddr_copy(pbuf->destipaddr, &conn->ripaddr);
-
- if (conn->tcpstateflags & UIP_STOPPED)
- {
- /* If the connection has issued uip_stop(), we advertise a zero
- * window so that the remote host will stop sending data.
- */
-
- pbuf->wnd[0] = 0;
- pbuf->wnd[1] = 0;
- }
- else
- {
- pbuf->wnd[0] = ((CONFIG_NET_RECEIVE_WINDOW) >> 8);
- pbuf->wnd[1] = ((CONFIG_NET_RECEIVE_WINDOW) & 0xff);
- }
-
- /* Finish the IP portion of the message, calculate checksums and send
- * the message.
- */
-
- uip_tcpsendcomplete(dev);
-
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcpsend
- *
- * Description:
- * Setup to send a TCP packet
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- * conn - The TCP connection structure holding connection information
- * flags - flags to apply to the TCP header
- * len - length of the message
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcpsend(struct uip_driver_s *dev, struct uip_conn *conn,
- uint16_t flags, uint16_t len)
-{
- struct uip_tcpip_hdr *pbuf = BUF;
-
- pbuf->flags = flags;
- dev->d_len = len;
- pbuf->tcpoffset = (UIP_TCPH_LEN / 4) << 4;
- uip_tcpsendcommon(dev, conn);
-}
-
-/****************************************************************************
- * Name: uip_tcpreset
- *
- * Description:
- * Send a TCP reset (no-data) message
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcpreset(struct uip_driver_s *dev)
-{
- struct uip_tcpip_hdr *pbuf = BUF;
-
- uint16_t tmp16;
- uint8_t seqbyte;
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.rst++;
-#endif
-
- pbuf->flags = TCP_RST | TCP_ACK;
- dev->d_len = UIP_IPTCPH_LEN;
- pbuf->tcpoffset = 5 << 4;
-
- /* Flip the seqno and ackno fields in the TCP header. */
-
- seqbyte = pbuf->seqno[3];
- pbuf->seqno[3] = pbuf->ackno[3];
- pbuf->ackno[3] = seqbyte;
-
- seqbyte = pbuf->seqno[2];
- pbuf->seqno[2] = pbuf->ackno[2];
- pbuf->ackno[2] = seqbyte;
-
- seqbyte = pbuf->seqno[1];
- pbuf->seqno[1] = pbuf->ackno[1];
- pbuf->ackno[1] = seqbyte;
-
- seqbyte = pbuf->seqno[0];
- pbuf->seqno[0] = pbuf->ackno[0];
- pbuf->ackno[0] = seqbyte;
-
- /* We also have to increase the sequence number we are
- * acknowledging. If the least significant byte overflowed, we need
- * to propagate the carry to the other bytes as well.
- */
-
- if (++(pbuf->ackno[3]) == 0)
- {
- if (++(pbuf->ackno[2]) == 0)
- {
- if (++(pbuf->ackno[1]) == 0)
- {
- ++(pbuf->ackno[0]);
- }
- }
- }
-
- /* Swap port numbers. */
-
- tmp16 = pbuf->srcport;
- pbuf->srcport = pbuf->destport;
- pbuf->destport = tmp16;
-
- /* Swap IP addresses. */
-
- uiphdr_ipaddr_copy(pbuf->destipaddr, pbuf->srcipaddr);
- uiphdr_ipaddr_copy(pbuf->srcipaddr, &dev->d_ipaddr);
-
- /* And send out the RST packet */
-
- uip_tcpsendcomplete(dev);
-}
-
-/****************************************************************************
- * Name: uip_tcpack
- *
- * Description:
- * Send the SYN or SYNACK response.
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- * conn - The TCP connection structure holding connection information
- * ack - The ACK response to send
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcpack(struct uip_driver_s *dev, struct uip_conn *conn, uint8_t ack)
-{
- struct uip_tcpip_hdr *pbuf = BUF;
-
- /* Save the ACK bits */
-
- pbuf->flags = ack;
-
- /* We send out the TCP Maximum Segment Size option with our ack. */
-
- pbuf->optdata[0] = TCP_OPT_MSS;
- pbuf->optdata[1] = TCP_OPT_MSS_LEN;
- pbuf->optdata[2] = (UIP_TCP_MSS) / 256;
- pbuf->optdata[3] = (UIP_TCP_MSS) & 255;
- dev->d_len = UIP_IPTCPH_LEN + TCP_OPT_MSS_LEN;
- pbuf->tcpoffset = ((UIP_TCPH_LEN + TCP_OPT_MSS_LEN) / 4) << 4;
-
- /* Complete the common portions of the TCP message */
-
- uip_tcpsendcommon(dev, conn);
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcpseqno.c b/nuttx/net/uip/uip_tcpseqno.c
deleted file mode 100644
index 2eca06e85..000000000
--- a/nuttx/net/uip/uip_tcpseqno.c
+++ /dev/null
@@ -1,173 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcpseqno.c
- *
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Large parts of this file were leveraged from uIP logic:
- *
- * 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Compilation Switches
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Public Data
- ****************************************************************************/
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* g_tcpsequence is used to generate initial TCP sequence numbers */
-
-static uint32_t g_tcpsequence;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcpsetsequence
- *
- * Description:
- * Set the TCP/IP sequence number
- *
- * Assumptions:
- * This function may called from the interrupt level
- *
- ****************************************************************************/
-
-void uip_tcpsetsequence(FAR uint8_t *seqno, uint32_t value)
-{
- /* Copy the sequence number in network (big-endian) order */
-
- *seqno++ = value >> 24;
- *seqno++ = (value >> 16) & 0xff;
- *seqno++ = (value >> 8) & 0xff;
- *seqno = value & 0xff;
-}
-
-/****************************************************************************
- * Name: uip_tcpgetsequence
- *
- * Description:
- * Get the TCP/IP sequence number
- *
- * Assumptions:
- * This function may called from the interrupt level
- *
- ****************************************************************************/
-
-uint32_t uip_tcpgetsequence(FAR uint8_t *seqno)
-{
- uint32_t value;
-
- /* Combine the sequence number from network (big-endian) order */
-
- value = (uint32_t)seqno[0] << 24 |
- (uint32_t)seqno[1] << 16 |
- (uint32_t)seqno[2] << 8 |
- (uint32_t)seqno[3];
- return value;
-}
-
-/****************************************************************************
- * Name: uip_tcpaddsequence
- *
- * Description:
- * Add the length to get the next TCP sequence number.
- *
- * Assumptions:
- * This function may called from the interrupt level
- *
- ****************************************************************************/
-
-uint32_t uip_tcpaddsequence(FAR uint8_t *seqno, uint16_t len)
-{
- return uip_tcpgetsequence(seqno) + (uint32_t)len;
-}
-
-/****************************************************************************
- * Name: uip_tcpinitsequence
- *
- * Description:
- * Set the (initial) the TCP/IP sequence number when a TCP connection is
- * established.
- *
- * Assumptions:
- * This function may called from the interrupt level
- *
- ****************************************************************************/
-
-void uip_tcpinitsequence(FAR uint8_t *seqno)
-{
- uip_tcpsetsequence(seqno, g_tcpsequence);
-}
-
-/****************************************************************************
- * Name: uip_tcpnextsequence
- *
- * Description:
- * Increment the TCP/IP sequence number
- *
- * Assumptions:
- * This function is called from the interrupt level
- *
- ****************************************************************************/
-
-void uip_tcpnextsequence(void)
-{
- g_tcpsequence++;
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_tcptimer.c b/nuttx/net/uip/uip_tcptimer.c
deleted file mode 100644
index a0772136e..000000000
--- a/nuttx/net/uip/uip_tcptimer.c
+++ /dev/null
@@ -1,250 +0,0 @@
-/****************************************************************************
- * net/uip/uip_tcptimer.c
- * Poll for the availability of TCP TX data
- *
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_TCP)
-
-#include <stdint.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Variables
- ****************************************************************************/
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_tcptimer
- *
- * Description:
- * Handle a TCP timer expiration for the provided TCP connection
- *
- * Parameters:
- * dev - The device driver structure to use in the send operation
- * conn - The TCP "connection" to poll for TX data
- * hsed - The polling interval in halves of a second
- *
- * Return:
- * None
- *
- * Assumptions:
- * Called from the interrupt level or with interrupts disabled.
- *
- ****************************************************************************/
-
-void uip_tcptimer(struct uip_driver_s *dev, struct uip_conn *conn, int hsec)
-{
- uint8_t result;
-
- dev->d_snddata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
- dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
-
- /* Increase the TCP sequence number */
-
- uip_tcpnextsequence();
-
- /* Reset the length variables. */
-
- dev->d_len = 0;
- dev->d_sndlen = 0;
-
- /* Check if the connection is in a state in which we simply wait
- * for the connection to time out. If so, we increase the
- * connection's timer and remove the connection if it times
- * out.
- */
-
- if (conn->tcpstateflags == UIP_TIME_WAIT || conn->tcpstateflags == UIP_FIN_WAIT_2)
- {
- /* Increment the connection timer */
-
- (conn->timer) += hsec;
- if (conn->timer >= UIP_TIME_WAIT_TIMEOUT)
- {
- conn->tcpstateflags = UIP_CLOSED;
- nllvdbg("TCP state: UIP_CLOSED\n");
- }
- }
- else if (conn->tcpstateflags != UIP_CLOSED)
- {
- /* If the connection has outstanding data, we increase the connection's
- * timer and see if it has reached the RTO value in which case we
- * retransmit.
- */
-
- if (conn->unacked > 0)
- {
- /* The connection has outstanding data */
-
- if (conn->timer > hsec)
- {
- /* Will not yet decrement to zero */
-
- conn->timer -= hsec;
- }
- else
- {
- /* Will decrement to zero */
-
- conn->timer = 0;
-
- /* Should we close the connection? */
-
- if (conn->nrtx == UIP_MAXRTX ||
- ((conn->tcpstateflags == UIP_SYN_SENT ||
- conn->tcpstateflags == UIP_SYN_RCVD) &&
- conn->nrtx == UIP_MAXSYNRTX))
- {
- conn->tcpstateflags = UIP_CLOSED;
- nllvdbg("TCP state: UIP_CLOSED\n");
-
- /* We call uip_tcpcallback() with UIP_TIMEDOUT to
- * inform the application that the connection has
- * timed out.
- */
-
- result = uip_tcpcallback(dev, conn, UIP_TIMEDOUT);
-
- /* We also send a reset packet to the remote host. */
-
- uip_tcpsend(dev, conn, TCP_RST | TCP_ACK, UIP_IPTCPH_LEN);
- goto done;
- }
-
- /* Exponential backoff. */
-
- conn->timer = UIP_RTO << (conn->nrtx > 4 ? 4: conn->nrtx);
- (conn->nrtx)++;
-
- /* Ok, so we need to retransmit. We do this differently
- * depending on which state we are in. In ESTABLISHED, we
- * call upon the application so that it may prepare the
- * data for the retransmit. In SYN_RCVD, we resend the
- * SYNACK that we sent earlier and in LAST_ACK we have to
- * retransmit our FINACK.
- */
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.tcp.rexmit++;
-#endif
- switch(conn->tcpstateflags & UIP_TS_MASK)
- {
- case UIP_SYN_RCVD:
- /* In the SYN_RCVD state, we should retransmit our
- * SYNACK.
- */
-
- uip_tcpack(dev, conn, TCP_ACK | TCP_SYN);
- goto done;
-
- case UIP_SYN_SENT:
- /* In the SYN_SENT state, we retransmit out SYN. */
-
- uip_tcpack(dev, conn, TCP_SYN);
- goto done;
-
- case UIP_ESTABLISHED:
- /* In the ESTABLISHED state, we call upon the application
- * to do the actual retransmit after which we jump into
- * the code for sending out the packet.
- */
-
- result = uip_tcpcallback(dev, conn, UIP_REXMIT);
- uip_tcprexmit(dev, conn, result);
- goto done;
-
- case UIP_FIN_WAIT_1:
- case UIP_CLOSING:
- case UIP_LAST_ACK:
- /* In all these states we should retransmit a FINACK. */
-
- uip_tcpsend(dev, conn, TCP_FIN | TCP_ACK, UIP_IPTCPH_LEN);
- goto done;
- }
- }
- }
-
- /* The connection does not have outstanding data */
-
- else if ((conn->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED)
- {
- /* If there was no need for a retransmission, we poll the
- * application for new data.
- */
-
- result = uip_tcpcallback(dev, conn, UIP_POLL);
- uip_tcpappsend(dev, conn, result);
- goto done;
- }
- }
-
- /* Nothing to be done */
-
- dev->d_len = 0;
-
-done:
- return;
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_TCP */
diff --git a/nuttx/net/uip/uip_udpcallback.c b/nuttx/net/uip/uip_udpcallback.c
deleted file mode 100644
index ef4b36e49..000000000
--- a/nuttx/net/uip/uip_udpcallback.c
+++ /dev/null
@@ -1,90 +0,0 @@
-/****************************************************************************
- * net/uip/uip_udpcallback.c
- *
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
-
-#include <stdint.h>
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#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, struct uip_udp_conn *conn,
- uint16_t flags)
-{
- nllvdbg("flags: %04x\n", flags);
-
- /* Some sanity checking */
-
- if (conn)
- {
- /* Perform the callback */
-
- flags = uip_callbackexecute(dev, conn, flags, conn->list);
- }
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/uip/uip_udpconn.c b/nuttx/net/uip/uip_udpconn.c
deleted file mode 100644
index 3c4ee5add..000000000
--- a/nuttx/net/uip/uip_udpconn.c
+++ /dev/null
@@ -1,492 +0,0 @@
-/****************************************************************************
- * net/uip/uip_udpconn.c
- *
- * Copyright (C) 2007-2009, 2011-2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Large parts of this file were leveraged from uIP logic:
- *
- * 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.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * Compilation Switches
- ****************************************************************************/
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
-
-#include <stdint.h>
-#include <string.h>
-#include <semaphore.h>
-#include <assert.h>
-#include <errno.h>
-#include <debug.h>
-
-#include <arch/irq.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* The array containing all uIP UDP connections. */
-
-struct uip_udp_conn g_udp_connections[CONFIG_NET_UDP_CONNS];
-
-/* A list of all free UDP connections */
-
-static dq_queue_t g_free_udp_connections;
-static sem_t g_free_sem;
-
-/* A list of all allocated UDP connections */
-
-static dq_queue_t g_active_udp_connections;
-
-/* Last port used by a UDP connection connection. */
-
-static uint16_t g_last_udp_port;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: _uip_semtake() and _uip_semgive()
- *
- * Description:
- * Take/give semaphore
- *
- ****************************************************************************/
-
-static inline void _uip_semtake(sem_t *sem)
-{
- /* Take the semaphore (perhaps waiting) */
-
- while (uip_lockedwait(sem) != 0)
- {
- /* The only case that an error should occur here is if
- * the wait was awakened by a signal.
- */
-
- ASSERT(*get_errno_ptr() == EINTR);
- }
-}
-
-#define _uip_semgive(sem) sem_post(sem)
-
-/****************************************************************************
- * Name: uip_find_conn()
- *
- * Description:
- * Find the UDP connection that uses this local port number. Called only
- * from user user level code, but with interrupts disabled.
- *
- ****************************************************************************/
-
-static struct uip_udp_conn *uip_find_conn(uint16_t portno)
-{
- int i;
-
- /* Now search each connection structure.*/
-
- for (i = 0; i < CONFIG_NET_UDP_CONNS; i++)
- {
- if (g_udp_connections[ i ].lport == portno)
- {
- return &g_udp_connections[ i ];
- }
- }
-
- return NULL;
-}
-
-/****************************************************************************
- * Name: uip_selectport()
- *
- * Description:
- * Select an unused port number.
- *
- * NOTE that in prinicple this function could fail if there is no available
- * port number. There is no check for that case and it would actually
- * in an infinite loop if that were the case. In this simple, small UDP
- * implementation, it is reasonable to assume that that error cannot happen
- * and that a port number will always be available.
- *
- * Input Parameters:
- * None
- *
- * Return:
- * Next available port number
- *
- ****************************************************************************/
-
-static uint16_t uip_selectport(void)
-{
- uint16_t portno;
-
- /* Find an unused local port number. Loop until we find a valid
- * listen port number that is not being used by any other connection.
- */
-
- uip_lock_t flags = uip_lock();
- 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_conn(htons(g_last_udp_port)));
-
- /* Initialize and return the connection structure, bind it to the
- * port number
- */
-
- portno = g_last_udp_port;
- uip_unlock(flags);
-
- return portno;
-}
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: uip_udpinit()
- *
- * Description:
- * Initialize the UDP connection structures. Called once and only from
- * the UIP layer.
- *
- ****************************************************************************/
-
-void uip_udpinit(void)
-{
- int i;
-
- /* Initialize the queues */
-
- dq_init(&g_free_udp_connections);
- dq_init(&g_active_udp_connections);
- sem_init(&g_free_sem, 0, 1);
-
- for (i = 0; i < CONFIG_NET_UDP_CONNS; i++)
- {
- /* Mark the connection closed and move it to the free list */
-
- g_udp_connections[i].lport = 0;
- dq_addlast(&g_udp_connections[i].node, &g_free_udp_connections);
- }
-
- g_last_udp_port = 1024;
-}
-
-/****************************************************************************
- * Name: uip_udpalloc()
- *
- * Description:
- * Alloc a new, uninitialized UDP connection structure.
- *
- ****************************************************************************/
-
-struct uip_udp_conn *uip_udpalloc(void)
-{
- struct uip_udp_conn *conn;
-
- /* The free list is only accessed from user, non-interrupt level and
- * is protected by a semaphore (that behaves like a mutex).
- */
-
- _uip_semtake(&g_free_sem);
- conn = (struct uip_udp_conn *)dq_remfirst(&g_free_udp_connections);
- if (conn)
- {
- /* Make sure that the connection is marked as uninitialized */
-
- conn->lport = 0;
- }
- _uip_semgive(&g_free_sem);
- return conn;
-}
-
-/****************************************************************************
- * Name: uip_udpfree()
- *
- * Description:
- * Free a UDP connection structure that is no longer in use. This should be
- * done by the implementation of close(). uip_udpdisable must have been
- * previously called.
- *
- ****************************************************************************/
-
-void uip_udpfree(struct uip_udp_conn *conn)
-{
- /* The free list is only accessed from user, non-interrupt level and
- * is protected by a semaphore (that behaves like a mutex).
- */
-
- DEBUGASSERT(conn->crefs == 0);
-
- _uip_semtake(&g_free_sem);
- conn->lport = 0;
- dq_addlast(&conn->node, &g_free_udp_connections);
- _uip_semgive(&g_free_sem);
-}
-
-/****************************************************************************
- * Name: uip_udpactive()
- *
- * 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_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf)
-{
- struct uip_udp_conn *conn = (struct uip_udp_conn *)g_active_udp_connections.head;
-
- while (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
- * destination port number in the received packet. If the two port
- * numbers match, the remote port number is checked if the
- * connection is bound to a remote port. Finally, if the
- * connection is bound to a remote IP address, the source IP
- * address of the packet is checked.
- */
-
- if (conn->lport != 0 && buf->destport == conn->lport &&
- (conn->rport == 0 || buf->srcport == conn->rport) &&
- (uip_ipaddr_cmp(conn->ripaddr, g_allzeroaddr) ||
- uip_ipaddr_cmp(conn->ripaddr, g_alloneaddr) ||
- uiphdr_ipaddr_cmp(buf->srcipaddr, &conn->ripaddr)))
- {
- /* Matching connection found.. return a reference to it */
-
- break;
- }
-
- /* Look at the next active connection */
-
- conn = (struct uip_udp_conn *)conn->node.flink;
- }
-
- return conn;
-}
-
-/****************************************************************************
- * Name: uip_nextudpconn()
- *
- * Description:
- * Traverse the list of allocated UDP connections
- *
- * Assumptions:
- * This function is called from UIP logic at interrupt level (or with
- * interrupts disabled).
- *
- ****************************************************************************/
-
-struct uip_udp_conn *uip_nextudpconn(struct uip_udp_conn *conn)
-{
- if (!conn)
- {
- return (struct uip_udp_conn *)g_active_udp_connections.head;
- }
- else
- {
- return (struct uip_udp_conn *)conn->node.flink;
- }
-}
-
-/****************************************************************************
- * Name: uip_udpbind()
- *
- * Description:
- * This function implements the UIP specific parts of the standard UDP
- * bind() operation.
- *
- * Assumptions:
- * This function is called from normal user level code.
- *
- ****************************************************************************/
-
-#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
-{
- int ret = -EADDRINUSE;
- uip_lock_t flags;
-
- /* Is the user requesting to bind to any port? */
-
- if (!addr->sin_port)
- {
- /* Yes.. Find an unused local port number */
-
- conn->lport = htons(uip_selectport());
- ret = OK;
- }
- else
- {
- /* Interrupts must be disabled while access the UDP connection list */
-
- flags = uip_lock();
-
- /* Is any other UDP connection bound to this port? */
-
- if (!uip_find_conn(addr->sin_port))
- {
- /* No.. then bind the socket to the port */
-
- conn->lport = addr->sin_port;
- ret = OK;
- }
-
- uip_unlock(flags);
- }
- return ret;
-}
-
-/****************************************************************************
- * Name: uip_udpconnect()
- *
- * Description:
- * 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.
- *
- * uip_udpenable() must be called before the connection is made active (i.e.,
- * is eligible for callbacks.
- *
- * addr The address of the remote host.
- *
- * Assumptions:
- * This function is called user code. Interrupts may be enabled.
- *
- ****************************************************************************/
-
-#ifdef CONFIG_NET_IPv6
-int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in6 *addr)
-#else
-int uip_udpconnect(struct uip_udp_conn *conn, const struct sockaddr_in *addr)
-#endif
-{
- /* Has this address already been bound to a local port (lport)? */
-
- if (!conn->lport)
- {
- /* No.. Find an unused local port number and bind it to the
- * connection structure.
- */
-
- conn->lport = htons(uip_selectport());
- }
-
- /* Is there a remote port (rport) */
-
- if (addr)
- {
- conn->rport = addr->sin_port;
- uip_ipaddr_copy(conn->ripaddr, addr->sin_addr.s_addr);
- }
- else
- {
- conn->rport = 0;
- uip_ipaddr_copy(conn->ripaddr, g_allzeroaddr);
- }
-
- conn->ttl = UIP_TTL;
- return OK;
-}
-
-/****************************************************************************
- * Name: uip_udpenable() uip_udpdisable.
- *
- * Description:
- * Enable/disable callbacks for the specified connection
- *
- * Assumptions:
- * This function is called user code. Interrupts may be enabled.
- *
- ****************************************************************************/
-
-void uip_udpenable(struct uip_udp_conn *conn)
-{
- /* Add the connection structure to the active connectionlist. This list
- * is modifiable from interrupt level, we we must disable interrupts to
- * access it safely.
- */
-
- uip_lock_t flags = uip_lock();
- dq_addlast(&conn->node, &g_active_udp_connections);
- uip_unlock(flags);
-}
-
-void uip_udpdisable(struct uip_udp_conn *conn)
-{
- /* Remove the connection structure from the active connectionlist. This list
- * is modifiable from interrupt level, we we must disable interrupts to
- * access it safely.
- */
-
- uip_lock_t flags = uip_lock();
- dq_rem(&conn->node, &g_active_udp_connections);
- uip_unlock(flags);
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/uip/uip_udpinput.c b/nuttx/net/uip/uip_udpinput.c
deleted file mode 100644
index fa7bf8c41..000000000
--- a/nuttx/net/uip/uip_udpinput.c
+++ /dev/null
@@ -1,156 +0,0 @@
-/****************************************************************************
- * net/uip/uip_udpinput.c
- * Handling incoming UDP input
- *
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
-
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor 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)
-{
- struct uip_udp_conn *conn;
- struct uip_udpip_hdr *pbuf = UDPBUF;
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.udp.recv++;
-#endif
-
- /* 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 (pbuf->udpchksum != 0 && uip_udpchksum(dev) != 0xffff)
- {
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.udp.drop++;
- uip_stat.udp.chkerr++;
-#endif
- nlldbg("Bad UDP checksum\n");
- dev->d_len = 0;
- }
- else
-#endif
- {
- /* Demultiplex this UDP packet between the UDP "connections". */
-
- conn = uip_udpactive(pbuf);
- if (conn)
- {
- /* Setup for the application callback */
-
- 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_udpcallback(dev, conn, UIP_NEWDATA);
-
- /* If the application has data to send, setup the UDP/IP header */
-
- if (dev->d_sndlen > 0)
- {
- uip_udpsend(dev, conn);
- }
- }
- else
- {
- nlldbg("No listener on UDP port\n");
- 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
deleted file mode 100644
index 05c2508bc..000000000
--- a/nuttx/net/uip/uip_udppoll.c
+++ /dev/null
@@ -1,126 +0,0 @@
-/****************************************************************************
- * net/uip/uip_udppoll.c
- * Poll for the availability of UDP TX data
- *
- * Copyright (C) 2007-2009 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
-
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor 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 */
-
- 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_udpcallback(dev, conn, UIP_POLL);
-
- /* If the application has data to send, setup the UDP/IP header */
-
- if (dev->d_sndlen > 0)
- {
- uip_udpsend(dev, conn);
- return;
- }
- }
-
- /* Make sure that d_len is zero meaning that there is nothing to be sent */
-
- dev->d_len = 0;
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_UDP */
diff --git a/nuttx/net/uip/uip_udpsend.c b/nuttx/net/uip/uip_udpsend.c
deleted file mode 100644
index 9ba8ec8f5..000000000
--- a/nuttx/net/uip/uip_udpsend.c
+++ /dev/null
@@ -1,177 +0,0 @@
-/****************************************************************************
- * net/uip/uip_udpsend.c
- *
- * Copyright (C) 2007-2009, 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Adapted for NuttX from logic in uIP which also has a BSD-like license:
- *
- * Original author Adam Dunkels <adam@dunkels.com>
- * 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 <nuttx/config.h>
-#if defined(CONFIG_NET) && defined(CONFIG_NET_UDP)
-
-#include <debug.h>
-
-#include <nuttx/net/uip/uipopt.h>
-#include <nuttx/net/uip/uip.h>
-#include <nuttx/net/uip/uip-arch.h>
-
-#include "uip_internal.h"
-
-/****************************************************************************
- * Pre-processor 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)
-{
- struct uip_udpip_hdr *pudpbuf = UDPBUF;
-
- 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
-
- pudpbuf->vtc = 0x60;
- pudpbuf->tcf = 0x00;
- pudpbuf->flow = 0x00;
- pudpbuf->len[0] = (dev->d_sndlen >> 8);
- pudpbuf->len[1] = (dev->d_sndlen & 0xff);
- pudpbuf->nexthdr = UIP_PROTO_UDP;
- pudpbuf->hoplimit = conn->ttl;
-
- uip_ipaddr_copy(pudpbuf->srcipaddr, &dev->d_ipaddr);
- uip_ipaddr_copy(pudpbuf->destipaddr, &conn->ripaddr);
-
-#else /* CONFIG_NET_IPv6 */
-
- pudpbuf->vhl = 0x45;
- pudpbuf->tos = 0;
- pudpbuf->len[0] = (dev->d_len >> 8);
- pudpbuf->len[1] = (dev->d_len & 0xff);
- ++g_ipid;
- pudpbuf->ipid[0] = g_ipid >> 8;
- pudpbuf->ipid[1] = g_ipid & 0xff;
- pudpbuf->ipoffset[0] = 0;
- pudpbuf->ipoffset[1] = 0;
- pudpbuf->ttl = conn->ttl;
- pudpbuf->proto = UIP_PROTO_UDP;
-
- uiphdr_ipaddr_copy(pudpbuf->srcipaddr, &dev->d_ipaddr);
- uiphdr_ipaddr_copy(pudpbuf->destipaddr, &conn->ripaddr);
-
- /* Calculate IP checksum. */
-
- pudpbuf->ipchksum = 0;
- pudpbuf->ipchksum = ~(uip_ipchksum(dev));
-
-#endif /* CONFIG_NET_IPv6 */
-
- /* Initialize the UDP header */
-
- pudpbuf->srcport = conn->lport;
- pudpbuf->destport = conn->rport;
- pudpbuf->udplen = HTONS(dev->d_sndlen + UIP_UDPH_LEN);
-
-#ifdef CONFIG_NET_UDP_CHECKSUMS
- /* Calculate UDP checksum. */
-
- pudpbuf->udpchksum = 0;
- pudpbuf->udpchksum = ~(uip_udpchksum(dev));
- if (pudpbuf->udpchksum == 0)
- {
- pudpbuf->udpchksum = 0xffff;
- }
-#else
- pudpbuf->udpchksum = 0;
-#endif
-
- nllvdbg("Outgoing UDP packet length: %d (%d)\n",
- dev->d_len, (pudpbuf->len[0] << 8) | pudpbuf->len[1]);
-
-#ifdef CONFIG_NET_STATISTICS
- uip_stat.udp.sent++;
- uip_stat.ip.sent++;
-#endif
- }
-}
-
-#endif /* CONFIG_NET && CONFIG_NET_UDP */