summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c91
-rwxr-xr-xnuttx/configs/mbed/README.txt2
-rwxr-xr-xnuttx/configs/nucleus2g/README.txt4
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/README.txt4
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nettest/defconfig4
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nsh/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/ostest/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbserial/defconfig2
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbstorage/defconfig2
-rw-r--r--nuttx/examples/nettest/nettest.c4
10 files changed, 85 insertions, 32 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
index e7b5b500f..2b7f1fd21 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
@@ -72,6 +72,7 @@
* Definitions
****************************************************************************/
+/* Configuration ************************************************************/
/* CONFIG_LPC17_NINTERFACES determines the number of physical interfaces
* that will be supported -- unless it is more than actually supported by the
* hardware!
@@ -107,6 +108,29 @@
# define CONFIG_NET_PRIORITY NVIC_SYSH_PRIORITY_MAX
#endif
+/* Debug Configuration *****************************************************/
+/* Register debug -- can only happen of CONFIG_DEBUG is selected */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_NET_REGDEBUG
+#endif
+
+/* CONFIG_NET_DUMPPACKET will dump the contents of each packet to the
+ * console.
+ */
+
+#ifndef CONFIG_DEBUG
+# undef CONFIG_NET_DUMPPACKET
+#endif
+
+#ifdef CONFIG_NET_DUMPPACKET
+# define lpc17_dumppacket(m,a,n) lib_dumpbuffer(m,a,n)
+#else
+# define lpc17_dumppacket(m,a,n)
+#endif
+
+/* Timing *******************************************************************/
+
/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
#define LPC17_WDDELAY (1*CLK_TCK)
@@ -116,15 +140,22 @@
#define LPC17_TXTIMEOUT (60*CLK_TCK)
-/* Interrupts */
+/* Interrupts ***************************************************************/
#define ETH_RXINTS (ETH_INT_RXOVR | ETH_INT_RXERR | ETH_INT_RXFIN | ETH_INT_RXDONE)
#define ETH_TXINTS (ETH_INT_TXUNR | ETH_INT_TXERR | ETH_INT_TXFIN | ETH_INT_TXDONE)
+/* Misc. Helpers ***********************************************************/
+
/* This is a helper pointer for accessing the contents of the Ethernet header */
#define BUF ((struct uip_eth_hdr *)priv->lp_dev.d_buf)
+/* This is the number of ethernet GPIO pins that must be configured */
+
+#define GPIO_NENET_PINS 10
+
+/* PHYs *********************************************************************/
/* Select PHY-specific values. Add more PHYs as needed. */
#ifdef CONFIG_PHY_KS8721
@@ -168,10 +199,7 @@
# endif
#endif
-/* This is the number of ethernet GPIO pins that must be configured */
-
-#define GPIO_NENET_PINS 10
-
+/* Descriptors **************************************************************/
/* EMAC DMA RAM and descriptor definitions. The configured number of
* descriptors will determine the organization and the size of the
* descriptor and status tables. There is a complex interaction between
@@ -291,12 +319,6 @@
# error "Packet memory overlaps descriptor tables"
#endif
-/* Register debug -- can only happen of CONFIG_DEBUG is selected */
-
-#ifndef CONFIG_DEBUG
-# undef CONFIG_NET_REGDEBUG
-#endif
-
/****************************************************************************
* Private Types
****************************************************************************/
@@ -672,9 +694,11 @@ static int lpc17_transmit(struct lpc17_driver_s *priv)
DEBUGASSERT(lpc17_txdesc(priv) == OK);
- /* Increment statistics */
+ /* Increment statistics and dump the packet *if so configured) */
EMAC_STAT(priv, tx_packets);
+ lpc17_dumppacket("Transmit packet",
+ priv->lp_dev.d_buf, priv->lp_dev.d_len);
/* Get the current producer index */
@@ -929,6 +953,9 @@ static void lpc17_rxdone(struct lpc17_driver_s *priv)
memcpy(priv->lp_dev.d_buf, rxbuffer, pktlen);
priv->lp_dev.d_len = pktlen;
+ lpc17_dumppacket("Received packet",
+ priv->ld_dev.d_buf, priv->ld_dev.d_len);
+
/* We only accept IP packets of the configured type and ARP packets */
#ifdef CONFIG_NET_IPv6
@@ -1151,7 +1178,6 @@ static int lpc17_interrupt(int irq, void *context)
# warning "Missing logic"
}
#endif
-
}
return OK;
@@ -1367,11 +1393,30 @@ static int lpc17_ifup(struct uip_driver_s *dev)
lpc17_putreg(ETH_RXINTS, LPC17_ETH_INTEN);
#endif
+ /* Enable Rx */
+
+ regval = lpc17_getreg(LPC17_ETH_CMD);
+ regval |= ETH_CMD_RXEN;
+ lpc17_putreg(regval, LPC17_ETH_CMD);
+
+ regval = lpc17_getreg(LPC17_ETH_MAC1);
+ regval |= ETH_MAC1_RE;
+ lpc17_putreg(regval, LPC17_ETH_MAC1);
+
+ /* Enable Tx */
+
+ regval = lpc17_getreg(LPC17_ETH_CMD);
+ regval |= ETH_CMD_TXEN;
+ lpc17_putreg(regval, LPC17_ETH_CMD);
+
/* Set and activate a timer process */
- (void)wd_start(priv->lp_txpoll, LPC17_WDDELAY, lpc17_polltimer, 1, (uint32_t)priv);
+ (void)wd_start(priv->lp_txpoll, LPC17_WDDELAY, lpc17_polltimer, 1,
+ (uint32_t)priv);
- /* Finally, enable the Ethernet interrupt at the interrupt controller */
+ /* Finally, make the interface up and enable the Ethernet interrupt at
+ * the interrupt controller
+ */
priv->lp_ifup = true;
#if CONFIG_LPC17_NINTERFACES > 1
@@ -1573,13 +1618,13 @@ static void lpc17_showpins(void)
static void lpc17_showmii(uint8_t phyaddr, const char *msg)
{
dbg("PHY " LPC17_PHYNAME ": %s\n", msg);
- dbg(" MCR: %04x\n", lpc17_getreg(MII_MCR));
- dbg(" MSR: %04x\n", lpc17_getreg(MII_MSR));
- dbg(" ADVERTISE: %04x\n", lpc17_getreg(MII_ADVERTISE));
- dbg(" LPA: %04x\n", lpc17_getreg(MII_LPA));
- dbg(" EXPANSION: %04x\n", lpc17_getreg(MII_EXPANSION));
+ dbg(" MCR: %04x\n", lpc17_phyread(phyaddr, MII_MCR));
+ dbg(" MSR: %04x\n", lpc17_phyread(phyaddr, MII_MSR));
+ dbg(" ADVERTISE: %04x\n", lpc17_phyread(phyaddr, MII_ADVERTISE));
+ dbg(" LPA: %04x\n", lpc17_phyread(phyaddr, MII_LPA));
+ dbg(" EXPANSION: %04x\n", lpc17_phyread(phyaddr, MII_EXPANSION));
#ifdef CONFIG_PHY_KS8721
- dbg(" 10BTCR: %04x\n", lpc17_getreg(MII_KS8721_10BTCR));
+ dbg(" 10BTCR: %04x\n", lpc17_phyread(phyaddr, MII_KS8721_10BTCR));
#endif
}
#endif
@@ -2106,9 +2151,9 @@ static inline void lpc17_rxdescinit(struct lpc17_driver_s *priv)
*rxstat++ = 0;
}
- /* Point to first Tx descriptor */
+ /* Point to first Rx descriptor */
- lpc17_putreg(0, LPC17_ETH_RXPRODIDX);
+ lpc17_putreg(0, LPC17_ETH_RXCONSIDX);
}
/****************************************************************************
diff --git a/nuttx/configs/mbed/README.txt b/nuttx/configs/mbed/README.txt
index ac9047f62..c059f1de9 100755
--- a/nuttx/configs/mbed/README.txt
+++ b/nuttx/configs/mbed/README.txt
@@ -298,6 +298,8 @@ mbed Configuration Options
CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
CONFIG_DEBUG.
+ CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
+ Also needs CONFIG_DEBUG.
CONFIG_NET_BROADCAST - Enable receipt of broadcast frames
CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
diff --git a/nuttx/configs/nucleus2g/README.txt b/nuttx/configs/nucleus2g/README.txt
index 99aac4073..76864531e 100755
--- a/nuttx/configs/nucleus2g/README.txt
+++ b/nuttx/configs/nucleus2g/README.txt
@@ -249,7 +249,7 @@ LEDs
#define LED_INIRQ 4 /* NC NC ON (momentary) */
#define LED_SIGNAL 5 /* NC NC ON (momentary) */
#define LED_ASSERTION 6 /* NC NC ON (momentary) */
- #define LED_PANIC 7 /* NC NC ON (1Hz flashing) */
+ #define LED_PANIC 7 /* NC NC ON (0.5Hz flashing) */
After the system is booted, this logic will no longer use LEDs 1 and 2. They
are then available for use the application software using lpc17_led1() and
@@ -410,6 +410,8 @@ Nucleus 2G Configuration Options
CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
CONFIG_DEBUG.
+ CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
+ Also needs CONFIG_DEBUG.
CONFIG_NET_BROADCAST - Enable receipt of broadcast frames
CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt
index 14784e5c9..8f5c67188 100755
--- a/nuttx/configs/olimex-lpc1766stk/README.txt
+++ b/nuttx/configs/olimex-lpc1766stk/README.txt
@@ -293,7 +293,7 @@ LEDs
- ON/OFF toggles means that various events are happening.
- GLowing: LED2 is turned on and off on every interrupt so even timer interrupts
should cause LED2 to glow faintly in the normal case.
- - Flashing. If the LED2 is flashing at about 1Hz, that means that a crash
+ - Flashing. If the LED2 is flashing at about 0.5Hz, that means that a crash
has occurred. If CONFIG_ARCH_STACKDUMP=y, you will get some diagnostic
information on the console to help debug what happened.
@@ -616,6 +616,8 @@ Olimex LPC1766-STK Configuration Options
CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
CONFIG_DEBUG.
+ CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
+ Also needs CONFIG_DEBUG.
CONFIG_NET_BROADCAST - Enable receipt of broadcast frames
CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
index 25322b279..598f69f10 100755
--- a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
@@ -76,7 +76,7 @@ CONFIG_ARCH_CHIP=lpc17xx
CONFIG_ARCH_CHIP_LPC1766=y
CONFIG_ARCH_BOARD=olimex-lpc1766stk
CONFIG_ARCH_BOARD_LPC1766STK=y
-CONFIG_BOARD_LOOPSPERMSEC=7982
+CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=(32*1024)
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
@@ -195,6 +195,8 @@ CONFIG_UART3_2STOP=0
# CONFIG_NET_WOL - Enable Wake-up on Lan (not fully implemented).
# CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
# CONFIG_DEBUG.
+# CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
+# Also needs CONFIG_DEBUG.
# CONFIG_NET_BROADCAST - Enable receipt of broadcast frames
# CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
# CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
index f686bcb5c..b1b81f522 100755
--- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
@@ -76,7 +76,7 @@ CONFIG_ARCH_CHIP=lpc17xx
CONFIG_ARCH_CHIP_LPC1766=y
CONFIG_ARCH_BOARD=olimex-lpc1766stk
CONFIG_ARCH_BOARD_LPC1766STK=y
-CONFIG_BOARD_LOOPSPERMSEC=7982
+CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=(32*1024)
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
index 5c9051981..ba4713544 100755
--- a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
@@ -76,7 +76,7 @@ CONFIG_ARCH_CHIP=lpc17xx
CONFIG_ARCH_CHIP_LPC1766=y
CONFIG_ARCH_BOARD=olimex-lpc1766stk
CONFIG_ARCH_BOARD_LPC1766STK=y
-CONFIG_BOARD_LOOPSPERMSEC=7982
+CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=(32*1024)
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
index dc10183c0..ea00b69f5 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
@@ -76,7 +76,7 @@ CONFIG_ARCH_CHIP=lpc17xx
CONFIG_ARCH_CHIP_LPC1766=y
CONFIG_ARCH_BOARD=olimex-lpc1766stk
CONFIG_ARCH_BOARD_LPC1766STK=y
-CONFIG_BOARD_LOOPSPERMSEC=7982
+CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=(32*1024)
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
index 7f1c079d1..e24b14b7e 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
@@ -76,7 +76,7 @@ CONFIG_ARCH_CHIP=lpc17xx
CONFIG_ARCH_CHIP_LPC1766=y
CONFIG_ARCH_BOARD=olimex-lpc1766stk
CONFIG_ARCH_BOARD_LPC1766STK=y
-CONFIG_BOARD_LOOPSPERMSEC=7982
+CONFIG_BOARD_LOOPSPERMSEC=8111
CONFIG_DRAM_SIZE=(32*1024)
CONFIG_DRAM_START=0x10000000
CONFIG_DRAM_END=(CONFIG_DRAM_START+CONFIG_DRAM_SIZE)
diff --git a/nuttx/examples/nettest/nettest.c b/nuttx/examples/nettest/nettest.c
index 21dd79151..a59bccf58 100644
--- a/nuttx/examples/nettest/nettest.c
+++ b/nuttx/examples/nettest/nettest.c
@@ -1,7 +1,7 @@
/****************************************************************************
* examples/nettest/nettest.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009-2010 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -81,7 +81,7 @@ void user_initialize(void)
int user_start(int argc, char *argv[])
{
struct in_addr addr;
-#if defined(CONFIG_EXAMPLE_NETTEST_NOMAC)
+#ifdef CONFIG_EXAMPLE_NETTEST_NOMAC
uint8_t mac[IFHWADDRLEN];
#endif