summaryrefslogtreecommitdiff
path: root/nuttx/include/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-01 18:06:15 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-01 18:06:15 +0000
commit5d303ec17efc511d8cfe0919a790b44e24a8aad9 (patch)
tree76c519b5903e6d1e2880f7fb0d403838f7acddac /nuttx/include/net
parent0cab5d84f146c0f6105192db5593aa4019edcdcf (diff)
downloadpx4-nuttx-5d303ec17efc511d8cfe0919a790b44e24a8aad9.tar.gz
px4-nuttx-5d303ec17efc511d8cfe0919a790b44e24a8aad9.tar.bz2
px4-nuttx-5d303ec17efc511d8cfe0919a790b44e24a8aad9.zip
Added support for socket descriptors
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@318 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include/net')
-rw-r--r--nuttx/include/net/uip/dhcpc.h72
-rw-r--r--nuttx/include/net/uip/psock.h40
-rw-r--r--nuttx/include/net/uip/uip.h74
-rw-r--r--nuttx/include/net/uip/uipopt.h319
4 files changed, 285 insertions, 220 deletions
diff --git a/nuttx/include/net/uip/dhcpc.h b/nuttx/include/net/uip/dhcpc.h
new file mode 100644
index 000000000..f598c00ad
--- /dev/null
+++ b/nuttx/include/net/uip/dhcpc.h
@@ -0,0 +1,72 @@
+/****************************************************************************
+ * dhcpc.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * This logic was leveraged from uIP which also has a BSD-style license:
+ *
+ * Copyright (c) 2005, 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 NET_UIP_DHCP_H__
+#define NET_UIP_DHCP_H__
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/types.h>
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
+struct dhcpc_state
+{
+ uint16 lease_time[2];
+ uint8 serverid[4];
+ uint16 ipaddr[2];
+ uint16 netmask[2];
+ uint16 dnsaddr[2];
+ uint16 default_router[2];
+};
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+void *dhcpc_open(const void *mac_addr, int mac_len);
+int dhcpc_request(void *handle, struct dhcpc_state *ds);
+void dhcpc_close(void *handle);
+
+#endif /* NET_UIP_DHCP_H__ */
diff --git a/nuttx/include/net/uip/psock.h b/nuttx/include/net/uip/psock.h
index 9e505c970..3ecc7abdc 100644
--- a/nuttx/include/net/uip/psock.h
+++ b/nuttx/include/net/uip/psock.h
@@ -1,9 +1,15 @@
-/* psock.h
+/****************************************************************************
+ * psock.h
* Protosocket library header file
- * Author: Adam Dunkels <adam@sics.se>
*
- * Copyright (c) 2004, Swedish Institute of Computer Science.
- * All rights reserved.
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * This logic was leveraged from uIP which also has a BSD-style license:
+ *
+ * Author: Adam Dunkels <adam@sics.se>
+ * 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
@@ -28,7 +34,10 @@
* 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 __NET_UIP_PSOCK_H
+#define __NET_UIP_PSOCK_H
/* psock Protosockets library
*
@@ -65,12 +74,20 @@
*
*/
-#ifndef __PSOCK_H__
-#define __PSOCK_H__
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#ifdef CONFIG_NET
#include <sys/types.h>
#include <net/uip/uipopt.h>
+/****************************************************************************
+ * Public Types
+ ****************************************************************************/
+
/* The structure that holds the state of a buffer.
*
* This structure holds the state of a uIP buffer. The structure has
@@ -103,6 +120,10 @@ struct psock
unsigned char state; /* The state of the protosocket. */
};
+/****************************************************************************
+ * Public FunctionPrototypes
+ ****************************************************************************/
+
/* Initialize a protosocket.
*
* Initializes a protosocket and must be called before the
@@ -232,6 +253,5 @@ extern boolean psock_checknewdata(struct psock *s);
extern void psock_waitnewdata(struct psock *s);
-#endif /* __PSOCK_H__ */
-
-/** @} */
+#endif /* CONFIG_NET */
+#endif /* __NET_UIP_PSOCK_H */
diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h
index 0185a8da0..eddae8a66 100644
--- a/nuttx/include/net/uip/uip.h
+++ b/nuttx/include/net/uip/uip.h
@@ -1,14 +1,19 @@
-/**
+/****************************************************************************
* uip.h
* Header file for the uIP TCP/IP stack.
- * author Adam Dunkels <adam@dunkels.com>
*
* The uIP TCP/IP stack header file contains definitions for a number
* of C macros that are used by uIP programs as well as internal uIP
* structures, TCP/IP header structures and function declarations.
*
- * Copyright (c) 2001-2003, Adam Dunkels.
- * All rights reserved.
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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
@@ -34,14 +39,10 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
- * This file is part of the uIP TCP/IP stack.
- *
- * $Id: uip.h,v 1.1.1.1 2007-08-26 23:12:16 patacongo Exp $
- *
****************************************************************************/
-#ifndef __UIP_H__
-#define __UIP_H__
+#ifndef __NET_UIP_UIP_H
+#define __NET_UIP_UIP_H
/****************************************************************************
* Included Files
@@ -117,11 +118,11 @@
#define UIP_PROTO_ICMP6 58
/* Header sizes. */
-#ifdef CONFIG_NET_UIP_IPv6
+#ifdef CONFIG_NET_IPv6
# define UIP_IPH_LEN 40
-#else /* CONFIG_NET_UIP_IPv6 */
+#else /* CONFIG_NET_IPv6 */
# define UIP_IPH_LEN 20 /* Size of IP header */
-#endif /* CONFIG_NET_UIP_IPv6 */
+#endif /* CONFIG_NET_IPv6 */
#define UIP_UDPH_LEN 8 /* Size of UDP header */
#define UIP_TCPH_LEN 20 /* Size of TCP header */
#define UIP_IPUDPH_LEN (UIP_UDPH_LEN + UIP_IPH_LEN) /* Size of IP + UDP header */
@@ -137,11 +138,11 @@
typedef uint16 uip_ip4addr_t[2];
typedef uint16 uip_ip6addr_t[8];
-#ifdef CONFIG_NET_UIP_IPv6
+#ifdef CONFIG_NET_IPv6
typedef uip_ip6addr_t uip_ipaddr_t;
-#else /* CONFIG_NET_UIP_IPv6 */
+#else /* CONFIG_NET_IPv6 */
typedef uip_ip4addr_t uip_ipaddr_t;
-#endif /* CONFIG_NET_UIP_IPv6 */
+#endif /* CONFIG_NET_IPv6 */
/* Representation of a uIP TCP connection.
*
@@ -259,7 +260,7 @@ struct uip_stats {
/* The TCP and IP headers. */
struct uip_tcpip_hdr {
-#ifdef CONFIG_NET_UIP_IPv6
+#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
uint8 vtc,
@@ -268,7 +269,7 @@ struct uip_tcpip_hdr {
uint8 len[2];
uint8 proto, ttl;
uip_ip6addr_t srcipaddr, destipaddr;
-#else /* CONFIG_NET_UIP_IPv6 */
+#else /* CONFIG_NET_IPv6 */
/* IPv4 header. */
uint8 vhl,
@@ -281,7 +282,7 @@ struct uip_tcpip_hdr {
uint16 ipchksum;
uint16 srcipaddr[2],
destipaddr[2];
-#endif /* CONFIG_NET_UIP_IPv6 */
+#endif /* CONFIG_NET_IPv6 */
/* TCP header. */
@@ -300,7 +301,7 @@ struct uip_tcpip_hdr {
/* The ICMP and IP headers. */
struct uip_icmpip_hdr {
-#ifdef CONFIG_NET_UIP_IPv6
+#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
uint8 vtc,
@@ -309,7 +310,7 @@ struct uip_icmpip_hdr {
uint8 len[2];
uint8 proto, ttl;
uip_ip6addr_t srcipaddr, destipaddr;
-#else /* CONFIG_NET_UIP_IPv6 */
+#else /* CONFIG_NET_IPv6 */
/* IPv4 header. */
uint8 vhl,
@@ -322,24 +323,24 @@ struct uip_icmpip_hdr {
uint16 ipchksum;
uint16 srcipaddr[2],
destipaddr[2];
-#endif /* CONFIG_NET_UIP_IPv6 */
+#endif /* CONFIG_NET_IPv6 */
/* ICMP (echo) header. */
uint8 type, icode;
uint16 icmpchksum;
-#ifndef CONFIG_NET_UIP_IPv6
+#ifndef CONFIG_NET_IPv6
uint16 id, seqno;
-#else /* !CONFIG_NET_UIP_IPv6 */
+#else /* !CONFIG_NET_IPv6 */
uint8 flags, reserved1, reserved2, reserved3;
uint8 icmp6data[16];
uint8 options[1];
-#endif /* !CONFIG_NET_UIP_IPv6 */
+#endif /* !CONFIG_NET_IPv6 */
};
/* The UDP and IP headers. */
struct uip_udpip_hdr {
-#ifdef CONFIG_NET_UIP_IPv6
+#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
uint8 vtc,
@@ -348,7 +349,7 @@ struct uip_udpip_hdr {
uint8 len[2];
uint8 proto, ttl;
uip_ip6addr_t srcipaddr, destipaddr;
-#else /* CONFIG_NET_UIP_IPv6 */
+#else /* CONFIG_NET_IPv6 */
/* IP header. */
uint8 vhl,
@@ -361,7 +362,7 @@ struct uip_udpip_hdr {
uint16 ipchksum;
uint16 srcipaddr[2],
destipaddr[2];
-#endif /* CONFIG_NET_UIP_IPv6 */
+#endif /* CONFIG_NET_IPv6 */
/* UDP header. */
@@ -634,9 +635,6 @@ void uip_unlisten(uint16 port);
* which usually is done within 0.5 seconds after the call to
* uip_connect().
*
- * Note: This function is avaliable only if support for active open
- * has been configured by defining UIP_ACTIVE_OPEN to 1 in uipopt.h.
- *
* Note: Since this function requires the port number to be in network
* byte order, a conversion using HTONS() or htons() is necessary.
*
@@ -972,14 +970,14 @@ struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport);
* src The source from where to copy.
*/
-#ifndef CONFIG_NET_UIP_IPv6
+#ifndef CONFIG_NET_IPv6
#define uip_ipaddr_copy(dest, src) do { \
((uint16 *)dest)[0] = ((uint16 *)src)[0]; \
((uint16 *)dest)[1] = ((uint16 *)src)[1]; \
} while(0)
-#else /* !CONFIG_NET_UIP_IPv6 */
+#else /* !CONFIG_NET_IPv6 */
#define uip_ipaddr_copy(dest, src) memcpy(dest, src, sizeof(uip_ip6addr_t))
-#endif /* !CONFIG_NET_UIP_IPv6 */
+#endif /* !CONFIG_NET_IPv6 */
/* Compare two IP addresses
*
@@ -996,12 +994,12 @@ struct uip_udp_conn *uip_udp_new(uip_ipaddr_t *ripaddr, uint16 rport);
* addr2 The second IP address.
*/
-#ifndef CONFIG_NET_UIP_IPv6
+#ifndef CONFIG_NET_IPv6
#define uip_ipaddr_cmp(addr1, addr2) (((uint16 *)addr1)[0] == ((uint16 *)addr2)[0] && \
((uint16 *)addr1)[1] == ((uint16 *)addr2)[1])
-#else /* !CONFIG_NET_UIP_IPv6 */
+#else /* !CONFIG_NET_IPv6 */
#define uip_ipaddr_cmp(addr1, addr2) (memcmp(addr1, addr2, sizeof(uip_ip6addr_t)) == 0)
-#endif /* !CONFIG_NET_UIP_IPv6 */
+#endif /* !CONFIG_NET_IPv6 */
/**
* Compare two IP addresses with netmasks
@@ -1169,4 +1167,4 @@ extern int uip_event_timedwait(uint16 waitflags, int timeout);
extern void uip_event_signal(void);
-#endif /* __UIP_H__ */
+#endif /* __NET_UIP_UIP_H */
diff --git a/nuttx/include/net/uip/uipopt.h b/nuttx/include/net/uip/uipopt.h
index 1e468f6d8..5d19c778e 100644
--- a/nuttx/include/net/uip/uipopt.h
+++ b/nuttx/include/net/uip/uipopt.h
@@ -1,7 +1,6 @@
/****************************************************************************
* uipopt.h
* Configuration options for uIP.
- * author Adam Dunkels <adam@dunkels.com>
*
* This file is used for tweaking various configuration options for
* uIP. You should make a copy of this file into one of your project's
@@ -17,8 +16,14 @@
* Note: Most of the configuration options in the uipopt.h should not
* be changed, but rather the per-project defconfig file.
*
- * Copyright (c) 2001-2003, Adam Dunkels.
- * All rights reserved.
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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
@@ -44,22 +49,27 @@
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
* SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
- * This file is part of the uIP TCP/IP stack.
- *
- * $Id: uipopt.h,v 1.1.1.1 2007-08-26 23:12:17 patacongo Exp $
- *
- */
+ ****************************************************************************/
#ifndef __UIPOPT_H__
#define __UIPOPT_H__
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
#include <sys/types.h>
#include <nuttx/config.h>
-/*------------------------------------------------------------------------------*/
+/****************************************************************************
+ * Public Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
-/**
- * \name Static configuration options
+/* Static configuration options
*
* These configuration options can be used for setting the IP address
* settings statically, but only if UIP_FIXEDADDR is set to 1. The
@@ -69,64 +79,52 @@
* if uIP should be run over Ethernet.
*
* All of these should be changed to suit your project.
-*/
-
-/**
- * Statistics datatype
- *
- * This typedef defines the dataype used for keeping statistics in
- * uIP.
*/
-typedef uint16 uip_stats_t;
-/**
- * Determines if uIP should use a fixed IP address or not.
+/* Determines if uIP should use a fixed IP address or not.
*
* If uIP should use a fixed IP address, the settings are set in the
* uipopt.h file. If not, the macros uip_sethostaddr(),
* uip_setdraddr() and uip_setnetmask() should be used instead.
*/
+
#define UIP_FIXEDADDR 0
-/**
- * Ping IP address asignment.
+/* Ping IP address asignment.
*
* uIP uses a "ping" packets for setting its own IP address if this
* option is set. If so, uIP will start with an empty IP address and
* the destination IP address of the first incoming "ping" (ICMP echo)
* packet will be used for setting the hosts IP address.
*
- * \note This works only if UIP_FIXEDADDR is 0.
+ * Note: This works only if UIP_FIXEDADDR is 0.
*/
-#ifdef CONFIG_UIP_PINGADDRCONF
-#define UIP_PINGADDRCONF CONFIG_UIP_PINGADDRCONF
-#else /* CONFIG_UIP_PINGADDRCONF */
+#ifdef CONFIG_NET_PINGADDRCONF
+#define UIP_PINGADDRCONF CONFIG_NET_PINGADDRCONF
+#else /* CONFIG_NET_PINGADDRCONF */
#define UIP_PINGADDRCONF 0
-#endif /* CONFIG_UIP_PINGADDRCONF */
+#endif /* CONFIG_NET_PINGADDRCONF */
-/**
- * Specifies if the uIP ARP module should be compiled with a fixed
+/* Specifies if the uIP ARP module should be compiled with a fixed
* Ethernet MAC address or not.
*
* If this configuration option is 0, the macro uip_setethaddr() can
* be used to specify the Ethernet address at run-time.
*/
+
#define UIP_FIXEDETHADDR 0
-/*------------------------------------------------------------------------------*/
-/**
- * \name IP configuration options
- */
-/**
- * The IP TTL (time to live) of IP packets sent by uIP.
+/* IP configuration options */
+
+/* The IP TTL (time to live) of IP packets sent by uIP.
*
* This should normally not be changed.
*/
+
#define UIP_TTL 64
-/**
- * Turn on support for IP packet reassembly.
+/* Turn on support for IP packet reassembly.
*
* uIP supports reassembly of fragmented IP packets. This features
* requires an additonal amount of RAM to hold the reassembly buffer
@@ -134,268 +132,222 @@ typedef uint16 uip_stats_t;
* reassembly buffer is of the same size as the uip_buf buffer
* (configured by UIP_BUFSIZE).
*
- * \note IP packet reassembly is not heavily tested.
+ * Note: IP packet reassembly is not heavily tested.
*/
+
#define UIP_REASSEMBLY 0
-/**
- * The maximum time an IP fragment should wait in the reassembly
+/* The maximum time an IP fragment should wait in the reassembly
* buffer before it is dropped.
- *
*/
+
#define UIP_REASS_MAXAGE 40
-/*------------------------------------------------------------------------------*/
-/**
- * \name UDP configuration options
- */
+/* UDP configuration options */
-/**
- * Toggles wether UDP support should be compiled in or not.
- */
-#ifdef CONFIG_UIP_UDP
-# define UIP_UDP CONFIG_UIP_UDP
-#else /* CONFIG_UIP_UDP */
+/* Toggles wether UDP support should be compiled in or not. */
+
+#ifdef CONFIG_NET_UDP
+# define UIP_UDP CONFIG_NET_UDP
+#else /* CONFIG_NET_UDP */
# define UIP_UDP 0
-#endif /* CONFIG_UIP_UDP */
+#endif /* CONFIG_NET_UDP */
-/**
- * Toggles if UDP checksums should be used or not.
+/* Toggles if UDP checksums should be used or not.
*
- * \note Support for UDP checksums is currently not included in uIP,
+ * Note: Support for UDP checksums is currently not included in uIP,
* so this option has no function.
*/
-#ifdef CONFIG_UIP_UDP_CHECKSUMS
-# define UIP_UDP_CHECKSUMS CONFIG_UIP_UDP_CHECKSUMS
+
+#ifdef CONFIG_NET_UDP_CHECKSUMS
+# define UIP_UDP_CHECKSUMS CONFIG_NET_UDP_CHECKSUMS
#else
# define UIP_UDP_CHECKSUMS 0
#endif
-/**
- * The maximum amount of concurrent UDP connections.
- */
-#ifdef CONFIG_UIP_UDP_CONNS
-# define UIP_UDP_CONNS CONFIG_UIP_UDP_CONNS
-#else /* CONFIG_UIP_UDP_CONNS */
-# define UIP_UDP_CONNS 10
-#endif /* CONFIG_UIP_UDP_CONNS */
-
-/**
- * The name of the function that should be called when UDP datagrams arrive.
- */
+/* The maximum amount of concurrent UDP connections. */
+#ifdef CONFIG_NET_UDP_CONNS
+# define UIP_UDP_CONNS CONFIG_NET_UDP_CONNS
+#else /* CONFIG_NET_UDP_CONNS */
+# define UIP_UDP_CONNS 10
+#endif /* CONFIG_NET_UDP_CONNS */
-/*------------------------------------------------------------------------------*/
-/**
- * \name TCP configuration options
- */
+/* TCP configuration options */
-/**
- * Determines if support for opening connections from uIP should be
- * compiled in.
- *
- * If the applications that are running on top of uIP for this project
- * do not need to open outgoing TCP connections, this configration
- * option can be turned off to reduce the code size of uIP.
- */
-#define UIP_ACTIVE_OPEN 1
-
-/**
- * The maximum number of simultaneously open TCP connections.
+/* The maximum number of simultaneously open TCP connections.
*
* Since the TCP connections are statically allocated, turning this
* configuration knob down results in less RAM used. Each TCP
* connection requires approximatly 30 bytes of memory.
*/
-#ifndef CONFIG_UIP_MAX_CONNECTIONS
+
+#ifndef CONFIG_NET_MAX_CONNECTIONS
# define UIP_CONNS 10
-#else /* CONFIG_UIP_MAX_CONNECTIONS */
-# define UIP_CONNS CONFIG_UIP_MAX_CONNECTIONS
-#endif /* CONFIG_UIP_MAX_CONNECTIONS */
+#else /* CONFIG_NET_MAX_CONNECTIONS */
+# define UIP_CONNS CONFIG_NET_MAX_CONNECTIONS
+#endif /* CONFIG_NET_MAX_CONNECTIONS */
-/**
- * The maximum number of simultaneously listening TCP ports.
+/* The maximum number of simultaneously listening TCP ports.
*
* Each listening TCP port requires 2 bytes of memory.
*/
-#ifndef CONFIG_UIP_MAX_LISTENPORTS
+
+#ifndef CONFIG_NET_MAX_LISTENPORTS
# define UIP_LISTENPORTS 20
-#else /* CONFIG_UIP_MAX_LISTENPORTS */
-# define UIP_LISTENPORTS CONFIG_UIP_MAX_LISTENPORTS
-#endif /* CONFIG_UIP_MAX_LISTENPORTS */
+#else /* CONFIG_NET_MAX_LISTENPORTS */
+# define UIP_LISTENPORTS CONFIG_NET_MAX_LISTENPORTS
+#endif /* CONFIG_NET_MAX_LISTENPORTS */
-/**
- * Determines if support for TCP urgent data notification should be
+/* Determines if support for TCP urgent data notification should be
* compiled in.
*
* Urgent data (out-of-band data) is a rarely used TCP feature that
* very seldom would be required.
*/
+
#define UIP_URGDATA 0
-/**
- * The initial retransmission timeout counted in timer pulses.
+/* The initial retransmission timeout counted in timer pulses.
*
* This should not be changed.
*/
+
#define UIP_RTO 3
-/**
- * The maximum number of times a segment should be retransmitted
+/* The maximum number of times a segment should be retransmitted
* before the connection should be aborted.
*
* This should not be changed.
*/
+
#define UIP_MAXRTX 8
-/**
- * The maximum number of times a SYN segment should be retransmitted
+/* The maximum number of times a SYN segment should be retransmitted
* before a connection request should be deemed to have been
* unsuccessful.
*
* This should not need to be changed.
*/
+
#define UIP_MAXSYNRTX 5
-/**
- * The TCP maximum segment size.
+/* The TCP maximum segment size.
*
* This is should not be to set to more than
* UIP_BUFSIZE - UIP_LLH_LEN - UIP_TCPIP_HLEN.
*/
+
#define UIP_TCP_MSS (UIP_BUFSIZE - UIP_LLH_LEN - UIP_TCPIP_HLEN)
-/**
- * The size of the advertised receiver's window.
+/* The size of the advertised receiver's window.
*
* Should be set low (i.e., to the size of the uip_buf buffer) is the
* application is slow to process incoming data, or high (32768 bytes)
* if the application processes data quickly.
*/
-#ifndef CONFIG_UIP_RECEIVE_WINDOW
+
+#ifndef CONFIG_NET_RECEIVE_WINDOW
# define UIP_RECEIVE_WINDOW UIP_TCP_MSS
#else
-# define UIP_RECEIVE_WINDOW CONFIG_UIP_RECEIVE_WINDOW
+# define UIP_RECEIVE_WINDOW CONFIG_NET_RECEIVE_WINDOW
#endif
-/**
- * How long a connection should stay in the TIME_WAIT state.
+/* How long a connection should stay in the TIME_WAIT state.
*
* This configiration option has no real implication, and it should be
* left untouched.
*/
+
#define UIP_TIME_WAIT_TIMEOUT 120
+/* ARP configuration options */
-/*------------------------------------------------------------------------------*/
-/**
- * \name ARP configuration options
- */
-
-/**
- * The size of the ARP table.
+/* The size of the ARP table.
*
* This option should be set to a larger value if this uIP node will
* have many connections from the local network.
*/
-#ifdef CONFIG_UIP_ARPTAB_SIZE
-# define UIP_ARPTAB_SIZE CONFIG_UIP_ARPTAB_SIZE
+
+#ifdef CONFIG_NET_ARPTAB_SIZE
+# define UIP_ARPTAB_SIZE CONFIG_NET_ARPTAB_SIZE
#else
# define UIP_ARPTAB_SIZE 8
#endif
-/**
- * The maxium age of ARP table entries measured in 10ths of seconds.
+/* The maxium age of ARP table entries measured in 10ths of seconds.
*
* An UIP_ARP_MAXAGE of 120 corresponds to 20 minutes (BSD
* default).
*/
-#define UIP_ARP_MAXAGE 120
-/*------------------------------------------------------------------------------*/
+#define UIP_ARP_MAXAGE 120
-/**
- * \name General configuration options
- */
+/* General configuration options */
-/**
- * The size of the uIP packet buffer.
+/* The size of the uIP packet buffer.
*
* The uIP packet buffer should not be smaller than 60 bytes, and does
* not need to be larger than 1500 bytes. Lower size results in lower
* TCP throughput, larger size results in higher TCP throughput.
*/
-#ifndef CONFIG_UIP_BUFFER_SIZE
-# define UIP_BUFSIZE 400
-#else /* CONFIG_UIP_BUFFER_SIZE */
-# define UIP_BUFSIZE CONFIG_UIP_BUFFER_SIZE
-#endif /* CONFIG_UIP_BUFFER_SIZE */
+#ifndef CONFIG_NET_BUFFER_SIZE
+# define UIP_BUFSIZE 400
+#else /* CONFIG_NET_BUFFER_SIZE */
+# define UIP_BUFSIZE CONFIG_NET_BUFFER_SIZE
+#endif /* CONFIG_NET_BUFFER_SIZE */
-/**
- * Determines if statistics support should be compiled in.
+/* Determines if statistics support should be compiled in.
*
* The statistics is useful for debugging and to show the user.
*/
-#ifndef CONFIG_UIP_STATISTICS
+#ifndef CONFIG_NET_STATISTICS
# define UIP_STATISTICS 0
-#else /* CONFIG_UIP_STATISTICS */
-# define UIP_STATISTICS CONFIG_UIP_STATISTICS
-#endif /* CONFIG_UIP_STATISTICS */
+#else /* CONFIG_NET_STATISTICS */
+# define UIP_STATISTICS CONFIG_NET_STATISTICS
+#endif /* CONFIG_NET_STATISTICS */
-/**
- * Determines if logging of certain events should be compiled in.
+/* Determines if logging of certain events should be compiled in.
*
* This is useful mostly for debugging. The function uip_log()
* must be implemented to suit the architecture of the project, if
* logging is turned on.
*/
-#ifndef CONFIG_UIP_LOGGING
+#ifndef CONFIG_NET_LOGGING
# define UIP_LOGGING 0
-#else /* CONFIG_UIP_LOGGING */
-# define UIP_LOGGING CONFIG_UIP_LOGGING
-#endif /* CONFIG_UIP_LOGGING */
+#else /* CONFIG_NET_LOGGING */
+# define UIP_LOGGING CONFIG_NET_LOGGING
+#endif /* CONFIG_NET_LOGGING */
-/**
- * Broadcast support.
+/* Broadcast support.
*
* This flag configures IP broadcast support. This is useful only
* together with UDP.
*/
-#ifndef CONFIG_UIP_BROADCAST
+#ifndef CONFIG_NET_BROADCAST
# define UIP_BROADCAST 0
-#else /* CONFIG_UIP_BROADCAST */
-# define UIP_BROADCAST CONFIG_UIP_BROADCAST
-#endif /* CONFIG_UIP_BROADCAST */
+#else /* CONFIG_NET_BROADCAST */
+# define UIP_BROADCAST CONFIG_NET_BROADCAST
+#endif /* CONFIG_NET_BROADCAST */
-/**
- * Print out a uIP log message.
- *
- * This function must be implemented by the module that uses uIP, and
- * is called by uIP whenever a log message is generated.
- */
-void uip_log(char *msg);
-
-/**
- * The link level header length.
+/* The link level header length.
*
* This is the offset into the uip_buf where the IP header can be
* found. For Ethernet, this should be set to 14. For SLIP, this
* should be set to 0.
*/
-#ifdef CONFIG_UIP_LLH_LEN
-# define UIP_LLH_LEN CONFIG_UIP_LLH_LEN
-#else /* CONFIG_UIP_LLH_LEN */
+#ifdef CONFIG_NET_LLH_LEN
+# define UIP_LLH_LEN CONFIG_NET_LLH_LEN
+#else /* CONFIG_NET_LLH_LEN */
# define UIP_LLH_LEN 14
-#endif /* CONFIG_UIP_LLH_LEN */
+#endif /* CONFIG_NET_LLH_LEN */
-/*------------------------------------------------------------------------------*/
-/**
- * \name CPU architecture configuration
+/* CPU architecture configuration
*
* The CPU architecture configuration is where the endianess of the
* CPU on which uIP is to be run is specified. Most CPUs today are
@@ -404,8 +356,7 @@ void uip_log(char *msg);
* if uIP is to be run on a big endian architecture.
*/
-/**
- * The byte order of the CPU architecture on which uIP is to be run.
+/* The byte order of the CPU architecture on which uIP is to be run.
*
* This option can be either CONFIG_ENDIAN_BIG (Motorola byte order) or
* default little endian byte order (Intel byte order).
@@ -420,4 +371,28 @@ void uip_log(char *msg);
# define UIP_BYTE_ORDER UIP_LITTLE_ENDIAN
#endif
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/* Statistics datatype
+ *
+ * This typedef defines the dataype used for keeping statistics in
+ * uIP.
+ */
+
+typedef uint16 uip_stats_t;
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/* Print out a uIP log message.
+ *
+ * This function must be implemented by the module that uses uIP, and
+ * is called by uIP whenever a log message is generated.
+ */
+
+void uip_log(char *msg);
+
#endif /* __UIPOPT_H__ */