summaryrefslogtreecommitdiff
path: root/nuttx/net
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-06 16:17:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-06 16:17:50 +0000
commit4fc87116d818f5285403dbb37d2aa60d33e4203a (patch)
tree8e2327f902c41cf79ffab0997a6754d8e78b012a /nuttx/net
parent13a1d731ec51a27983bc9e6fcaa841607a090764 (diff)
downloadpx4-nuttx-4fc87116d818f5285403dbb37d2aa60d33e4203a.tar.gz
px4-nuttx-4fc87116d818f5285403dbb37d2aa60d33e4203a.tar.bz2
px4-nuttx-4fc87116d818f5285403dbb37d2aa60d33e4203a.zip
Reduce debug output; calibrate DM320 timer
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@372 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/net')
-rw-r--r--nuttx/net/connect.c14
-rw-r--r--nuttx/net/netdev-ioctl.c47
-rw-r--r--nuttx/net/recvfrom.c14
-rw-r--r--nuttx/net/send.c10
-rw-r--r--nuttx/net/uip/uip-arp.c37
-rw-r--r--nuttx/net/uip/uip-fw.c2
-rw-r--r--nuttx/net/uip/uip-neighbor.c12
-rw-r--r--nuttx/net/uip/uip-poll.c4
-rw-r--r--nuttx/net/uip/uip-tcpconn.c10
-rw-r--r--nuttx/net/uip/uip.c181
10 files changed, 118 insertions, 213 deletions
diff --git a/nuttx/net/connect.c b/nuttx/net/connect.c
index 7f3d17609..47047b3cf 100644
--- a/nuttx/net/connect.c
+++ b/nuttx/net/connect.c
@@ -100,8 +100,11 @@ static inline int tcp_connect(FAR struct socket *psock, const struct sockaddr_in
static void connection_event(void *private)
{
FAR struct socket *psock = (FAR struct socket *)private;
+
if (psock)
{
+ vdbg("uip_flags: %02x s_flags: %02x\n", uip_flags, psock->s_flags);
+
/* 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.
@@ -189,7 +192,7 @@ static void tcp_connect_interrupt(struct uip_driver_s *dev, void *private)
{
struct tcp_connect_s *pstate = (struct tcp_connect_s *)private;
- vdbg("Interrupt uip_flags=%02x\n", uip_flags);
+ vdbg("uip_flags: %02x\n", uip_flags);
/* 'private' might be null in some race conditions (?) */
@@ -214,7 +217,6 @@ static void tcp_connect_interrupt(struct uip_driver_s *dev, void *private)
{
/* Indicate that remote host refused the connection */
- vdbg("ECONNREFUSED\n");
pstate->tc_result = -ECONNREFUSED;
}
@@ -224,7 +226,6 @@ static void tcp_connect_interrupt(struct uip_driver_s *dev, void *private)
{
/* Indicate that the remote host is unreachable (or should this be timedout?) */
- vdbg("ETIMEDOUT\n");
pstate->tc_result = -ETIMEDOUT;
}
@@ -234,7 +235,6 @@ static void tcp_connect_interrupt(struct uip_driver_s *dev, void *private)
{
/* Indicate that the socket is no longer connected */
- vdbg("Connected\n");
pstate->tc_result = OK;
}
@@ -245,6 +245,8 @@ static void tcp_connect_interrupt(struct uip_driver_s *dev, void *private)
return;
}
+ vdbg("Resuming: %d\n", pstate->tc_result);
+
/* Stop further callbacks */
tcp_teardown_callbacks(pstate->tc_conn, pstate->tc_result);
@@ -469,8 +471,6 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
{
case SOCK_STREAM:
{
- dbg("TCP\n");
-
/* Verify that the socket is not already connected */
if (_SS_ISCONNECTED(psock->s_flags))
@@ -493,8 +493,6 @@ int connect(int sockfd, const struct sockaddr *addr, socklen_t addrlen)
#ifdef CONFIG_NET_UDP
case SOCK_DGRAM:
{
- dbg("UDP\n");
-
ret = uip_udpconnect(psock->s_conn, inaddr);
if (ret < 0)
{
diff --git a/nuttx/net/netdev-ioctl.c b/nuttx/net/netdev-ioctl.c
index f093e6133..3825a5f7b 100644
--- a/nuttx/net/netdev-ioctl.c
+++ b/nuttx/net/netdev-ioctl.c
@@ -106,17 +106,17 @@ static void ioctl_setipaddr(uip_ipaddr_t *outaddr, struct sockaddr *inaddr)
static void ioctl_ifup(FAR struct uip_driver_s *dev)
{
- if (dev->ifup)
+ if (dev->d_ifup)
{
- dev->ifup(dev);
+ dev->d_ifup(dev);
}
}
static void ioctl_ifdown(FAR struct uip_driver_s *dev)
{
- if (dev->ifdown)
+ if (dev->d_ifdown)
{
- dev->ifdown(dev);
+ dev->d_ifdown(dev);
}
}
@@ -190,95 +190,56 @@ int netdev_ioctl(int sockfd, int cmd, struct ifreq *req)
{
case SIOCGIFADDR: /* Get IP address */
ioctl_getipaddr(&req->ifr_addr, &dev->d_ipaddr);
- dbg("Dev: %s IP: %d.%d.%d.%d\n",
- dev->d_ifname,
- (dev->d_ipaddr >> 24) & 0xff, (dev->d_ipaddr >> 16) & 0xff,
- (dev->d_ipaddr >> 8) & 0xff, dev->d_ipaddr & 0xff);
break;
case SIOCSIFADDR: /* Set IP address */
ioctl_ifdown(dev);
ioctl_setipaddr(&dev->d_ipaddr, &req->ifr_addr);
- dbg("Dev: %s IP: %d.%d.%d.%d\n",
- dev->d_ifname,
- (dev->d_ipaddr >> 24) & 0xff, (dev->d_ipaddr >> 16) & 0xff,
- (dev->d_ipaddr >> 8) & 0xff, dev->d_ipaddr & 0xff);
ioctl_ifup(dev);
break;
case SIOCGIFDSTADDR: /* Get P-to-P address */
ioctl_getipaddr(&req->ifr_dstaddr, &dev->d_draddr);
- dbg("Dev: %s Default router: %d.%d.%d.%d\n",
- dev->d_ifname,
- (dev->d_draddr >> 24) & 0xff, (dev->d_draddr >> 16) & 0xff,
- (dev->d_draddr >> 8) & 0xff, dev->d_draddr & 0xff);
break;
case SIOCSIFDSTADDR: /* Set P-to-P address */
ioctl_setipaddr(&dev->d_draddr, &req->ifr_dstaddr);
- dbg("Dev: %s Default router: %d.%d.%d.%d\n",
- dev->d_ifname,
- (dev->d_draddr >> 24) & 0xff, (dev->d_draddr >> 16) & 0xff,
- (dev->d_draddr >> 8) & 0xff, dev->d_draddr & 0xff);
break;
case SIOCGIFNETMASK: /* Get network mask */
ioctl_getipaddr(&req->ifr_addr, &dev->d_netmask);
- dbg("Dev: %s Netmask: %d.%d.%d.%d\n",
- dev->d_ifname,
- (dev->d_netmask >> 24) & 0xff, (dev->d_netmask >> 16) & 0xff,
- (dev->d_netmask >> 8) & 0xff, dev->d_netmask & 0xff);
break;
case SIOCSIFNETMASK: /* Set network mask */
ioctl_setipaddr(&dev->d_netmask, &req->ifr_addr);
- dbg("Dev: %s Netmask: %d.%d.%d.%d\n",
- dev->d_ifname,
- (dev->d_netmask >> 24) & 0xff, (dev->d_netmask >> 16) & 0xff,
- (dev->d_netmask >> 8) & 0xff, dev->d_netmask & 0xff);
break;
case SIOCGIFMTU: /* Get MTU size */
req->ifr_mtu = UIP_BUFSIZE;
- dbg("Dev: %s MTU: %d\n", dev->d_ifname, UIP_BUFSIZE);
break;
case SIOCGIFHWADDR: /* Get hardware address */
req->ifr_hwaddr.sa_family = AF_INETX;
memcpy(req->ifr_hwaddr.sa_data, dev->d_mac.addr, IFHWADDRLEN);
- dbg("Dev: %s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
- dev->d_ifname,
- dev->d_mac.addr[0], dev->d_mac.addr[1], dev->d_mac.addr[2],
- dev->d_mac.addr[3], dev->d_mac.addr[4], dev->d_mac.addr[5]);
break;
case SIOCSIFHWADDR: /* Set hardware address */
req->ifr_hwaddr.sa_family = AF_INETX;
memcpy(dev->d_mac.addr, req->ifr_hwaddr.sa_data, IFHWADDRLEN);
- dbg("Dev: %s MAC: %02x:%02x:%02x:%02x:%02x:%02x\n",
- dev->d_ifname,
- dev->d_mac.addr[0], dev->d_mac.addr[1], dev->d_mac.addr[2],
- dev->d_mac.addr[3], dev->d_mac.addr[4], dev->d_mac.addr[5]);
break;
case SIOCDIFADDR: /* Delete IP address */
ioctl_ifdown(dev);
memset(&dev->d_ipaddr, 0, sizeof(uip_ipaddr_t));
- dbg("Dev: %s IP: %d.%d.%d.%d\n",
- dev->d_ifname,
- (dev->d_ipaddr >> 24) & 0xff, (dev->d_ipaddr >> 16) & 0xff,
- (dev->d_ipaddr >> 8) & 0xff, dev->d_ipaddr & 0xff);
break;
case SIOCGIFCOUNT: /* Get number of devices */
req->ifr_count = netdev_count();
- dbg("Dev: %s I/F count: %d\n", netdev_count());
err = ENOSYS;
break;
case SIOCGIFBRDADDR: /* Get broadcast IP address */
case SIOCSIFBRDADDR: /* Set broadcast IP address */
- dbg("Dev: %s Broadcast: 255.255.255.255d\n", dev->d_ifname);
err = ENOSYS;
goto errout;
diff --git a/nuttx/net/recvfrom.c b/nuttx/net/recvfrom.c
index 1ea76981f..149abc10b 100644
--- a/nuttx/net/recvfrom.c
+++ b/nuttx/net/recvfrom.c
@@ -107,7 +107,7 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
#endif
size_t recvlen;
- vdbg("Interrupt uip_flags: %02x\n", uip_flags);
+ vdbg("uip_flags: %02x\n", uip_flags);
/* 'private' might be null in some race conditions (?) */
@@ -154,7 +154,7 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
{
struct uip_udp_conn *udp_conn;
- vdbg("UDP complete\n");
+ vdbg("UDP resume\n");
/* Don't allow any further UDP call backs. */
@@ -174,7 +174,7 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
{
struct uip_conn *conn;
- vdbg("TCP complete\n");
+ vdbg("TCP resume\n");
/* The TCP receive buffer is full. Return now, perhaps truncating
* the received data (need to fix that).
@@ -206,7 +206,7 @@ static void recvfrom_interrupt(struct uip_driver_s *dev, void *private)
else if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
{
- vdbg("Receive error\n");
+ vdbg("error\n");
/* Stop further callbacks */
@@ -480,9 +480,7 @@ static ssize_t udp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
* and automatically re-enabled when the task restarts.
*/
- vdbg("Receiving UDP ...\n");
ret = sem_wait(&state. rf_sem);
- vdbg("Received\n");
/* Make sure that no further interrupts are processed */
@@ -531,7 +529,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
/* Verify that the SOCK_STREAM has been connected */
- if (_SS_ISCONNECTED(psock->s_flags))
+ if (!_SS_ISCONNECTED(psock->s_flags))
{
/* The SOCK_STREAM must be connected in order to receive */
@@ -559,9 +557,7 @@ static ssize_t tcp_recvfrom(FAR struct socket *psock, FAR void *buf, size_t len,
* and automatically re-enabled when the task restarts.
*/
- vdbg("Receiving UDP ...\n");
ret = sem_wait(&state.rf_sem);
- vdbg("Received\n");
/* Make sure that no further interrupts are processed */
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index 07a3a0a72..1827a86e5 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -104,7 +104,7 @@ static void send_interrupt(struct uip_driver_s *dev, void *private)
struct send_s *pstate = (struct send_s *)private;
struct uip_conn *conn;
- vdbg("Interrupt uip_flags: %02x state: %d\n", uip_flags, pstate->snd_state);
+ vdbg("uip_flags: %02x state: %d\n", uip_flags, pstate->snd_state);
/* If the data has not been sent OR if it needs to be retransmitted,
* then send it now.
@@ -122,7 +122,6 @@ static void send_interrupt(struct uip_driver_s *dev, void *private)
}
pstate->snd_state = STATE_DATA_SENT;
- vdbg("state: STATE_DATA_SENT(%d)\n", STATE_DATA_SENT);
}
/* Check if all data has been sent and acknowledged */
@@ -142,12 +141,9 @@ static void send_interrupt(struct uip_driver_s *dev, void *private)
/* Send again on the next poll */
pstate->snd_state = STATE_POLLWAIT;
- vdbg("state: STATE_POLLWAIT(%d)\n", STATE_POLLWAIT);
}
else
{
- vdbg("state: Data sent\n");
-
/* All data has been sent */
pstate->snd_sent += pstate->snd_buflen;
@@ -172,8 +168,6 @@ static void send_interrupt(struct uip_driver_s *dev, void *private)
else if ((uip_flags & (UIP_CLOSE|UIP_ABORT|UIP_TIMEDOUT)) != 0)
{
- vdbg("state: TCP failure\n");
-
/* Stop further callbacks */
conn = (struct uip_conn *)pstate->snd_sock->s_conn;
@@ -316,14 +310,12 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
* automatically re-enabled when the task restarts.
*/
- vdbg("Sending %d bytes...\n", len);
ret = sem_wait(&state. snd_sem);
/* Make sure that no further interrupts are processed */
conn->data_private = NULL;
conn->data_event = NULL;
- vdbg("Sent\n");
}
sem_destroy(&state. snd_sem);
diff --git a/nuttx/net/uip/uip-arp.c b/nuttx/net/uip/uip-arp.c
index fa64f9876..13dd1ba03 100644
--- a/nuttx/net/uip/uip-arp.c
+++ b/nuttx/net/uip/uip-arp.c
@@ -137,23 +137,23 @@ static uint8 g_arptime;
* Private Functions
****************************************************************************/
-#ifdef CONFIG_DEBUG_VERBOSE
+#if defined(CONFIG_NET_DUMPARP) && defined(CONFIG_DEBUG)
static void uip_arp_dump(struct arp_hdr *arp)
{
- vdbg(" HW type: %04x Protocol: %04x\n",
- arp->ah_hwtype, arp->ah_protocol);\
- vdbg(" HW len: %02x Proto len: %02x Operation: %04x\n",
- arp->ah_hwlen, arp->ah_protolen, arp->ah_opcode);
- vdbg(" Sender MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
- arp->ah_shwaddr[0], arp->ah_shwaddr[1], arp->ah_shwaddr[2],
- arp->ah_shwaddr[3], arp->ah_shwaddr[4], arp->ah_shwaddr[5],
- arp->ah_sipaddr[0] & 0xff, arp->ah_sipaddr[0] >> 8,
- arp->ah_sipaddr[1] & 0xff, arp->ah_sipaddr[1] >> 8);
- vdbg(" Dest MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
- arp->ah_dhwaddr[0], arp->ah_dhwaddr[1], arp->ah_dhwaddr[2],
- arp->ah_dhwaddr[3], arp->ah_dhwaddr[4], arp->ah_dhwaddr[5],
- arp->ah_dipaddr[0] & 0xff, arp->ah_dipaddr[0] >> 8,
- arp->ah_dipaddr[1] & 0xff, arp->ah_dipaddr[1] >> 8);
+ dbg(" HW type: %04x Protocol: %04x\n",
+ arp->ah_hwtype, arp->ah_protocol);\
+ dbg(" HW len: %02x Proto len: %02x Operation: %04x\n",
+ arp->ah_hwlen, arp->ah_protolen, arp->ah_opcode);
+ dbg(" Sender MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
+ arp->ah_shwaddr[0], arp->ah_shwaddr[1], arp->ah_shwaddr[2],
+ arp->ah_shwaddr[3], arp->ah_shwaddr[4], arp->ah_shwaddr[5],
+ arp->ah_sipaddr[0] & 0xff, arp->ah_sipaddr[0] >> 8,
+ arp->ah_sipaddr[1] & 0xff, arp->ah_sipaddr[1] >> 8);
+ dbg(" Dest MAC: %02x:%02x:%02x:%02x:%02x:%02x IP: %d.%d.%d.%d\n",
+ arp->ah_dhwaddr[0], arp->ah_dhwaddr[1], arp->ah_dhwaddr[2],
+ arp->ah_dhwaddr[3], arp->ah_dhwaddr[4], arp->ah_dhwaddr[5],
+ arp->ah_dipaddr[0] & 0xff, arp->ah_dipaddr[0] >> 8,
+ arp->ah_dipaddr[1] & 0xff, arp->ah_dipaddr[1] >> 8);
}
#else
# define uip_arp_dump(arp)
@@ -449,12 +449,6 @@ void uip_arp_out(struct uip_driver_s *dev)
uip_ipaddr_copy(ipaddr, destipaddr);
}
- vdbg("Dest IP addr: %d.%d.%d.%d -> ARP IP addr: %d.%d.%d.%d\n",
- (destipaddr >> 24) & 0xff, (destipaddr >> 16) & 0xff,
- (destipaddr >> 8) & 0xff, destipaddr & 0xff,
- (ipaddr >> 24) & 0xff, (ipaddr >> 16) & 0xff,
- (ipaddr >> 8) & 0xff, ipaddr & 0xff);
-
/* Check if we already have this destination address in the ARP table */
for (i = 0; i < UIP_ARPTAB_SIZE; ++i)
@@ -462,7 +456,6 @@ void uip_arp_out(struct uip_driver_s *dev)
tabptr = &arp_table[i];
if (uip_ipaddr_cmp(ipaddr, tabptr->at_ipaddr))
{
- vdbg("Dest IP found in ARP table\n");
break;
}
}
diff --git a/nuttx/net/uip/uip-fw.c b/nuttx/net/uip/uip-fw.c
index b529c6e06..187fb6c39 100644
--- a/nuttx/net/uip/uip-fw.c
+++ b/nuttx/net/uip/uip-fw.c
@@ -323,7 +323,7 @@ uint8 uip_fw_output(struct uip_driver_s *dev)
#endif /* UIP_BROADCAST */
netif = find_netif (dev);
- dbg("uip_fw_output: netif %p ->output %p len %d\n", netif, netif->output, dev->d_len);
+ dbg("netif: %p output: %p len: %d\n", netif, netif->output, dev->d_len);
if (netif == NULL) {
return UIP_FW_NOROUTE;
diff --git a/nuttx/net/uip/uip-neighbor.c b/nuttx/net/uip/uip-neighbor.c
index d2fb74304..0e849bac1 100644
--- a/nuttx/net/uip/uip-neighbor.c
+++ b/nuttx/net/uip/uip-neighbor.c
@@ -81,9 +81,9 @@ void uip_neighbor_add(uip_ipaddr_t ipaddr, struct uip_neighbor_addr *addr)
int i, oldest;
uint8 oldest_time;
- dbg("Adding neighbor with link address %02x:%02x:%02x:%02x:%02x:%02x\n",
- addr->addr.addr[0], addr->addr.addr[1], addr->addr.addr[2], addr->addr.addr[3],
- addr->addr.addr[4], addr->addr.addr[5]);
+ dbg("Add neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ addr->addr.addr[0], addr->addr.addr[1], addr->addr.addr[2],
+ addr->addr.addr[3], addr->addr.addr[4], addr->addr.addr[5]);
/* Find the first unused entry or the oldest used entry. */
@@ -149,9 +149,9 @@ struct uip_neighbor_addr *uip_neighbor_lookup(uip_ipaddr_t ipaddr)
e = find_entry(ipaddr);
if (e != NULL)
{
- dbg("Lookup neighbor with link address %02x:%02x:%02x:%02x:%02x:%02x\n",
- e->addr.addr.addr[0], e->addr.addr.addr[1], e->addr.addr.addr[2], e->addr.addr.addr[3],
- e->addr.addr.addr[4], e->addr.addr.addr[5]);
+ dbg("Lookup neighbor: %02x:%02x:%02x:%02x:%02x:%02x\n",
+ e->addr.addr.addr[0], e->addr.addr.addr[1], e->addr.addr.addr[2],
+ e->addr.addr.addr[3], e->addr.addr.addr[4], e->addr.addr.addr[5]);
return &e->addr;
}
diff --git a/nuttx/net/uip/uip-poll.c b/nuttx/net/uip/uip-poll.c
index e6470dfe7..b61eb32aa 100644
--- a/nuttx/net/uip/uip-poll.c
+++ b/nuttx/net/uip/uip-poll.c
@@ -125,7 +125,7 @@ int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback, int event)
/* Traverse all of the active TCP connections and perform the poll action */
conn = NULL;
- while ((conn = uip_nexttcpconn(uip_conn)))
+ while ((conn = uip_nexttcpconn(conn)))
{
uip_conn = conn;
uip_interrupt(dev, event);
@@ -141,7 +141,7 @@ int uip_poll(struct uip_driver_s *dev, uip_poll_callback_t callback, int event)
/* Traverse all of the allocated UDP connections and perform a poll action */
udp_conn = NULL;
- while ((udp_conn = uip_nextudpconn(uip_udp_conn)))
+ while ((udp_conn = uip_nextudpconn(udp_conn)))
{
uip_udp_conn = udp_conn;
uip_interrupt(dev, UIP_UDP_POLL);
diff --git a/nuttx/net/uip/uip-tcpconn.c b/nuttx/net/uip/uip-tcpconn.c
index 2a341019e..0dc9f9f25 100644
--- a/nuttx/net/uip/uip-tcpconn.c
+++ b/nuttx/net/uip/uip-tcpconn.c
@@ -321,20 +321,10 @@ struct uip_conn *uip_tcpactive(struct uip_tcpip_hdr *buf)
struct uip_conn *conn = (struct uip_conn *)g_active_tcp_connections.head;
in_addr_t srcipaddr = uip_ip4addr_conv(buf->srcipaddr);
- vdbg("BUF: destport: %04x srcport: %04x IP: %d.%d.%d.%d\n",
- buf->destport, buf->srcport,
- (srcipaddr >> 24) & 0xff, (srcipaddr >> 16) & 0xff,
- (srcipaddr >> 8) & 0xff, srcipaddr & 0xff);
-
while (conn)
{
/* Find an open connection matching the tcp input */
- vdbg("conn: lport: %04x rport: %04x IP: %d.%d.%d.%d\n",
- conn->lport, conn->rport,
- (conn->ripaddr >> 24) & 0xff, (conn->ripaddr >> 16) & 0xff,
- (conn->ripaddr >> 8) & 0xff, conn->ripaddr & 0xff);
-
if (conn->tcpstateflags != UIP_CLOSED &&
buf->destport == conn->lport && buf->srcport == conn->rport &&
uip_ipaddr_cmp(srcipaddr, conn->ripaddr))
diff --git a/nuttx/net/uip/uip.c b/nuttx/net/uip/uip.c
index cc5c93e8a..3a8e4fb8e 100644
--- a/nuttx/net/uip/uip.c
+++ b/nuttx/net/uip/uip.c
@@ -333,7 +333,6 @@ uint16 uip_ipchksum(struct uip_driver_s *dev)
uint16 sum;
sum = chksum(0, &dev->d_buf[UIP_LLH_LEN], UIP_IPH_LEN);
- vdbg("Checksum 0x%04x\n", sum);
return (sum == 0) ? 0xffff : htons(sum);
}
#endif
@@ -537,7 +536,7 @@ static void uip_add_rcv_nxt(uint16 n)
#ifdef CONFIG_NET_UDP
static void uip_udp_callback(struct uip_driver_s *dev)
{
- vdbg("UDP callback uip_flags: %02x\n", uip_flags);
+ vdbg("uip_flags: %02x\n", uip_flags);
/* Some sanity checking */
@@ -552,7 +551,7 @@ static void uip_udp_callback(struct uip_driver_s *dev)
static void uip_tcp_callback(struct uip_driver_s *dev)
{
- vdbg("TCP callback uip_flags: %02x\n", uip_flags);
+ vdbg("uip_flags: %02x\n", uip_flags);
/* Some sanity checking */
@@ -588,6 +587,8 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event)
int len;
int i;
+ vdbg("event: %d\n", event);
+
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
@@ -596,7 +597,6 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event)
if (event == UIP_POLL_REQUEST)
{
- vdbg("event: UIP_POLL_REQUEST\n");
if ((uip_connr->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED &&
!uip_outstanding(uip_connr))
{
@@ -650,92 +650,92 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event)
* in which case we retransmit.
*/
- if (uip_outstanding(uip_connr))
- {
- if (uip_connr->timer-- == 0)
- {
- if (uip_connr->nrtx == UIP_MAXRTX ||
- ((uip_connr->tcpstateflags == UIP_SYN_SENT ||
- uip_connr->tcpstateflags == UIP_SYN_RCVD) &&
- uip_connr->nrtx == UIP_MAXSYNRTX))
- {
- uip_connr->tcpstateflags = UIP_CLOSED;
- vdbg("TCP state: UIP_CLOSED\n");
-
- /* We call uip_tcp_callback() with uip_flags set to
- * UIP_TIMEDOUT to inform the application that the
- * connection has timed out.
- */
+ if (uip_outstanding(uip_connr))
+ {
+ if (uip_connr->timer-- == 0)
+ {
+ if (uip_connr->nrtx == UIP_MAXRTX ||
+ ((uip_connr->tcpstateflags == UIP_SYN_SENT ||
+ uip_connr->tcpstateflags == UIP_SYN_RCVD) &&
+ uip_connr->nrtx == UIP_MAXSYNRTX))
+ {
+ uip_connr->tcpstateflags = UIP_CLOSED;
+ vdbg("TCP state: UIP_CLOSED\n");
+
+ /* We call uip_tcp_callback() with uip_flags set to
+ * UIP_TIMEDOUT to inform the application that the
+ * connection has timed out.
+ */
- uip_flags = UIP_TIMEDOUT;
- uip_tcp_callback(dev);
+ uip_flags = UIP_TIMEDOUT;
+ uip_tcp_callback(dev);
- /* We also send a reset packet to the remote host. */
+ /* We also send a reset packet to the remote host. */
- BUF->flags = TCP_RST | TCP_ACK;
- goto tcp_send_nodata;
- }
+ BUF->flags = TCP_RST | TCP_ACK;
+ goto tcp_send_nodata;
+ }
- /* Exponential backoff. */
+ /* Exponential backoff. */
- uip_connr->timer = UIP_RTO << (uip_connr->nrtx > 4 ? 4: uip_connr->nrtx);
- ++(uip_connr->nrtx);
+ uip_connr->timer = UIP_RTO << (uip_connr->nrtx > 4 ? 4: uip_connr->nrtx);
+ ++(uip_connr->nrtx);
- /* Ok, so we need to retransmit. We do this differently
- * depending on which state we are in. In ESTABLISHED, we
- * call upon the application so that it may prepare the
- * data for the retransmit. In SYN_RCVD, we resend the
- * SYNACK that we sent earlier and in LAST_ACK we have to
- * retransmit our FINACK.
- */
+ /* Ok, so we need to retransmit. We do this differently
+ * depending on which state we are in. In ESTABLISHED, we
+ * call upon the application so that it may prepare the
+ * data for the retransmit. In SYN_RCVD, we resend the
+ * SYNACK that we sent earlier and in LAST_ACK we have to
+ * retransmit our FINACK.
+ */
- UIP_STAT(++uip_stat.tcp.rexmit);
- switch(uip_connr->tcpstateflags & UIP_TS_MASK)
- {
- case UIP_SYN_RCVD:
- /* In the SYN_RCVD state, we should retransmit our
- * SYNACK.
- */
+ UIP_STAT(++uip_stat.tcp.rexmit);
+ switch(uip_connr->tcpstateflags & UIP_TS_MASK)
+ {
+ case UIP_SYN_RCVD:
+ /* In the SYN_RCVD state, we should retransmit our
+ * SYNACK.
+ */
- goto tcp_send_synack;
+ goto tcp_send_synack;
- case UIP_SYN_SENT:
- /* In the SYN_SENT state, we retransmit out SYN. */
+ case UIP_SYN_SENT:
+ /* In the SYN_SENT state, we retransmit out SYN. */
- BUF->flags = 0;
- goto tcp_send_syn;
+ BUF->flags = 0;
+ goto tcp_send_syn;
- case UIP_ESTABLISHED:
- /* In the ESTABLISHED state, we call upon the application
- * to do the actual retransmit after which we jump into
- * the code for sending out the packet (the apprexmit
- * label).
- */
+ case UIP_ESTABLISHED:
+ /* In the ESTABLISHED state, we call upon the application
+ * to do the actual retransmit after which we jump into
+ * the code for sending out the packet (the apprexmit
+ * label).
+ */
- uip_flags = UIP_REXMIT;
- uip_tcp_callback(dev);
- goto apprexmit;
+ uip_flags = UIP_REXMIT;
+ uip_tcp_callback(dev);
+ goto apprexmit;
- case UIP_FIN_WAIT_1:
- case UIP_CLOSING:
- case UIP_LAST_ACK:
- /* In all these states we should retransmit a FINACK. */
+ case UIP_FIN_WAIT_1:
+ case UIP_CLOSING:
+ case UIP_LAST_ACK:
+ /* In all these states we should retransmit a FINACK. */
- goto tcp_send_finack;
- }
- }
- }
- else if ((uip_connr->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED)
- {
- /* If there was no need for a retransmission, we poll the
- * application for new data.
- */
+ goto tcp_send_finack;
+ }
+ }
+ }
+ else if ((uip_connr->tcpstateflags & UIP_TS_MASK) == UIP_ESTABLISHED)
+ {
+ /* If there was no need for a retransmission, we poll the
+ * application for new data.
+ */
- uip_flags = UIP_POLL;
- uip_tcp_callback(dev);
- goto appsend;
- }
- }
+ uip_flags = UIP_POLL;
+ uip_tcp_callback(dev);
+ goto appsend;
+ }
+ }
goto drop;
}
@@ -761,7 +761,6 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event)
/* This is where the input processing starts. */
- vdbg("event: %d\n", event);
UIP_STAT(++uip_stat.ip.recv);
/* Start of IP input header processing code. */
@@ -867,10 +866,7 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event)
*/
#if UIP_BROADCAST
- vdbg("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(dev) == 0xffff*/)
+ if (BUF->proto == UIP_PROTO_UDP && uip_ipaddr_cmp(BUF->destipaddr, all_ones_addr)
{
goto udp_input;
}
@@ -941,7 +937,6 @@ void uip_interrupt(struct uip_driver_s *dev, uint8 event)
#if UIP_PINGADDRCONF
icmp_input:
- vdbg("icmp_input\n");
#endif /* UIP_PINGADDRCONF */
UIP_STAT(++uip_stat.icmp.recv);
@@ -992,8 +987,6 @@ icmp_input:
/* This is IPv6 ICMPv6 processing code. */
- vdbg("ICMP6 input length %d\n", dev->d_len);
-
if (BUF->proto != UIP_PROTO_ICMP6)
{
/* We only allow ICMPv6 packets from here. */
@@ -1060,7 +1053,6 @@ icmp_input:
}
else
{
- vdbg("Unknown ICMP6 message: %d\n", ICMPBUF->type);
UIP_STAT(++uip_stat.icmp.drop);
UIP_STAT(++uip_stat.icmp.typeerr);
UIP_LOG("icmp: unknown ICMP message.");
@@ -1072,7 +1064,6 @@ icmp_input:
/* UDP input processing. */
udp_input:
- vdbg("udp_input\n");
/* 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
@@ -1106,7 +1097,6 @@ udp_input:
goto drop;
udp_found:
- vdbg("udp_found\n");
uip_conn = NULL;
uip_flags = UIP_NEWDATA;
@@ -1115,7 +1105,7 @@ udp_found:
uip_udp_callback(dev);
udp_send:
- vdbg("udp_send\n");
+
if (dev->d_sndlen == 0)
{
goto drop;
@@ -1164,7 +1154,6 @@ udp_send:
/* TCP input processing. */
tcp_input:
- vdbg("tcp_input\n");
UIP_STAT(++uip_stat.tcp.recv);
@@ -1213,7 +1202,6 @@ tcp_input:
UIP_STAT(++uip_stat.tcp.synrst);
reset:
- vdbg("reset\n");
/* We do not send resets in response to resets. */
@@ -1283,7 +1271,6 @@ reset:
*/
found_listen:
- vdbg("found_listen\n");
/* First allocate a new connection structure and see if there is any
* user application to accept it.
@@ -1377,11 +1364,9 @@ found_listen:
/* Our response will be a SYNACK. */
tcp_send_synack:
- vdbg("tcp_send_synack\n");
BUF->flags = TCP_ACK;
tcp_send_syn:
- vdbg("tcp_send_syn\n");
BUF->flags |= TCP_SYN;
/* We send out the TCP Maximum Segment Size option with our SYNACK. */
@@ -1397,7 +1382,6 @@ tcp_send_syn:
/* This label will be jumped to if we found an active connection. */
found:
- vdbg("found\n");
uip_conn = uip_connr;
uip_flags = 0;
@@ -1671,7 +1655,6 @@ found:
vdbg("TCP state: UIP_LAST_ACK\n");
tcp_send_finack:
- vdbg("tcp_send_finack\n");
BUF->flags = TCP_FIN | TCP_ACK;
goto tcp_send_nodata;
@@ -1763,7 +1746,6 @@ tcp_send_finack:
uip_tcp_callback(dev);
appsend:
- vdbg("appsend\n");
if (uip_flags & UIP_ABORT)
{
@@ -1836,7 +1818,6 @@ appsend:
}
uip_connr->nrtx = 0;
apprexmit:
- vdbg("apprexmit\n");
dev->d_appdata = dev->d_snddata;
/* If the application has data to be sent, or if the incoming
@@ -1972,19 +1953,16 @@ apprexmit:
*/
tcp_send_ack:
- vdbg("tcp_send_ack\n");
BUF->flags = TCP_ACK;
tcp_send_nodata:
- vdbg("tcp_send_nodata\n");
dev->d_len = UIP_IPTCPH_LEN;
tcp_send_noopts:
BUF->tcpoffset = (UIP_TCPH_LEN / 4) << 4;
tcp_send:
- vdbg("tcp_send\n");
/* We're done with the input processing. We are now ready to send a
* reply. Our job is to fill in all the fields of the TCP and IP
@@ -2025,7 +2003,6 @@ tcp_send:
}
tcp_send_noconn:
- vdbg("tcp_send_noconn\n");
BUF->ttl = UIP_TTL;
#ifdef CONFIG_NET_IPv6
@@ -2049,7 +2026,6 @@ tcp_send_noconn:
#ifdef CONFIG_NET_UDP
ip_send_nolen:
- vdbg("ip_send_nolen\n");
#endif /* CONFIG_NET_UDP */
#ifdef CONFIG_NET_IPv6
@@ -2069,13 +2045,12 @@ ip_send_nolen:
BUF->ipchksum = 0;
BUF->ipchksum = ~(uip_ipchksum(dev));
- vdbg("checksum: 0x%04x\n", uip_ipchksum(dev));
#endif /* CONFIG_NET_IPv6 */
UIP_STAT(++uip_stat.tcp.sent);
send:
- vdbg("send: packet length %d (%d)\n",
+ vdbg("Sending packet length %d (%d)\n",
dev->d_len, (BUF->len[0] << 8) | BUF->len[1]);
UIP_STAT(++uip_stat.ip.sent);