From 5c2ab2b81b0e0e851d73fb49cf21def02931e4b9 Mon Sep 17 00:00:00 2001 From: patacongo Date: Thu, 21 May 2009 00:23:53 +0000 Subject: LM3S ethernet driver development git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1811 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/arch/arm/src/lm3s/lm3s_ethernet.c | 547 ++++++++++++++++++++++++++------ nuttx/arch/arm/src/lm3s/lm3s_ethernet.h | 1 + 2 files changed, 455 insertions(+), 93 deletions(-) (limited to 'nuttx/arch') diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c index b7aab1544..84dadc700 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c +++ b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c @@ -53,12 +53,20 @@ #include #include +#include "up_arch.h" +#include "chip.h" #include "lm3s_internal.h" /**************************************************************************** * Definitions ****************************************************************************/ +#ifdef CONFIG_ARCH_CHIP_LM3S6918 +# define LM3S_NINTERFACES 1 +#else +# error "No Ethernet support for this LM3S chip" +#endif + /* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */ #define LM3S_WDDELAY (1*CLK_TCK) @@ -70,7 +78,7 @@ /* This is a helper pointer for accessing the contents of the Ethernet header */ -#define BUF ((struct uip_eth_hdr *)skel->ld_dev.d_buf) +#define BUF ((struct uip_eth_hdr *)priv->ld_dev.d_buf) /**************************************************************************** * Private Types @@ -82,6 +90,15 @@ struct lm3s_driver_s { + /* The following fields would only be necessary on chips that support + * multiple Ethernet controllers. + */ + +#if LM3S_NINTERFACES > 1 + uint32 ld_base; /* Ethernet controller base address */ + int ld-irq; /* Ethernet controller IRQ */ +#endif + boolean ld_bifup; /* TRUE:ifup FALSE:ifdown */ WDOG_ID ld_txpoll; /* TX poll timer */ WDOG_ID ld_txtimeout; /* TX timeout timer */ @@ -95,21 +112,34 @@ struct lm3s_driver_s * Private Data ****************************************************************************/ -static struct lm3s_driver_s g_lm3sdev; +static struct lm3s_driver_s g_lm3sdev[LM3S_NINTERFACES]; /**************************************************************************** * Private Function Prototypes ****************************************************************************/ +/* Miscellaneous low level helpers */ + +#if LM3S_NINTERFACES > 1 +static uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset); +static void lm3s_ethout(struct lm3s_driver_s *priv, int offset, uint32 value); +#else +static inline uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset); +static inline void lm3s_ethout(struct lm3s_driver_s *priv, int offset, uint32 value); +#endif +static void lm3s_ethreset(struct lm3s_driver_s *priv); +static void lm3s_phywrite(struct lm3s_driver_s *priv, int regaddr, uint16 value); +static uint16 lm3s_phyread(struct lm3s_driver_s *priv, int regaddr); + /* Common TX logic */ -static int lm3s_transmit(struct lm3s_driver_s *skel); +static int lm3s_transmit(struct lm3s_driver_s *priv); static int lm3s_uiptxpoll(struct uip_driver_s *dev); /* Interrupt handling */ -static void lm3s_receive(struct lm3s_driver_s *skel); -static void lm3s_txdone(struct lm3s_driver_s *skel); +static void lm3s_receive(struct lm3s_driver_s *priv); +static void lm3s_txdone(struct lm3s_driver_s *priv); static int lm3s_interrupt(int irq, FAR void *context); /* Watchdog timer expirations */ @@ -127,6 +157,191 @@ static int lm3s_txavail(struct uip_driver_s *dev); * Private Functions ****************************************************************************/ +/**************************************************************************** + * Function: lm3s_ethin + * + * Description: + * Read a register from the Ethernet module + * + * Parameters: + * priv - Reference to the driver state structure + * offset - Byte offset of the register from the ethernet base address + * + * Returned Value: + * Register value + * + ****************************************************************************/ + +#if LM3S_NINTERFACES > 1 +static uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset) +{ + return getreg32(priv->ld_base + offset); +} +#else +static inline uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset) +{ + return getreg32(LM3S_ETHCON_BASE + offset); +} +#endif + +/**************************************************************************** + * Function: lm3s_ethout + * + * Description: + * Write a register to the Ethernet module + * + * Parameters: + * priv - Reference to the driver state structure + * offset - Byte offset of the register from the ethernet base address + * value - The value to write the the Ethernet register + * + * Returned Value: + * None + * + ****************************************************************************/ + +#if LM3S_NINTERFACES > 1 +static void lm3s_ethout(struct lm3s_driver_s *priv, int offset, uint32 value) +{ + putreg32(value, priv->ld_base + offset); +} +#else +static inline void lm3s_ethout(struct lm3s_driver_s *priv, int offset, uint32 value) +{ + putreg32(value, LM3S_ETHCON_BASE + offset); +} +#endif + +/**************************************************************************** + * Function: lm3s_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 lm3s_ethreset(struct lm3s_driver_s *priv) +{ + irqstate_t flags; + uint32 regval; + volatile uint32 delay; + uint32 div; + +#if LM3S_NINTERFACES > 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(); + regval = getreg32(LM3S_SYSCON_RCGC2); + regval |= (SYSCON_RCGC2_EMAC0|SYSCON_RCGC2_EPHY0); + putreg32(regval, LM3S_SYSCON_RCGC2); + nvdbg("RCGC2: %08x\n", regval); + + /* Put the Ethernet controller into the reset state */ + + regval = getreg32(LM3S_SYSCON_SRCR2); + regval |= (SYSCON_SRCR2_EMAC0|SYSCON_SRCR2_EPHY0); + putreg32(regval, LM3S_SYSCON_SRCR2); + + /* Wait just a bit */ + + for (delay = 0; delay < 16; delay++); + + /* Then take the Ethernet controller out of the reset state */ + + regval &= ~(SYSCON_SRCR2_EMAC0|SYSCON_SRCR2_EPHY0); + putreg32(regval, LM3S_SYSCON_SRCR2); + nvdbg("SRCR2: %08x\n", regval); + + /* Enable Port F for Ethernet LEDs: LED0=Bit 3; LED1=Bit 2 */ + +#ifdef CONFIG_LM3S_ETHLEDS + /* Configure the pins for the peripheral function */ + + lm3s_configgpio(GPIO_ETHPHY_LED0 | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD); + lm3s_configgpio(GPIO_ETHPHY_LED1 | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD); +#endif + + /* Disable all Ethernet controller interrupts */ + + regval = lm3s_ethin(priv, LM3S_MAC_IM_OFFSET); + regval &= ~MAC_IM_ALLINTS; + lm3s_ethout(priv, LM3S_MAC_IM_OFFSET, regval); + + /* Clear any pending interrupts (shouldn't be any) */ + + regval = lm3s_ethin(priv, LM3S_MAC_RIS_OFFSET); + lm3s_ethout(priv, LM3S_MAC_IACK_OFFSET, regval); + + /* Set the management clock divider register for access to the PHY + * register set. The MDC clock is divided down from the system clock per: + * + * MCLK_FREQUENCY = SYSCLK_FREQUENCY / (2 * (div + 1)) + * div = (SYSCLK_FREQUENCY / 2 / MCLK_FREQUENCY) - 1 + * + * Where MCLK_FREQUENCY is 2,500,000. We will add 1 to assure the max + * MCLK_FREQUENCY is not exceeded. + */ + + div = SYSCLK_FREQUENCY / 2 / 2500000; + lm3s_ethout(priv, LM3S_MAC_MDV_OFFSET, div); + nvdbg("MDV: %08x\n", div); + irqrestore(flags); +} + +/**************************************************************************** + * Function: lm3s_phywrite + * + * Description: + * Write a 16-bit word to a PHY register + * + * Parameters: + * priv - Reference to the driver state structure + * regaddr - Address of the PHY register to write + * value - The value to write to the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static void lm3s_phywrite(struct lm3s_driver_s *priv, int regaddr, uint16 value) +{ +# warning "Missing Logic" +} + +/**************************************************************************** + * Function: lm3s_phywrite + * + * Description: + * Write a 16-bit word to a PHY register + * + * Parameters: + * priv - Reference to the driver state structure + * regaddr - Address of the PHY register to write + * value - The value to write to the register + * + * Returned Value: + * None + * + ****************************************************************************/ + +static uint16 lm3s_phyread(struct lm3s_driver_s *priv, int regaddr) +{ +# warning "Missing Logic" + return 0; +} + /**************************************************************************** * Function: lm3s_transmit * @@ -135,16 +350,14 @@ static int lm3s_txavail(struct uip_driver_s *dev); * handling or from watchdog based polling. * * Parameters: - * skel - Reference to the driver state structure + * priv - Reference to the driver state structure * * Returned Value: * OK on success; a negated errno on failure * - * Assumptions: - * ****************************************************************************/ -static int lm3s_transmit(struct lm3s_driver_s *skel) +static int lm3s_transmit(struct lm3s_driver_s *priv) { /* Verify that the hardware is ready to send another packet */ #warning "Missing logic" @@ -152,13 +365,13 @@ static int lm3s_transmit(struct lm3s_driver_s *skel) /* Disable Ethernet interrupts */ - /* Send the packet: address=skel->ld_dev.d_buf, length=skel->ld_dev.d_len */ + /* Send the packet: address=priv->ld_dev.d_buf, length=priv->ld_dev.d_len */ /* Restore Ethernet interrupts */ /* Setup the TX timeout watchdog (perhaps restarting the timer) */ - (void)wd_start(skel->ld_txtimeout, LM3S_TXTIMEOUT, lm3s_txtimeout, 1, (uint32)skel); + (void)wd_start(priv->ld_txtimeout, LM3S_TXTIMEOUT, lm3s_txtimeout, 1, (uint32)priv); return OK; } @@ -185,16 +398,16 @@ static int lm3s_transmit(struct lm3s_driver_s *skel) static int lm3s_uiptxpoll(struct uip_driver_s *dev) { - struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private; + struct lm3s_driver_s *priv = (struct lm3s_driver_s *)dev->d_private; /* If the polling resulted in data that should be sent out on the network, * the field d_len is set to a value > 0. */ - if (skel->ld_dev.d_len > 0) + if (priv->ld_dev.d_len > 0) { - uip_arp_out(&skel->ld_dev); - lm3s_transmit(skel); + uip_arp_out(&priv->ld_dev); + lm3s_transmit(priv); /* Check if there is room in the device to hold another packet. If not, * return a non-zero value to terminate the poll. @@ -216,7 +429,7 @@ static int lm3s_uiptxpoll(struct uip_driver_s *dev) * An interrupt was received indicating the availability of a new RX packet * * Parameters: - * skel - Reference to the driver state structure + * priv - Reference to the driver state structure * * Returned Value: * None @@ -225,7 +438,7 @@ static int lm3s_uiptxpoll(struct uip_driver_s *dev) * ****************************************************************************/ -static void lm3s_receive(struct lm3s_driver_s *skel) +static void lm3s_receive(struct lm3s_driver_s *priv) { do { @@ -234,8 +447,8 @@ static void lm3s_receive(struct lm3s_driver_s *skel) /* Check if the packet is a valid size for the uIP buffer configuration */ - /* Copy the data data from the hardware to skel->ld_dev.d_buf. Set - * amount of data in skel->ld_dev.d_len + /* Copy the data data from the hardware to priv->ld_dev.d_buf. Set + * amount of data in priv->ld_dev.d_len */ /* We only accept IP packets of the configured type and ARP packets */ @@ -247,34 +460,33 @@ static void lm3s_receive(struct lm3s_driver_s *skel) #endif { uip_arp_ipin(); - uip_input(&skel->ld_dev); + uip_input(&priv->ld_dev); /* If the above function invocation resulted in data that should be * sent out on the network, the field d_len will set to a value > 0. */ - if (skel->ld_dev.d_len > 0) - { - uip_arp_out(&skel->ld_dev); - lm3s_transmit(skel); - } - } - else if (BUF->type == htons(UIP_ETHTYPE_ARP)) - { - uip_arp_arpin(&skel->ld_dev); - - /* If the above function invocation resulted in data that should be - * sent out on the network, the field d_len will set to a value > 0. - */ - - if (skel->ld_dev.d_len > 0) - { - lm3s_transmit(skel); - } - } - } + if (priv->ld_dev.d_len > 0) + { + uip_arp_out(&priv->ld_dev); + lm3s_transmit(priv); + } + } + else if (BUF->type == htons(UIP_ETHTYPE_ARP)) + { + uip_arp_arpin(&priv->ld_dev); + + /* If the above function invocation resulted in data that should be + * sent out on the network, the field d_len will set to a value > 0. + */ + + if (priv->ld_dev.d_len > 0) + { + lm3s_transmit(priv); + } + } } - while (); /* While there are more packets to be processed */ + while ( /* FIX ME */ TRUE /* FIX ME */); /* While there are more packets to be processed */ } /**************************************************************************** @@ -284,7 +496,7 @@ static void lm3s_receive(struct lm3s_driver_s *skel) * An interrupt was received indicating that the last TX packet(s) is done * * Parameters: - * skel - Reference to the driver state structure + * priv - Reference to the driver state structure * * Returned Value: * None @@ -293,18 +505,18 @@ static void lm3s_receive(struct lm3s_driver_s *skel) * ****************************************************************************/ -static void lm3s_txdone(struct lm3s_driver_s *skel) +static void lm3s_txdone(struct lm3s_driver_s *priv) { /* Check for errors and update statistics */ #warning "Missing logic" /* If no further xmits are pending, then cancel the TX timeout */ - wd_cancel(skel->ld_txtimeout); + wd_cancel(priv->ld_txtimeout); /* Then poll uIP for new XMIT data */ - (void)uip_poll(&skel->ld_dev, lm3s_uiptxpoll); + (void)uip_poll(&priv->ld_dev, lm3s_uiptxpoll); } /**************************************************************************** @@ -326,7 +538,13 @@ static void lm3s_txdone(struct lm3s_driver_s *skel) static int lm3s_interrupt(int irq, FAR void *context) { - register struct lm3s_driver_s *skel = &g_lm3sdev; + register struct lm3s_driver_s *priv; + +#if LM3S_NINTERFACES > 1 +# error "A mechanism to associate and interface with an IRQ is needed" +#else + priv = &g_lm3sdev[0]; +#endif /* Disable Ethernet interrupts */ #warning "Missing logic" @@ -337,11 +555,11 @@ static int lm3s_interrupt(int irq, FAR void *context) /* Check if we received an incoming packet, if so, call lm3s_receive() */ - lm3s_receive(skel); + lm3s_receive(priv); /* Check is a packet transmission just completed. If so, call lm3s_txdone */ - lm3s_txdone(skel); + lm3s_txdone(priv); /* Enable Ethernet interrupts (perhaps excluding the TX done interrupt if * there are no pending transmissions. @@ -370,7 +588,7 @@ static int lm3s_interrupt(int irq, FAR void *context) static void lm3s_txtimeout(int argc, uint32 arg, ...) { - struct lm3s_driver_s *skel = (struct lm3s_driver_s *)arg; + struct lm3s_driver_s *priv = (struct lm3s_driver_s *)arg; /* Increment statistics and dump debug info */ #warning "Missing logic" @@ -379,7 +597,7 @@ static void lm3s_txtimeout(int argc, uint32 arg, ...) /* Then poll uIP for new XMIT data */ - (void)uip_poll(&skel->ld_dev, lm3s_uiptxpoll); + (void)uip_poll(&priv->ld_dev, lm3s_uiptxpoll); } /**************************************************************************** @@ -401,18 +619,18 @@ static void lm3s_txtimeout(int argc, uint32 arg, ...) static void lm3s_polltimer(int argc, uint32 arg, ...) { - struct lm3s_driver_s *skel = (struct lm3s_driver_s *)arg; + struct lm3s_driver_s *priv = (struct lm3s_driver_s *)arg; /* Check if there is room in the send another Tx packet. */ #warning "Missing logic" /* If so, update TCP timing states and poll uIP for new XMIT data */ - (void)uip_timer(&skel->ld_dev, lm3s_uiptxpoll, LM3S_POLLHSEC); + (void)uip_timer(&priv->ld_dev, lm3s_uiptxpoll, LM3S_POLLHSEC); /* Setup the watchdog poll timer again */ - (void)wd_start(skel->ld_txpoll, LM3S_WDDELAY, lm3s_polltimer, 1, arg); + (void)wd_start(priv->ld_txpoll, LM3S_WDDELAY, lm3s_polltimer, 1, arg); } /**************************************************************************** @@ -434,23 +652,123 @@ static void lm3s_polltimer(int argc, uint32 arg, ...) static int lm3s_ifup(struct uip_driver_s *dev) { - struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private; + struct lm3s_driver_s *priv = (struct lm3s_driver_s *)dev->d_private; + irqstate_t flags; + uint32 regval; + uint16 phyreg; ndbg("Bringing up: %d.%d.%d.%d\n", dev->d_ipaddr & 0xff, (dev->d_ipaddr >> 8) & 0xff, (dev->d_ipaddr >> 16) & 0xff, dev->d_ipaddr >> 24 ); - /* Initilize Ethernet interface */ -#warning "Missing logic" + /* Enable and reset the Ethernet controller */ - /* Set and activate a timer process */ + flags = irqsave(); + lm3s_ethreset(priv); + + /* Then configure the Ethernet Controller for normal operation + * + * Setup the transmit control register (Full duplex, TX CRC Auto Generation, + * TX Padding Enabled). + */ + +# warning "These should be configurable items" + regval = lm3s_ethin(priv, LM3S_MAC_TCTL_OFFSET); + regval |= (MAC_TCTL_DUPLEX|MAC_TCTL_CRC|MAC_TCTL_PADEN); + lm3s_ethout(priv, LM3S_MAC_TCTL_OFFSET, regval); + nvdbg("TCTL: %08x\n", regval); + + /* Setup the receive control register (Disable multicast frames, disable + * promiscuous mode, disable bad CRC rejection). >>> These should be configurable items <<< + */ + +# warning "These should be configurable items" + regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET); + regval &= ~(MAC_RCTL_BADCRC | MAC_RCTL_PRMS | MAC_RCTL_AMUL); + lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval); + nvdbg("RCTL: %08x\n", regval); + + /* Setup the time stamp configuration register */ + +#ifndef CONFIG_ARCH_CHIP_LM3S6918 + regval = lm3s_ethin(priv, LM3S_MAC_TS_OFFSET); +#ifdef CONFIG_LM3S_TIMESTAMP + regval |= MAC_TS_EN; +#else + regval &= ~(MAC_TS_EN); +#endif + lm3s_ethout(priv, LM3S_MAC_TS_OFFSET, regval); + nvdbg("TS: %08x\n", regval); +#endif + + /* Wait for the link to come up */ + +# warning "This should use a semaphore and an interrupt" + + ndbg("Waiting for link\n"); + do + { + phyreg = lm3s_phyread(priv, MII_MSR); + } + while ((phyreg & MII_MSR_LINKSTATUS) == 0); + ndbg("Link established\n"); + + /* Reset the receive FIFO */ + + regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET); + regval |= MAC_RCTL_RSTFIFO; + lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval); + + /* Enable the Ethernet receiver */ + + regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET); + regval |= MAC_RCTL_RXEN; + lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval); + + /* Enable the Ethernet transmitter */ - (void)wd_start(skel->ld_txpoll, LM3S_WDDELAY, lm3s_polltimer, 1, (uint32)skel); + regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET); + regval |= MAC_TCTL_TXEN; + lm3s_ethout(priv, LM3S_MAC_TCTL_OFFSET, regval); + + /* Reset the receive FIFO (again) */ + + regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET); + regval |= MAC_RCTL_RSTFIFO; + lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval); /* Enable the Ethernet interrupt */ - skel->ld_bifup = TRUE; - up_enable_irq(CONFIG_LM3S_IRQ); +#if LM3S_NINTERFACES > 1 + up_enable_irq(priv->irq); +#else + up_enable_irq(LM3S_IRQ_ETHCON); +#endif + + /* Enable the Ethernet RX packet receipt interrupt */ + + regval = lm3s_ethin(priv, LM3S_MAC_IM_OFFSET); + regval |= MAC_IM_RXINTM; + lm3s_ethout(priv, LM3S_MAC_IM_OFFSET, regval); + + /* Program the hardware with it's MAC address (for filtering) */ + + regval = (uint32)priv->ld_dev.d_mac.ether_addr_octet[3] << 24 | + (uint32)priv->ld_dev.d_mac.ether_addr_octet[2] << 16 | + (uint32)priv->ld_dev.d_mac.ether_addr_octet[1] << 8 | + (uint32)priv->ld_dev.d_mac.ether_addr_octet[0]; + lm3s_ethout(priv, LM3S_MAC_IA0_OFFSET, regval); + + regval = (uint32)priv->ld_dev.d_mac.ether_addr_octet[5] << 8 | + (uint32)priv->ld_dev.d_mac.ether_addr_octet[4]; + lm3s_ethout(priv, LM3S_MAC_IA1_OFFSET, regval); + + /* Set and activate a timer process */ + + (void)wd_start(priv->ld_txpoll, LM3S_WDDELAY, lm3s_polltimer, 1, (uint32)priv); + + priv->ld_bifup = TRUE; + irqrestore(flags); return OK; } @@ -472,22 +790,26 @@ static int lm3s_ifup(struct uip_driver_s *dev) static int lm3s_ifdown(struct uip_driver_s *dev) { - struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private; + struct lm3s_driver_s *priv = (struct lm3s_driver_s *)dev->d_private; irqstate_t flags; /* Disable the Ethernet interrupt */ flags = irqsave(); - up_disable_irq(CONFIG_LM3S_IRQ); +#if LM3S_NINTERFACES > 1 + up_disable_irq(priv->irq); +#else + up_disable_irq(LM3S_IRQ_ETHCON); +#endif /* Cancel the TX poll timer and TX timeout timers */ - wd_cancel(skel->ld_txpoll); - wd_cancel(skel->ld_txtimeout); + wd_cancel(priv->ld_txpoll); + wd_cancel(priv->ld_txtimeout); /* Reset the device */ - skel->ld_bifup = FALSE; + priv->ld_bifup = FALSE; irqrestore(flags); return OK; } @@ -513,21 +835,21 @@ static int lm3s_ifdown(struct uip_driver_s *dev) static int lm3s_txavail(struct uip_driver_s *dev) { - struct lm3s_driver_s *skel = (struct lm3s_driver_s *)dev->d_private; + struct lm3s_driver_s *priv = (struct lm3s_driver_s *)dev->d_private; irqstate_t flags; flags = irqsave(); /* Ignore the notification if the interface is not yet up */ - if (skel->ld_bifup) + if (priv->ld_bifup) { /* Check if there is room in the hardware to hold another outgoing packet. */ #warning "Missing logic" /* If so, then poll uIP for new XMIT data */ - (void)uip_poll(&skel->ld_dev, lm3s_uiptxpoll); + (void)uip_poll(&priv->ld_dev, lm3s_uiptxpoll); } irqrestore(flags); @@ -542,7 +864,7 @@ static int lm3s_txavail(struct uip_driver_s *dev) * Function: lm3s_initialize * * Description: - * Initialize the Ethernet driver + * Initialize the Ethernet driver for one interface * * Parameters: * None @@ -556,51 +878,90 @@ static int lm3s_txavail(struct uip_driver_s *dev) /* Initialize the Ethernet controller and driver */ -int lm3s_initialize(void) +#if LM3S_NINTERFACES > 1 +int lm3s_initialize(int intf) +#else +static inline int lm3s_initialize(int intf) +#endif { + struct lm3s_driver_s *priv = &g_lm3sdev[intf]; + int ret; + /* Check if the Ethernet module is present */ +#if LM3S_NINTERFACES > 1 +# error "This debug check only works with one interface" +#else DEBUGASSERT((getreg32(LM3S_SYSCON_DC4) & (SYSCON_DC4_EMAC0|SYSCON_DC4_EPHY0)) == (SYSCON_DC4_EMAC0|SYSCON_DC4_EPHY0)); +#endif + DEBUGASSERT((unsigned)intf < LM3S_NINTERFACES); - /* Enable Port F for Ethernet LEDs: LED0=Bit 3; LED1=Bit 2 */ + /* Initialize the driver structure */ -#ifdef CONFIG_LM3S_ETHLEDS - /* Configure the pins for the peripheral function */ + memset(priv, 0, sizeof(struct lm3s_driver_s)); + priv->ld_dev.d_ifup = lm3s_ifup; /* I/F down callback */ + priv->ld_dev.d_ifdown = lm3s_ifdown; /* I/F up (new IP address) callback */ + priv->ld_dev.d_txavail = lm3s_txavail; /* New TX data callback */ + priv->ld_dev.d_private = (void*)&g_lm3sdev[0]; /* Used to recover private state from dev */ - lm3s_configgpio(GPIO_ETHPHY_LED0 | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD); - lm3s_configgpio(GPIO_ETHPHY_LED1 | GPIO_STRENGTH_2MA | GPIO_PADTYPE_STD); + /* Create a watchdog for timing polling for and timing of transmisstions */ + +#if LM3S_NINTERFACES > 1 +# error "A mechanism to associate base address an IRQ with an interface is needed" + priv->ld_base = ??; /* Ethernet controller base address */ + priv->ld_irq = ??; /* Ethernet controller IRQ number */ #endif + priv->ld_txpoll = wd_create(); /* Create periodic poll timer */ + priv->ld_txtimeout = wd_create(); /* Create TX timeout timer */ -#warning "Missing logic" + /* If the board can provide us with a MAC address, get the address + * from the board now. The MAC will not be applied until lm3s_ifup() + * is caleld (and the MAC can be overwritten with a netdev ioctl call). + */ + +#ifdef CONFIG_LM3S_BOARDMAC + lm3s_ethernetmac(&priv->ld_dev.d_mac); +#endif + + /* 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 lm3s_ifup() is called. + */ + + lm3s_ethreset(priv); /* Attach the IRQ to the driver */ - if (irq_attach(CONFIG_LM3S_IRQ, lm3s_interrupt)) +#if LM3S_NINTERFACES > 1 + ret = irq_attach(priv->irq, lm3s_interrupt); +#else + ret = irq_attach(LM3S_IRQ_ETHCON, lm3s_interrupt); +#endif + if (ret != 0) { - /* We could not attach the ISR to the ISR */ + /* We could not attach the ISR to the IRQ */ return -EAGAIN; } - /* Initialize the driver structure */ - - memset(g_lm3sdev, 0, sizeof(struct lm3s_driver_s)); - g_lm3sdev.ld_dev.d_ifup = lm3s_ifup; /* I/F down callback */ - g_lm3sdev.ld_dev.d_ifdown = lm3s_ifdown; /* I/F up (new IP address) callback */ - g_lm3sdev.ld_dev.d_txavail = lm3s_txavail; /* New TX data callback */ - g_lm3sdev.ld_dev.d_private = (void*)g_lm3sdev; /* Used to recover private state from dev */ - - /* Create a watchdog for timing polling for and timing of transmisstions */ + /* Register the device with the OS so that socket IOCTLs can be performed */ - g_lm3sdev.ld_txpoll = wd_create(); /* Create periodic poll timer */ - g_lm3sdev.ld_txtimeout = wd_create(); /* Create TX timeout timer */ + (void)netdev_register(&priv->ld_dev); + return OK; +} - /* Read the MAC address from the hardware into g_lm3sdev.ld_dev.d_mac.ether_addr_octet */ - /* Register the device with the OS so that socket IOCTLs can be performed */ +/************************************************************************************ + * Name: up_netinitialize + * + * Description: + * Initialize the first network interface + * + ************************************************************************************/ - (void)netdev_register(&g_lm3sdev.ld_dev); - return OK; +void up_netinitialize(void) +{ + (void)lm3s_initialize(0); } #endif /* CONFIG_NET && CONFIG_LM3S_ETHERNET */ diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h index c479c593a..ec32fb029 100644 --- a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h +++ b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.h @@ -139,6 +139,7 @@ #define MAC_IM_RXERM (1 << 4) /* Bit 4: Mask Receive Error */ #define MAC_IM_MDINTM (1 << 5) /* Bit 5: Mask MII Transaction Complete */ #define MAC_IM_PHYINTM (1 << 6) /* Bit 6: Mask PHY Interrupt */ +#define MAC_IM_ALLINTS 0x7f /* Ethernet MAC Receive Control (MACRCTL), offset 0x008 */ -- cgit v1.2.3