summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/arpa/inet.h2
-rw-r--r--nuttx/include/net/uip/uip-arch.h45
-rw-r--r--nuttx/include/net/uip/uip.h225
-rw-r--r--nuttx/include/netinet/in.h58
-rw-r--r--nuttx/include/netinet/ip6.h54
-rw-r--r--nuttx/include/nuttx/net.h20
-rw-r--r--nuttx/include/sys/socket.h23
7 files changed, 259 insertions, 168 deletions
diff --git a/nuttx/include/arpa/inet.h b/nuttx/include/arpa/inet.h
index 74e3bbda4..d97ee9ff5 100644
--- a/nuttx/include/arpa/inet.h
+++ b/nuttx/include/arpa/inet.h
@@ -64,7 +64,7 @@
# define HTONS(ns) \
(uint16)((((uint16) (ns)) << 8) | (((uint16) (ns)) >> 8))
# define HTONL(nl) htonl(nl) \
- ((uint32)HTONS((uint16)((hs) << 16)) | (uint32)HTONS((uint16)((hs) & 0xffff)))
+ (((uint32)HTONS((uint16)((hs) & 0xffff)) << 16) | (uint32)HTONS((uint16)((uint16)((hs) >> 16))))
#endif
#define NTOHS(hs) HTONS(hs)
diff --git a/nuttx/include/net/uip/uip-arch.h b/nuttx/include/net/uip/uip-arch.h
index e0cbb84f2..31552e082 100644
--- a/nuttx/include/net/uip/uip-arch.h
+++ b/nuttx/include/net/uip/uip-arch.h
@@ -141,38 +141,39 @@
* The ususal way of calling the function is through a for() loop like
* this:
*
- * for(i = 0; i < UIP_CONNS; ++i) {
- * uip_periodic(i);
- * if(uip_len > 0) {
- * devicedriver_send();
+ * for(i = 0; i < UIP_CONNS; ++i)
+ * {
+ * uip_tcppoll(i);
+ * if (uip_len > 0)
+ * {
+ * devicedriver_send();
+ * }
* }
- * }
*
* Note: If you are writing a uIP device driver that needs ARP
* (Address Resolution Protocol), e.g., when running uIP over
* Ethernet, you will need to call the uip_arp_out() function before
* calling the device driver:
*
- * for(i = 0; i < UIP_CONNS; ++i) {
- * uip_periodic(i);
- * if(uip_len > 0) {
- * uip_arp_out();
- * ethernet_devicedriver_send();
+ * for(i = 0; i < UIP_CONNS; ++i)
+ * {
+ * uip_tcppoll(i);
+ * if (uip_len > 0)
+ * {
+ * uip_arp_out();
+ * ethernet_devicedriver_send();
+ * }
* }
- * }
*
* conn The number of the connection which is to be periodically polled.
*/
-#define uip_periodic(conn) do { uip_conn = &uip_conns[conn]; \
- uip_interrupt(UIP_TIMER); } while (0)
-
-#define uip_conn_active(conn) (uip_conns[conn].tcpstateflags != UIP_CLOSED)
+extern void uip_tcppoll( unsigned int conn );
/* Perform periodic processing for a connection identified by a pointer
* to its structure.
*
- * Same as uip_periodic() but takes a pointer to the actual uip_conn
+ * Same as uip_tcppoll() but takes a pointer to the actual uip_conn
* struct instead of an integer as its argument. This function can be
* used to force periodic processing of a specific connection.
*
@@ -180,11 +181,11 @@
* be processed.
*/
-#define uip_periodic_conn(conn) do { uip_conn = conn; uip_interrupt(UIP_TIMER); } while (0)
+#define uip_tcppoll_conn(conn) do { uip_conn = conn; uip_interrupt(UIP_TIMER); } while (0)
/* Request that a particular connection should be polled.
*
- * Similar to uip_periodic_conn() but does not perform any timer
+ * Similar to uip_tcppoll_conn() but does not perform any timer
* processing. The application is polled for new data.
*
* conn A pointer to the uip_conn struct for the connection to
@@ -197,9 +198,9 @@
#ifdef CONFIG_NET_UDP
/* Periodic processing for a UDP connection identified by its number.
*
- * This function is essentially the same as uip_periodic(), but for
+ * This function is essentially the same as uip_tcppoll(), but for
* UDP connections. It is called in a similar fashion as the
- * uip_periodic() function:
+ * uip_tcppoll() function:
*
* for(i = 0; i < UIP_UDP_CONNS; i++) {
* uip_udp_periodic(i);
@@ -208,7 +209,7 @@
* }
* }
*
- * Note: As for the uip_periodic() function, special care has to be
+ * Note: As for the uip_tcppoll() function, special care has to be
* taken when using uIP together with ARP and Ethernet:
*
* for(i = 0; i < UIP_UDP_CONNS; i++) {
@@ -287,9 +288,7 @@ extern void uip_interrupt(uint8 flag);
* op16 A 16-bit integer in host byte order.
*/
-#if UIP_ARCH_ADD32
extern void uip_add32(uint8 *op32, uint16 op16);
-#endif
/* Calculate the Internet checksum over a buffer.
*
diff --git a/nuttx/include/net/uip/uip.h b/nuttx/include/net/uip/uip.h
index 043d6d377..6815e3527 100644
--- a/nuttx/include/net/uip/uip.h
+++ b/nuttx/include/net/uip/uip.h
@@ -86,17 +86,18 @@
/* The TCP states used in the uip_conn->tcpstateflags. */
-#define UIP_CLOSED 0
-#define UIP_SYN_RCVD 1
-#define UIP_SYN_SENT 2
-#define UIP_ESTABLISHED 3
-#define UIP_FIN_WAIT_1 4
-#define UIP_FIN_WAIT_2 5
-#define UIP_CLOSING 6
-#define UIP_TIME_WAIT 7
-#define UIP_LAST_ACK 8
-#define UIP_TS_MASK 15
+#define UIP_CLOSED 0 /* The connection is not in use and available */
+#define UIP_ALLOCATED 1 /* The connection is allocated, but not yet initialized */
+#define UIP_SYN_RCVD 2
+#define UIP_SYN_SENT 3
+#define UIP_ESTABLISHED 4
+#define UIP_FIN_WAIT_1 5
+#define UIP_FIN_WAIT_2 6
+#define UIP_CLOSING 7
+#define UIP_TIME_WAIT 8
+#define UIP_LAST_ACK 9
+#define UIP_TS_MASK 15
#define UIP_STOPPED 16
/* The buffer size available for user data in the \ref uip_buf buffer.
@@ -112,18 +113,19 @@
#define UIP_APPDATA_SIZE (UIP_BUFSIZE - UIP_LLH_LEN - UIP_TCPIP_HLEN)
-
#define UIP_PROTO_ICMP 1
#define UIP_PROTO_TCP 6
#define UIP_PROTO_UDP 17
#define UIP_PROTO_ICMP6 58
/* Header sizes. */
+
#ifdef CONFIG_NET_IPv6
# define UIP_IPH_LEN 40
#else /* CONFIG_NET_IPv6 */
# define UIP_IPH_LEN 20 /* Size of IP header */
#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 */
@@ -188,7 +190,7 @@ struct uip_conn
void *private;
};
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
/* Representation of a uIP UDP connection. */
struct uip_udp_conn
@@ -206,13 +208,14 @@ struct uip_udp_conn
};
#endif /* CONFIG_NET_UDP */
-/**
- * The structure holding the TCP/IP statistics that are gathered if
+/* The structure holding the TCP/IP statistics that are gathered if
* UIP_STATISTICS is set to 1.
- *
*/
-struct uip_stats {
- struct {
+
+struct uip_stats
+{
+ struct
+ {
uip_stats_t drop; /* Number of dropped packets at the IP layer. */
uip_stats_t recv; /* Number of received packets at the IP layer. */
uip_stats_t sent; /* Number of sent packets at the IP layer. */
@@ -229,13 +232,15 @@ struct uip_stats {
uip_stats_t protoerr; /* Number of packets dropped since they
were neither ICMP, UDP nor TCP. */
} ip; /* IP statistics. */
- struct {
+ struct
+ {
uip_stats_t drop; /* Number of dropped ICMP packets. */
uip_stats_t recv; /* Number of received ICMP packets. */
uip_stats_t sent; /* Number of sent ICMP packets. */
uip_stats_t typeerr; /* Number of ICMP packets with a wrong type. */
} icmp; /* ICMP statistics. */
- struct {
+ struct
+ {
uip_stats_t drop; /* Number of dropped TCP segments. */
uip_stats_t recv; /* Number of recived TCP segments. */
uip_stats_t sent; /* Number of sent TCP segments. */
@@ -248,8 +253,9 @@ struct uip_stats {
uip_stats_t synrst; /* Number of SYNs for closed ports,
triggering a RST. */
} tcp; /* TCP statistics. */
- #ifdef CONFIG_NET_UDP
- struct {
+#ifdef CONFIG_NET_UDP
+ struct
+ {
uip_stats_t drop; /* Number of dropped UDP segments. */
uip_stats_t recv; /* Number of recived UDP segments. */
uip_stats_t sent; /* Number of sent UDP segments. */
@@ -260,70 +266,76 @@ struct uip_stats {
/* The TCP and IP headers. */
-struct uip_tcpip_hdr {
+struct uip_tcpip_hdr
+{
#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
- uint8 vtc,
- tcflow;
+ uint8 vtc;
+ uint8 tcflow;
uint16 flow;
uint8 len[2];
uint8 proto, ttl;
uip_ip6addr_t srcipaddr, destipaddr;
+
#else /* CONFIG_NET_IPv6 */
/* IPv4 header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
+ uint16 srcipaddr[2];
+ uint16 destipaddr[2];
#endif /* CONFIG_NET_IPv6 */
/* TCP header. */
- uint16 srcport,
- destport;
- uint8 seqno[4],
- ackno[4],
- tcpoffset,
- flags,
- wnd[2];
+ 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];
+ uint8 urgp[2];
+ uint8 optdata[4];
};
/* The ICMP and IP headers. */
-struct uip_icmpip_hdr {
+struct uip_icmpip_hdr
+{
#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
- uint8 vtc,
- tcf;
+ uint8 vtc;
+ uint8 tcf;
uint16 flow;
- uint8 len[2];
- uint8 proto, ttl;
- uip_ip6addr_t srcipaddr, destipaddr;
+ uint8 len[2];
+ uint8 proto;
+ uint8 ttl;
+ uip_ip6addr_t srcipaddr;
+ uip_ip6addr_t destipaddr;
+
#else /* CONFIG_NET_IPv6 */
/* IPv4 header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
+ uint16 srcipaddr[2];
+ uint16 destipaddr[2];
#endif /* CONFIG_NET_IPv6 */
/* ICMP (echo) header. */
@@ -340,42 +352,45 @@ struct uip_icmpip_hdr {
/* The UDP and IP headers. */
-struct uip_udpip_hdr {
+struct uip_udpip_hdr
+{
#ifdef CONFIG_NET_IPv6
/* IPv6 header. */
- uint8 vtc,
- tcf;
+ uint8 vtc;
+ uint8 tcf;
uint16 flow;
uint8 len[2];
uint8 proto, ttl;
- uip_ip6addr_t srcipaddr, destipaddr;
+ uip_ip6addr_t srcipaddr;
+ uip_ip6addr_t destipaddr;
#else /* CONFIG_NET_IPv6 */
/* IP header. */
- uint8 vhl,
- tos,
- len[2],
- ipid[2],
- ipoffset[2],
- ttl,
- proto;
+ uint8 vhl;
+ uint8 tos;
+ uint8 len[2];
+ uint8 ipid[2];
+ uint8 ipoffset[2];
+ uint8 ttl;
+ uint8 proto;
uint16 ipchksum;
- uint16 srcipaddr[2],
- destipaddr[2];
+ uint16 srcipaddr[2];
+ uint16 destipaddr[2];
#endif /* CONFIG_NET_IPv6 */
/* UDP header. */
- uint16 srcport,
- destport;
+ uint16 srcport;
+ uint16 destport;
uint16 udplen;
uint16 udpchksum;
};
/* Representation of a 48-bit Ethernet address. */
-struct uip_eth_addr {
+struct uip_eth_addr
+{
uint8 addr[6];
};
@@ -463,16 +478,13 @@ extern uint16 uip_urglen, uip_surglen;
extern struct uip_conn *uip_conn;
-/* The array containing all uIP connections. */
-extern struct uip_conn uip_conns[UIP_CONNS];
-
/* 4-byte array used for the 32-bit sequence number calculations.*/
extern uint8 uip_acc32[4];
/* The current UDP connection. */
- #ifdef CONFIG_NET_UDP
+#ifdef CONFIG_NET_UDP
extern struct uip_udp_conn *uip_udp_conn;
extern struct uip_udp_conn uip_udp_conns[UIP_UDP_CONNS];
#endif /* CONFIG_NET_UDP */
@@ -601,9 +613,27 @@ void uip_setipid(uint16 id);
* detected that may be of interest to the application.
*/
-void uip_interrupt_event(void);
- #ifdef CONFIG_NET_UDP
-void uip_interrupt_udp_event(void);
+extern void uip_interrupt_event(void);
+#ifdef CONFIG_NET_UDP
+extern void uip_interrupt_udp_event(void);
+#endif
+
+/* Find a free connection structure and allocate it for use. This is
+ * normally something done by the implementation of the socket() API
+ */
+
+extern struct uip_conn *uip_tcpalloc(void);
+#ifdef CONFIG_NET_UDP
+extern struct uip_udp_conn *uip_udpalloc(void);
+#endif
+
+/* Free a connection structure that is no longer in use. This should
+ * be done by the implementation of close()
+ */
+
+extern void uip_tcpfree(struct uip_conn *conn);
+#ifdef CONFIG_NET_UDP
+extern void uip_udpfree(struct uip_udp_conn *conn);
#endif
/* Start listening to the specified port.
@@ -626,37 +656,6 @@ void uip_listen(uint16 port);
void uip_unlisten(uint16 port);
-/* Connect to a remote host using TCP.
- *
- * This function is used to start a new connection to the specified
- * port on the specied host. It allocates a new connection identifier,
- * 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_connect().
- *
- * Note: Since this function requires the port number to be in network
- * byte order, a conversion using HTONS() or htons() is necessary.
- *
- * Example:
- *
- * uip_ipaddr_t ipaddr;
- *
- * uip_ipaddr(&ipaddr, 192,168,1,2);
- * uip_connect(&ipaddr, HTONS(80));
- *
- * ripaddr The IP address of the remote hot.
- *
- * port A 16-bit port number in network byte order.
- *
- * Return: A pointer to the uIP connection identifier for the new connection,
- * or NULL if no connection could be allocated.
- */
-
-struct uip_conn *uip_connect(uip_ipaddr_t *ripaddr, uint16 port);
-
-
/* Check if a connection has outstanding (i.e., unacknowledged) data.
*
* conn A pointer to the uip_conn structure for the connection.
@@ -837,7 +836,7 @@ void uip_send(const void *data, int len);
* connection.
*/
-#define uip_initialmss() (uip_conn->initialmss)
+#define uip_initialmss() (uip_conn->initialmss)
/* Get the current maxium segment size that can be sent on the current
* connection.
@@ -848,7 +847,7 @@ void uip_send(const void *data, int len);
* uip_initialmss()).
*/
-#define uip_mss() (uip_conn->mss)
+#define uip_mss() (uip_conn->mss)
/* Set up a new UDP connection.
*
diff --git a/nuttx/include/netinet/in.h b/nuttx/include/netinet/in.h
index e2ed78363..dd518388a 100644
--- a/nuttx/include/netinet/in.h
+++ b/nuttx/include/netinet/in.h
@@ -43,34 +43,68 @@
#include <sys/types.h>
/****************************************************************************
- * Public Type Definitions
+ * Public Macro Definitions
****************************************************************************/
-/* Address to accept any incoming messages. */
-#define INADDR_ANY ((in_addr_t)0x00000000)
+/* Values for protocol argument to socket() */
+
+#define IPPROTO_TCP 1
+#define IPPROTO_UDP 2
+
+/* Special values of in_addr_t */
+
+#define INADDR_ANY ((in_addr_t)0x00000000) /* Address to accept any incoming messages */
+#define INADDR_BROADCAST ((in_addr_t)0xffffffff) /* Address to send to all hosts */
+#define INADDR_NONE ((in_addr_t)0xffffffff) /* Address indicating an error return */
+
+#define IN6ADDR_ANY_INIT {{{0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0}}}
-/* Address to send to all hosts. */
-#define INADDR_BROADCAST ((in_addr_t)0xffffffff)
+/* struct in6_addr union selectors */
-/* Address indicating an error return. */
-#define INADDR_NONE ((in_addr_t)0xffffffff)
+#define s6_addr in6_u.u6_addr8
+#define s6_addr16 in6_u.u6_addr16
+#define s6_addr32 in6_u.u6_addr32
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
/****************************************************************************
* Public Type Definitions
****************************************************************************/
-/* Internet address. */
+/* IPv4 Internet address */
+
typedef uint32 in_addr_t;
struct in_addr
{
- in_addr_t s_addr; /* address in network byte order */
+ in_addr_t s_addr; /* Address (network byte order) */
};
struct sockaddr_in
{
- sa_family_t sin_family; /* address family: AF_INET */
- uint16 sin_port; /* port in network byte order */
- struct in_addr sin_addr; /* internet address */
+ sa_family_t sin_family; /* address family: AF_INET */
+ uint16 sin_port; /* port in network byte order */
+ struct in_addr sin_addr; /* internet address */
+};
+
+/* IPv6 Internet address */
+
+struct in6_addr
+{
+ union
+ {
+ uint8 u6_addr8[16];
+ uint16 u6_addr16[8];
+ uint32 u6_addr32[4];
+ } in6_u;
+};
+
+struct sockaddr_in6
+{
+ sa_family_t sin_family; /* Address family: AF_INET */
+ uint16 sin_port; /* Port in network byte order */
+ struct in6_addr sin6_addr; /* IPv6 internet address */
};
/****************************************************************************
diff --git a/nuttx/include/netinet/ip6.h b/nuttx/include/netinet/ip6.h
new file mode 100644
index 000000000..cc6a5295c
--- /dev/null
+++ b/nuttx/include/netinet/ip6.h
@@ -0,0 +1,54 @@
+/****************************************************************************
+ * netinet/ip6.h
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 Gregory Nutt 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.
+ *
+ ****************************************************************************/
+
+#ifndef __NETINET_IP6_H
+#define __NETINET_IP6_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <sys/socket.h>
+#include <netinet/in.h>
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#endif /* __NETINET_IP6_H */
diff --git a/nuttx/include/nuttx/net.h b/nuttx/include/nuttx/net.h
index c51c4f281..bb8ec8da3 100644
--- a/nuttx/include/nuttx/net.h
+++ b/nuttx/include/nuttx/net.h
@@ -1,5 +1,5 @@
/****************************************************************************
- * net.h
+ * nuttx/net.h
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -73,23 +73,9 @@
struct socket
{
- /* Socket state info */
-
- int s_crefs; /* Reference counts on the socket */
+ int s_crefs; /* Reference count on the socket */
uint8 s_type; /* Protocol type: Only SOCK_STREAM or SOCK_DGRAM */
-
- /* Proto-socket */
-
- struct psock s_psock;
-
- /* Connection */
-
- union
- {
- struct uip_udp_conn udp;
- struct uip_conn tcp;
- }
- s_conn;
+ void *s_conn; /* Connection: struct uip_conn * or uip_udp_conn * */
};
/* This defines a list of sockets indexed by the socket descriptor */
diff --git a/nuttx/include/sys/socket.h b/nuttx/include/sys/socket.h
index 0223e0375..589fafe13 100644
--- a/nuttx/include/sys/socket.h
+++ b/nuttx/include/sys/socket.h
@@ -50,6 +50,8 @@
* the protocol family which will be used for communication.
*/
+/* Protocol families */
+
#define PF_UNIX 0 /* Local communication */
#define PF_LOCAL 1 /* Local communication */
#define PF_INET 2 /* IPv4 Internet protocols */
@@ -62,6 +64,20 @@
#define PF_APPLETALK 9 /* Appletalk */
#define PF_PACKET 10 /* Low level packet interface */
+/* Address families */
+
+#define AF_UNIX PF_UNIX
+#define AF_LOCAL PF_LOCAL
+#define AF_INET PF_INET
+#define AF_INET6 PF_INET6
+#define AF_IPX PF_IPX
+#define AF_NETLINK PF_NETLINK
+#define AF_X25 PF_X25
+#define AF_AX25 PF_AX25
+#define AF_ATMPVC PF_ATMPVC
+#define AF_APPLETALK PF_APPLETALK
+#define AF_PACKET PF_PACKET
+
/*The socket created by socket() has the indicated type, which specifies
* the communication semantics.
*/
@@ -100,9 +116,12 @@ extern "C" {
#endif
EXTERN int socket(int domain, int type, int protocol);
-EXTERN int bind(int sockfd, const struct sockaddr *my_addr, socklen_t addrlen);
-EXTERN int connect(int sockfd, const struct sockaddr *serv_addr, socklen_t addrlen);
+EXTERN int bind(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
+EXTERN int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen);
+EXTERN ssize_t send(int s, const void *buf, size_t len, int flags);
+EXTERN ssize_t sendto(int s, const void *buf, size_t len, int flags,
+ const struct sockaddr *to, socklen_t tolen);
#undef EXTERN
#if defined(__cplusplus)
}