summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/examples/nsh/nsh_netcmds.c59
-rw-r--r--nuttx/include/net/uip/uip-tcp.h8
-rw-r--r--nuttx/net/net-internal.h4
-rw-r--r--nuttx/net/netdev-findbyaddr.c2
-rw-r--r--nuttx/net/netdev-txnotify.c2
-rw-r--r--nuttx/net/uip/uip-arp.c5
-rw-r--r--nuttx/net/uip/uip-callback.c2
-rw-r--r--nuttx/net/uip/uip-chksum.c2
-rw-r--r--nuttx/net/uip/uip-icmpinput.c18
-rw-r--r--nuttx/net/uip/uip-icmpping.c34
10 files changed, 105 insertions, 31 deletions
diff --git a/nuttx/examples/nsh/nsh_netcmds.c b/nuttx/examples/nsh/nsh_netcmds.c
index c5eebe425..01f472a31 100644
--- a/nuttx/examples/nsh/nsh_netcmds.c
+++ b/nuttx/examples/nsh/nsh_netcmds.c
@@ -270,14 +270,14 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
uip_ipaddr_t ipaddr;
uint32 start;
uint32 next;
- uint32 dsec;
+ uint32 dsec = 10;
uint16 id;
- int sec = 1;
int count = 10;
int option;
int seqno;
int replies = 0;
int elapsed;
+ int tmp;
int i;
/* Get the ping options */
@@ -296,12 +296,13 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
break;
case 'i':
- sec = atoi(optarg);
- if (sec < 1 || sec >= 4294)
+ tmp = atoi(optarg);
+ if (tmp < 1 || tmp >= 4294)
{
fmt = g_fmtargrange;
goto errout;
}
+ dsec = 10 * tmp;
break;
case ':':
@@ -334,39 +335,67 @@ int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
goto errout;
}
- /* Convert the ping interval to microseconds and deciseconds*/
-
- dsec = 10 * sec;
-
/* Get the ID to use */
id = ping_newid();
/* Loop for the specified count */
- nsh_output(vtbl, "PING %s %dbytes of data\n", staddr, DEFAULT_PING_DATALEN);
+ nsh_output(vtbl, "PING %s %d bytes of data\n", staddr, DEFAULT_PING_DATALEN);
start = g_system_timer;
- for (i = 0; i < count; i++)
+ for (i = 1; i <= count; i++)
{
- next = g_system_timer;
+ /* Send the ECHO request and wait for the response */
+
+ next = g_system_timer;
seqno = uip_ping(ipaddr, id, i, DEFAULT_PING_DATALEN, dsec);
- elapsed = TICK2MSEC(g_system_timer - next);
- if (seqno >= 0)
+
+ /* Was any response returned? We can tell if a non-negative sequence
+ * number was returned.
+ */
+
+ if (seqno >= 0 && seqno <= i)
{
+ /* Get the elpased time from the time that the request was
+ * sent until the response was received. If we got a response
+ * to an earlier request, then fudge the elpased time.
+ */
+
+ elapsed = TICK2MSEC(g_system_timer - next);
+ if (seqno < i)
+ {
+ elapsed += 100*dsec*(i - seqno);
+ }
+
+ /* Report the receipt of the reply */
+
nsh_output(vtbl, "%d bytes from %s: icmp_seq=%d time=%d ms\n",
DEFAULT_PING_DATALEN, staddr, seqno, elapsed);
replies++;
}
+
+ /* Wait for the remainder of the interval. If the last seqno<i,
+ * then this is a bad idea... we will probably lose the response
+ * to the current request!
+ */
+
elapsed = TICK2DSEC(g_system_timer - next);
if (elapsed < dsec)
{
usleep(100000*dsec);
}
}
+
+ /* Get the total elapsed time */
+
elapsed = TICK2MSEC(g_system_timer - start);
- nsh_output(vtbl, "%d packets transmitted, %d received, %d%% packet loss, time %dms\n",
- count, replies, (100*replies + count/2)/count, elapsed);
+ /* Calculate the percentage of lost packets */
+
+ tmp = (100*(count - replies) + (count >> 1)) / count;
+
+ nsh_output(vtbl, "%d packets transmitted, %d received, %d%% packet loss, time %d ms\n",
+ count, replies, tmp, elapsed);
return OK;
errout:
diff --git a/nuttx/include/net/uip/uip-tcp.h b/nuttx/include/net/uip/uip-tcp.h
index e0d696981..e625e8865 100644
--- a/nuttx/include/net/uip/uip-tcp.h
+++ b/nuttx/include/net/uip/uip-tcp.h
@@ -91,7 +91,13 @@
#define UIP_TS_MASK 15
#define UIP_STOPPED 16
-/* Header sizes */
+/* Flag bits in 16-bit flags+ipoffset IPv4 TCP header field */
+
+#define UIP_TCPFLAG_RESERVED 0x8000
+#define UIP_TCPFLAG_DONTFRAG 0x4000
+#define UIP_TCPFLAG_MOREFRAGS 0x2000
+
+/* TCP header sizes */
#define UIP_TCPH_LEN 20 /* Size of TCP header */
#define UIP_IPTCPH_LEN (UIP_TCPH_LEN + UIP_IPH_LEN) /* Size of IP + TCP header */
diff --git a/nuttx/net/net-internal.h b/nuttx/net/net-internal.h
index 6573850c4..43d8d81df 100644
--- a/nuttx/net/net-internal.h
+++ b/nuttx/net/net-internal.h
@@ -174,13 +174,13 @@ EXTERN FAR struct uip_driver_s *netdev_findbyname(const char *ifname);
/* net-findbyaddr.c **********************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
-EXTERN FAR struct uip_driver_s *netdev_findbyaddr(uip_ipaddr_t *raddr);
+EXTERN FAR struct uip_driver_s *netdev_findbyaddr(const uip_ipaddr_t *raddr);
#endif
/* net-txnotify.c ************************************************************/
#if CONFIG_NSOCKET_DESCRIPTORS > 0
-EXTERN void netdev_txnotify(uip_ipaddr_t *raddr);
+EXTERN void netdev_txnotify(const uip_ipaddr_t *raddr);
#endif
/* net-count.c ***************************************************************/
diff --git a/nuttx/net/netdev-findbyaddr.c b/nuttx/net/netdev-findbyaddr.c
index c751960bf..0167f6312 100644
--- a/nuttx/net/netdev-findbyaddr.c
+++ b/nuttx/net/netdev-findbyaddr.c
@@ -105,7 +105,7 @@ static inline boolean netdev_maskcmp(uip_ipaddr_t *ipaddr, uip_ipaddr_t *raddr,
*
****************************************************************************/
-FAR struct uip_driver_s *netdev_findbyaddr(uip_ipaddr_t *raddr)
+FAR struct uip_driver_s *netdev_findbyaddr(const uip_ipaddr_t *raddr)
{
struct uip_driver_s *dev;
diff --git a/nuttx/net/netdev-txnotify.c b/nuttx/net/netdev-txnotify.c
index 91a225eff..c600e34d3 100644
--- a/nuttx/net/netdev-txnotify.c
+++ b/nuttx/net/netdev-txnotify.c
@@ -90,7 +90,7 @@
*
****************************************************************************/
-void netdev_txnotify(uip_ipaddr_t *raddr)
+void netdev_txnotify(const uip_ipaddr_t *raddr)
{
/* Find the device driver that serves the subnet of the remote address */
diff --git a/nuttx/net/uip/uip-arp.c b/nuttx/net/uip/uip-arp.c
index 0c33eabfe..6c48ec1b0 100644
--- a/nuttx/net/uip/uip-arp.c
+++ b/nuttx/net/uip/uip-arp.c
@@ -323,10 +323,7 @@ void uip_arp_arpin(struct uip_driver_s *dev)
uip_arp_update(ARPBUF->ah_sipaddr, ARPBUF->ah_shwaddr);
- /* The reply opcode is 2. */
-
- ARPBUF->ah_opcode = HTONS(2);
-
+ ARPBUF->ah_opcode = HTONS(ARP_REPLY);
memcpy(ARPBUF->ah_dhwaddr, ARPBUF->ah_shwaddr, ETHER_ADDR_LEN);
memcpy(ARPBUF->ah_shwaddr, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
memcpy(ETHBUF->src, dev->d_mac.ether_addr_octet, ETHER_ADDR_LEN);
diff --git a/nuttx/net/uip/uip-callback.c b/nuttx/net/uip/uip-callback.c
index 22755a43a..9a2ad7816 100644
--- a/nuttx/net/uip/uip-callback.c
+++ b/nuttx/net/uip/uip-callback.c
@@ -236,7 +236,7 @@ uint16 uip_callbackexecute(FAR struct uip_driver_s *dev, void *pvconn, uint16 fl
* beginning of the list (which will be ignored on this pass)
*/
- vdbg("Call event=%p with flags=%04x\n", list->event, flags);
+ nvdbg("Call event=%p with flags=%04x\n", list->event, flags);
flags = list->event(dev, pvconn, list->private, flags);
}
diff --git a/nuttx/net/uip/uip-chksum.c b/nuttx/net/uip/uip-chksum.c
index 479ebc797..0bfa82861 100644
--- a/nuttx/net/uip/uip-chksum.c
+++ b/nuttx/net/uip/uip-chksum.c
@@ -1,7 +1,7 @@
/****************************************************************************
* net/uip/uip-chksum.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
*
diff --git a/nuttx/net/uip/uip-icmpinput.c b/nuttx/net/uip/uip-icmpinput.c
index b6cad0118..32bfe2db9 100644
--- a/nuttx/net/uip/uip-icmpinput.c
+++ b/nuttx/net/uip/uip-icmpinput.c
@@ -243,7 +243,23 @@ typeerr:
#ifdef CONFIG_NET_ICMP_PING
else if (ICMPBUF->type == ICMP6_ECHO_REPLY && g_echocallback)
{
- (void)uip_callbackexecute(dev, ICMPBUF, UIP_ECHOREPLY, g_echocallback);
+ uint16 flags = UIP_ECHOREPLY;
+
+ if (g_echocallback)
+ {
+ /* Dispatch the ECHO reply to the waiting thread */
+
+ flags = uip_callbackexecute(dev, ICMPBUF, flags, g_echocallback);
+ }
+
+ /* If the ECHO reply was not handled, then drop the packet */
+
+ if (flags == UIP_ECHOREPLY)
+ {
+ /* The ECHO reply was not handled */
+
+ goto drop;
+ }
}
#endif
diff --git a/nuttx/net/uip/uip-icmpping.c b/nuttx/net/uip/uip-icmpping.c
index 5bc9b68b0..3029e2fc2 100644
--- a/nuttx/net/uip/uip-icmpping.c
+++ b/nuttx/net/uip/uip-icmpping.c
@@ -58,7 +58,7 @@
****************************************************************************/
#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
-#define ICMPDAT &dev->d_buf[UIP_LLH_LEN + sizeof(struct uip_icmpip_hdr)]
+#define ICMPDAT (&dev->d_buf[UIP_LLH_LEN + sizeof(struct uip_icmpip_hdr)])
/* Allocate a new ICMP data callback */
@@ -149,6 +149,7 @@ static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
{
struct icmp_ping_s *pstate = (struct icmp_ping_s *)pvprivate;
int failcode = -ETIMEDOUT;
+ int i;
nvdbg("flags: %04x\n", flags);
if (pstate)
@@ -162,6 +163,7 @@ static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
* that the destination address is not reachable.
*/
+ nvdbg("Not reachable\n");
failcode = -ENETUNREACH;
}
else
@@ -175,8 +177,17 @@ static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
if ((flags & UIP_ECHOREPLY) != 0 && conn != NULL)
{
struct uip_icmpip_hdr *icmp = (struct uip_icmpip_hdr *)conn;
+ ndbg("ECHO reply: id=%d seqno=%d\n", ntohs(icmp->id), ntohs(icmp->seqno));
+
if (ntohs(icmp->id) == pstate->png_id)
{
+ /* Consume the ECHOREPLY */
+
+ flags &= ~UIP_ECHOREPLY;
+ dev->d_len = 0;
+
+ /* Return the result to the caller */
+
pstate->png_result = OK;
pstate->png_seqno = ntohs(icmp->seqno);
goto end_wait;
@@ -213,13 +224,19 @@ static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
#else
# error "IPv6 ECHO Request not implemented"
#endif
- memset(ICMPDAT, 0, pstate->png_datlen);
+ /* Add some easily verifiable data */
+
+ for (i = 0; i < pstate->png_datlen; i++)
+ {
+ ICMPDAT[i] = i;
+ }
/* Send the ICMP echo request. Note that d_sndlen is set to
* the size of the ICMP payload and does not include the size
* of the ICMP header.
*/
+ ndbg("Send ECHO request: seqno=%d\n", pstate->png_seqno);
dev->d_sndlen= pstate->png_datlen + 4;
uip_icmpsend(dev, &pstate->png_addr);
pstate->png_sent = TRUE;
@@ -233,7 +250,7 @@ static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
{
/* Yes.. report the timeout */
- nvdbg("Ping timeout\n");
+ ndbg("Ping timeout\n");
pstate->png_result = failcode;
goto end_wait;
}
@@ -243,6 +260,8 @@ static uint16 ping_interrupt(struct uip_driver_s *dev, void *conn,
return flags;
end_wait:
+ nvdbg("Resuming\n");
+
/* Do not allow any further callbacks */
pstate->png_cb->flags = 0;
@@ -313,6 +332,11 @@ int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, uint16 datalen, int dse
state.png_cb->flags = UIP_POLL|UIP_ECHOREPLY;
state.png_cb->private = (void*)&state;
state.png_cb->event = ping_interrupt;
+ state.png_result = -EINTR; /* Assume sem-wait interrupted by signal */
+
+ /* Notify the device driver of the availaibilty of TX data */
+
+ netdev_txnotify(&state.png_addr);
/* Wait for either the full round trip transfer to complete or
* for timeout to occur. (1) sem_wait will also terminate if a
@@ -321,7 +345,7 @@ int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, uint16 datalen, int dse
* re-enabled when the task restarts.
*/
- state.png_result = -EINTR; /* Assume sem-waited interrupt by signal */
+ ndbg("Start time: 0x%08x seqno: %d\n", state.png_time, seqno);
sem_wait(&state.png_sem);
uip_icmpcallbackfree(state.png_cb);
@@ -334,10 +358,12 @@ int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, uint16 datalen, int dse
if (!state.png_result)
{
+ ndbg("Return seqno=%d\n", state.png_seqno);
return (int)state.png_seqno;
}
else
{
+ ndbg("Return error=%d\n", -state.png_result);
return state.png_result;
}
}