summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-15 22:45:45 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-09-15 22:45:45 +0000
commit42027d080b72b8198072e7dc3933d8b70b6b40a5 (patch)
treed471d699ed674cbc615d89cd830e83c1b61d9eea /nuttx/net
parent8bd136d2202c6706ac2166a31b90f1ec18139dea (diff)
downloadpx4-nuttx-42027d080b72b8198072e7dc3933d8b70b6b40a5.tar.gz
px4-nuttx-42027d080b72b8198072e7dc3933d8b70b6b40a5.tar.bz2
px4-nuttx-42027d080b72b8198072e7dc3933d8b70b6b40a5.zip
Add basic structure to support multiple network interfaces
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@343 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/Makefile1
-rw-r--r--nuttx/net/connect.c82
-rw-r--r--nuttx/net/recvfrom.c104
-rw-r--r--nuttx/net/send.c42
-rw-r--r--nuttx/net/sendto.c68
-rw-r--r--nuttx/net/uip/Make.defs2
-rw-r--r--nuttx/net/uip/uip-arp.c130
-rw-r--r--nuttx/net/uip/uip-fw.c232
-rw-r--r--nuttx/net/uip/uip-fw.h90
-rw-r--r--nuttx/net/uip/uip-send.c99
-rw-r--r--nuttx/net/uip/uip-split.c48
-rw-r--r--nuttx/net/uip/uip-split.h15
-rw-r--r--nuttx/net/uip/uip-tcpconn.c4
-rw-r--r--nuttx/net/uip/uip-udpconn.c4
-rw-r--r--nuttx/net/uip/uip.c343
15 files changed, 720 insertions, 544 deletions
diff --git a/nuttx/net/Makefile b/nuttx/net/Makefile
index 31ccd2a26..2257e446e 100644
--- a/nuttx/net/Makefile
+++ b/nuttx/net/Makefile
@@ -90,6 +90,7 @@ depend: .depend
clean:
rm -f $(BIN) *.o *.rel *.asm *.lst *.sym *.adb *~
+ rm -f uip/*~
if [ ! -z "$(OBJEXT)" ]; then rm -f *$(OBJEXT); fi
distclean: clean
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index 2a9708b9a..523c1d7c1 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -47,7 +47,55 @@
#include "net-internal.h"
/****************************************************************************
- * Global Functions
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Function: connection_event
+ *
+ * Description:
+ * Some connection related event has occurred
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * private An instance of struct recvfrom_s cast to void*
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static void connection_event(void *private)
+{
+ FAR struct socket *psock = (FAR struct socket *)private;
+ if (psock)
+ {
+ /* UIP_CLOSE: The remote host has closed the connection
+ * UIP_ABORT: The remote host has aborted the connection
+ * UIP_TIMEDOUT: Connection aborted due to too many retransmissions.
+ */
+ if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ /* Indicate that the socet is no longer connected */
+
+ psock->s_flags &= ~_SF_CONNECTED;
+ }
+
+ /* UIP_CONNECTED: The socket is successfully connected */
+
+ else if ((uip_flags & UIP_CONNECTED) != 0)
+ {
+ /* Indicate that the socet is no longer connected */
+
+ psock->s_flags |= _SF_CONNECTED;
+ }
+ }
+}
+
+/****************************************************************************
+ * Public Functions
****************************************************************************/
/****************************************************************************
@@ -128,6 +176,7 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
FAR const struct sockaddr_in *inaddr = (const struct sockaddr_in *)addr;
#endif
int err;
+ int ret;
/* Verify that the sockfd corresponds to valid, allocated socket */
@@ -155,7 +204,7 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
{
case SOCK_STREAM:
{
- int ret;
+ struct uip_conn *conn;
/* Verify that the socket is not already connected */
@@ -165,25 +214,36 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
goto errout;
}
- /* Perform the uIP connection operation */
+ /* Get the connection reference from the socket */
- ret = uip_tcpconnect(psock->s_conn, inaddr);
- if (ret < 0)
+ conn = psock->s_conn;
+ if (conn) /* Should alwasy be non-NULL */
{
- err = -ret;
- goto errout;
- }
+ /* Perform the uIP connection operation */
- /* Mark the connection bound and connected */
+ ret = uip_tcpconnect(psock->s_conn, inaddr);
+ if (ret < 0)
+ {
+ err = -ret;
+ goto errout;
+ }
- psock->s_flags |= (_SF_BOUND|_SF_CONNECTED);
+ /* Mark the connection bound and connected */
+
+ psock->s_flags |= (_SF_BOUND|_SF_CONNECTED);
+
+ /* Set up to receive callbacks on connection-related events */
+
+ conn->connection_private = (void*)psock;
+ conn->connection_event = connection_event;
+ }
}
break;
#ifdef CONFIG_NET_UDP
case SOCK_DGRAM:
{
- int ret = uip_udpconnect(psock->s_conn, inaddr);
+ ret = uip_udpconnect(psock->s_conn, inaddr);
if (ret < 0)
{
err = -ret;
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 401580f37..0665b54f1 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -46,6 +46,7 @@
#include <errno.h>
#include <arch/irq.h>
#include <nuttx/clock.h>
+#include <net/uip/uip-arch.h>
#include "net-internal.h"
@@ -78,7 +79,26 @@ struct recvfrom_s
* Private Functions
****************************************************************************/
-static void recvfrom_interrupt(void *private)
+/****************************************************************************
+ * Function: recvfrom_interrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * receive operation via by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * private An instance of struct recvfrom_s cast to void*
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
{
struct recvfrom_s *pstate = (struct recvfrom_s *)private;
FAR struct socket *psock;
@@ -97,18 +117,18 @@ static void recvfrom_interrupt(void *private)
if (uip_newdata())
{
/* Get the length of the data to return */
- if (uip_len > pstate->rf_buflen)
+ if (dev->d_len > pstate->rf_buflen)
{
recvlen = pstate->rf_buflen;
}
else
{
- recvlen = uip_len;
+ recvlen = dev->d_len;
}
/* Copy the new appdata into the user buffer */
- memcpy(pstate->rf_buffer, uip_appdata, recvlen);
+ memcpy(pstate->rf_buffer, dev->d_appdata, recvlen);
/* Update the accumulated size of the data read */
@@ -127,9 +147,9 @@ static void recvfrom_interrupt(void *private)
/* Don't allow any further UDP call backs. */
- udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = NULL;
- udp_conn->callback = NULL;
+ udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ udp_conn->private = NULL;
+ udp_conn->event = NULL;
/* Wake up the waiting thread, returning the number of bytes
* actually read.
@@ -149,9 +169,9 @@ static void recvfrom_interrupt(void *private)
* Don't allow any further TCP call backs.
*/
- conn = (struct uip_conn *)psock->s_conn;
- conn->private = NULL;
- conn->callback = NULL;
+ conn = (struct uip_conn *)psock->s_conn;
+ conn->data_private = NULL;
+ conn->data_event = NULL;
/* Wake up the waiting thread, returning the number of bytes
* actually read.
@@ -169,6 +189,36 @@ static void recvfrom_interrupt(void *private)
#endif
}
+ /* Check for a loss of connection */
+
+ else if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ /* Stop further callbacks */
+
+#ifdef CONFIG_NET_UDP
+ if (psock->s_type == SOCK_DGRAM)
+ {
+ struct uip_udp_conn *udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ udp_conn->private = NULL;
+ udp_conn->event = NULL;
+ }
+ else
+#endif
+ {
+ struct uip_conn *conn = (struct uip_conn *)psock->s_conn;
+ conn->data_private = NULL;
+ conn->data_event = NULL;
+ }
+
+ /* Report not connected */
+
+ pstate->rf_result = -ENOTCONN;
+
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->rf_sem);
+ }
+
/* No data has been received -- this is some other event... probably a
* poll -- check for a timeout.
*/
@@ -221,9 +271,9 @@ static void recvfrom_interrupt(void *private)
/* Stop further callbacks */
- udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = NULL;
- udp_conn->callback = NULL;
+ udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ udp_conn->private = NULL;
+ udp_conn->event = NULL;
/* Report a timeout error */
@@ -234,9 +284,9 @@ static void recvfrom_interrupt(void *private)
{
struct uip_conn *conn;
- conn = (struct uip_conn *)psock->s_conn;
- conn->private = NULL;
- conn->callback = NULL;
+ conn = (struct uip_conn *)psock->s_conn;
+ conn->data_private = NULL;
+ conn->data_event = NULL;
/* Report an error only if no data has been received */
@@ -329,7 +379,7 @@ static ssize_t recvfrom_result(int result, struct recvfrom_s *pstate)
if (pstate->rf_result < 0)
{
- /* Return EGAIN on a timeout */
+ /* Return EGAIN on a timeout or ENOTCONN on loss of connection */
return pstate->rf_result;
}
@@ -401,9 +451,9 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Set up the callback in the connection */
- udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = (void*)&state;
- udp_conn->callback = recvfrom_interrupt;
+ udp_conn = (struct uip_udp_conn *)psock->s_conn;
+ udp_conn->private = (void*)&state;
+ udp_conn->event = recvfrom_interrupt;
/* Enable the UDP socket */
@@ -420,8 +470,8 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Make sure that no further interrupts are processed */
uip_udpdisable(psock->s_conn);
- udp_conn->private = NULL;
- udp_conn->callback = NULL;
+ udp_conn->private = NULL;
+ udp_conn->event = NULL;
irqrestore(save);
#warning "Needs to return server address"
@@ -482,9 +532,9 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Set up the callback in the connection */
- conn = (struct uip_conn *)psock->s_conn;
- conn->private = (void*)&state;
- conn->callback = recvfrom_interrupt;
+ conn = (struct uip_conn *)psock->s_conn;
+ conn->data_private = (void*)&state;
+ conn->data_event = recvfrom_interrupt;
/* Wait for either the receive to complete or for an error/timeout to occur.
* NOTES: (1) sem_wait will also terminate if a signal is received, (2)
@@ -496,8 +546,8 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Make sure that no further interrupts are processed */
- conn->private = NULL;
- conn->callback = NULL;
+ conn->data_private = NULL;
+ conn->data_event = NULL;
irqrestore(save);
#warning "Needs to return server address"
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index 037455faf..57e19ade7 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -78,13 +78,14 @@ struct send_s
****************************************************************************/
/****************************************************************************
- * Function: send_Interrupt
+ * Function: send_interrupt
*
* Description:
* This function is called from the interrupt level to perform the actual
* send operation when polled by the uIP layer.
*
* Parameters:
+ * dev The sructure of the network driver that caused the interrupt
* private An instance of struct send_s cast to void*
*
* Returned Value:
@@ -95,7 +96,7 @@ struct send_s
*
****************************************************************************/
-static void send_interrupt(void *private)
+static void send_interrupt(struct uip_driver_s *dev, void *private)
{
struct send_s *pstate = (struct send_s *)private;
struct uip_conn *conn;
@@ -108,11 +109,11 @@ static void send_interrupt(void *private)
{
if (pstate->snd_buflen > uip_mss())
{
- uip_send(pstate->snd_buffer, uip_mss());
+ uip_send(dev, pstate->snd_buffer, uip_mss());
}
else
{
- uip_send(pstate->snd_buffer, pstate->snd_buflen);
+ uip_send(dev, pstate->snd_buffer, pstate->snd_buflen);
}
pstate->snd_state = STATE_DATA_SENT;
@@ -146,9 +147,9 @@ static void send_interrupt(void *private)
/* Don't allow any further call backs. */
- conn = (struct uip_conn *)pstate->snd_sock->s_conn;
- conn->private = NULL;
- conn->callback = NULL;
+ conn = (struct uip_conn *)pstate->snd_sock->s_conn;
+ conn->data_private = NULL;
+ conn->data_event = NULL;
/* Wake up the waiting thread, returning the number of bytes
* actually sent.
@@ -157,6 +158,23 @@ static void send_interrupt(void *private)
sem_post(&pstate->snd_sem);
}
}
+
+ /* Check for a loss of connection */
+
+ else if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ /* Stop further callbacks */
+
+ uip_udp_conn->private = NULL;
+ uip_udp_conn->event = NULL;
+
+ /* Report not connected */
+
+ pstate->snd_sent = -ENOTCONN;
+ /* Wake up the waiting thread */
+
+ sem_post(&pstate->snd_sem);
+ }
}
/****************************************************************************
@@ -275,9 +293,9 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
{
/* Set up the callback in the connection */
- conn = (struct uip_conn *)psock->s_conn;
- conn->private = (void*)&state;
- conn->callback = send_interrupt;
+ conn = (struct uip_conn *)psock->s_conn;
+ conn->data_private = (void*)&state;
+ conn->data_event = send_interrupt;
/* Wait for the send to complete or an error to occur: NOTES: (1)
* sem_wait will also terminate if a signal is received, (2) interrupts
@@ -289,8 +307,8 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
/* Make sure that no further interrupts are processed */
- conn->private = NULL;
- conn->callback = NULL;
+ conn->data_private = NULL;
+ conn->data_event = NULL;
}
sem_destroy(&state. snd_sem);
diff --git a/nuttx/net/sendto.c b/nuttx/net/sendto.c
index b14f301a2..0d03252f5 100644
--- a/nuttx/net/sendto.c
+++ b/nuttx/net/sendto.c
@@ -45,6 +45,7 @@
#include <string.h>
#include <errno.h>
#include <arch/irq.h>
+#include <net/uip/uip-arch.h>
#include "net-internal.h"
@@ -61,32 +62,64 @@ struct sendto_s
sem_t st_sem; /* Semaphore signals sendto completion */
uint16 st_buflen; /* Length of send buffer (error if <0) */
const char *st_buffer; /* Pointer to send buffer */
+ int st_sndlen; /* Result of the send (length sent or negated errno) */
};
/****************************************************************************
* Private Functions
****************************************************************************/
-void sendto_interrupt(void *private)
+/****************************************************************************
+ * Function: sendto_interrupt
+ *
+ * Description:
+ * This function is called from the interrupt level to perform the actual
+ * send operation when polled by the uIP layer.
+ *
+ * Parameters:
+ * dev The sructure of the network driver that caused the interrupt
+ * private An instance of struct sendto_s cast to void*
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * Running at the interrupt level
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_UDP
+void sendto_interrupt(struct uip_driver_s *dev, void *private)
{
struct sendto_s *pstate = (struct sendto_s *)private;
if (private)
{
- /* Copy the user data into appdata and send it */
+ /* Check if the connectin was rejected */
+
+ if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
+ {
+ pstate->st_sndlen = -ENOTCONN;
+ }
+ else
+ {
+ /* Copy the user data into d_appdata and send it */
- memcpy(uip_appdata, pstate->st_buffer, pstate->st_buflen);
- uip_udp_send(pstate->st_buflen);
+ memcpy(dev->d_appdata, pstate->st_buffer, pstate->st_buflen);
+ uip_send(dev, dev->d_appdata, pstate->st_buflen);
+ pstate->st_sndlen = pstate->st_buflen;
+ }
- /* Don't allow any furhter call backs. */
+ /* Don't allow any further call backs. */
- uip_conn->private = NULL;
- uip_conn->callback = NULL;
+ uip_udp_conn->private = NULL;
+ uip_udp_conn->event = NULL;
/* Wake up the waiting thread */
sem_post(&pstate->st_sem);
}
}
+#endif
/****************************************************************************
* Global Functions
@@ -242,8 +275,8 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* Set up the callback in the connection */
udp_conn = (struct uip_udp_conn *)psock->s_conn;
- udp_conn->private = (void*)&state;
- udp_conn->callback = sendto_interrupt;
+ udp_conn->private = (void*)&state;
+ udp_conn->event = sendto_interrupt;
/* Enable the UDP socket */
@@ -260,8 +293,8 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* Make sure that no further interrupts are processed */
uip_udpdisable(psock->s_conn);
- udp_conn->private = NULL;
- udp_conn->callback = NULL;
+ udp_conn->private = NULL;
+ udp_conn->event = NULL;
irqrestore(save);
sem_destroy(&state.st_sem);
@@ -269,7 +302,18 @@ ssize_t sendto(int sockfd, const void *buf, size_t len, int flags,
/* Set the socket state to idle */
psock->s_flags = _SS_SETSTATE(psock->s_flags, _SF_IDLE);
- return len;
+
+ /* Check for errors */
+
+ if (state.st_sndlen < 0)
+ {
+ err = -state.st_sndlen;
+ goto errout;
+ }
+
+ /* Sucess */
+
+ return state.st_sndlen;
#else
err = ENOSYS;
#endif
diff --git a/nuttx/net/uip/Make.defs b/nuttx/net/uip/Make.defs
index 628b39638..fd20143ff 100644
--- a/nuttx/net/uip/Make.defs
+++ b/nuttx/net/uip/Make.defs
@@ -34,6 +34,6 @@
############################################################################
UIP_ASRCS =
-UIP_CSRCS = uip-arp.c uip.c uip-fw.c uip-neighbor.c uip-split.c \
+UIP_CSRCS = uip-arp.c uip.c uip-send.c uip-fw.c uip-neighbor.c uip-split.c \
uip-tcpconn.c uip-udpconn.c
diff --git a/nuttx/net/uip/uip-arp.c b/nuttx/net/uip/uip-arp.c
index f27f5bb2e..ac2a952c7 100644
--- a/nuttx/net/uip/uip-arp.c
+++ b/nuttx/net/uip/uip-arp.c
@@ -41,6 +41,7 @@
#include <sys/types.h>
#include <string.h>
+#include <net/uip/uip-arch.h>
#include <net/uip/uip-arp.h>
struct arp_hdr
@@ -94,36 +95,29 @@ static uint8 i, c;
static uint8 arptime;
static uint8 tmpage;
-#define BUF ((struct arp_hdr *)&uip_buf[0])
-#define IPBUF ((struct ethip_hdr *)&uip_buf[0])
-/*-----------------------------------------------------------------------------------*/
-/**
- * Initialize the ARP module.
- *
- */
-/*-----------------------------------------------------------------------------------*/
-void
-uip_arp_init(void)
+#define BUF ((struct arp_hdr *)&dev->d_buf[0])
+#define IPBUF ((struct ethip_hdr *)&dev->d_buf[0])
+
+/* Initialize the ARP module. */
+
+void uip_arp_init(void)
{
for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
memset(arp_table[i].ipaddr, 0, 4);
}
}
-/*-----------------------------------------------------------------------------------*/
-/**
- * Periodic ARP processing function.
+
+/* Periodic ARP processing function.
*
* 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.
- *
*/
-/*-----------------------------------------------------------------------------------*/
-void
-uip_arp_timer(void)
+
+void uip_arp_timer(void)
{
struct arp_entry *tabptr;
-
+
++arptime;
for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
tabptr = &arp_table[i];
@@ -135,9 +129,7 @@ uip_arp_timer(void)
}
-/*-----------------------------------------------------------------------------------*/
-static void
-uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
+static void uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
{
register struct arp_entry *tabptr;
/* Walk through the ARP mapping table and try to find an entry to
@@ -154,7 +146,7 @@ uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
the IP address in this ARP table entry. */
if(pipaddr[0] == tabptr->ipaddr[0] &&
pipaddr[1] == tabptr->ipaddr[1]) {
-
+
/* An old entry found, update this and return. */
memcpy(tabptr->ethaddr.addr, ethaddr->addr, 6);
tabptr->time = arptime;
@@ -198,9 +190,8 @@ uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
memcpy(tabptr->ethaddr.addr, ethaddr->addr, 6);
tabptr->time = arptime;
}
-/*-----------------------------------------------------------------------------------*/
-/**
- * ARP processing for incoming IP packets
+
+/* 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
@@ -208,16 +199,15 @@ uip_arp_update(uint16 *pipaddr, struct uip_eth_addr *ethaddr)
* 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 uip_buf[] buffer, and the length of the packet in the global
- * variable uip_len.
+ * in the d_buf[] buffer, and the length of the packet in the field
+ * d_len.
*/
-/*-----------------------------------------------------------------------------------*/
+
#if 0
-void
-uip_arp_ipin(void)
+void uip_arp_ipin(void)
{
- uip_len -= sizeof(struct uip_eth_hdr);
-
+ dev->d_len -= sizeof(struct uip_eth_hdr);
+
/* Only insert/update an entry if the source IP address of the
incoming IP packet comes from a host on the local network. */
if((IPBUF->srcipaddr[0] & uip_netmask[0]) !=
@@ -229,13 +219,12 @@ uip_arp_ipin(void)
return;
}
uip_arp_update(IPBUF->srcipaddr, &(IPBUF->ethhdr.src));
-
+
return;
}
#endif /* 0 */
-/*-----------------------------------------------------------------------------------*/
-/**
- * ARP processing for incoming ARP packets.
+
+/* 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
@@ -243,29 +232,27 @@ uip_arp_ipin(void)
* 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 uip_buf[] buffer.
+ * into the d_buf[] buffer.
*
- * When the function returns, the value of the global variable uip_len
+ * When the function returns, the value of the field d_len
* indicates whether the device driver should send out a packet or
- * not. If uip_len is zero, no packet should be sent. If uip_len is
+ * 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 uip_buf[] buffer.
+ * present in the d_buf[] buffer.
*
* This function expects an ARP packet with a prepended Ethernet
- * header in the uip_buf[] buffer, and the length of the packet in the
- * global variable uip_len.
+ * header in the d_buf[] buffer, and the length of the packet in the
+ * global variable d_len.
*/
-/*-----------------------------------------------------------------------------------*/
-void
-uip_arp_arpin(void)
+
+void uip_arp_arpin(struct uip_driver_s *dev)
{
-
- if(uip_len < sizeof(struct arp_hdr)) {
- uip_len = 0;
+ if(dev->d_len < sizeof(struct arp_hdr)) {
+ dev->d_len = 0;
return;
}
- uip_len = 0;
-
+ dev->d_len = 0;
+
switch(BUF->opcode) {
case HTONS(ARP_REQUEST):
/* ARP request. If it asked for our address, we send out a
@@ -275,7 +262,7 @@ uip_arp_arpin(void)
table, since it is likely that we will do more communication
with this host in the future. */
uip_arp_update(BUF->sipaddr, &BUF->shwaddr);
-
+
/* The reply opcode is 2. */
BUF->opcode = HTONS(2);
@@ -283,14 +270,14 @@ uip_arp_arpin(void)
memcpy(BUF->shwaddr.addr, uip_ethaddr.addr, 6);
memcpy(BUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
memcpy(BUF->ethhdr.dest.addr, BUF->dhwaddr.addr, 6);
-
+
BUF->dipaddr[0] = BUF->sipaddr[0];
BUF->dipaddr[1] = BUF->sipaddr[1];
BUF->sipaddr[0] = uip_hostaddr[0];
BUF->sipaddr[1] = uip_hostaddr[1];
BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
- uip_len = sizeof(struct arp_hdr);
+ dev->d_len = sizeof(struct arp_hdr);
}
break;
case HTONS(ARP_REPLY):
@@ -304,9 +291,8 @@ uip_arp_arpin(void)
return;
}
-/*-----------------------------------------------------------------------------------*/
-/**
- * Prepend Ethernet header to an outbound IP packet and see if we need
+
+/* 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
@@ -319,7 +305,7 @@ uip_arp_arpin(void)
* 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 uip_buf[] is replaced by
+ * 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.
@@ -327,16 +313,14 @@ uip_arp_arpin(void)
* 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 uip_buf[]
- * buffer, and the length of the packet is in the global variable
- * uip_len.
+ * 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(void)
+
+void uip_arp_out(struct uip_driver_s *dev)
{
struct arp_entry *tabptr;
-
+
/* 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.
@@ -358,7 +342,7 @@ uip_arp_out(void)
/* Else, we use the destination IP address. */
uip_ipaddr_copy(ipaddr, IPBUF->destipaddr);
}
-
+
for(i = 0; i < UIP_ARPTAB_SIZE; ++i) {
tabptr = &arp_table[i];
if(uip_ipaddr_cmp(ipaddr, tabptr->ipaddr)) {
@@ -374,7 +358,7 @@ uip_arp_out(void)
memset(BUF->dhwaddr.addr, 0x00, 6);
memcpy(BUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
memcpy(BUF->shwaddr.addr, uip_ethaddr.addr, 6);
-
+
uip_ipaddr_copy(BUF->dipaddr, ipaddr);
uip_ipaddr_copy(BUF->sipaddr, uip_hostaddr);
BUF->opcode = HTONS(ARP_REQUEST); /* ARP request. */
@@ -384,9 +368,9 @@ uip_arp_out(void)
BUF->protolen = 4;
BUF->ethhdr.type = HTONS(UIP_ETHTYPE_ARP);
- uip_appdata = &uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN];
-
- uip_len = sizeof(struct arp_hdr);
+ dev->d_appdata = &dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN];
+
+ dev->d_len = sizeof(struct arp_hdr);
return;
}
@@ -394,12 +378,8 @@ uip_arp_out(void)
memcpy(IPBUF->ethhdr.dest.addr, tabptr->ethaddr.addr, 6);
}
memcpy(IPBUF->ethhdr.src.addr, uip_ethaddr.addr, 6);
-
+
IPBUF->ethhdr.type = HTONS(UIP_ETHTYPE_IP);
- uip_len += sizeof(struct uip_eth_hdr);
+ dev->d_len += sizeof(struct uip_eth_hdr);
}
-/*-----------------------------------------------------------------------------------*/
-
-/** @} */
-/** @} */
diff --git a/nuttx/net/uip/uip-fw.c b/nuttx/net/uip/uip-fw.c
index 8914994ea..18834c883 100644
--- a/nuttx/net/uip/uip-fw.c
+++ b/nuttx/net/uip/uip-fw.c
@@ -33,6 +33,8 @@
* SUCH DAMAGE.
*/
+#include <nuttx/config.h>
+#include <debug.h>
#include <net/uip/uip.h>
#include <net/uip/uip-arch.h>
@@ -40,17 +42,16 @@
#include <string.h> /* for memcpy() */
-/*
- * The list of registered network interfaces.
- */
+/* The list of registered network interfaces. */
+
static struct uip_fw_netif *netifs = NULL;
-/*
- * A pointer to the default network interface.
- */
+/* A pointer to the default network interface. */
+
static struct uip_fw_netif *defaultnetif = NULL;
-struct tcpip_hdr {
+struct tcpip_hdr
+{
/* IP header. */
uint8 vhl,
tos;
@@ -101,23 +102,19 @@ struct icmpip_hdr {
/* ICMP TIME-EXCEEDED. */
#define ICMP_TE 11
-/*
- * Pointer to the TCP/IP headers of the packet in the uip_buf buffer.
- */
-#define BUF ((struct tcpip_hdr *)&uip_buf[UIP_LLH_LEN])
+/* 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 uip_buf buffer.
- */
-#define ICMPBUF ((struct icmpip_hdr *)&uip_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
+/* Certain fields of an IP packet that are used for identifying
* duplicate packets.
*/
-struct fwcache_entry {
- uint16 timer;
+struct fwcache_entry
+{
+ uint16 timer;
uint16 srcipaddr[2];
uint16 destipaddr[2];
uint16 ipid;
@@ -133,35 +130,25 @@ struct fwcache_entry {
#endif
};
-/*
- * The number of packets to remember when looking for duplicates.
- */
+/* 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
+/* A cache of packet header fields which are used for
* identifying duplicate packets.
*/
+
static struct fwcache_entry fwcache[FWCACHE_SIZE];
-/**
- * \internal
- * The time that a packet cache is active.
- */
+/* The time that a packet cache is active. */
#define FW_TIME 20
-/*------------------------------------------------------------------------------*/
-/**
- * Initialize the uIP packet forwarding module.
- */
-/*------------------------------------------------------------------------------*/
-void
-uip_fw_init(void)
+/* Initialize the uIP packet forwarding module. */
+
+void uip_fw_init(void)
{
struct uip_fw_netif *t;
defaultnetif = NULL;
@@ -171,42 +158,36 @@ uip_fw_init(void)
t->next = NULL;
}
}
-/*------------------------------------------------------------------------------*/
-/**
- * \internal
- * Check if an IP address is within the network defined by an IP
+
+/* Check if an IP address is within the network defined by an IP
* address and a netmask.
*
- * \param ipaddr The IP address to be checked.
- * \param netipaddr The IP address of the network.
- * \param netmask The netmask of the network.
+ * ipaddr The IP address to be checked.
+ * netipaddr The IP address of the network.
+ * netmask The netmask of the network.
*
- * \return Non-zero if IP address is in network, zero otherwise.
+ * Return: Non-zero if IP address is in network, zero otherwise.
*/
-/*------------------------------------------------------------------------------*/
-static unsigned char
-ipaddr_maskcmp(uint16 *ipaddr, uint16 *netipaddr, uint16 *netmask)
+
+static unsigned char ipaddr_maskcmp(uint16 *ipaddr, uint16 *netipaddr, uint16 *netmask)
{
return (ipaddr[0] & netmask [0]) == (netipaddr[0] & netmask[0]) &&
(ipaddr[1] & netmask[1]) == (netipaddr[1] & netmask[1]);
}
-/*------------------------------------------------------------------------------*/
-/**
- * \internal
- * Send out an ICMP TIME-EXCEEDED message.
+
+/* Send out an ICMP TIME-EXCEEDED message.
*
- * This function replaces the packet in the uip_buf buffer with the
+ * This function replaces the packet in the d_buf buffer with the
* ICMP packet.
*/
-/*------------------------------------------------------------------------------*/
-static void
-time_exceeded(void)
+
+static void time_exceeded(struct uip_driver_s *dev)
{
uint16 tmp16;
/* We don't send out ICMP errors for ICMP messages. */
if(ICMPBUF->proto == UIP_PROTO_ICMP) {
- uip_len = 0;
+ dev->d_len = 0;
return;
}
/* Copy fields from packet header into payload of this ICMP packet. */
@@ -235,9 +216,9 @@ time_exceeded(void)
/* The size of the ICMP time exceeded packet is 36 + the size of the
IP header (20) = 56. */
- uip_len = 56;
+ dev->d_len = 56;
ICMPBUF->len[0] = 0;
- ICMPBUF->len[1] = uip_len;
+ ICMPBUF->len[1] = dev->d_len;
/* Fill in the other fields in the IP header. */
ICMPBUF->vhl = 0x45;
@@ -245,29 +226,24 @@ time_exceeded(void)
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());
-
-
+ ICMPBUF->ipchksum = ~(uip_ipchksum(dev));
}
-/*------------------------------------------------------------------------------*/
-/**
- * \internal
- * Register a packet in the forwarding cache so that it won't be
+
+/* Register a packet in the forwarding cache so that it won't be
* forwarded again.
*/
-/*------------------------------------------------------------------------------*/
-static void
-fwcache_register(void)
+
+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) {
@@ -295,17 +271,13 @@ fwcache_register(void)
fw->offset = BUF->ipoffset;
#endif
}
-/*------------------------------------------------------------------------------*/
-/**
- * \internal
- * Find a network interface for the IP packet in uip_buf.
- */
-/*------------------------------------------------------------------------------*/
-static struct uip_fw_netif *
-find_netif(void)
+
+/* 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(ipaddr_maskcmp(BUF->destipaddr, netif->ipaddr,
@@ -314,37 +286,35 @@ find_netif(void)
return netif;
}
}
-
+
/* If no matching netif was found, we use default netif. */
return defaultnetif;
}
-/*------------------------------------------------------------------------------*/
-/**
- * Output an IP packet on the correct network interface.
+
+/* Output an IP packet on the correct network interface.
*
- * The IP packet should be present in the uip_buf buffer and its
- * length in the global uip_len variable.
+ * The IP packet should be present in the d_buf buffer and its
+ * length in the d_len field.
*
- * \retval UIP_FW_ZEROLEN Indicates that a zero-length packet
+ * Return: UIP_FW_ZEROLEN Indicates that a zero-length packet
* transmission was attempted and that no packet was sent.
*
- * \retval UIP_FW_NOROUTE No suitable network interface could be found
+ * 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
+ * Return: The return value from the actual network interface output
* function is passed unmodified as a return value.
*/
-/*------------------------------------------------------------------------------*/
-uint8
-uip_fw_output(void)
+
+uint8 uip_fw_output(struct uip_driver_s *dev)
{
struct uip_fw_netif *netif;
- if(uip_len == 0) {
+ if(dev->d_len == 0) {
return UIP_FW_ZEROLEN;
}
- fwcache_register();
+ fwcache_register(dev);
#if UIP_BROADCAST
/* Link local broadcasts go out on all interfaces. */
@@ -360,11 +330,9 @@ uip_fw_output(void)
return UIP_FW_OK;
}
#endif /* UIP_BROADCAST */
-
- netif = find_netif();
- /* printf("uip_fw_output: netif %p ->output %p len %d\n", netif,
- netif->output,
- uip_len);*/
+
+ netif = find_netif(dev);
+ dbg("uip_fw_output: netif %p ->output %p len %d\n", netif, netif->output, dev->d_len);
if(netif == NULL) {
return UIP_FW_NOROUTE;
@@ -373,18 +341,14 @@ uip_fw_output(void)
output function to send out the packet. */
return netif->output();
}
-/*------------------------------------------------------------------------------*/
-/**
- * Forward an IP packet in the uip_buf buffer.
- *
- *
+
+/* Forward an IP packet in the d_buf buffer.
*
- * \return UIP_FW_FORWARDED if the packet was forwarded, UIP_FW_LOCAL if
+ * Return: UIP_FW_FORWARDED if the packet was forwarded, UIP_FW_LOCAL if
* the packet should be processed locally.
*/
-/*------------------------------------------------------------------------------*/
-uint8
-uip_fw_forward(void)
+
+uint8 uip_fw_forward(struct uip_driver_s *dev)
{
struct fwcache_entry *fw;
@@ -430,19 +394,21 @@ uip_fw_forward(void)
}
/* If the TTL reaches zero we produce an ICMP time exceeded message
- in the uip_buf buffer and forward that packet back to the sender
- of the packet. */
+ 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[0] == 0xffff && BUF->destipaddr[1] == 0xffff) {
return UIP_FW_LOCAL;
}
- time_exceeded();
+ 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;
@@ -450,9 +416,9 @@ uip_fw_forward(void)
BUF->ipchksum = BUF->ipchksum + HTONS(0x0100);
}
- if(uip_len > 0) {
- uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_TCPIP_HLEN];
- uip_fw_output();
+ if(dev->d_len > 0) {
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_TCPIP_HLEN];
+ uip_fw_output(dev);
}
#if UIP_BROADCAST
@@ -465,43 +431,36 @@ uip_fw_forward(void)
other processing should be made. */
return UIP_FW_FORWARDED;
}
-/*------------------------------------------------------------------------------*/
-/**
- * Register a network interface with the forwarding module.
+
+/* Register a network interface with the forwarding module.
*
- * \param netif A pointer to the network interface that is to be
+ * netif A pointer to the network interface that is to be
* registered.
*/
-/*------------------------------------------------------------------------------*/
-void
-uip_fw_register(struct uip_fw_netif *netif)
+
+void uip_fw_register(struct uip_fw_netif *netif)
{
netif->next = netifs;
netifs = netif;
}
-/*------------------------------------------------------------------------------*/
-/**
- * Register a default network interface.
+
+/* 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.
*
- * \param netif A pointer to the network interface that is to be
+ * netif A pointer to the network interface that is to be
* registered.
*/
-/*------------------------------------------------------------------------------*/
-void
-uip_fw_default(struct uip_fw_netif *netif)
+
+void uip_fw_default(struct uip_fw_netif *netif)
{
defaultnetif = netif;
}
-/*------------------------------------------------------------------------------*/
-/**
- * Perform periodic processing.
- */
-/*------------------------------------------------------------------------------*/
-void
-uip_fw_periodic(void)
+
+/* Perform periodic processing. */
+
+void uip_fw_periodic(void)
{
struct fwcache_entry *fw;
for(fw = fwcache; fw < &fwcache[FWCACHE_SIZE]; ++fw) {
@@ -510,4 +469,3 @@ uip_fw_periodic(void)
}
}
}
-/*------------------------------------------------------------------------------*/
diff --git a/nuttx/net/uip/uip-fw.h b/nuttx/net/uip/uip-fw.h
index b3153cd31..2be62078a 100644
--- a/nuttx/net/uip/uip-fw.h
+++ b/nuttx/net/uip/uip-fw.h
@@ -60,116 +60,92 @@ struct uip_fw_netif
sends a packet. */
};
-/**
- * Intantiating macro for a uIP network interface.
+/* Intantiating macro for a uIP network interface.
*
* Example:
- \code
- struct uip_fw_netif slipnetif =
- {UIP_FW_NETIF(192,168,76,1, 255,255,255,0, slip_output)};
- \endcode
- * \param ip1,ip2,ip3,ip4 The IP address of the network interface.
*
- * \param nm1,nm2,nm3,nm4 The netmask of the network interface.
+ * struct uip_fw_netif slipnetif =
+ * {UIP_FW_NETIF(192,168,76,1, 255,255,255,0, slip_output)};
*
- * \param outputfunc A pointer to the output function of the network interface.
+ * ip1,ip2,ip3,ip4 The IP address of the network interface.
*
- * \hideinitializer
+ * nm1,nm2,nm3,nm4 The netmask of the network interface.
+ *
+ * outputfunc A pointer to the output function of the network interface.
*/
+
#define UIP_FW_NETIF(ip1,ip2,ip3,ip4, nm1,nm2,nm3,nm4, outputfunc) \
NULL, \
{HTONS((ip1 << 8) | ip2), HTONS((ip3 << 8) | ip4)}, \
{HTONS((nm1 << 8) | nm2), HTONS((nm3 << 8) | nm4)}, \
outputfunc
-/**
- * Set the IP address of a network interface.
+/* Set the IP address of a network interface.
*
- * \param netif A pointer to the uip_fw_netif structure for the network interface.
+ * netif A pointer to the uip_fw_netif structure for the network interface.
*
- * \param addr A pointer to an IP address.
- *
- * \hideinitializer
+ * addr A pointer to an IP address.
*/
+
#define uip_fw_setipaddr(netif, addr) \
do { (netif)->ipaddr[0] = ((uint16 *)(addr))[0]; \
(netif)->ipaddr[1] = ((uint16 *)(addr))[1]; } while(0)
-/**
- * Set the netmask of a network interface.
- *
- * \param netif A pointer to the uip_fw_netif structure for the network interface.
+
+/* Set the netmask of a network interface.
*
- * \param addr A pointer to an IP address representing the netmask.
+ * netif A pointer to the uip_fw_netif structure for the network interface.
*
- * \hideinitializer
+ * addr A pointer to an IP address representing the netmask.
*/
+
#define uip_fw_setnetmask(netif, addr) \
do { (netif)->netmask[0] = ((uint16 *)(addr))[0]; \
(netif)->netmask[1] = ((uint16 *)(addr))[1]; } while(0)
void uip_fw_init(void);
-uint8 uip_fw_forward(void);
-uint8 uip_fw_output(void);
+uint8 uip_fw_forward(struct uip_driver_s *dev);
+uint8 uip_fw_output(struct uip_driver_s *dev);
void uip_fw_register(struct uip_fw_netif *netif);
void uip_fw_default(struct uip_fw_netif *netif);
void uip_fw_periodic(void);
-/**
- * A non-error message that indicates that a packet should be
+/* A non-error message that indicates that a packet should be
* processed locally.
- *
- * \hideinitializer
*/
+
#define UIP_FW_LOCAL 0
-/**
- * A non-error message that indicates that something went OK.
- *
- * \hideinitializer
- */
+/* A non-error message that indicates that something went OK. */
+
#define UIP_FW_OK 0
-/**
- * A non-error message that indicates that a packet was forwarded.
- *
- * \hideinitializer
- */
+/* A non-error message that indicates that a packet was forwarded. */
+
#define UIP_FW_FORWARDED 1
-/**
- * A non-error message that indicates that a zero-length packet
+/* A non-error message that indicates that a zero-length packet
* transmission was attempted, and that no packet was sent.
- *
- * \hideinitializer
*/
+
#define UIP_FW_ZEROLEN 2
-/**
- * An error message that indicates that a packet that was too large
+/* An error message that indicates that a packet that was too large
* for the outbound network interface was detected.
- *
- * \hideinitializer
*/
+
#define UIP_FW_TOOLARGE 3
-/**
- * An error message that indicates that no suitable interface could be
+/* An error message that indicates that no suitable interface could be
* found for an outbound packet.
- *
- * \hideinitializer
*/
+
#define UIP_FW_NOROUTE 4
-/**
- * An error message that indicates that a packet that should be
+/* An error message that indicates that a packet that should be
* forwarded or output was dropped.
- *
- * \hideinitializer
*/
-#define UIP_FW_DROPPED 5
+#define UIP_FW_DROPPED 5
#endif /* __UIP_FW_H__ */
-
-/** @} */
diff --git a/nuttx/net/uip/uip-send.c b/nuttx/net/uip/uip-send.c
new file mode 100644
index 000000000..d5acbb0e4
--- /dev/null
+++ b/nuttx/net/uip/uip-send.c
@@ -0,0 +1,99 @@
+/****************************************************************************
+ * uip-send.c
+ *
+ * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 <net/uip/uip.h>
+#include <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)
+{
+ if (dev && len > 0 && len < UIP_BUFSIZE)
+ {
+ dev->d_sndlen = len;
+ memcpy(dev->d_snddata, buf, len );
+ }
+}
diff --git a/nuttx/net/uip/uip-split.c b/nuttx/net/uip/uip-split.c
index a85a8db96..8488bd3d1 100644
--- a/nuttx/net/uip/uip-split.c
+++ b/nuttx/net/uip/uip-split.c
@@ -38,19 +38,17 @@
#include "uip-split.h"
#include "uip-fw.h"
-#define BUF ((struct uip_tcpip_hdr *)&uip_buf[UIP_LLH_LEN])
+#define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-/*-----------------------------------------------------------------------------*/
-void
-uip_split_output(void)
+void uip_split_output(struct uip_driver_s *dev)
{
uint16 tcplen, len1, len2;
/* We only try to split maximum sized TCP segments. */
if(BUF->proto == UIP_PROTO_TCP &&
- uip_len == UIP_BUFSIZE - UIP_LLH_LEN) {
+ dev->d_len == UIP_BUFSIZE - UIP_LLH_LEN) {
- tcplen = uip_len - UIP_TCPIP_HLEN;
+ tcplen = dev->d_len - UIP_TCPIP_HLEN;
/* Split the segment in two. If the original packet length was
odd, we make the second packet one byte larger. */
len1 = len2 = tcplen / 2;
@@ -60,49 +58,49 @@ uip_split_output(void)
/* Create the first packet. This is done by altering the length
field of the IP header and updating the checksums. */
- uip_len = len1 + UIP_TCPIP_HLEN;
+ dev->d_len = len1 + UIP_TCPIP_HLEN;
#ifdef CONFIG_NET_IPv6
/* For IPv6, the IP length field does not include the IPv6 IP header
length. */
- BUF->len[0] = ((uip_len - UIP_IPH_LEN) >> 8);
- BUF->len[1] = ((uip_len - UIP_IPH_LEN) & 0xff);
+ BUF->len[0] = ((dev->d_len - UIP_IPH_LEN) >> 8);
+ BUF->len[1] = ((dev->d_len - UIP_IPH_LEN) & 0xff);
#else /* CONFIG_NET_IPv6 */
- BUF->len[0] = uip_len >> 8;
- BUF->len[1] = uip_len & 0xff;
+ BUF->len[0] = dev->d_len >> 8;
+ BUF->len[1] = dev->d_len & 0xff;
#endif /* CONFIG_NET_IPv6 */
/* Recalculate the TCP checksum. */
BUF->tcpchksum = 0;
- BUF->tcpchksum = ~(uip_tcpchksum());
+ BUF->tcpchksum = ~(uip_tcpchksum(dev));
#ifndef CONFIG_NET_IPv6
/* Recalculate the IP checksum. */
BUF->ipchksum = 0;
- BUF->ipchksum = ~(uip_ipchksum());
+ BUF->ipchksum = ~(uip_ipchksum(dev));
#endif /* CONFIG_NET_IPv6 */
-
+
/* Transmit the first packet. */
/* uip_fw_output();*/
tcpip_output();
/* Now, create the second packet. To do this, it is not enough to
just alter the length field, but we must also update the TCP
- sequence number and point the uip_appdata to a new place in
+ sequence number and point the d_appdata to a new place in
memory. This place is detemined by the length of the first
packet (len1). */
- uip_len = len2 + UIP_TCPIP_HLEN;
+ dev->d_len = len2 + UIP_TCPIP_HLEN;
#ifdef CONFIG_NET_IPv6
/* For IPv6, the IP length field does not include the IPv6 IP header
length. */
- BUF->len[0] = ((uip_len - UIP_IPH_LEN) >> 8);
- BUF->len[1] = ((uip_len - UIP_IPH_LEN) & 0xff);
+ BUF->len[0] = ((dev->d_len - UIP_IPH_LEN) >> 8);
+ BUF->len[1] = ((dev->d_len - UIP_IPH_LEN) & 0xff);
#else /* CONFIG_NET_IPv6 */
- BUF->len[0] = uip_len >> 8;
- BUF->len[1] = uip_len & 0xff;
+ BUF->len[0] = dev->d_len >> 8;
+ BUF->len[1] = dev->d_len & 0xff;
#endif /* CONFIG_NET_IPv6 */
- /* uip_appdata += len1;*/
- memcpy(uip_appdata, (uint8 *)uip_appdata + len1, len2);
+ /* dev->d_appdata += len1;*/
+ memcpy(dev->d_appdata, dev->d_appdata + len1, len2);
uip_add32(BUF->seqno, len1);
BUF->seqno[0] = uip_acc32[0];
@@ -112,12 +110,12 @@ uip_split_output(void)
/* Recalculate the TCP checksum. */
BUF->tcpchksum = 0;
- BUF->tcpchksum = ~(uip_tcpchksum());
+ BUF->tcpchksum = ~(uip_tcpchksum(dev));
#ifndef CONFIG_NET_IPv6
/* Recalculate the IP checksum. */
BUF->ipchksum = 0;
- BUF->ipchksum = ~(uip_ipchksum());
+ BUF->ipchksum = ~(uip_ipchksum(dev));
#endif /* CONFIG_NET_IPv6 */
/* Transmit the second packet. */
@@ -127,6 +125,4 @@ uip_split_output(void)
/* uip_fw_output();*/
tcpip_output();
}
-
}
-/*-----------------------------------------------------------------------------*/
diff --git a/nuttx/net/uip/uip-split.h b/nuttx/net/uip/uip-split.h
index 4779b017a..9e9635cae 100644
--- a/nuttx/net/uip/uip-split.h
+++ b/nuttx/net/uip/uip-split.h
@@ -66,23 +66,22 @@
#ifndef __UIP_SPLIT_H__
#define __UIP_SPLIT_H__
-/**
- * Handle outgoing packets.
+/* Handle outgoing packets.
*
- * This function inspects an outgoing packet in the uip_buf buffer and
+ * This function inspects an outgoing packet in the d_buf buffer and
* sends it out using the uip_fw_output() function. If the packet is a
* full-sized TCP segment it will be split into two segments and
* transmitted separately. This function should be called instead of
* the actual device driver output function, or the uip_fw_output()
* function.
*
- * The headers of the outgoing packet is assumed to be in the uip_buf
- * buffer and the payload is assumed to be wherever uip_appdata
+ * The headers of the outgoing packet is assumed to be in the d_buf
+ * buffer and the payload is assumed to be wherever d_appdata
* points. The length of the outgoing packet is assumed to be in the
- * uip_len variable.
- *
+ * d_len field.
*/
-void uip_split_output(void);
+
+void uip_split_output(struct uip_driver_s *dev);
#endif /* __UIP_SPLIT_H__ */
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
index 8f14dc24b..37ee80ae3 100644
--- a/nuttx/net/uip/uip-tcpconn.c
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -434,10 +434,10 @@ struct uip_conn *uip_tcplistener(struct uip_tcpip_hdr *buf)
*
****************************************************************************/
-void uip_tcppoll(unsigned int conn)
+void uip_tcppoll(struct uip_driver_s *dev, unsigned int conn)
{
uip_conn = &g_tcp_connections[conn];
- uip_interrupt(UIP_TIMER);
+ uip_interrupt(dev, UIP_TIMER);
}
/****************************************************************************
diff --git a/nuttx/net/uip/uip-udpconn.c b/nuttx/net/uip/uip-udpconn.c
index 8c88a9bc0..e67bbd04b 100644
--- a/nuttx/net/uip/uip-udpconn.c
+++ b/nuttx/net/uip/uip-udpconn.c
@@ -282,10 +282,10 @@ struct uip_udp_conn *uip_udpactive(struct uip_udpip_hdr *buf)
*
****************************************************************************/
-void uip_udppoll(unsigned int conn)
+void uip_udppoll(struct uip_driver_s *dev, unsigned int conn)
{
uip_udp_conn = &g_udp_connections[conn];
- uip_interrupt(UIP_UDP_TIMER);
+ uip_interrupt(dev, UIP_UDP_TIMER);
}
/****************************************************************************
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index bf4d94733..bd3f2e69c 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -51,17 +51,17 @@
* 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 uip_buf,
+ * 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 uip_buf and the application read the
+ * 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 uip_buf. The uip_appdata pointer points to the
+ * 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.
@@ -129,10 +129,10 @@ extern void uip_log(char *msg);
/* Macros. */
-#define BUF ((struct uip_tcpip_hdr *)&uip_buf[UIP_LLH_LEN])
+#define BUF ((struct uip_tcpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
#define FBUF ((struct uip_tcpip_hdr *)&uip_reassbuf[0])
-#define ICMPBUF ((struct uip_icmpip_hdr *)&uip_buf[UIP_LLH_LEN])
-#define UDPBUF ((struct uip_udpip_hdr *)&uip_buf[UIP_LLH_LEN])
+#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+#define UDPBUF ((struct uip_udpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
/****************************************************************************
* Public Variables
@@ -159,22 +159,13 @@ uip_ipaddr_t uip_draddr;
uip_ipaddr_t uip_netmask;
#endif /* UIP_FIXEDADDR */
-#ifndef CONFIG_NET_EXTERNAL_BUFFER
-uint8 uip_buf[UIP_BUFSIZE + 2]; /* The packet buffer that contains incoming packets. */
-#endif /* CONFIG_NET_EXTERNAL_BUFFER */
-
-void *uip_appdata; /* The uip_appdata pointer points to application data. */
-void *uip_sappdata; /* The uip_appdata pointer points to the application
- * data which is to be sent. */
#if UIP_URGDATA > 0
void *uip_urgdata; /* The uip_urgdata pointer points to urgent data
* (out-of-band data), if present. */
-uint16 uip_urglen, uip_surglen;
+uint16 uip_urglen;
+uint16 uip_surglen;
#endif /* UIP_URGDATA > 0 */
-uint16 uip_len, uip_slen; /* The uip_len is either 8 or 16 bits, depending
- * on the maximum packet size. */
-
uint8 uip_flags; /* The uip_flags variable is used for communication
* between the TCP/IP stack and the application
* program. */
@@ -273,7 +264,7 @@ static uint16 chksum(uint16 sum, const uint8 *data, uint16 len)
return sum;
}
-static uint16 upper_layer_chksum(uint8 proto)
+static uint16 upper_layer_chksum(struct uip_driver_s *dev, uint8 proto)
{
uint16 upper_layer_len;
uint16 sum;
@@ -293,15 +284,15 @@ static uint16 upper_layer_chksum(uint8 proto)
sum = chksum(sum, (uint8 *)&BUF->srcipaddr[0], 2 * sizeof(uip_ipaddr_t));
/* Sum TCP header and data. */
- sum = chksum(sum, &uip_buf[UIP_IPH_LEN + UIP_LLH_LEN], upper_layer_len);
+ sum = chksum(sum, &dev->d_buf[UIP_IPH_LEN + UIP_LLH_LEN], upper_layer_len);
return (sum == 0) ? 0xffff : htons(sum);
}
#ifdef CONFIG_NET_IPv6
-static uint16 uip_icmp6chksum(void)
+static uint16 uip_icmp6chksum(struct uip_driver_s *dev)
{
- return upper_layer_chksum(UIP_PROTO_ICMP6);
+ return upper_layer_chksum(dev, UIP_PROTO_ICMP6);
}
#endif /* CONFIG_NET_IPv6 */
@@ -358,32 +349,32 @@ uint16 uip_chksum(uint16 *data, uint16 len)
return htons(chksum(0, (uint8 *)data, len));
}
-/* Calculate the IP header checksum of the packet header in uip_buf. */
+/* Calculate the IP header checksum of the packet header in d_buf. */
#ifndef UIP_ARCH_IPCHKSUM
-uint16 uip_ipchksum(void)
+uint16 uip_ipchksum(struct uip_driver_s *dev)
{
uint16 sum;
- sum = chksum(0, &uip_buf[UIP_LLH_LEN], UIP_IPH_LEN);
+ sum = chksum(0, &dev->d_buf[UIP_LLH_LEN], UIP_IPH_LEN);
dbg("uip_ipchksum: sum 0x%04x\n", sum);
return (sum == 0) ? 0xffff : htons(sum);
}
#endif
-/* Calculate the TCP checksum of the packet in uip_buf and uip_appdata. */
+/* Calculate the TCP checksum of the packet in d_buf and d_appdata. */
-uint16 uip_tcpchksum(void)
+uint16 uip_tcpchksum(struct uip_driver_s *dev)
{
- return upper_layer_chksum(UIP_PROTO_TCP);
+ return upper_layer_chksum(dev, UIP_PROTO_TCP);
}
-/* Calculate the UDP checksum of the packet in uip_buf and uip_appdata. */
+/* Calculate the UDP checksum of the packet in d_buf and d_appdata. */
#ifdef CONFIG_NET_UDP_CHECKSUMS
-uint16 uip_udpchksum(void)
+uint16 uip_udpchksum(struct uip_driver_s *dev)
{
- return upper_layer_chksum(UIP_PROTO_UDP);
+ return upper_layer_chksum(dev, UIP_PROTO_UDP);
}
#endif /* UIP_UDP_CHECKSUMS */
#endif /* UIP_ARCH_CHKSUM */
@@ -573,7 +564,7 @@ static uint8 uip_reass(void)
BUF->len[0] = uip_reasslen >> 8;
BUF->len[1] = uip_reasslen & 0xff;
BUF->ipchksum = 0;
- BUF->ipchksum = ~(uip_ipchksum());
+ BUF->ipchksum = ~(uip_ipchksum(dev));
return uip_reasslen;
}
@@ -593,31 +584,46 @@ static void uip_add_rcv_nxt(uint16 n)
uip_conn->rcv_nxt[3] = uip_acc32[3];
}
-static void uip_udp_callback(void)
+static void uip_udp_callback(struct uip_driver_s *dev)
{
/* Some sanity checking */
- if (uip_udp_conn && uip_udp_conn->callback)
+ if (uip_udp_conn && uip_udp_conn->event)
{
/* Perform the callback */
- uip_udp_conn->callback(uip_udp_conn->private);
+ uip_udp_conn->event(dev, uip_udp_conn->private);
}
}
-static void uip_tcp_callback(void)
+static void uip_tcp_callback(struct uip_driver_s *dev)
{
/* Some sanity checking */
- if (uip_conn && uip_conn->callback)
+ if (uip_conn)
{
- /* Perform the callback */
+ /* Check if there is a data callback */
+
+ if (uip_conn->data_event)
+ {
+ /* Perform the callback */
+
+ uip_conn->data_event(dev, uip_conn->data_private);
+ }
+
+ /* Check if there is a connection-related event and a connection
+ * callback.
+ */
+ if (((uip_flags & UIP_CONN_EVENTS) != 0) && uip_conn->connection_event)
+ {
+ /* Perform the callback */
- uip_conn->callback(uip_conn->private);
+ uip_conn->connection_event(uip_conn->connection_private);
+ }
}
}
-void uip_interrupt(uint8 flag)
+void uip_interrupt(struct uip_driver_s *dev, uint8 flag)
{
register struct uip_conn *uip_connr = uip_conn;
@@ -628,7 +634,7 @@ void uip_interrupt(uint8 flag)
}
#endif /* CONFIG_NET_UDP */
- uip_sappdata = uip_appdata = &uip_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
+ dev->d_snddata = dev->d_appdata = &dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN];
/* Check if we were invoked because of a poll request for a
* particular connection.
@@ -640,13 +646,13 @@ void uip_interrupt(uint8 flag)
!uip_outstanding(uip_connr))
{
uip_flags = UIP_POLL;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
goto appsend;
}
goto drop;
}
- /* Check if we were invoked because of the perodic timer fireing. */
+ /* Check if we were invoked because of the perodic timer firing. */
else if (flag == UIP_TIMER)
{
@@ -663,8 +669,8 @@ void uip_interrupt(uint8 flag)
/* Reset the length variables. */
- uip_len = 0;
- uip_slen = 0;
+ 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
@@ -705,7 +711,7 @@ void uip_interrupt(uint8 flag)
*/
uip_flags = UIP_TIMEDOUT;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
/* We also send a reset packet to the remote host. */
@@ -749,7 +755,7 @@ void uip_interrupt(uint8 flag)
*/
uip_flags = UIP_REXMIT;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
goto apprexmit;
case UIP_FIN_WAIT_1:
@@ -768,7 +774,7 @@ void uip_interrupt(uint8 flag)
*/
uip_flags = UIP_POLL;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
goto appsend;
}
}
@@ -781,10 +787,11 @@ void uip_interrupt(uint8 flag)
if (uip_udp_conn->lport != 0)
{
uip_conn = NULL;
- uip_sappdata = uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
- uip_len = uip_slen = 0;
+ dev->d_snddata = dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
uip_flags = UIP_POLL;
- uip_udp_callback();
+ uip_udp_callback(dev);
goto udp_send;
}
else
@@ -822,19 +829,19 @@ void uip_interrupt(uint8 flag)
#endif /* CONFIG_NET_IPv6 */
/* Check the size of the packet. If the size reported to us in
- uip_len is smaller the size reported in the IP header, we assume
+ 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
- uip_len is larger than the size reported in the IP packet header,
- the packet has been padded and we set uip_len to the correct
+ 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.. */
- if ((BUF->len[0] << 8) + BUF->len[1] <= uip_len)
+ if ((BUF->len[0] << 8) + BUF->len[1] <= dev->d_len)
{
- uip_len = (BUF->len[0] << 8) + BUF->len[1];
+ dev->d_len = (BUF->len[0] << 8) + BUF->len[1];
#ifdef CONFIG_NET_IPv6
- uip_len += 40; /* The length reported in the IPv6 header is the
+ dev->d_len += 40; /* The length reported in the IPv6 header is the
length of the payload that follows the
- header. However, uIP uses the uip_len variable
+ 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
@@ -856,8 +863,8 @@ void uip_interrupt(uint8 flag)
BUF->ipoffset[1] != 0)
{
#if UIP_REASSEMBLY
- uip_len = uip_reass();
- if (uip_len == 0)
+ dev->d_len = uip_reass();
+ if (dev->d_len == 0)
{
goto drop;
}
@@ -894,10 +901,10 @@ void uip_interrupt(uint8 flag)
/* If IP broadcast support is configured, we check for a broadcast
UDP packet, which may be destined to us. */
#if UIP_BROADCAST
- dbg("UDP IP checksum 0x%04x\n", uip_ipchksum());
+ dbg("UDP IP checksum 0x%04x\n", uip_ipchksum(dev));
if (BUF->proto == UIP_PROTO_UDP &&
uip_ipaddr_cmp(BUF->destipaddr, all_ones_addr)
- /*&& uip_ipchksum() == 0xffff*/)
+ /*&& uip_ipchksum(dev) == 0xffff*/)
{
goto udp_input;
}
@@ -926,7 +933,7 @@ void uip_interrupt(uint8 flag)
}
#ifndef CONFIG_NET_IPv6
- if (uip_ipchksum() != 0xffff)
+ if (uip_ipchksum(dev) != 0xffff)
{
/* Compute and check the IP header checksum. */
@@ -1013,7 +1020,7 @@ void uip_interrupt(uint8 flag)
#else /* !CONFIG_NET_IPv6 */
/* This is IPv6 ICMPv6 processing code. */
- dbg("icmp6_input: length %d\n", uip_len);
+ dbg("icmp6_input: length %d\n", dev->d_len);
if (BUF->proto != UIP_PROTO_ICMP6)
{
@@ -1052,7 +1059,7 @@ void uip_interrupt(uint8 flag)
ICMPBUF->options[1] = 1; /* Options length, 1 = 8 bytes. */
memcpy(&(ICMPBUF->options[2]), &uip_ethaddr, sizeof(uip_ethaddr));
ICMPBUF->icmpchksum = 0;
- ICMPBUF->icmpchksum = ~uip_icmp6chksum();
+ ICMPBUF->icmpchksum = ~uip_icmp6chksum(dev);
goto send;
}
goto drop;
@@ -1068,7 +1075,7 @@ void uip_interrupt(uint8 flag)
uip_ipaddr_copy(BUF->destipaddr, BUF->srcipaddr);
uip_ipaddr_copy(BUF->srcipaddr, uip_hostaddr);
ICMPBUF->icmpchksum = 0;
- ICMPBUF->icmpchksum = ~uip_icmp6chksum();
+ ICMPBUF->icmpchksum = ~uip_icmp6chksum(dev);
UIP_STAT(++uip_stat.icmp.sent);
goto send;
@@ -1091,12 +1098,12 @@ void uip_interrupt(uint8 flag)
udp_input:
/* UDP processing is really just a hack. We don't do anything to the
UDP/IP headers, but let the UDP application do all the hard
- work. If the application sets uip_slen, it has a packet to
+ work. If the application sets d_sndlen, it has a packet to
send. */
#ifdef CONFIG_NET_UDP_CHECKSUMS
- uip_len = uip_len - UIP_IPUDPH_LEN;
- uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
- if (UDPBUF->udpchksum != 0 && uip_udpchksum() != 0xffff)
+ dev->d_len -= UIP_IPUDPH_LEN;
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+ if (UDPBUF->udpchksum != 0 && uip_udpchksum(dev) != 0xffff)
{
UIP_STAT(++uip_stat.udp.drop);
UIP_STAT(++uip_stat.udp.chkerr);
@@ -1104,7 +1111,7 @@ void uip_interrupt(uint8 flag)
goto drop;
}
#else /* UIP_UDP_CHECKSUMS */
- uip_len = uip_len - UIP_IPUDPH_LEN;
+ dev->d_len -= UIP_IPUDPH_LEN;
#endif /* UIP_UDP_CHECKSUMS */
/* Demultiplex this UDP packet between the UDP "connections". */
@@ -1121,31 +1128,31 @@ void uip_interrupt(uint8 flag)
udp_found:
uip_conn = NULL;
uip_flags = UIP_NEWDATA;
- uip_sappdata = uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
- uip_slen = 0;
- uip_udp_callback();
+ dev->d_snddata = dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPUDPH_LEN];
+ dev->d_sndlen = 0;
+ uip_udp_callback(dev);
udp_send:
- if (uip_slen == 0)
+ if (dev->d_sndlen == 0)
{
goto drop;
}
- uip_len = uip_slen + UIP_IPUDPH_LEN;
+ dev->d_len = dev->d_sndlen + UIP_IPUDPH_LEN;
#ifdef CONFIG_NET_IPv6
/* For IPv6, the IP length field does not include the IPv6 IP header
length. */
- BUF->len[0] = ((uip_len - UIP_IPH_LEN) >> 8);
- BUF->len[1] = ((uip_len - UIP_IPH_LEN) & 0xff);
+ BUF->len[0] = ((dev->d_len - UIP_IPH_LEN) >> 8);
+ BUF->len[1] = ((dev->d_len - UIP_IPH_LEN) & 0xff);
#else /* CONFIG_NET_IPv6 */
- BUF->len[0] = (uip_len >> 8);
- BUF->len[1] = (uip_len & 0xff);
+ BUF->len[0] = (dev->d_len >> 8);
+ BUF->len[1] = (dev->d_len & 0xff);
#endif /* CONFIG_NET_IPv6 */
BUF->ttl = uip_udp_conn->ttl;
BUF->proto = UIP_PROTO_UDP;
- UDPBUF->udplen = HTONS(uip_slen + UIP_UDPH_LEN);
+ UDPBUF->udplen = HTONS(dev->d_sndlen + UIP_UDPH_LEN);
UDPBUF->udpchksum = 0;
BUF->srcport = uip_udp_conn->lport;
@@ -1154,11 +1161,11 @@ void uip_interrupt(uint8 flag)
uip_ipaddr_copy(BUF->srcipaddr, uip_hostaddr);
uip_ipaddr_copy(BUF->destipaddr, uip_udp_conn->ripaddr);
- uip_appdata = &uip_buf[UIP_LLH_LEN + UIP_IPTCPH_LEN];
+ dev->d_appdata = &dev->d_buf[UIP_LLH_LEN + UIP_IPTCPH_LEN];
#ifdef CONFIG_NET_UDP_CHECKSUMS
/* Calculate UDP checksum. */
- UDPBUF->udpchksum = ~(uip_udpchksum());
+ UDPBUF->udpchksum = ~(uip_udpchksum(dev));
if (UDPBUF->udpchksum == 0)
{
UDPBUF->udpchksum = 0xffff;
@@ -1174,7 +1181,7 @@ void uip_interrupt(uint8 flag)
/* Start of TCP input header processing code. */
- if (uip_tcpchksum() != 0xffff)
+ if (uip_tcpchksum(dev) != 0xffff)
{
/* Compute and check the TCP checksum. */
@@ -1225,7 +1232,7 @@ void uip_interrupt(uint8 flag)
UIP_STAT(++uip_stat.tcp.rst);
BUF->flags = TCP_RST | TCP_ACK;
- uip_len = UIP_IPTCPH_LEN;
+ dev->d_len = UIP_IPTCPH_LEN;
BUF->tcpoffset = 5 << 4;
/* Flip the seqno and ackno fields in the TCP header. */
@@ -1302,7 +1309,7 @@ found_listen:
{
for (c = 0; c < ((BUF->tcpoffset >> 4) - 5) << 2 ;)
{
- opt = uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + c];
+ opt = dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + c];
if (opt == TCP_OPT_END)
{
/* End of options. */
@@ -1314,11 +1321,11 @@ found_listen:
/* NOP option. */
}
else if (opt == TCP_OPT_MSS &&
- uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == TCP_OPT_MSS_LEN)
+ dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == TCP_OPT_MSS_LEN)
{
/* An MSS option with the right option length. */
- tmp16 = ((uint16)uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + c] << 8) |
- (uint16)uip_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + 3 + c];
+ tmp16 = ((uint16)dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + c] << 8) |
+ (uint16)dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + 3 + c];
uip_connr->initialmss = uip_connr->mss =
tmp16 > UIP_TCP_MSS? UIP_TCP_MSS: tmp16;
@@ -1329,13 +1336,13 @@ found_listen:
{
/* All other options have a length field, so that we easily
can skip past them. */
- if (uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == 0)
+ if (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == 0)
{
/* If the length field is zero, the options are malformed
and we don't process them further. */
break;
}
- c += uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c];
+ c += dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c];
}
}
}
@@ -1353,7 +1360,7 @@ tcp_send_synack:
BUF->optdata[1] = TCP_OPT_MSS_LEN;
BUF->optdata[2] = (UIP_TCP_MSS) / 256;
BUF->optdata[3] = (UIP_TCP_MSS) & 255;
- uip_len = UIP_IPTCPH_LEN + TCP_OPT_MSS_LEN;
+ dev->d_len = UIP_IPTCPH_LEN + TCP_OPT_MSS_LEN;
BUF->tcpoffset = ((UIP_TCPH_LEN + TCP_OPT_MSS_LEN) / 4) << 4;
goto tcp_send;
@@ -1373,7 +1380,7 @@ tcp_send_synack:
uip_connr->tcpstateflags = UIP_CLOSED;
UIP_LOG("tcp: got reset, aborting connection.");
uip_flags = UIP_ABORT;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
goto drop;
}
@@ -1383,12 +1390,12 @@ tcp_send_synack:
c = (BUF->tcpoffset >> 4) << 2;
- /* uip_len will contain the length of the actual TCP data. This is
+ /* d_len will contain the length of the actual TCP data. This is
* calculated by subtracing the length of the TCP header (in
* c) and the length of the IP header (20 bytes).
*/
- uip_len = uip_len - c - UIP_IPH_LEN;
+ dev->d_len -= (c + 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
@@ -1398,7 +1405,7 @@ tcp_send_synack:
if (!(((uip_connr->tcpstateflags & UIP_TS_MASK) == UIP_SYN_SENT) &&
((BUF->flags & TCP_CTL) == (TCP_SYN | TCP_ACK))))
{
- if ((uip_len > 0 || ((BUF->flags & (TCP_SYN | TCP_FIN)) != 0)) &&
+ if ((dev->d_len > 0 || ((BUF->flags & (TCP_SYN | TCP_FIN)) != 0)) &&
(BUF->seqno[0] != uip_connr->rcv_nxt[0] ||
BUF->seqno[1] != uip_connr->rcv_nxt[1] ||
BUF->seqno[2] != uip_connr->rcv_nxt[2] ||
@@ -1476,14 +1483,14 @@ tcp_send_synack:
uip_flags = UIP_CONNECTED;
uip_connr->len = 0;
- if (uip_len > 0)
+ if (dev->d_len > 0)
{
uip_flags |= UIP_NEWDATA;
- uip_add_rcv_nxt(uip_len);
+ uip_add_rcv_nxt(dev->d_len);
}
- uip_slen = 0;
- uip_tcp_callback();
+ dev->d_sndlen = 0;
+ uip_tcp_callback(dev);
goto appsend;
}
goto drop;
@@ -1501,7 +1508,7 @@ tcp_send_synack:
{
for (c = 0; c < ((BUF->tcpoffset >> 4) - 5) << 2 ;)
{
- opt = uip_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + c];
+ opt = dev->d_buf[UIP_IPTCPH_LEN + UIP_LLH_LEN + c];
if (opt == TCP_OPT_END)
{
/* End of options. */
@@ -1513,11 +1520,11 @@ tcp_send_synack:
/* NOP option. */
}
else if (opt == TCP_OPT_MSS &&
- uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == TCP_OPT_MSS_LEN)
+ dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == TCP_OPT_MSS_LEN)
{
/* An MSS option with the right option length. */
- tmp16 = (uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + c] << 8) |
- uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 3 + c];
+ tmp16 = (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 2 + c] << 8) |
+ dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 3 + c];
uip_connr->initialmss =
uip_connr->mss = tmp16 > UIP_TCP_MSS? UIP_TCP_MSS: tmp16;
@@ -1528,13 +1535,13 @@ tcp_send_synack:
{
/* All other options have a length field, so that we easily
can skip past them. */
- if (uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == 0)
+ if (dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c] == 0)
{
/* If the length field is zero, the options are malformed
and we don't process them further. */
break;
}
- c += uip_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c];
+ c += dev->d_buf[UIP_TCPIP_HLEN + UIP_LLH_LEN + 1 + c];
}
}
}
@@ -1547,15 +1554,15 @@ tcp_send_synack:
uip_add_rcv_nxt(1);
uip_flags = UIP_CONNECTED | UIP_NEWDATA;
uip_connr->len = 0;
- uip_len = 0;
- uip_slen = 0;
- uip_tcp_callback();
+ dev->d_len = 0;
+ dev->d_sndlen = 0;
+ uip_tcp_callback(dev);
goto appsend;
}
/* Inform the application that the connection failed */
uip_flags = UIP_ABORT;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
/* The connection is closed after we send the RST */
uip_conn->tcpstateflags = UIP_CLOSED;
@@ -1563,7 +1570,7 @@ tcp_send_synack:
case UIP_ESTABLISHED:
/* In the ESTABLISHED state, we call upon the application to feed
- data into the uip_buf. If the UIP_ACKDATA flag is set, the
+ 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.
@@ -1580,15 +1587,15 @@ tcp_send_synack:
goto drop;
}
- uip_add_rcv_nxt(1 + uip_len);
+ uip_add_rcv_nxt(dev->d_len + 1);
uip_flags |= UIP_CLOSE;
- if (uip_len > 0)
+ if (dev->d_len > 0)
{
uip_flags |= UIP_NEWDATA;
}
- uip_tcp_callback();
+ uip_tcp_callback(dev);
uip_connr->len = 1;
uip_connr->tcpstateflags = UIP_LAST_ACK;
uip_connr->nrtx = 0;
@@ -1604,34 +1611,34 @@ tcp_send_synack:
{
#if UIP_URGDATA > 0
uip_urglen = (BUF->urgp[0] << 8) | BUF->urgp[1];
- if (uip_urglen > uip_len)
+ if (uip_urglen > dev->d_len)
{
/* There is more urgent data in the next segment to come. */
- uip_urglen = uip_len;
+ uip_urglen = dev->d_len;
}
uip_add_rcv_nxt(uip_urglen);
- uip_len -= uip_urglen;
- uip_urgdata = uip_appdata;
- uip_appdata += uip_urglen;
+ dev->d_len -= uip_urglen;
+ uip_urgdata = dev->d_appdata;
+ dev->d_appdata += uip_urglen;
}
else
{
uip_urglen = 0;
#else /* UIP_URGDATA > 0 */
- uip_appdata = ((char *)uip_appdata) + ((BUF->urgp[0] << 8) | BUF->urgp[1]);
- uip_len -= (BUF->urgp[0] << 8) | BUF->urgp[1];
+ dev->d_appdata = ((char *)dev->d_appdata) + ((BUF->urgp[0] << 8) | BUF->urgp[1]);
+ dev->d_len -= (BUF->urgp[0] << 8) | BUF->urgp[1];
#endif /* UIP_URGDATA > 0 */
}
- /* If uip_len > 0 we have TCP data in the packet, and we flag this
+ /* If d_len > 0 we have TCP data in the packet, and we flag this
by setting the UIP_NEWDATA flag and update the sequence number
we acknowledge. If the application has stopped the dataflow
using uip_stop(), we must not accept any data packets from the
remote host. */
- if (uip_len > 0 && !(uip_connr->tcpstateflags & UIP_STOPPED))
+ if (dev->d_len > 0 && !(uip_connr->tcpstateflags & UIP_STOPPED))
{
uip_flags |= UIP_NEWDATA;
- uip_add_rcv_nxt(uip_len);
+ uip_add_rcv_nxt(dev->d_len);
}
/* Check if the available buffer space advertised by the other end
@@ -1659,25 +1666,25 @@ tcp_send_synack:
from the peer (as flagged by the UIP_NEWDATA flag), the
application must also be notified.
- When the application is called, the global variable uip_len
+ 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
- uip_appdata, which usually points UIP_IPTCPH_LEN + UIP_LLH_LEN
- bytes into the uip_buf array.
+ 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 uip_appdata and the length of the data should be
- put into uip_len. If the application don't have any data to
- send, uip_len must be set to 0. */
+ 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 (uip_flags & (UIP_NEWDATA | UIP_ACKDATA))
{
- uip_slen = 0;
- uip_tcp_callback();
+ dev->d_sndlen = 0;
+ uip_tcp_callback(dev);
appsend:
if (uip_flags & UIP_ABORT)
{
- uip_slen = 0;
+ dev->d_sndlen = 0;
uip_connr->tcpstateflags = UIP_CLOSED;
BUF->flags = TCP_RST | TCP_ACK;
goto tcp_send_nodata;
@@ -1685,7 +1692,7 @@ tcp_send_synack:
if (uip_flags & UIP_CLOSE)
{
- uip_slen = 0;
+ dev->d_sndlen = 0;
uip_connr->len = 1;
uip_connr->tcpstateflags = UIP_FIN_WAIT_1;
uip_connr->nrtx = 0;
@@ -1693,8 +1700,8 @@ tcp_send_synack:
goto tcp_send_nodata;
}
- /* If uip_slen > 0, the application has data to be sent. */
- if (uip_slen > 0)
+ /* If d_sndlen > 0, the application has data to be sent. */
+ if (dev->d_sndlen > 0)
{
/* If the connection has acknowledged data, the contents of
the ->len variable should be discarded. */
@@ -1711,33 +1718,33 @@ tcp_send_synack:
/* The application cannot send more than what is allowed by
the mss (the minumum of the MSS and the available
window). */
- if (uip_slen > uip_connr->mss)
+ if (dev->d_sndlen > uip_connr->mss)
{
- uip_slen = uip_connr->mss;
+ dev->d_sndlen = uip_connr->mss;
}
/* Remember how much data we send out now so that we know
when everything has been acknowledged. */
- uip_connr->len = uip_slen;
+ uip_connr->len = dev->d_sndlen;
}
else
{
/* If the application already had unacknowledged data, we
make sure that the application does not send (i.e.,
retransmit) out more than it previously sent out. */
- uip_slen = uip_connr->len;
+ dev->d_sndlen = uip_connr->len;
}
}
uip_connr->nrtx = 0;
apprexmit:
- uip_appdata = uip_sappdata;
+ 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 (uip_slen > 0 && uip_connr->len > 0)
+ if (dev->d_sndlen > 0 && uip_connr->len > 0)
{
/* Add the length of the IP and TCP headers. */
- uip_len = uip_connr->len + UIP_TCPIP_HLEN;
+ dev->d_len = uip_connr->len + UIP_TCPIP_HLEN;
/* We always set the ACK flag in response packets. */
BUF->flags = TCP_ACK | TCP_PSH;
@@ -1750,7 +1757,7 @@ tcp_send_synack:
there is newdata. */
if (uip_flags & UIP_NEWDATA)
{
- uip_len = UIP_TCPIP_HLEN;
+ dev->d_len = UIP_TCPIP_HLEN;
BUF->flags = TCP_ACK;
goto tcp_send_noopts;
}
@@ -1764,7 +1771,7 @@ tcp_send_synack:
{
uip_connr->tcpstateflags = UIP_CLOSED;
uip_flags = UIP_CLOSE;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
}
break;
@@ -1772,9 +1779,9 @@ tcp_send_synack:
/* 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 (uip_len > 0)
+ if (dev->d_len > 0)
{
- uip_add_rcv_nxt(uip_len);
+ uip_add_rcv_nxt(dev->d_len);
}
if (BUF->flags & TCP_FIN)
{
@@ -1791,7 +1798,7 @@ tcp_send_synack:
uip_add_rcv_nxt(1);
uip_flags = UIP_CLOSE;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
goto tcp_send_ack;
}
else if (uip_flags & UIP_ACKDATA)
@@ -1800,16 +1807,16 @@ tcp_send_synack:
uip_connr->len = 0;
goto drop;
}
- if (uip_len > 0)
+ if (dev->d_len > 0)
{
goto tcp_send_ack;
}
goto drop;
case UIP_FIN_WAIT_2:
- if (uip_len > 0)
+ if (dev->d_len > 0)
{
- uip_add_rcv_nxt(uip_len);
+ uip_add_rcv_nxt(dev->d_len);
}
if (BUF->flags & TCP_FIN)
{
@@ -1817,10 +1824,10 @@ tcp_send_synack:
uip_connr->timer = 0;
uip_add_rcv_nxt(1);
uip_flags = UIP_CLOSE;
- uip_tcp_callback();
+ uip_tcp_callback(dev);
goto tcp_send_ack;
}
- if (uip_len > 0)
+ if (dev->d_len > 0)
{
goto tcp_send_ack;
}
@@ -1843,7 +1850,7 @@ tcp_send_synack:
tcp_send_ack:
BUF->flags = TCP_ACK;
tcp_send_nodata:
- uip_len = UIP_IPTCPH_LEN;
+ dev->d_len = UIP_IPTCPH_LEN;
tcp_send_noopts:
BUF->tcpoffset = (UIP_TCPH_LEN / 4) << 4;
tcp_send:
@@ -1886,18 +1893,18 @@ tcp_send_synack:
#ifdef CONFIG_NET_IPv6
/* For IPv6, the IP length field does not include the IPv6 IP header
length. */
- BUF->len[0] = ((uip_len - UIP_IPH_LEN) >> 8);
- BUF->len[1] = ((uip_len - UIP_IPH_LEN) & 0xff);
+ BUF->len[0] = ((dev->d_len - UIP_IPH_LEN) >> 8);
+ BUF->len[1] = ((dev->d_len - UIP_IPH_LEN) & 0xff);
#else /* CONFIG_NET_IPv6 */
- BUF->len[0] = (uip_len >> 8);
- BUF->len[1] = (uip_len & 0xff);
+ BUF->len[0] = (dev->d_len >> 8);
+ BUF->len[1] = (dev->d_len & 0xff);
#endif /* CONFIG_NET_IPv6 */
BUF->urgp[0] = BUF->urgp[1] = 0;
/* Calculate TCP checksum. */
BUF->tcpchksum = 0;
- BUF->tcpchksum = ~(uip_tcpchksum());
+ BUF->tcpchksum = ~(uip_tcpchksum(dev));
#ifdef CONFIG_NET_UDP
ip_send_nolen:
@@ -1917,13 +1924,13 @@ tcp_send_synack:
/* Calculate IP checksum. */
BUF->ipchksum = 0;
- BUF->ipchksum = ~(uip_ipchksum());
- dbg("uip ip_send_nolen: chkecum 0x%04x\n", uip_ipchksum());
+ BUF->ipchksum = ~(uip_ipchksum(dev));
+ dbg("uip ip_send_nolen: chkecum 0x%04x\n", uip_ipchksum(dev));
#endif /* CONFIG_NET_IPv6 */
UIP_STAT(++uip_stat.tcp.sent);
send:
- dbg("Sending packet with length %d (%d)\n", uip_len,
+ dbg("Sending packet with length %d (%d)\n", dev->d_len,
(BUF->len[0] << 8) | BUF->len[1]);
UIP_STAT(++uip_stat.ip.sent);
@@ -1932,19 +1939,7 @@ tcp_send_synack:
uip_flags = 0;
return;
drop:
- uip_len = 0;
+ dev->d_len = 0;
uip_flags = 0;
return;
}
-
-void uip_send(const void *data, int len)
-{
- if (len > 0)
- {
- uip_slen = len;
- if (data != uip_sappdata)
- {
- memcpy(uip_sappdata, (data), uip_slen);
- }
- }
-}