summaryrefslogtreecommitdiff
path: root/nuttx/net/uip/uip-fw.c
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/net/uip/uip-fw.c')
-rw-r--r--nuttx/net/uip/uip-fw.c508
1 files changed, 0 insertions, 508 deletions
diff --git a/nuttx/net/uip/uip-fw.c b/nuttx/net/uip/uip-fw.c
deleted file mode 100644
index fa9b5fc4e..000000000
--- a/nuttx/net/uip/uip-fw.c
+++ /dev/null
@@ -1,508 +0,0 @@
-/* uip-fw.c
- * uIP packet forwarding.
- * Author: Adam Dunkels <adam@sics.se>
- *
- * This file implements a number of simple functions which do packet
- * forwarding over multiple network interfaces with uIP.
- *
- * Copyright (c) 2004, 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 <nuttx/config.h>
-#include <debug.h>
-#include <net/uip/uip.h>
-#include <net/uip/uip-arch.h>
-
-#include "uip-fw.h"
-
-#include <string.h> /* for memcpy() */
-
-/* The list of registered network interfaces. */
-
-static struct uip_fw_netif *netifs = NULL;
-
-/* A pointer to the default network interface. */
-
-static struct uip_fw_netif *defaultnetif = NULL;
-
-struct tcpip_hdr
-{
- /* IP header */
-
- uint8 vhl;
- uint8 tos;
- uint16 len;
- uint16 ipid;
- uint16 ipoffset;
- uint8 ttl;
- uint8 proto;
- uint16 ipchksum;
- in_addr_t srcipaddr;
- in_addr_t destipaddr;
-
- /* TCP header */
-
- uint16 srcport;
- uint16 destport;
- uint8 seqno[4];
- uint8 ackno[4];
- uint8 tcpoffset;
- uint8 flags;
- uint8 wnd[2];
- uint16 tcpchksum;
- uint8 urgp[2];
- uint8 optdata[4];
-};
-
-struct icmpip_hdr
-{
- /* IP header */
-
- uint8 vhl;
- uint8 tos;
- uint8 len[2];
- uint8 ipid[2];
- uint8 ipoffset[2];
- uint8 ttl;
- uint8 proto;
- uint16 ipchksum;
- in_addr_t srcipaddr;
- in_addr_t destipaddr;
-
- /* ICMP (echo) header */
-
- uint8 type, icode;
- uint16 icmpchksum;
- uint16 id, seqno;
- uint8 payload[1];
-};
-
-/* ICMP ECHO. */
-
-#define ICMP_ECHO 8
-
-/* ICMP TIME-EXCEEDED. */
-
-#define ICMP_TE 11
-
-/* Pointer to the TCP/IP headers of the packet in the d_buf buffer. */
-
-#define BUF ((struct tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-
-/* Pointer to the ICMP/IP headers of the packet in the d_buf buffer. */
-
-#define ICMPBUF ((struct icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-
-/* Certain fields of an IP packet that are used for identifying
- * duplicate packets.
- */
-
-struct fwcache_entry
-{
- uint16 timer;
- in_addr_t srcipaddr;
- in_addr_t destipaddr;
- uint16 ipid;
- uint8 proto;
- uint8 unused;
-
-#if notdef
- uint16 payload[2];
-#endif
-
-#if UIP_REASSEMBLY > 0
- uint16 len, offset;
-#endif
-};
-
-/* The number of packets to remember when looking for duplicates. */
-#ifdef CONFIG_NET_FWCACHE_SIZE
-# define FWCACHE_SIZE CONFIG_NET_FWCACHE_SIZE
-#else
-# define FWCACHE_SIZE 2
-#endif
-
-/* A cache of packet header fields which are used for
- * identifying duplicate packets.
- */
-
-static struct fwcache_entry fwcache[FWCACHE_SIZE];
-
-/* The time that a packet cache is active. */
-#define FW_TIME 20
-
-/* Initialize the uIP packet forwarding module. */
-
-void uip_fw_init(void)
-{
- struct uip_fw_netif *t;
- defaultnetif = NULL;
- while(netifs != NULL)
- {
- t = netifs;
- netifs = netifs->next;
- t->next = NULL;
- }
-}
-
-/* Send out an ICMP TIME-EXCEEDED message.
- *
- * This function replaces the packet in the d_buf buffer with the
- * ICMP packet.
- */
-
-static void time_exceeded(struct uip_driver_s *dev)
-{
- in_addr_t tmp_addr;
-
- /* We don't send out ICMP errors for ICMP messages. */
-
- if (ICMPBUF->proto == UIP_PROTO_ICMP)
- {
- dev->d_len = 0;
- return;
- }
-
- /* Copy fields from packet header into payload of this ICMP packet. */
-
- memcpy(&(ICMPBUF->payload[0]), ICMPBUF, 28);
-
- /* Set the ICMP type and code. */
-
- ICMPBUF->type = ICMP_TE;
- ICMPBUF->icode = 0;
-
- /* Calculate the ICMP checksum. */
-
- ICMPBUF->icmpchksum = 0;
- ICMPBUF->icmpchksum = ~uip_chksum((uint16 *)&(ICMPBUF->type), 36);
-
- /* Set the IP destination address to be the source address of the
- * original packet.
- */
-
- tmp_addr = BUF->destipaddr;
- BUF->destipaddr = BUF->srcipaddr;
- BUF->srcipaddr = tmp_addr;
-
- /* Set our IP address as the source address. */
-
- BUF->srcipaddr = dev->d_ipaddr;
-
- /* The size of the ICMP time exceeded packet is 36 + the size of the
- * IP header (20) = 56.
- */
-
- dev->d_len = 56;
- ICMPBUF->len[0] = 0;
- ICMPBUF->len[1] = dev->d_len;
-
- /* Fill in the other fields in the IP header. */
-
- ICMPBUF->vhl = 0x45;
- ICMPBUF->tos = 0;
- ICMPBUF->ipoffset[0] = ICMPBUF->ipoffset[1] = 0;
- ICMPBUF->ttl = UIP_TTL;
- ICMPBUF->proto = UIP_PROTO_ICMP;
-
- /* Calculate IP checksum. */
-
- ICMPBUF->ipchksum = 0;
- ICMPBUF->ipchksum = ~(uip_ipchksum(dev));
-}
-
-/* Register a packet in the forwarding cache so that it won't be
- * forwarded again.
- */
-
-static void fwcache_register(struct uip_driver_s *dev)
-{
- struct fwcache_entry *fw;
- int i, oldest;
-
- oldest = FW_TIME;
- fw = NULL;
-
- /* Find the oldest entry in the cache. */
-
- for (i = 0; i < FWCACHE_SIZE; ++i)
- {
- if (fwcache[i].timer == 0)
- {
- fw = &fwcache[i];
- break;
- }
- else if (fwcache[i].timer <= oldest)
- {
- fw = &fwcache[i];
- oldest = fwcache[i].timer;
- }
- }
-
- fw->timer = FW_TIME;
- fw->ipid = BUF->ipid;
- fw->srcipaddr = BUF->srcipaddr;
- fw->destipaddr = BUF->destipaddr;
- fw->proto = BUF->proto;
-#if notdef
- fw->payload[0] = BUF->srcport;
- fw->payload[1] = BUF->destport;
-#endif
-#if UIP_REASSEMBLY > 0
- fw->len = BUF->len;
- fw->offset = BUF->ipoffset;
-#endif
-}
-
-/* Find a network interface for the IP packet in d_buf. */
-
-static struct uip_fw_netif *find_netif (struct uip_driver_s *dev)
-{
- struct uip_fw_netif *netif;
-
- /* Walk through every network interface to check for a match. */
-
- for (netif = netifs; netif != NULL; netif = netif->next)
- {
- if (uip_ipaddr_maskcmp(BUF->destipaddr, netif->ipaddr, netif->netmask))
- {
- /* If there was a match, we break the loop. */
-
- return netif;
- }
- }
-
- /* If no matching netif was found, we use default netif. */
-
- return defaultnetif;
-}
-
-/* Output an IP packet on the correct network interface.
- *
- * The IP packet should be present in the d_buf buffer and its
- * length in the d_len field.
- *
- * Return: UIP_FW_ZEROLEN Indicates that a zero-length packet
- * transmission was attempted and that no packet was sent.
- *
- * Return: UIP_FW_NOROUTE No suitable network interface could be found
- * for the outbound packet, and the packet was not sent.
- *
- * Return: The return value from the actual network interface output
- * function is passed unmodified as a return value.
- */
-
-uint8 uip_fw_output(struct uip_driver_s *dev)
-{
- struct uip_fw_netif *netif;
-
- if (dev->d_len == 0)
- {
- return UIP_FW_ZEROLEN;
- }
-
- fwcache_register(dev);
-
-#ifdef CONFIG_NET_BROADCAST
- /* Link local broadcasts go out on all interfaces. */
-
- if (/*BUF->proto == UIP_PROTO_UDP &&*/
- BUF->destipaddr[0] == 0xffff &&
- BUF->destipaddr[1] == 0xffff)
- {
- if (defaultnetif != NULL)
- {
- defaultnetif->output();
- }
- for (netif = netifs; netif != NULL; netif = netif->next)
- {
- netif->output();
- }
- return UIP_FW_OK;
- }
-#endif
-
- netif = find_netif (dev);
- dbg("netif: %p output: %p len: %d\n", netif, netif->output, dev->d_len);
-
- if (netif == NULL)
- {
- return UIP_FW_NOROUTE;
- }
-
- /* If we now have found a suitable network interface, we call its
- * output function to send out the packet.
- */
-
- return netif->output();
-}
-
-/* Forward an IP packet in the d_buf buffer.
- *
- * Return: UIP_FW_FORWARDED if the packet was forwarded, UIP_FW_LOCAL if
- * the packet should be processed locally.
- */
-
-uint8 uip_fw_forward(struct uip_driver_s *dev)
-{
- struct fwcache_entry *fw;
-
- /* First check if the packet is destined for ourselves and return 0
- * to indicate that the packet should be processed locally.
- */
-
- if (BUF->destipaddr == dev->d_ipaddr)
- {
- return UIP_FW_LOCAL;
- }
-
- /* If we use ping IP address configuration, and our IP address is
- * not yet configured, we should intercept all ICMP echo packets.
- */
-
-#ifdef CONFIG_NET_PINGADDRCONF
- if (dev->d_ipaddr == 0 && BUF->proto == UIP_PROTO_ICMP && ICMPBUF->type == ICMP_ECHO)
- {
- return UIP_FW_LOCAL;
- }
-#endif
-
- /* Check if the packet is in the forwarding cache already, and if so
- we drop it. */
-
- for (fw = fwcache; fw < &fwcache[FWCACHE_SIZE]; ++fw)
- {
- if (fw->timer != 0 &&
-#if UIP_REASSEMBLY > 0
- fw->len == BUF->len &&
- fw->offset == BUF->ipoffset &&
-#endif
- fw->ipid == BUF->ipid &&
- fw->srcipaddr == BUF->srcipaddr &&
- fw->destipaddr == BUF->destipaddr &&
-#if notdef
- fw->payload[0] == BUF->srcport &&
- fw->payload[1] == BUF->destport &&
-#endif
- fw->proto == BUF->proto)
- {
- /* Drop packet. */
- return UIP_FW_FORWARDED;
- }
- }
-
- /* If the TTL reaches zero we produce an ICMP time exceeded message
- * in the d_buf buffer and forward that packet back to the sender
- * of the packet.
- */
-
- if (BUF->ttl <= 1)
- {
- /* No time exceeded for broadcasts and multicasts! */
-
- if (BUF->destipaddr == 0xffffffff)
- {
- return UIP_FW_LOCAL;
- }
- time_exceeded(dev);
- }
-
- /* Decrement the TTL (time-to-live) value in the IP header */
-
- BUF->ttl = BUF->ttl - 1;
-
- /* Update the IP checksum. */
-
- if (BUF->ipchksum >= HTONS(0xffff - 0x0100))
- {
- BUF->ipchksum = BUF->ipchksum + HTONS(0x0100) + 1;
- }
- else
- {
- BUF->ipchksum = BUF->ipchksum + HTONS(0x0100);
- }
-
- if (dev->d_len > 0)
- {
- dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_TCPIP_HLEN];
- uip_fw_output(dev);
- }
-
-#ifdef CONFIG_NET_BROADCAST
- if (BUF->destipaddr[0] == 0xffff && BUF->destipaddr[1] == 0xffff)
- {
- return UIP_FW_LOCAL;
- }
-#endif
-
- /* Return non-zero to indicate that the packet was forwarded and that no
- * other processing should be made.
- */
-
- return UIP_FW_FORWARDED;
-}
-
-/* Register a network interface with the forwarding module.
- *
- * netif A pointer to the network interface that is to be
- * registered.
- */
-
-void uip_fw_register(struct uip_fw_netif *netif)
-{
- netif->next = netifs;
- netifs = netif;
-}
-
-/* Register a default network interface.
- *
- * All packets that don't go out on any of the other interfaces will
- * be routed to the default interface.
- *
- * netif A pointer to the network interface that is to be
- * registered.
- */
-
-void uip_fw_default(struct uip_fw_netif *netif)
-{
- defaultnetif = netif;
-}
-
-/* Perform periodic processing. */
-
-void uip_fw_periodic(void)
-{
- struct fwcache_entry *fw;
- for (fw = fwcache; fw < &fwcache[FWCACHE_SIZE]; ++fw)
- {
- if (fw->timer > 0)
- {
- --fw->timer;
- }
- }
-}