summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog9
-rw-r--r--nuttx/Documentation/NuttX.html7
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_ethernet.c2
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c610
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h6
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/README.txt8
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/include/board.h5
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nettest/defconfig13
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nsh/defconfig13
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/ostest/defconfig13
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbserial/defconfig13
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbstorage/defconfig13
-rw-r--r--nuttx/include/nuttx/mii.h6
13 files changed, 666 insertions, 52 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index a897124bd..3e4e4fdb9 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -1239,7 +1239,7 @@
For people who have their own configurations and/or Makefiles,
you will need to make a couple of changes:
- - Replace all occurrences of CONFIG_EXAMPLE=foobar with
+ - Replace all occurrences of CONFIG_EXAMPLE=foobar with
CONFIG_APP_DIR=examples/foobar in all of the configuration
files.
- Replace any occurrences of examples/$(CONFIG_EXAMPLE) with
@@ -1329,8 +1329,13 @@
not refer to an open file.
* configs/olimex-lpc1766stk - Add support for the Olimex LPC1766-STK
development board. The OS test and NSH configurations (only) have been
- verified.
+ verified.
5.14 2010-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
+ * configs/olimex-lpc1766stk/nettest - Add examples/nettest configuration to
+ verify the LPC17xx ethernet driver currently under development.
+ * arch/arm/src/lpc17xx/lpc17xx_ethernet.c/.h - Began development of
+ the LPC17xx Ethernet driver.
+
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 996ffea4c..a7d04ce99 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: November 9, 2010</p>
+ <p>Last Updated: November 11, 2010</p>
</td>
</tr>
</table>
@@ -1982,6 +1982,11 @@ buildroot-1.8 2009-12-21 &lt;spudmonkey@racsa.co.cr&gt;
<ul><pre>
nuttx-5.14 2010-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
+ * configs/olimex-lpc1766stk/nettest - Add examples/nettest configuration to
+ verify the LPC17xx ethernet driver currently under development.
+ * arch/arm/src/lpc17xx/lpc17xx_ethernet.c/.h - Began development of
+ the LPC17xx Ethernet driver.
+
pascal-2.1 2010-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
buildroot-1.9 2010-xx-xx <spudmonkey@racsa.co.cr>
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
index feb3b9a90..b66e8be42 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
@@ -192,7 +192,7 @@ struct lm3s_driver_s
#if LM3S_NETHCONTROLLERS > 1
uint32_t ld_base; /* Ethernet controller base address */
- int ld-irq; /* Ethernet controller IRQ */
+ int ld_irq; /* Ethernet controller IRQ */
#endif
bool ld_bifup; /* true:ifup false:ifdown */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
index e144eb191..b8648f4e6 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
@@ -50,6 +50,7 @@
#include <nuttx/irq.h>
#include <nuttx/arch.h>
+#include <nuttx/mii.h>
#include <net/uip/uip.h>
#include <net/uip/uip-arp.h>
@@ -103,9 +104,23 @@
#define BUF ((struct uip_eth_hdr *)priv->lp_dev.d_buf)
+/* Select PHY-specific values. Add more PHYs as needed. */
+
+#ifdef CONFIG_PHY_KS8721
+# define LPC17_PHYNAME "KS8721"
+# define LPC17_PHYID1 MII_PHYID1_KS8721
+# define LPC17_PHYID2 MII_PHYID2_KS8721
+# define LPC17_HAVE_PHY 1
+#else
+# warning "No PHY specified!"
+# undef LPC17_HAVE_PHY
+#endif
+
+#define MII_BIG_TIMEOUT 666666
+
/* This is the number of ethernet GPIO pins that must be configured */
-#define GPIO_NENET_PINS 10
+#define GPIO_NENET_PINS 10
/* Register debug */
@@ -123,7 +138,19 @@
struct lpc17_driver_s
{
+ /* The following fields would only be necessary on chips that support
+ * multiple Ethernet controllers.
+ */
+
+#if LM3S_NETHCONTROLLERS > 1
+ uint32_t lp_base; /* Ethernet controller base address */
+ int lp_irq; /* Ethernet controller IRQ */
+#endif
+
bool lp_bifup; /* true:ifup false:ifdown */
+#ifdef LPC17_HAVE_PHY
+ uint8_t lp_phyaddr; /* PHY device address */
+#endif
WDOG_ID lp_txpoll; /* TX poll timer */
WDOG_ID lp_txtimeout; /* TX timeout timer */
@@ -157,18 +184,16 @@ static const uint16_t g_enetpins[GPIO_NENET_PINS] =
* Private Function Prototypes
****************************************************************************/
-/* Register operations ********************************************************/
+/* Register operations */
#ifdef CONFIG_LPC17_ENET_REGDEBUG
static void lpc17_printreg(uint32_t addr, uint32_t val, bool iswrite);
static void lpc17_checkreg(uint32_t addr, uint32_t val, bool iswrite);
static uint32_t lpc17_getreg(uint32_t addr);
static void lpc17_putreg(uint32_t val, uint32_t addr);
-static void lpc17_showpins(void);
#else
# define lpc17_getreg(addr) getreg32(addr)
# define lpc17_putreg(val,addr) putreg32(val,addr)
-# define lpc17_showpins()
#endif
/* Common TX logic */
@@ -199,8 +224,38 @@ static int lpc17_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac);
/* Initialization functions */
-static void lpc17_phywrite(uint8_t phyaddr, uint8_t regaddr, uint16_t phydata);
+#ifdef CONFIG_LPC17_ENET_REGDEBUG
+static void lpc17_showpins(void);
+#else
+# define lpc17_showpins()
+#endif
+
+/* PHY initialization functions */
+
+#ifdef LPC17_HAVE_PHY
+# ifdef CONFIG_LPC17_ENET_REGDEBUG
+static void lpc17_showmii(uint8_t phyaddr, const char *msg);
+# else
+# define lpc17_showmii(phyaddr,msg)
+# endif
+
+static void lpc17_phywrite(uint8_t phyaddr, uint8_t regaddr,
+ uint16_t phydata);
static uint16_t lpc17_phyread(uint8_t phyaddr, uint8_t regaddr);
+static inline int lpc17_phyreset(uint8_t phyaddr);
+# ifdef CONFIG_PHY_AUTONEG
+static inline int lpc17_phyautoneg(uint8_t phyaddr);
+# endif
+static int lpc17_phyfixed(uint8_t phyaddr, bool speed100, bool fullduplex);
+static void lpc17_phyfullduplex(uint8_t phyaddr);
+static inline int lpc17_phyinit(struct lpc17_driver_s *priv);
+#else
+# define lpc17_phyinit()
+#endif
+
+/* EMAC Initialization functions */
+
+static void lpc17_ethreset(struct lpc17_driver_s *priv);
/****************************************************************************
* Private Functions
@@ -328,22 +383,6 @@ static void lpc17_putreg(uint32_t val, uint32_t addr)
}
#endif
-/*******************************************************************************
- * Name: lpc17_showpins
- *
- * Description:
- * Dump GPIO register
- *
- *******************************************************************************/
-
-#ifdef CONFIG_LPC17_ENET_REGDEBUG
-static void lpc17_showpins(void)
-{
- lpc17_dumpgpio(GPIO_PORT0|GPIO_PIN0, "P0[1-15]");
- lpc17_dumpgpio(GPIO_PORT0|GPIO_PIN16, "P0[16-31]");
-}
-#endif
-
/****************************************************************************
* Function: lpc17_transmit
*
@@ -653,6 +692,7 @@ static void lpc17_polltimer(int argc, uint32_t arg, ...)
static int lpc17_ifup(struct uip_driver_s *dev)
{
FAR struct lpc17_driver_s *priv = (FAR struct lpc17_driver_s *)dev->d_private;
+ uint32_t regval;
ndbg("Bringing up: %d.%d.%d.%d\n",
dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff,
@@ -660,6 +700,20 @@ static int lpc17_ifup(struct uip_driver_s *dev)
/* Initilize Ethernet interface */
+ /* Configure the MAC station address */
+
+ regval = (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[1] << 8 |
+ (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[0];
+ lpc17_putreg(regval, LPC17_ETH_SA0);
+
+ regval = (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[3] << 8 |
+ (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[2];
+ lpc17_putreg(regval, LPC17_ETH_SA1);
+
+ regval = (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[5] << 8 |
+ (uint32_t)priv->lp_dev.d_mac.ether_addr_octet[4];
+ lpc17_putreg(regval, LPC17_ETH_SA2);
+
/* Set and activate a timer process */
(void)wd_start(priv->lp_txpoll, LPC17_WDDELAY, lpc17_polltimer, 1, (uint32_t)priv);
@@ -809,6 +863,61 @@ static int lpc17_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
}
#endif
+/*******************************************************************************
+ * Name: lpc17_showpins
+ *
+ * Description:
+ * Dump GPIO registers
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ *******************************************************************************/
+
+#ifdef CONFIG_LPC17_ENET_REGDEBUG
+static void lpc17_showpins(void)
+{
+ lpc17_dumpgpio(GPIO_PORT0|GPIO_PIN0, "P0[1-15]");
+ lpc17_dumpgpio(GPIO_PORT0|GPIO_PIN16, "P0[16-31]");
+}
+#endif
+
+/*******************************************************************************
+ * Name: lpc17_showmii
+ *
+ * Description:
+ * Dump PHY MII registers
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ *******************************************************************************/
+
+#if defined(CONFIG_LPC17_ENET_REGDEBUG) && defined(LPC17_HAVE_PHY)
+static void lpc17_showmii(uint8_t phyaddr, const char *msg)
+{
+ lldbg("PHY " LPC17_PHYNAME ": %s\n", msg);
+ lldbg(" MCR: %04x\n", lpc17_getreg(MII_MCR));
+ lldbg(" MSR: %04x\n", lpc17_getreg(MII_MSR));
+ lldbg(" ADVERTISE: %04x\n", lpc17_getreg(MII_ADVERTISE));
+ lldbg(" LPA: %04x\n", lpc17_getreg(MII_LPA));
+ lldbg(" EXPANSION: %04x\n", lpc17_getreg(MII_EXPANSION));
+#ifdef CONFIG_PHY_KS8721
+ lldbg(" 10BTCR: %04x\n", lpc17_getreg(MII_KS8721_10BTCR));
+#endif
+}
+#endif
+
/****************************************************************************
* Function: lpc17_phywrite
*
@@ -827,6 +936,7 @@ static int lpc17_rmmac(struct uip_driver_s *dev, FAR const uint8_t *mac)
*
****************************************************************************/
+#ifdef LPC17_HAVE_PHY
static void lpc17_phywrite(uint8_t phyaddr, uint8_t regaddr, uint16_t phydata)
{
uint32_t regval;
@@ -849,9 +959,10 @@ static void lpc17_phywrite(uint8_t phyaddr, uint8_t regaddr, uint16_t phydata)
while ((lpc17_getreg(LPC17_ETH_MIND) & ETH_MIND_BUSY) != 0);
}
+#endif
/****************************************************************************
- * Function: lpc17_phywrite
+ * Function: lpc17_phyread
*
* Description:
* Read a value from an MII PHY register
@@ -867,6 +978,7 @@ static void lpc17_phywrite(uint8_t phyaddr, uint8_t regaddr, uint16_t phydata)
*
****************************************************************************/
+#ifdef LPC17_HAVE_PHY
static uint16_t lpc17_phyread(uint8_t phyaddr, uint8_t regaddr)
{
uint32_t regval;
@@ -890,7 +1002,400 @@ static uint16_t lpc17_phyread(uint8_t phyaddr, uint8_t regaddr)
/* Return the PHY register data */
- return (uint16_t)lpc17_getreg(LPC17_ETH_MRDD);
+ return (uint16_t)(lpc17_getreg(LPC17_ETH_MRDD) & ETH_MRDD_MASK);
+}
+#endif
+
+/****************************************************************************
+ * Function: lpc17_phyreset
+ *
+ * Description:
+ * Reset the PHY
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef LPC17_HAVE_PHY
+static inline int lpc17_phyreset(uint8_t phyaddr)
+{
+ int32_t timeout;
+ uint16_t phyreg;
+
+ /* Reset the PHY. Needs a minimal 50uS delay after reset. */
+
+ lpc17_phywrite(phyaddr, MII_MCR, MII_MCR_RESET);
+
+ /* Wait for a minimum of 50uS no matter what */
+
+ up_udelay(50);
+
+ /* The MCR reset bit is self-clearing. Wait for it to be clear
+ * indicating that the reset is complete.
+ */
+
+ for (timeout = MII_BIG_TIMEOUT; timeout > 0; timeout--)
+ {
+ phyreg = lpc17_phyread(phyaddr, MII_MCR);
+ if ((phyreg & MII_MCR_RESET) == 0)
+ {
+ return OK;
+ }
+ }
+
+ nlldbg("Reset failed. MCR: %04x\n", phyreg);
+ return -ETIMEDOUT;
+}
+#endif
+
+/****************************************************************************
+ * Function: lpc17_phyautoneg
+ *
+ * Description:
+ * Enable auto-negotiation.
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ * The adverisement regiser has already been configured.
+ *
+ ****************************************************************************/
+
+#if defined(LPC17_HAVE_PHY) && defined(CONFIG_PHY_AUTONEG)
+static inline int lpc17_phyautoneg(uint8_t phyaddr)
+{
+ int32_t timeout;
+ uint16_t phyreg;
+
+ /* Start auto-negotiation */
+
+ lpc17_phywrite(phyaddr, MII_MCR, MII_MCR_ANENABLE | MII_MCR_ANRESTART);
+
+ /* Wait for autonegotiation to complete */
+
+ for (timeout = MII_BIG_TIMEOUT; timeout > 0; timeout--)
+ {
+ /* Check if auto-negotiation has completed */
+
+ phyreg = lpc17_phyread(phyaddr, MII_MSR);
+ if ((phyreg & (MII_MSR_LINKSTATUS | MII_MSR_ANEGCOMPLETE)) ==
+ (MII_MSR_LINKSTATUS | MII_MSR_ANEGCOMPLETE))
+ {
+ /* Yes.. return success */
+
+ return OK;
+ }
+ }
+
+ nlldbg("Auto-negotiation failed. MSR: %04x\n", phyreg);
+ return -ETIMEDOUT;
+}
+#endif
+
+/****************************************************************************
+ * Function: lpc17_phyfixed
+ *
+ * Description:
+ * Set fixed PHY configuration.
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef LPC17_HAVE_PHY
+static int lpc17_phyfixed(uint8_t phyaddr, bool speed100, bool fullduplex)
+{
+ int32_t timeout;
+ uint16_t phyreg;
+
+ /* Disable auto-negotiation and set fixed Speed and Duplex settings */
+
+ phyreg = 0;
+ if (speed100)
+ {
+ phyreg = MII_MCR_SPEED100;
+ }
+
+ if (fullduplex)
+ {
+ phyreg |= MII_MCR_FULLDPLX;
+ }
+
+ lpc17_phywrite(phyaddr, MII_MCR, phyreg);
+
+ /* Then wait for the link to be established */
+
+ for (timeout = MII_BIG_TIMEOUT; timeout > 0; timeout--)
+ {
+ phyreg = lpc17_phyread(phyaddr, MII_MSR);
+ if (phyreg & MII_MSR_LINKSTATUS)
+ {
+ /* Yes.. return success */
+
+ return OK;
+ }
+ }
+
+ nlldbg("Link failed. MSR: %04x\n", phyreg);
+ return -ETIMEDOUT;
+}
+#endif
+
+/****************************************************************************
+ * Function: lpc17_phyfulldplex
+ *
+ * Description:
+ * Tweak a few things for full duplex.
+ *
+ * Parameters:
+ * phyaddr - The device address where the PHY was discovered
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef LPC17_HAVE_PHY
+static void lpc17_phyfullduplex(uint8_t phyaddr)
+{
+ uint32_t regval;
+
+ /* Set the inter-packet gap */
+
+ lpc17_putreg(21,LPC17_ETH_IPGT);
+
+ /* Set MAC to operate in full duplex mode */
+
+ regval = lpc17_getreg(LPC17_ETH_MAC2);
+ regval |= ETH_MAC2_FD;
+ lpc17_putreg(regval, LPC17_ETH_MAC2);
+
+ /* Select full duplex operation for ethernet controller */
+
+ regval = lpc17_getreg(LPC17_ETH_CMD);
+ regval |= ETH_CMD_FD;
+ lpc17_putreg(regval, LPC17_ETH_CMD);
+}
+#endif
+
+/****************************************************************************
+ * Function: lpc17_phyinit
+ *
+ * Description:
+ * Initialize the PHY
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#ifdef LPC17_HAVE_PHY
+static inline int lpc17_phyinit(struct lpc17_driver_s *priv)
+{
+ unsigned int phyaddr;
+ uint16_t phyreg;
+ uint32_t regval;
+ int ret;
+
+ /* MII configuration: host clocked divided per board.h, no suppress
+ * preambl,e no scan increment.
+ */
+
+ lpc17_putreg(ETH_MCFG_CLKSEL_DIV, LPC17_ETH_MCFG);
+ lpc17_putreg(0, LPC17_ETH_MCMD);
+
+ /* Enter RMII mode and select 100 MBPS support */
+
+ lpc17_putreg(ETH_CMD_RMII, LPC17_ETH_CMD);
+ lpc17_putreg(ETH_SUPP_SPEED, LPC17_ETH_SUPP);
+
+ /* Find PHY Address. Because controller has a pull-up and the
+ * PHY have pull-down resistors on RXD lines some times the PHY
+ * latches different at different addresses.
+ */
+
+ for (phyaddr = 1; phyaddr < 32; phyaddr++)
+ {
+ /* Check if we can see the selected device ID at this
+ * PHY address.
+ */
+
+ phyreg = (unsigned int)lpc17_phyread(phyaddr, MII_PHYID1);
+ if (phyreg == LPC17_PHYID1)
+ {
+ phyreg = lpc17_phyread(phyaddr, MII_PHYID2);
+ if (phyreg == LPC17_PHYID2)
+ {
+ break;
+ }
+ }
+ }
+ nlldbg("phyaddr: %d\n", phyaddr);
+
+ /* Check if the PHY device address was found */
+
+ if (phyaddr > 31)
+ {
+ /* Failed to find PHY at any location */
+
+ return -ENODEV;
+ }
+
+ /* Save the discovered PHY device address */
+
+ priv->lp_phyaddr = phyaddr;
+
+ /* Reset the PHY */
+
+ ret = lpc17_phyreset(phyaddr);
+ if (ret < 0)
+ {
+ return ret;
+ }
+ lpc17_showmii(phyaddr, "After reset");
+
+ /* Check for preamble suppression support */
+
+ phyreg = lpc17_phyread(phyaddr, MII_MSR);
+ if ((phyreg & MII_MSR_MFRAMESUPPRESS) != 0)
+ {
+ /* The PHY supports preamble suppression */
+
+ regval = lpc17_getreg(LPC17_ETH_MCFG);
+ regval |= ETH_MCFG_SUPPRE;
+ lpc17_putreg(regval, LPC17_ETH_MCFG);
+ }
+
+ /* Are we configured to do auto-negotiation? */
+
+#ifdef CONFIG_PHY_AUTONEG
+ /* Setup the Auto-negotiation advertisement: 100 or 10, and HD or FD */
+
+ lpc17_phywrite(phyaddr, MII_ADVERTISE,
+ (MII_ADVERTISE_100BASETXFULL | MII_ADVERTISE_100BASETXHALF |
+ MII_ADVERTISE_10BASETXFULL | MII_ADVERTISE_10BASETXHALF |
+ MII_ADVERTISE_CSMA));
+ ret = lpc17_phyautoneg(phyaddr);
+ if (ret < 0)
+ {
+ return ret;
+ }
+#else
+ /* Set up the fixed PHY configuration */
+
+ ret = lpc17_phyfixed(phyaddr, );
+ if (ret < 0)
+ {
+ return ret;
+ }
+#endif
+
+ /* The link is established */
+
+ lpc17_showmii(phyaddr, "After link established");
+
+ /* Check configuration */
+
+#ifdef CONFIG_PHY_KS8721
+ phyreg = lpc17_phyread(phyaddr, MII_KS8721_10BTCR);
+
+ switch (phyreg & KS8721_10BTCR_MODE_MASK)
+ {
+ case KS8721_10BTCR_MODE_10BTHD: /* 10BASE-T half duplex */
+ nlldbg("10BASE-T half duplex\n");
+ lpc17_putreg(0, LPC17_ETH_SUPP);
+ lpc17_phyfixed(phyaddr, false, false);
+ break;
+ case KS8721_10BTCR_MODE_100BTHD: /* 100BASE-T half duplex */
+ nlldbg("100BASE-T half duplex\n");
+ lpc17_phyfixed(phyaddr, true, false);
+ break;
+ case KS8721_10BTCR_MODE_10BTFD: /* 10BASE-T full duplex */
+ nlldbg("10BASE-T full duplex\n");
+ lpc17_putreg(0, LPC17_ETH_SUPP);
+ lpc17_phyfullduplex(phyaddr);
+ lpc17_phyfixed(phyaddr, false, true);
+ break;
+ case KS8721_10BTCR_MODE_100BTFD: /* 100BASE-T full duplex */
+ nlldbg("100BASE-T full duplex\n");
+ lpc17_phyfullduplex(phyaddr);
+ lpc17_phyfixed(phyaddr, true, true);
+ break;
+ default:
+ lldbg("Unrecognized mode: %04x\n", phyreg);
+ return -ENODEV;
+ }
+#endif
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Function: lpc17_ethreset
+ *
+ * Description:
+ * Configure and reset the Ethernet module, leaving it in a disabled state.
+ *
+ * Parameters:
+ * priv - Reference to the driver state structure
+ *
+ * Returned Value:
+ * OK on success; a negated errno on failure
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static void lpc17_ethreset(struct lpc17_driver_s *priv)
+{
+ irqstate_t flags;
+ uint32_t regval;
+
+#if LPC17_NETHCONTROLLERS > 1
+# error "If multiple interfaces are supported, this function would have to be redesigned"
+#endif
+
+ /* Make sure that clocking is enabled for the Ethernet (and PHY) peripherals */
+
+ flags = irqsave();
+
+ /* Put the Ethernet controller into the reset state */
+
+ /* Wait just a bit. This is a much longer delay than necessary */
+
+ up_mdelay(2);
+
+ /* Then take the Ethernet controller out of the reset state */
+
+ /* Disable all Ethernet controller interrupts */
+
+ /* Clear any pending interrupts (shouldn't be any) */
+
+ irqrestore(flags);
}
/****************************************************************************
@@ -919,10 +1424,14 @@ int lpc17_ethinitialize(int intf)
static inline int lpc17_ethinitialize(int intf)
#endif
{
- struct lpc17_driver_s *priv = &g_ethdrvr[intf];
+ struct lpc17_driver_s *priv;
uint32_t regval;
+ int ret;
int i;
+ DEBUGASSERT(inf < LPC17_NETHCONTROLLERS);
+ priv = &g_ethdrvr[intf];
+
/* Turn on the ethernet MAC clock */
regval = lpc17_getreg(LPC17_SYSCON_PCONP);
@@ -937,33 +1446,50 @@ static inline int lpc17_ethinitialize(int intf)
}
lpc17_showpins();
- /* Attach the IRQ to the driver */
-
- if (irq_attach(LPC17_IRQ_ETH, lpc17_interrupt))
- {
- /* We could not attach the ISR to the the interrupt */
-
- return -EAGAIN;
- }
-
/* Initialize the driver structure */
memset(g_ethdrvr, 0, CONFIG_LPC17_NINTERFACES*sizeof(struct lpc17_driver_s));
- priv->lp_dev.d_ifup = lpc17_ifup; /* I/F down callback */
- priv->lp_dev.d_ifdown = lpc17_ifdown; /* I/F up (new IP address) callback */
- priv->lp_dev.d_txavail = lpc17_txavail; /* New TX data callback */
+ priv->lp_dev.d_ifup = lpc17_ifup; /* I/F down callback */
+ priv->lp_dev.d_ifdown = lpc17_ifdown; /* I/F up (new IP address) callback */
+ priv->lp_dev.d_txavail = lpc17_txavail; /* New TX data callback */
#ifdef CONFIG_NET_IGMP
- priv->lp_dev.d_addmac = lpc17_addmac; /* Add multicast MAC address */
- priv->lp_dev.d_rmmac = lpc17_rmmac; /* Remove multicast MAC address */
+ priv->lp_dev.d_addmac = lpc17_addmac; /* Add multicast MAC address */
+ priv->lp_dev.d_rmmac = lpc17_rmmac; /* Remove multicast MAC address */
+#endif
+ priv->lp_dev.d_private = (void*)priv; /* Used to recover private state from dev */
+
+#if LM3S_NETHCONTROLLERS > 1
+# error "A mechanism to associate base address an IRQ with an interface is needed"
+ priv->lp_base = ??; /* Ethernet controller base address */
+ priv->lp_irq = ??; /* Ethernet controller IRQ number */
#endif
- priv->lp_dev.d_private = (void*)g_ethdrvr; /* Used to recover private state from dev */
/* Create a watchdog for timing polling for and timing of transmisstions */
- priv->lp_txpoll = wd_create(); /* Create periodic poll timer */
- priv->lp_txtimeout = wd_create(); /* Create TX timeout timer */
+ priv->lp_txpoll = wd_create(); /* Create periodic poll timer */
+ priv->lp_txtimeout = wd_create(); /* Create TX timeout timer */
+
+ /* Perform minimal, one-time initialization -- just reset the controller and
+ * leave it disabled. The Ethernet controller will be reset and properly
+ * re-initialized each time lpc17_ifup() is called.
+ */
+
+ lpc17_ethreset(priv);
+ lpc17_ifdown(&priv->lp_dev);
+
+ /* Attach the IRQ to the driver */
+
+#if LM3S_NETHCONTROLLERS > 1
+ ret = irq_attach(priv->irq, lpc17_interrupt);
+#else
+ ret = irq_attach(LPC17_IRQ_ETH, lpc17_interrupt);
+#endif
+ if (ret != 0)
+ {
+ /* We could not attach the ISR to the the interrupt */
- /* Read the MAC address from the hardware into priv->lp_dev.d_mac.ether_addr_octet */
+ return -EAGAIN;
+ }
/* Register the device with the OS so that socket IOCTLs can be performed */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h
index 81b517f54..58533c227 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.h
@@ -185,7 +185,7 @@
#define ETH_MAC2_FD (1 << 0) /* Bit 0: Full duplex */
#define ETH_MAC2_FLC (1 << 1) /* Bit 1: Frame length checking */
-#define ETH_MAC2_HFE (1 << 2) /* Bit 2: Huge fram enable */
+#define ETH_MAC2_HFE (1 << 2) /* Bit 2: Huge frame enable */
#define ETH_MAC2_DCRC (1 << 3) /* Bit 3: Delayed CRC */
#define ETH_MAC2_CRCEN (1 << 4) /* Bit 4: CRC enable */
#define ETH_MAC2_PADCRCEN (1 << 5) /* Bit 5: Pad/CRC enable */
@@ -238,7 +238,7 @@
#define ETH_MCFG_SCANINC (1 << 0) /* Bit 0: Scan increment */
#define ETH_MCFG_SUPPRE (1 << 1) /* Bit 1: Suppress preamble */
-#define ETH_MCFG_CLKSEL_SHIFT (2) /* Bits 2-5:Clock select */
+#define ETH_MCFG_CLKSEL_SHIFT (2) /* Bits 2-5: Clock select */
#define ETH_MCFG_CLKSEL_MASK (15 << ETH_MCFG_CLKSEL_SHIFT)
# define ETH_MCFG_CLKSEL_DIV4 (0 << ETH_MCFG_CLKSEL_SHIFT)
# define ETH_MCFG_CLKSEL_DIV6 (2 << ETH_MCFG_CLKSEL_SHIFT)
@@ -316,7 +316,7 @@
#define ETH_CMD_RXEN (1 << 0) /* Bit 0: Receive enable */
#define ETH_CMD_TXEN (1 << 1) /* Bit 1: Transmit enable */
- /* Bit 2: Reserved */
+ /* Bit 2: Reserved */
#define ETH_CMD_REGRST (1 << 3) /* Bit 3: Reset host registers */
#define ETH_CMD_TXRST (1 << 4) /* Bit 4: Reset transmit datapath */
#define ETH_CMD_RXRST (1 << 5) /* Bit 5: Reset receive datapath */
diff --git a/nuttx/configs/olimex-lpc1766stk/README.txt b/nuttx/configs/olimex-lpc1766stk/README.txt
index ca878488f..aba93f829 100755
--- a/nuttx/configs/olimex-lpc1766stk/README.txt
+++ b/nuttx/configs/olimex-lpc1766stk/README.txt
@@ -601,6 +601,14 @@ Olimex LPC1766-STK Configuration Options
CONFIG_UARTn_PARTIY - 0=no parity, 1=odd parity, 2=even parity
CONFIG_UARTn_2STOP - Two stop bits
+
+ LPC17xx specific PHY/Ethernet device driver settings
+
+ CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
+ CONFIG_PHY_AUTONEG - Enable auto-negotion
+ CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
+ CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
+
LPC17xx USB Configuration
CONFIG_LPC17_USBDEV_FRAME_INTERRUPT
diff --git a/nuttx/configs/olimex-lpc1766stk/include/board.h b/nuttx/configs/olimex-lpc1766stk/include/board.h
index 0ac0466a8..cf25cfc0c 100755
--- a/nuttx/configs/olimex-lpc1766stk/include/board.h
+++ b/nuttx/configs/olimex-lpc1766stk/include/board.h
@@ -122,6 +122,11 @@
#define CONFIG_LP17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
+/* Ethernet configuration */
+
+//#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV44
+#define ETH_MCFG_CLKSEL_DIV ETH_MCFG_CLKSEL_DIV20
+
/* LED definitions ******************************************************************/
/* LED1 LED2 */
diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
index 76902eb0f..fd1e18d78 100755
--- a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
@@ -182,6 +182,19 @@ CONFIG_UART2_2STOP=0
CONFIG_UART3_2STOP=0
#
+# LPC17xx specific PHY/Ethernet device driver settings
+#
+# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
+# CONFIG_PHY_AUTONEG - Enable auto-negotion
+# CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
+# CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
+#
+CONFIG_PHY_KS8721=y
+CONFIG_PHY_AUTONEG=y
+CONFIG_PHY_SPEED100=n
+CONFIG_PHY_FDUPLEX=y
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
index 9d1486d7f..cf612d47c 100755
--- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
@@ -182,6 +182,19 @@ CONFIG_UART2_2STOP=0
CONFIG_UART3_2STOP=0
#
+# LPC17xx specific PHY/Ethernet device driver settings
+#
+# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
+# CONFIG_PHY_AUTONEG - Enable auto-negotion
+# CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
+# CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
+#
+CONFIG_PHY_KS8721=y
+CONFIG_PHY_AUTONEG=y
+CONFIG_PHY_SPEED100=n
+CONFIG_PHY_FDUPLEX=y
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
index 29daca2b6..76fb01198 100755
--- a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
@@ -182,6 +182,19 @@ CONFIG_UART2_2STOP=0
CONFIG_UART3_2STOP=0
#
+# LPC17xx specific PHY/Ethernet device driver settings
+#
+# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
+# CONFIG_PHY_AUTONEG - Enable auto-negotion
+# CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
+# CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
+#
+CONFIG_PHY_KS8721=y
+CONFIG_PHY_AUTONEG=y
+CONFIG_PHY_SPEED100=n
+CONFIG_PHY_FDUPLEX=y
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
index e06fa3a98..7d5f2dd6c 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
@@ -182,6 +182,19 @@ CONFIG_UART2_2STOP=0
CONFIG_UART3_2STOP=0
#
+# LPC17xx specific PHY/Ethernet device driver settings
+#
+# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
+# CONFIG_PHY_AUTONEG - Enable auto-negotion
+# CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
+# CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
+#
+CONFIG_PHY_KS8721=y
+CONFIG_PHY_AUTONEG=y
+CONFIG_PHY_SPEED100=n
+CONFIG_PHY_FDUPLEX=y
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
index d62bfd55c..f1befb446 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
@@ -182,6 +182,19 @@ CONFIG_UART2_2STOP=0
CONFIG_UART3_2STOP=0
#
+# LPC17xx specific PHY/Ethernet device driver settings
+#
+# CONFIG_PHY_KS8721 - Selects Micrel KS8721 PHY
+# CONFIG_PHY_AUTONEG - Enable auto-negotion
+# CONFIG_PHY_SPEED100 - Select 100Mbit vs. 10Mbit speed.
+# CONFIG_PHY_FDUPLEX - Select full (vs. half) duplex
+#
+CONFIG_PHY_KS8721=y
+CONFIG_PHY_AUTONEG=y
+CONFIG_PHY_SPEED100=n
+CONFIG_PHY_FDUPLEX=y
+
+#
# General build options
#
# CONFIG_RRLOAD_BINARY - make the rrload binary format used with
diff --git a/nuttx/include/nuttx/mii.h b/nuttx/include/nuttx/mii.h
index 0fa788588..5b82ac600 100644
--- a/nuttx/include/nuttx/mii.h
+++ b/nuttx/include/nuttx/mii.h
@@ -305,7 +305,7 @@
/* LM3S6918 LED Configuration, address 0x17 */
-#define LM3S_LEDCONFIG_LED0_SHIFT 0 /* Bits 3-0: LED0 Source */
+#define LM3S_LEDCONFIG_LED0_SHIFT (0) /* Bits 3-0: LED0 Source */
#define LM3S_LEDCONFIG_LED0_MASK (0x0f << LM3S_LEDCONFIG_LED0_SHIFT)
#define LM3S_LEDCONFIG_LED0_LINKOK (0 << LM3S_LEDCONFIG_LED0_SHIFT) /* Link OK */
#define LM3S_LEDCONFIG_LED0_RXTX (1 << LM3S_LEDCONFIG_LED0_SHIFT) /* RX or TX activity */
@@ -313,7 +313,7 @@
#define LM3S_LEDCONFIG_LED0_10BASET (6 << LM3S_LEDCONFIG_LED0_SHIFT) /* 10BASE-T mode */
#define LM3S_LEDCONFIG_LED0_FDUPLEX (7 << LM3S_LEDCONFIG_LED0_SHIFT) /* Full duplex */
#define LM3S_LEDCONFIG_LED0_OKRXTX (8 << LM3S_LEDCONFIG_LED0_SHIFT) /* Full duplex */
-#define LM3S_LEDCONFIG_LED1_SHIFT 4 /* Bits 7-4: LED1 Source */
+#define LM3S_LEDCONFIG_LED1_SHIFT (4) /* Bits 7-4: LED1 Source */
#define LM3S_LEDCONFIG_LED1_MASK (0x0f << LM3S_LEDCONFIG_LED1_SHIFT)
#define LM3S_LEDCONFIG_LED1_LINKOK (0 << LM3S_LEDCONFIG_LED1_SHIFT) /* Link OK */
#define LM3S_LEDCONFIG_LED1_RXTX (1 << LM3S_LEDCONFIG_LED1_SHIFT) /* RX or TX activity */
@@ -324,7 +324,7 @@
/* LM3S6918 MDI/MDIX Control, address 0x18 */
-#define LM3S_MDICONTROL_MDIXSD_SHIFT 0 /* Bits 3-0: Auto-Switching Seed */
+#define LM3S_MDICONTROL_MDIXSD_SHIFT (0) /* Bits 3-0: Auto-Switching Seed */
#define LM3S_MDICONTROL_MDIXSD_MASK (0x0f << LM3S_MDICONTROL_MDIXSD_SHIFT)
#define LM3S_MDICONTROL_MDIXCM (1 << 4) /* Bit 4: Auto-Switching Complete */
#define LM3S_MDICONTROL_MDIX (1 << 5) /* Bit 5: Auto-Switching Configuration */