summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-02 23:04:10 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-02 23:04:10 +0000
commit9f60d09c6faaac732a62a188228a88321aad7368 (patch)
tree4404ee0e25d63abaad5e23b9aa8dce9ed6a9c8e9
parent8a2d54981a1c1ee6563f3444cffc1d2d4784156e (diff)
downloadpx4-nuttx-9f60d09c6faaac732a62a188228a88321aad7368.tar.gz
px4-nuttx-9f60d09c6faaac732a62a188228a88321aad7368.tar.bz2
px4-nuttx-9f60d09c6faaac732a62a188228a88321aad7368.zip
Add NSH ping command
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@870 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/examples/README.txt3
-rw-r--r--nuttx/examples/nsh/Makefile2
-rw-r--r--nuttx/examples/nsh/nsh.h6
-rw-r--r--nuttx/examples/nsh/nsh_main.c6
-rw-r--r--nuttx/examples/nsh/nsh_netcmds.c150
-rw-r--r--nuttx/include/net/uip/uip-arch.h2
-rw-r--r--nuttx/include/net/uip/uip-icmp.h13
-rw-r--r--nuttx/include/net/uip/uip-lib.h3
-rw-r--r--nuttx/include/nuttx/clock.h14
-rw-r--r--nuttx/net/uip/uip-chksum.c11
-rw-r--r--nuttx/net/uip/uip-icmpping.c10
-rw-r--r--nuttx/net/uip/uip-icmpsend.c6
-rw-r--r--nuttx/netutils/uiplib/uiplib.c56
13 files changed, 245 insertions, 37 deletions
diff --git a/nuttx/examples/README.txt b/nuttx/examples/README.txt
index 4cbec9515..469a84b92 100644
--- a/nuttx/examples/README.txt
+++ b/nuttx/examples/README.txt
@@ -45,7 +45,7 @@ examples/nsh
exec --
exit --
help --
- ifconfig CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS > 0
+ ifconfig CONFIG_NET
ls CONFIG_NFILE_DESCRIPTORS > 0
mb,mh,mw ---
mem ---
@@ -53,6 +53,7 @@ examples/nsh
mkfatfs !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_FAT
mkfifo !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0
mount !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0 && CONFIG_FS_FAT
+ ping CONFIG_NET && CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING && !CONFIG_DISABLE_CLOCK && !CONFIG_DISABLE_SIGNALS
ps --
pwd !CONFIG_DISABLE_ENVIRON && CONFIG_NFILE_DESCRIPTORS > 0
rm !CONFIG_DISABLE_MOUNTPOINT && CONFIG_NFILE_DESCRIPTORS > 0
diff --git a/nuttx/examples/nsh/Makefile b/nuttx/examples/nsh/Makefile
index 5ff7e3c6a..8e308d43f 100644
--- a/nuttx/examples/nsh/Makefile
+++ b/nuttx/examples/nsh/Makefile
@@ -40,10 +40,8 @@ ASRCS =
CSRCS = nsh_main.c nsh_fscmds.c nsh_proccmds.c nsh_envcmds.c nsh_dbgcmds.c
ifeq ($(CONFIG_NET),y)
-ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
CSRCS += nsh_netcmds.c
endif
-endif
ifeq ($(CONFIG_EXAMPLES_NSH_CONSOLE),y)
CSRCS += nsh_serial.c
diff --git a/nuttx/examples/nsh/nsh.h b/nuttx/examples/nsh/nsh.h
index 9203d7c0f..861be30c2 100644
--- a/nuttx/examples/nsh/nsh.h
+++ b/nuttx/examples/nsh/nsh.h
@@ -296,8 +296,12 @@ extern int cmd_lbracket(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
# endif /* !CONFIG_DISABLE_MOUNTPOINT */
#endif /* CONFIG_NFILE_DESCRIPTORS */
-#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+#if defined(CONFIG_NET)
extern int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) && \
+ !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_DISABLE_SIGNALS)
+ extern int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv);
+#endif
#endif
#ifndef CONFIG_DISABLE_ENVIRON
diff --git a/nuttx/examples/nsh/nsh_main.c b/nuttx/examples/nsh/nsh_main.c
index a70d2176d..ba7ad389f 100644
--- a/nuttx/examples/nsh/nsh_main.c
+++ b/nuttx/examples/nsh/nsh_main.c
@@ -146,7 +146,7 @@ static const struct cmdmap_s g_cmdmap[] =
{ "exec", cmd_exec, 2, 3, "<hex-address>" },
{ "exit", cmd_exit, 1, 1, NULL },
{ "help", cmd_help, 1, 1, NULL },
-#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+#ifdef CONFIG_NET
{ "ifconfig", cmd_ifconfig, 1, 1, NULL },
#endif
#if CONFIG_NFILE_DESCRIPTORS > 0
@@ -169,6 +169,10 @@ static const struct cmdmap_s g_cmdmap[] =
#endif
{ "mw", cmd_mw, 2, 3, "<hex-address>[=<hex-value>][ <hex-byte-count>]" },
{ "ps", cmd_ps, 1, 1, NULL },
+#if defined(CONFIG_NET) && defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) && \
+ !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_DISABLE_SIGNALS)
+ { "ping", cmd_ping, 2, 6, "[-c <count>] [-i <interval>] <ip-address>" },
+#endif
#if CONFIG_NFILE_DESCRIPTORS > 0 && !defined(CONFIG_DISABLE_ENVIRON)
{ "pwd", cmd_pwd, 1, 1, NULL },
#endif
diff --git a/nuttx/examples/nsh/nsh_netcmds.c b/nuttx/examples/nsh/nsh_netcmds.c
index df4197c87..c5eebe425 100644
--- a/nuttx/examples/nsh/nsh_netcmds.c
+++ b/nuttx/examples/nsh/nsh_netcmds.c
@@ -38,14 +38,16 @@
****************************************************************************/
#include <nuttx/config.h>
-#if defined(CONFIG_NET) && CONFIG_NSOCKET_DESCRIPTORS > 0
+#ifdef CONFIG_NET
#include <sys/types.h>
#include <stdio.h>
#include <stdlib.h>
+#include <unistd.h>
#include <sched.h>
#include <nuttx/net.h>
+#include <nuttx/clock.h>
#include <net/ethernet.h>
#include <net/uip/uip.h>
#include <net/uip/uip-arch.h>
@@ -55,12 +57,19 @@
#include <net/uip/uip.h>
#endif
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) && \
+ !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_DISABLE_SIGNALS)
+#include <net/uip/uip-lib.h>
+#endif
+
#include "nsh.h"
/****************************************************************************
* Definitions
****************************************************************************/
+#define DEFAULT_PING_DATALEN 56
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -73,6 +82,11 @@
* Private Data
****************************************************************************/
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) && \
+ !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_DISABLE_SIGNALS)
+static uint16 g_pingid = 0;
+#endif
+
/****************************************************************************
* Public Data
****************************************************************************/
@@ -82,6 +96,21 @@
****************************************************************************/
/****************************************************************************
+ * Name: ping_newid
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) && \
+ !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_DISABLE_SIGNALS)
+static inline uint16 ping_newid(void)
+{
+ irqstate_t save = irqsave();
+ uint16 ret = ++g_pingid;
+ irqrestore(save);
+ return ret;
+}
+#endif
+
+/****************************************************************************
* Name: uip_statistics
****************************************************************************/
@@ -228,4 +257,121 @@ int cmd_ifconfig(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
return OK;
}
-#endif /* CONFIG_NET && CONFIG_NSOCKET_DESCRIPTORS */
+/****************************************************************************
+ * Name: cmd_ping
+ ****************************************************************************/
+
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING) && \
+ !defined(CONFIG_DISABLE_CLOCK) && !defined(CONFIG_DISABLE_SIGNALS)
+int cmd_ping(FAR struct nsh_vtbl_s *vtbl, int argc, char **argv)
+{
+ FAR const char *fmt = g_fmtarginvalid;
+ const char *staddr;
+ uip_ipaddr_t ipaddr;
+ uint32 start;
+ uint32 next;
+ uint32 dsec;
+ uint16 id;
+ int sec = 1;
+ int count = 10;
+ int option;
+ int seqno;
+ int replies = 0;
+ int elapsed;
+ int i;
+
+ /* Get the ping options */
+
+ while ((option = getopt(argc, argv, ":c:i:")) != ERROR)
+ {
+ switch (option)
+ {
+ case 'c':
+ count = atoi(optarg);
+ if (count < 1 || count > 10000)
+ {
+ fmt = g_fmtargrange;
+ goto errout;
+ }
+ break;
+
+ case 'i':
+ sec = atoi(optarg);
+ if (sec < 1 || sec >= 4294)
+ {
+ fmt = g_fmtargrange;
+ goto errout;
+ }
+ break;
+
+ case ':':
+ fmt = g_fmtargrequired;
+
+ case '?':
+ default:
+ goto errout;
+ }
+ }
+
+ /* There should be exactly on parameter left on the command-line */
+
+ if (optind == argc-1)
+ {
+ staddr = argv[optind];
+ if (!uiplib_ipaddrconv(staddr, (FAR unsigned char*)&ipaddr))
+ {
+ goto errout;
+ }
+ }
+ else if (optind >= argc)
+ {
+ fmt = g_fmttoomanyargs;
+ goto errout;
+ }
+ else
+ {
+ fmt = g_fmtargrequired;
+ 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);
+ start = g_system_timer;
+ for (i = 0; i < count; i++)
+ {
+ next = g_system_timer;
+ seqno = uip_ping(ipaddr, id, i, DEFAULT_PING_DATALEN, dsec);
+ elapsed = TICK2MSEC(g_system_timer - next);
+ if (seqno >= 0)
+ {
+ nsh_output(vtbl, "%d bytes from %s: icmp_seq=%d time=%d ms\n",
+ DEFAULT_PING_DATALEN, staddr, seqno, elapsed);
+ replies++;
+ }
+ elapsed = TICK2DSEC(g_system_timer - next);
+ if (elapsed < dsec)
+ {
+ usleep(100000*dsec);
+ }
+ }
+ 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);
+ return OK;
+
+errout:
+ nsh_output(vtbl, fmt, argv[0]);
+ return ERROR;
+}
+#endif /* CONFIG_NET_ICMP && CONFIG_NET_ICMP_PING */
+#endif /* CONFIG_NET */
diff --git a/nuttx/include/net/uip/uip-arch.h b/nuttx/include/net/uip/uip-arch.h
index 6f2781eb3..c0044fdfe 100644
--- a/nuttx/include/net/uip/uip-arch.h
+++ b/nuttx/include/net/uip/uip-arch.h
@@ -366,5 +366,7 @@ extern uint16 uip_ipchksum(struct uip_driver_s *dev);
extern uint16 uip_tcpchksum(struct uip_driver_s *dev);
extern uint16 uip_udpchksum(struct uip_driver_s *dev);
+extern uint16 uip_icmpchksum(struct uip_driver_s *dev);
#endif /* __UIP_ARCH_H */
+
diff --git a/nuttx/include/net/uip/uip-icmp.h b/nuttx/include/net/uip/uip-icmp.h
index 632653ab8..67d6941d3 100644
--- a/nuttx/include/net/uip/uip-icmp.h
+++ b/nuttx/include/net/uip/uip-icmp.h
@@ -194,4 +194,17 @@ struct uip_icmp_stats_s
* Public Function Prototypes
****************************************************************************/
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, uint16 datalen, int dsecs);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
#endif /* __NET_UIP_UIP_ICMP_H */
diff --git a/nuttx/include/net/uip/uip-lib.h b/nuttx/include/net/uip/uip-lib.h
index 307a6b277..ce81dca67 100644
--- a/nuttx/include/net/uip/uip-lib.h
+++ b/nuttx/include/net/uip/uip-lib.h
@@ -47,6 +47,7 @@
****************************************************************************/
#include <nuttx/config.h>
+#include <sys/types.h>
#include <pthread.h>
#include <netinet/in.h>
@@ -85,7 +86,7 @@
* Return: Non-zero If the IP address was parsed.
*/
-extern unsigned char uiplib_ipaddrconv(char *addrstr, unsigned char *addr);
+extern boolean uiplib_ipaddrconv(const char *addrstr, ubyte *addr);
/* Get and set IP/MAC addresses */
diff --git a/nuttx/include/nuttx/clock.h b/nuttx/include/nuttx/clock.h
index b57b8e4f8..6d4d20dd4 100644
--- a/nuttx/include/nuttx/clock.h
+++ b/nuttx/include/nuttx/clock.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * nuttx/clock.h
+ * include/nuttx/clock.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
@@ -78,6 +78,7 @@
# define MSEC_PER_TICK (10)
#endif
+#define TICK_PER_DSEC (MSEC_PER_DSEC / MSEC_PER_TICK) /* Truncates! */
#define TICK_PER_SEC (MSEC_PER_SEC / MSEC_PER_TICK) /* Truncates! */
#define NSEC_PER_TICK (MSEC_PER_TICK * NSEC_PER_MSEC) /* Exact */
#define USEC_PER_TICK (MSEC_PER_TICK * USEC_PER_MSEC) /* Exact */
@@ -88,6 +89,13 @@
#define DSEC2TICK(dsec) MSEC2TICK((dsec)*MSEC_PER_DSEC)
#define SEC2TICK(sec) MSEC2TICK((sec)*MSEC_PER_SEC)
+#define TICK2NSEC(tick) ((tick)*NSEC_PER_TICK) /* Exact */
+#define TICK2USEC(tick) ((tick)*USEC_PER_TICK) /* Exact */
+#define TICK2MSEC(tick) ((tick)*MSEC_PER_TICK) /* Exact */
+#define TICK2DSEC(tick) (((tick)+(TICK_PER_DSEC/2))/TICK_PER_DSEC) /* Rounds */
+#define TICK2SEC(tick) (((tick)+(TICK_PER_SEC/2))/TICK_PER_SEC) /* Rounds */
+
+
/****************************************************************************
* Global Data
****************************************************************************/
diff --git a/nuttx/net/uip/uip-chksum.c b/nuttx/net/uip/uip-chksum.c
index 50602f481..479ebc797 100644
--- a/nuttx/net/uip/uip-chksum.c
+++ b/nuttx/net/uip/uip-chksum.c
@@ -55,6 +55,7 @@
****************************************************************************/
#define BUF ((struct uip_ip_hdr *)&dev->d_buf[UIP_LLH_LEN])
+#define ICMPBUF ((struct uip_icmpip_hdr *)&dev->d_buf[UIP_LLH_LEN])
/****************************************************************************
* Private Data
@@ -224,6 +225,16 @@ uint16 uip_udpchksum(struct uip_driver_s *dev)
return upper_layer_chksum(dev, UIP_PROTO_UDP);
}
#endif
+
+/* Calculate the checksum of the ICMP message */
+
+#if defined(CONFIG_NET_ICMP) && defined(CONFIG_NET_ICMP_PING)
+uint16 uip_icmpchksum(struct uip_driver_s *dev)
+{
+ return uip_chksum((uint16*)&ICMPBUF->type, dev->d_sndlen);
+}
+#endif
+
#endif /* UIP_ARCH_CHKSUM */
#endif /* CONFIG_NET */
diff --git a/nuttx/net/uip/uip-icmpping.c b/nuttx/net/uip/uip-icmpping.c
index e62209dcd..5bc9b68b0 100644
--- a/nuttx/net/uip/uip-icmpping.c
+++ b/nuttx/net/uip/uip-icmpping.c
@@ -58,6 +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)]
/* Allocate a new ICMP data callback */
@@ -79,6 +80,7 @@ struct icmp_ping_s
uip_ipaddr_t png_addr; /* The peer to be ping'ed */
uint16 png_id; /* Used to match requests with replies */
uint16 png_seqno; /* IN: seqno to send; OUT: seqno recieved */
+ uint16 png_datlen; /* The length of data to send in the ECHO request */
boolean png_sent; /* TRUE... the PING request has been sent */
};
@@ -211,13 +213,14 @@ 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);
/* 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.
*/
- dev->d_sndlen= 4;
+ dev->d_sndlen= pstate->png_datlen + 4;
uip_icmpsend(dev, &pstate->png_addr);
pstate->png_sent = TRUE;
return flags;
@@ -283,7 +286,7 @@ end_wait:
*
****************************************************************************/
-int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, int dsecs)
+int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, uint16 datalen, int dsecs)
{
struct icmp_ping_s state;
irqstate_t save;
@@ -296,6 +299,7 @@ int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, int dsecs)
state.png_addr = addr; /* Address of the peer to be ping'ed */
state.png_id = id; /* The ID to use in the ECHO request */
state.png_seqno = seqno; /* The seqno to use int the ECHO request */
+ state.png_datlen = datalen; /* The length of data to send in the ECHO request */
state.png_sent = FALSE; /* ECHO request not yet sent */
save = irqsave();
@@ -303,7 +307,7 @@ int uip_ping(uip_ipaddr_t addr, uint16 id, uint16 seqno, int dsecs)
/* Set up the callback */
- state.png_cb = uip_icmpcallbackalloc();
+ state.png_cb = uip_icmpcallbackalloc();
if (state.png_cb)
{
state.png_cb->flags = UIP_POLL|UIP_ECHOREPLY;
diff --git a/nuttx/net/uip/uip-icmpsend.c b/nuttx/net/uip/uip-icmpsend.c
index 90c2a6c6e..c0076b0e8 100644
--- a/nuttx/net/uip/uip-icmpsend.c
+++ b/nuttx/net/uip/uip-icmpsend.c
@@ -98,6 +98,12 @@ void uip_icmpsend(struct uip_driver_s *dev, uip_ipaddr_t *destaddr)
dev->d_len = dev->d_sndlen + UIP_IPICMPH_LEN;
+ /* The total size of the data (for ICMP checksum calculation) includes
+ * the size of the ICMP header
+ */
+
+ dev->d_sndlen += UIP_ICMPH_LEN;
+
/* Initialize the IP header. Note that for IPv6, the IP length field
* does not include the IPv6 IP header length.
*/
diff --git a/nuttx/netutils/uiplib/uiplib.c b/nuttx/netutils/uiplib/uiplib.c
index a60d5743b..4dd2e31da 100644
--- a/nuttx/netutils/uiplib/uiplib.c
+++ b/nuttx/netutils/uiplib/uiplib.c
@@ -46,33 +46,43 @@
#include <net/uip/uip.h>
#include <net/uip/uip-lib.h>
-unsigned char uiplib_ipaddrconv(char *addrstr, unsigned char *ipaddr)
+boolean uiplib_ipaddrconv(const char *addrstr, ubyte *ipaddr)
{
unsigned char tmp;
char c;
- unsigned char i, j;
+ unsigned char i;
+ unsigned char j;
tmp = 0;
- for(i = 0; i < 4; ++i) {
- j = 0;
- do {
- c = *addrstr;
- ++j;
- if(j > 4) {
- return 0;
- }
- if(c == '.' || c == 0) {
- *ipaddr = tmp;
- ++ipaddr;
- tmp = 0;
- } else if(c >= '0' && c <= '9') {
- tmp = (tmp * 10) + (c - '0');
- } else {
- return 0;
- }
- ++addrstr;
- } while(c != '.' && c != 0);
- }
- return 1;
+ for (i = 0; i < 4; ++i)
+ {
+ j = 0;
+ do
+ {
+ c = *addrstr;
+ ++j;
+ if (j > 4)
+ {
+ return FALSE;
+ }
+ if (c == '.' || c == 0)
+ {
+ *ipaddr = tmp;
+ ++ipaddr;
+ tmp = 0;
+ }
+ else if(c >= '0' && c <= '9')
+ {
+ tmp = (tmp * 10) + (c - '0');
+ }
+ else
+ {
+ return FALSE;
+ }
+ ++addrstr;
+ }
+ while(c != '.' && c != 0);
+ }
+ return TRUE;
}