summaryrefslogtreecommitdiff
path: root/nuttx/arch/mips/src/pic32mx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-17 00:00:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-17 00:00:25 +0000
commit890c7e343d820612308ec3c38a8e6037e7dc8695 (patch)
tree242fe7daa8a1b11275ac16b9afe1d7a1a2f7812d /nuttx/arch/mips/src/pic32mx
parent331c8f43eca498006f83c7a6e3b80ade63982b62 (diff)
downloadpx4-nuttx-890c7e343d820612308ec3c38a8e6037e7dc8695.tar.gz
px4-nuttx-890c7e343d820612308ec3c38a8e6037e7dc8695.tar.bz2
px4-nuttx-890c7e343d820612308ec3c38a8e6037e7dc8695.zip
More PIC32 Ethernet stuff (still incomplete)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4305 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/mips/src/pic32mx')
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c483
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h36
2 files changed, 340 insertions, 179 deletions
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
index 4d5867242..16232ca5c 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
@@ -98,6 +98,12 @@
# define CONFIG_PIC32MX_NINTERFACES 1
#endif
+/* CONFIG_NET_MULTIBUFFER is required */
+
+#ifndef CONFIG_NET_MULTIBUFFER
+# error "CONFIG_NET_MULTIBUFFER=y is required"
+#endif
+
/* If IGMP is enabled, then accept multi-cast frames. */
#if defined(CONFIG_NET_IGMP) && !defined(CONFIG_NET_MULTICAST)
@@ -112,6 +118,20 @@
# define CONFIG_NET_PRIORITY NVIC_SYSH_PRIORITY_MAX
#endif
+/* Use defaults if the number of discriptors is not provided */
+
+#ifndef CONFIG_NET_NTXDESC
+# define CONFIG_NET_NTXDESC 2
+#endif
+
+#ifndef CONFIG_NET_NRXDESC
+# define CONFIG_NET_NRXDESC 4
+#endif
+
+/* The number of buffers will, then, be one for each descriptor plus one extra */
+
+#define PIC32MX_NBUFFERS (CONFIG_NET_NRXDESC + CONFIG_NET_NTXDESC + 1)
+
/* Debug Configuration *****************************************************/
/* Register debug -- can only happen of CONFIG_DEBUG is selected */
@@ -270,21 +290,23 @@ struct pic32mx_driver_s
*/
#if CONFIG_PIC32MX_NINTERFACES > 1
- uint32_t pd_base; /* Ethernet controller base address */
- int pd_irq; /* Ethernet controller IRQ vector number */
- int pd_irqsrc; /* Ethernet controller IRQ source number */
+ uint32_t pd_base; /* Ethernet controller base address */
+ int pd_irq; /* Ethernet controller IRQ vector number */
+ int pd_irqsrc; /* Ethernet controller IRQ source number */
#endif
- bool pd_ifup; /* true:ifup false:ifdown */
- bool pd_mode; /* speed/duplex */
- bool pd_txpending; /* There is a pending Tx in pd_dev */
+ bool pd_ifup; /* true:ifup false:ifdown */
+ bool pd_mode; /* speed/duplex */
+ bool pd_txpending; /* There is a pending Tx in pd_dev */
#ifdef PIC32MX_HAVE_PHY
- uint8_t pd_phyaddr; /* PHY device address */
+ uint8_t pd_phyaddr; /* PHY device address */
#endif
- uint32_t pd_inten; /* Shadow copy of INTEN register */
- WDOG_ID pd_txpoll; /* TX poll timer */
- WDOG_ID pd_txtimeout; /* TX timeout timer */
-
+ uint32_t pd_inten; /* Shadow copy of INTEN register */
+ WDOG_ID pd_txpoll; /* TX poll timer */
+ WDOG_ID pd_txtimeout; /* TX timeout timer */
+
+ sq_queue_t pd_freebuffers; /* The free buffer list */
+
#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
struct pic32mx_statistics_s pd_stat;
#endif
@@ -292,6 +314,12 @@ struct pic32mx_driver_s
/* This holds the information visible to uIP/NuttX */
struct uip_driver_s pd_dev; /* Interface understood by uIP */
+
+ /* Descriptors and packet buffers */
+
+ struct pic32mx_rxdesc_s pd_rxdesc[CONFIG_NET_NRXDESC];
+ struct pic32mx_txdesc_s pd_txdesc[CONFIG_NET_NTXDESC];
+ uint8_t pd_buffers[PIC32MX_NBUFFERS * CONFIG_NET_BUFSIZE];
};
/****************************************************************************
@@ -318,12 +346,16 @@ static void pic32mx_putreg(uint32_t val, uint32_t addr);
# define pic32mx_putreg(val,addr) putreg32(val,addr)
#endif
-/* Descriptor management */
+/* Buffer and descriptor management */
+
+static inline void pic32mx_bufferinit(struct pic32mx_driver_s *priv);
+static uint8_t *pic32mx_allocbuffer(struct pic32mx_driver_s *priv);
+static void pic32mx_freebuffer(struct pic32mx_driver_s *priv, uint8_t *buffer);
static inline void pic32mx_txdescinit(struct pic32mx_driver_s *priv);
static inline void pic32mx_rxdescinit(struct pic32mx_driver_s *priv);
-static uint32_t *pic32mx_txdesc(struct pic32mx_driver_s *priv);
-static uint32_t *pic32mx_rxdesc(struct pic32mx_driver_s *priv);
+static struct pic32mx_txdesc_s *pic32mx_txdesc(struct pic32mx_driver_s *priv);
+static struct pic32mx_rxdesc_s *pic32mx_rxdesc(struct pic32mx_driver_s *priv);
/* Common TX logic */
@@ -506,6 +538,70 @@ static void pic32mx_putreg(uint32_t val, uint32_t addr)
#endif
/****************************************************************************
+ * Function: pic32mx_bufferinit
+ *
+ * Description:
+ * Initialize the buffers by placing them all in a free list
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static inline void pic32mx_bufferinit(struct pic32mx_driver_s *priv)
+{
+ uint8_t *buffer;
+ int i;
+
+ for (i = 0, buffer = priv->pd_buffers; i < PIC32MX_NBUFFERS; i++)
+ {
+ sq_addlast((sq_entry_t*)buffer, &priv->pd_freebuffers);
+ buffer += CONFIG_NET_BUFSIZE;
+ }
+}
+
+/****************************************************************************
+ * Function: pic32mx_allocbuffer
+ *
+ * Description:
+ * Allocate one buffer by removing it from the free list
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * Pointer to the allocated buffer (or NULL on failure)
+ *
+ ****************************************************************************/
+
+static uint8_t *pic32mx_allocbuffer(struct pic32mx_driver_s *priv)
+{
+ return (uint8_t*)sq_remfirst(&priv->pd_freebuffers);
+}
+
+/****************************************************************************
+ * Function: pic32mx_freebuffer
+ *
+ * Description:
+ * Free one buffer by returning it to the free list
+ *
+ * Parameters:
+ * priv - Pointer to EMAC device driver structure
+ *
+ * Returned Value:
+ * Pointer to the allocated buffer (or NULL on failure)
+ *
+ ****************************************************************************/
+
+static void pic32mx_freebuffer(struct pic32mx_driver_s *priv, uint8_t *buffer)
+{
+ sq_addlast((sq_entry_t*)buffer, &priv->pd_freebuffers);
+}
+
+/****************************************************************************
* Function: pic32mx_txdescinit
*
* Description:
@@ -515,9 +611,7 @@ static void pic32mx_putreg(uint32_t val, uint32_t addr)
* priv - Pointer to EMAC device driver structure
*
* Returned Value:
- * None directory.
- * As a side-effect, it will initialize priv->pd_phyaddr and
- * priv->pd_phymode.
+ * None
*
* Assumptions:
*
@@ -525,34 +619,32 @@ static void pic32mx_putreg(uint32_t val, uint32_t addr)
static inline void pic32mx_txdescinit(struct pic32mx_driver_s *priv)
{
- uint32_t *txdesc;
- uint32_t pktaddr;
+ struct pic32mx_txdesc_s *txdesc;
int i;
/* Assign a buffer to each TX descriptor. For now, just mark each TX
* descriptor as owned by softare andnot linked.
*/
- txdesc = (uint32_t*)PIC32MX_TXDESC_BASE;
- pktaddr = PIC32MX_TXBUFFER_BASE;
-
for (i = 0; i < CONFIG_NET_NTXDESC; i++)
{
- txdesc[TXDESC_STATUS] = TXDESC_STATUS_SOWN;
- txdesc[TXDESC_ADDRESS] = PHYS_ADDR(pktaddr);
- txdesc[TXDESC_TSV1] = 0;
- txdesc[TXDESC_TSV2] = 0;
- txdesc[TXDESC_NEXTED] = 0;
-
- txdesc += TXDESC_SIZE;
- pktaddr += PIC32MX_MAXPACKET_SIZE;
+ txdesc = &priv->pd_txdesc[i];
+ txdesc->status = TXDESC_STATUS_SOWN;
+ txdesc->address = 0;
+ txdesc->tsv1 = 0;
+ txdesc->tsv2 = 0;
+ txdesc->nexted = (uint32_t)&priv->pd_txdesc[i+1];
}
+ /* Terminate the last entry with a null NEXTED pointer */
+
+ txdesc[CONFIG_NET_NTXDESC-1].nexted = 0;
+
/* Update the ETHTXST register with the physical address of the head of
* the TX descriptors list.
*/
- pic32mx_putreg(PHYS_ADDR(PIC32MX_TXDESC_BASE), PIC32MX_ETH_TXST);
+ pic32mx_putreg(PHYS_ADDR(priv->pd_txdesc), PIC32MX_ETH_TXST);
}
/****************************************************************************
@@ -565,9 +657,7 @@ static inline void pic32mx_txdescinit(struct pic32mx_driver_s *priv)
* priv - Pointer to EMAC device driver structure
*
* Returned Value:
- * None directory.
- * As a side-effect, it will initialize priv->pd_phyaddr and
- * priv->pd_phymode.
+ * None
*
* Assumptions:
*
@@ -575,8 +665,7 @@ static inline void pic32mx_txdescinit(struct pic32mx_driver_s *priv)
static inline void pic32mx_rxdescinit(struct pic32mx_driver_s *priv)
{
- uint32_t *rxdesc;
- uint32_t pktaddr;
+ struct pic32mx_rxdesc_s *rxdesc;
int i;
/* Prepare a list of RX descriptors populated with valid buffers for
@@ -586,32 +675,30 @@ static inline void pic32mx_rxdescinit(struct pic32mx_driver_s *priv)
* corresponding RX buffer.
*/
- rxdesc = (uint32_t*)PIC32MX_RXDESC_BASE;
- pktaddr = PIC32MX_RXBUFFER_BASE;
+ rxdesc = priv->pd_rxdesc;
for (i = 0; i < (CONFIG_NET_NRXDESC-1); i++)
{
- rxdesc[RXDESC_STATUS] = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
- rxdesc[RXDESC_ADDRESS] = PHYS_ADDR(pktaddr);
- rxdesc[RXDESC_RSV1] = 0;
- rxdesc[RXDESC_RSV2] = 0;
- rxdesc[RXDESC_NEXTED] = rxdesc + 5;
-
- rxdesc += RXDESC_SIZE;
- pktaddr += PIC32MX_MAXPACKET_SIZE;
+ rxdesc = &priv->pd_rxdesc[i];
+ rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
+ rxdesc->address = PHYS_ADDR(pic32mx_allocbuffer(priv));
+ rxdesc->rsv1 = 0;
+ rxdesc->rsv2 = 0;
+ rxdesc->nexted = (uint32_t)&priv->pd_rxdesc[i+1];
}
- rxdesc[RXDESC_STATUS] = RXDESC_STATUS_EOWN;
- rxdesc[RXDESC_ADDRESS] = PHYS_ADDR(pktaddr);
- rxdesc[RXDESC_RSV1] = 0;
- rxdesc[RXDESC_RSV2] = 0;
- rxdesc[RXDESC_NEXTED] = 0;
+ rxdesc = &priv->pd_rxdesc[CONFIG_NET_NRXDESC-1];
+ rxdesc->status = RXDESC_STATUS_EOWN;
+ rxdesc->address = PHYS_ADDR(pic32mx_allocbuffer(priv));
+ rxdesc->rsv1 = 0;
+ rxdesc->rsv2 = 0;
+ rxdesc->nexted = 0;
/* Update the ETHRXST register with the physical address of the head of the
* RX descriptors list.
*/
- pic32mx_putreg(PHYS_ADDR(PIC32MX_RXDESC_BASE), PIC32MX_ETH_RXST);
+ pic32mx_putreg(PHYS_ADDR(priv->pd_rxdesc), PIC32MX_ETH_RXST);
}
/****************************************************************************
@@ -633,28 +720,27 @@ static inline void pic32mx_rxdescinit(struct pic32mx_driver_s *priv)
*
****************************************************************************/
-static uint32_t pic32mx_txdesc(struct pic32mx_driver_s *priv)
+static struct pic32mx_txdesc_s *pic32mx_txdesc(struct pic32mx_driver_s *priv)
{
- uint32_t *txdesc;
+ struct pic32mx_txdesc_s *txdesc;
+ int i;
/* Inspect the list of TX descriptors to see if the EOWN bit is cleared. If it
* is, this descriptor is now under software control and the message was
* transmitted.
*/
- txdesc = (uint32_t*)PIC32MX_TXDESC_BASE;
-
for (i = 0; i < CONFIG_NET_NTXDESC; i++)
{
/* Check if software owns this descriptor */
- if ((txdesc[TXDESC_STATUS] & TXDESC_STATUS_EOWN) == 0)
+ txdesc = &priv->pd_txdesc[i];
+ if ((txdesc->status & TXDESC_STATUS_EOWN) == 0)
{
/* Yes.. return a pointer to the desciptor */
return txdesc;
}
- txdesc += TXDESC_SIZE;
}
/* All descriptors are owned by the Ethernet controller.. return NULL */
@@ -681,9 +767,10 @@ static uint32_t pic32mx_txdesc(struct pic32mx_driver_s *priv)
*
****************************************************************************/
-static uint32_t *pic32mx_rxdesc(struct pic32mx_driver_s *priv)
+static struct pic32mx_rxdesc_s *pic32mx_rxdesc(struct pic32mx_driver_s *priv)
{
- uint32_t *rxdesc;
+ struct pic32mx_rxdesc_s *rxdesc;
+ int i;
/* Inspect the list of RX descriptors to see if the EOWN bit is cleared.
* If it is, this descriptor is now under software control and a message was
@@ -691,19 +778,17 @@ static uint32_t *pic32mx_rxdesc(struct pic32mx_driver_s *priv)
* RSV and PKT_CHECKSUM to get the message characteristics.
*/
- rxdesc = (uint32_t*)PIC32MX_RXDESC_BASE;
-
for (i = 0; i < CONFIG_NET_NRXDESC; i++)
{
/* Check if software owns this descriptor */
- if ((rxdesc[RXDESC_STATUS] & RXDESC_STATUS_EOWN) == 0)
+ rxdesc = &priv->pd_rxdesc[i];
+ if ((rxdesc->status & RXDESC_STATUS_EOWN) == 0)
{
/* Yes.. return a pointer to the desciptor */
return rxdesc;
}
- rxdesc += RXDESC_SIZE;
}
/* All descriptors are owned by the Ethernet controller.. return NULL */
@@ -733,21 +818,19 @@ static uint32_t *pic32mx_rxdesc(struct pic32mx_driver_s *priv)
static int pic32mx_transmit(struct pic32mx_driver_s *priv)
{
- uint32_t *txdesc;
- void *txbuffer;
+ struct pic32mx_txdesc_s *txdesc;
/* Verify that the hardware is ready to send another packet. If we get
* here, then we are committed to sending a packet; Higher level logic
* must have assured that there is no transmission in progress.
*/
- DEBUGASSERT(pic32mx_txdesc(priv) != NULL);
+ DEBUGASSERT(priv->pd_dev.d_buf && priv->pd_dev.d_len < CONFIG_NET_BUFSIZE);
/* Increment statistics and dump the packet *if so configured) */
EMAC_STAT(priv, tx_packets);
- pic32mx_dumppacket("Transmit packet",
- priv->pd_dev.d_buf, priv->pd_dev.d_len);
+ pic32mx_dumppacket("Transmit packet", priv->pd_dev.d_buf, priv->pd_dev.d_len);
/* In order to transmit a message:
*
@@ -758,59 +841,37 @@ static int pic32mx_transmit(struct pic32mx_driver_s *priv)
* the message.
*/
- /* Update the necessary number of TX descriptors, starting with the head of
- * the list, by setting the DATA_BUFFER_ADDRESS to be the physical address of
- * the corresponding buffer in the message to be transmitted.
- */
-#warning "Missing logic"
-
- /* Update BYTE_COUNT for each descriptor with the number of bytes contained in
- * each buffer.
+ /* Find the first available TX descriptor. We are guaranteed that is will
+ * not fail by upstream logic that assures that a TX packet is available
+ * before polling uIP.
*/
-#warning "Missing logic"
-
- /* Set EOWN = 1 for each descriptor that belongs to the packet. */
-#warning "Missing logic"
-
- /* Use SOP and EOP to specify that the message uses one or more TX descriptors. */
-#warning "Missing logic"
-
- /* Enable the transmission of the message, set the TXRTS bit (ETHCON1:9). */
-#warning "Missing logic"
+ txdesc = pic32mx_txdesc(priv);
+ DEBUGASSERT(txdesc != NULL);
- /* Inspect the list of TX descriptors to see if the EOWN bit is cleared. If it
- * is, this descriptor is now under software control and the message was
- * transmitted. Use TSV to check for the transmission result.
+ /* Remove the transmit buffer from the device structure and assign it to
+ * the TX descriptor.
*/
-#warning "Missing logic"
- txdesc = (uint32_t*)NULL;
-#warning "The rest is residual LPC17xx logic that needs to be removed"
+ txdesc->address = PHYS_ADDR(priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
- /* Get the packet address from the descriptor and set the descriptor control
- * fields.
+ /* Set the BYTE_COUNT for in the TX descriptor with the number of bytes
+ * contained in the buffer.
*/
- txbuffer = (void*)*txdesc++;
- *txdesc = TXDESC_CONTROL_INT | TXDESC_CONTROL_LAST | TXDESC_CONTROL_CRC |
- (priv->pd_dev.d_len - 1);
+ txdesc->tsv2 &= TXDESC_TSV2_BYTECOUNT_MASK;
+ txdesc->tsv2 |= ((uint32_t)priv->pd_dev.d_len << TXDESC_TSV2_BYTECOUNT_SHIFT);
+ priv->pd_dev.d_len = 0;
- /* Copy the packet data into the Tx buffer assignd to this descriptor. It
- * should fit because each packet buffer is the MTU size and breaking up
- * largerTCP messasges is handled by higher level logic. The hardware
- * does, however, support breaking up larger messages into many fragments,
- * however, that capability is not exploited here.
- *
- * This would be a great performance improvement: Remove the buffer from
- * the pd_dev structure and replace it a pointer directly into the EMAC
- * DMA memory. This could eliminate the following, costly memcpy.
+ /* Set EOWN = 1 to indicate that the packet belongs to Ethernet and set both
+ * SOP and EOP to indicate that the packet both begins and ends with this
+ * frame.
*/
- DEBUGASSERT(priv->pd_dev.d_len <= PIC32MX_MAXPACKET_SIZE);
- memcpy(txbuffer, priv->pd_dev.d_buf, priv->pd_dev.d_len);
+ txdesc->status |= (TXDESC_STATUS_EOWN | TXDESC_STATUS_EOP | TXDESC_STATUS_SOP);
- /* Make sure that the TX transfer is enabled */
+ /* Enable the transmission of the message by setting the TXRTS bit (ETHCON1:9). */
pic32mx_putreg(ETH_CON1_TXRTS | ETH_CON1_ON, PIC32MX_ETH_CON1SET);
@@ -872,9 +933,9 @@ static int pic32mx_uiptxpoll(struct uip_driver_s *dev)
* return any non-zero value to terminate the poll.
*/
- if (pic32mx_txdesc(priv) == NULL)
+ if (pic32mx_txdesc(priv) == NULL || sq_empty(&priv->pd_freebuffers))
{
- /* There are no more TX descriptors available.. stop the poll */
+ /* There are no more TX descriptors/buffers available.. stop the poll */
return -EAGAIN;
}
@@ -913,7 +974,7 @@ static int pic32mx_uiptxpoll(struct uip_driver_s *dev)
static void pic32mx_response(struct pic32mx_driver_s *priv)
{
- uint32_t *txdesc;
+ struct pic32mx_txdesc_s *txdesc;
/* Check if there is room in the device to hold another packet. */
@@ -956,15 +1017,12 @@ static void pic32mx_response(struct pic32mx_driver_s *priv)
static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
{
- uint32_t *rxdesc;
- bool fragment;
- unsigned int pktlen;
+ struct pic32mx_rxdesc_s *rxdesc;
/* Loop while there are incoming packets to be processed, that is, while
* the producer index is not equal to the consumer index.
*/
- fragment = false;
for (;;)
{
/* Check if any RX descriptor has the EOWN bit cleared meaning that the
@@ -986,70 +1044,56 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
EMAC_STAT(priv, rx_packets);
- /* Use SOP and EOP to extract the message, use BYTE_COUNT, RXF_RSV,
- * RSV and PKT_CHECKSUM to get the message characteristics.
- */
-#warning "Missing logic"
-
/* Get the packet length */
- pktlen = (rxdesc[RXDESC_RSV1] & RXDESC_RSV1_BYTECOUNT_MASK) >> RXDESC_RSV1_BYTECOUNT_SHIFT;
+ priv->pd_dev.d_len = (rxdesc->rsv1 & RXDESC_RSV1_BYTECOUNT_MASK) >> RXDESC_RSV1_BYTECOUNT_SHIFT;
- /* Check for errors. NOTE: The DMA engine reports bogus length errors,
- * making this a pretty useless check.
- */
+ /* Check for errors */
-#warning "The rest is residual LPC17xx logic that needs to be removed"
- if ((*rxdesc & RXSTAT_INFO_ERROR) != 0)
+ if ((rxdesc->status & RXDESC_RSV1_OK) == 0)
{
- nlldbg("Error. rxdesc: %08x\n", *rxdesc);
+ nlldbg("Error. rxdesc: %08x\n", rxdesc->status);
EMAC_STAT(priv, rx_pkterr);
}
- /* If the pktlen is greater then the buffer, then we cannot accept
+ /* If the packet length is greater then the buffer, then we cannot accept
* the packet. Also, since the DMA packet buffers are set up to
* be the same size as our max packet size, any fragments also
* imply that the packet is too big.
*/
- /* else */ if (pktlen > CONFIG_NET_BUFSIZE + CONFIG_NET_GUARDSIZE)
+ else if (priv->pd_dev.d_len > CONFIG_NET_BUFSIZE)
{
- nlldbg("Too big. pktlen: %d rxdesc: %08x\n", pktlen, *rxdesc);
+ nlldbg("Too big. packet length: %d rxdesc: %08x\n", priv->pd_dev.d_len, rxdesc->status);
EMAC_STAT(priv, rx_pktsize);
}
- else if ((*rxdesc & RXSTAT_INFO_LASTFLAG) == 0)
- {
- nlldbg("Fragment. pktlen: %d rxdesc: %08x\n", pktlen, *rxdesc);
- EMAC_STAT(priv, rx_fragment);
- fragment = true;
- }
- else if (fragment)
+
+ /* We don't have any logic here for reassembling packets from fragments. */
+
+ else if ((rxdesc->status & (RXDESC_STATUS_EOP|RXDESC_STATUS_SOP)) != (RXDESC_STATUS_EOP|RXDESC_STATUS_SOP))
{
- nlldbg("Last fragment. pktlen: %d rxdesc: %08x\n", pktlen, *rxdesc);
+ nlldbg("Fragment. packet length: %d rxdesc: %08x\n", priv->pd_dev.d_len, rxdesc->status);
EMAC_STAT(priv, rx_fragment);
- fragment = false;
}
else
{
- uint32_t *rxdesc;
- void *rxbuffer;
+ uint8_t *rxbuffer;
/* Get the Rx buffer address from the Rx descriptor */
- rxdesc = (uint32_t*)NULL; // ###### FOR NOW
- rxbuffer = (void*)*rxdesc;
-
- /* Copy the data data from the EMAC DMA RAM to priv->pd_dev.d_buf.
- * Set amount of data in priv->pd_dev.d_len
- *
- * Here would be a great performance improvement: Remove the
- * buffer from the pd_dev structure and replace it with a pointer
- * directly into the EMAC DMA memory. This could eliminate the
- * following, costly memcpy.
- */
+ priv->pd_dev.d_buf = (uint8_t*)VIRT_ADDR(rxdesc->address);
+
+ /* Replace the buffer in the RX descriptor with a new one */
+
+ rxbuffer = pic32mx_allocbuffer(priv);
+ DEBUGASSERT(rxbuffer != NULL);
+ rxdesc->address = PHYS_ADDR(rxbuffer);
+
+ /* And give the RX descriptor back to the hardware */
- memcpy(priv->pd_dev.d_buf, rxbuffer, pktlen);
- priv->pd_dev.d_len = pktlen;
+ rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
+ rxdesc->rsv1 = 0;
+ rxdesc->rsv1 = 0;
pic32mx_dumppacket("Received packet",
priv->pd_dev.d_buf, priv->pd_dev.d_len);
@@ -1100,6 +1144,15 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
EMAC_STAT(priv, rx_dropped);
}
+
+ /* Discard any buffers still attached to the device structure */
+
+ priv->pd_dev.d_len = 0;
+ if (priv->pd_dev.d_buf)
+ {
+ pic32mx_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
}
}
}
@@ -1123,6 +1176,9 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
static void pic32mx_txdone(struct pic32mx_driver_s *priv)
{
+ struct pic32mx_txdesc_s *txdesc;
+ int i;
+
/* Cancel the pending Tx timeout */
wd_cancel(priv->pd_txtimeout);
@@ -1144,9 +1200,34 @@ static void pic32mx_txdone(struct pic32mx_driver_s *priv)
* is, this descriptor is now under software control and the message was
* transmitted. Use TSV to check for the transmission result.
*/
-#warning "Missing logic"
-#warning "The rest is residual LPC17xx logic that needs to be removed"
+ for (i = 0; i < CONFIG_NET_NTXDESC; i++)
+ {
+ txdesc = &priv->pd_txdesc[i];
+
+ /* Check if software owns this descriptor */
+
+ if ((txdesc->status & TXDESC_STATUS_EOWN) == 0)
+ {
+ /* Yes.. Check if there is a buffer attached? */
+
+ if (txdesc->address != 0)
+ {
+ /* Reset status */
+
+ txdesc->status = TXDESC_STATUS_SOWN;
+ txdesc->tsv1 = 0;
+ txdesc->tsv2 = 0;
+
+ /* Free the TX buffer */
+
+ pic32mx_freebuffer(priv, (uint8_t *)VIRT_ADDR(txdesc->address));
+ txdesc->address = 0;
+ }
+ }
+ txdesc += TXDESC_SIZE;
+ }
+
/* Check if there is a pending Tx transfer that was scheduled by Rx handling
* while the Tx logic was busy. If so, processing that pending Tx now.
*/
@@ -1168,7 +1249,24 @@ static void pic32mx_txdone(struct pic32mx_driver_s *priv)
else
{
- (void)uip_poll(&priv->pd_dev, pic32mx_uiptxpoll);
+ /* Assign a buffer for the poll */
+
+ DEBUGASSERT(priv->pd_dev.d_buf == NULL);
+ priv->pd_dev.d_buf = pic32mx_allocbuffer(priv);
+ if (priv->pd_dev.d_buf)
+ {
+ /* And perform the poll */
+
+ (void)uip_poll(&priv->pd_dev, pic32mx_uiptxpoll);
+
+ /* Free any buffer left attached after the poll */
+
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ pic32mx_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
+ }
}
}
@@ -1258,7 +1356,6 @@ static int pic32mx_interrupt(int irq, void *context)
* or by writing the BUFCDEC bit to decrement the BUFCNT counter.
* Writing a ‘0’ or a ‘1’ has no effect.
*/
-#warning "Missing logic"
/* RXDONE: Receive Done Interrupt. This bit is set whenever an RX packet
* is successfully received. It is cleared by either a Reset or CPU
@@ -1342,9 +1439,9 @@ static int pic32mx_interrupt(int irq, void *context)
/* Clear the pending interrupt */
# if CONFIG_PIC32MX_NINTERFACES > 1
- pic32mx_clrpend(priv->pd_irqsrc);
+ up_clrpend_irq(priv->pd_irqsrc);
# else
- pic32mx_clrpend(PIC32MX_IRQSRC_ETH);
+ up_clrpend_irq(PIC32MX_IRQSRC_ETH);
# endif
return OK;
@@ -1384,9 +1481,20 @@ static void pic32mx_txtimeout(int argc, uint32_t arg, ...)
(void)pic32mx_ifup(&priv->pd_dev);
- /* Then poll uIP for new XMIT data */
+ /* Then poll uIP for new XMIT data (We are guaranteed to have a free
+ * buffer here).
+ */
+ priv->pd_dev.d_buf = pic32mx_allocbuffer(priv);
(void)uip_poll(&priv->pd_dev, pic32mx_uiptxpoll);
+
+ /* Free any buffer left attached after the poll */
+
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ pic32mx_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
}
}
@@ -1423,7 +1531,22 @@ static void pic32mx_polltimer(int argc, uint32_t arg, ...)
* we will missing TCP time state updates?
*/
- (void)uip_timer(&priv->pd_dev, pic32mx_uiptxpoll, PIC32MX_POLLHSEC);
+ DEBUGASSERT(priv->pd_dev.d_buf == NULL);
+ priv->pd_dev.d_buf = pic32mx_allocbuffer(priv);
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ /* And perform the poll */
+
+ (void)uip_timer(&priv->pd_dev, pic32mx_uiptxpoll, PIC32MX_POLLHSEC);
+
+ /* Free any buffer left attached after the poll */
+
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ pic32mx_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
+ }
}
/* Setup the watchdog poll timer again */
@@ -1585,7 +1708,7 @@ static int pic32mx_ifup(struct uip_driver_s *dev)
* length restriction is desired, program this 16-bit field.
*/
- pic32mx_putreg(PIC32MX_MAXPACKET_SIZE, PIC32MX_EMAC1_MAXF);
+ pic32mx_putreg(CONFIG_NET_BUFSIZE, PIC32MX_EMAC1_MAXF);
/* Configure the MAC station address in the EMAC1SA0, EMAC1SA1 and
* EMAC1SA2 registers (these registers are loaded at reset from the
@@ -1641,6 +1764,10 @@ static int pic32mx_ifup(struct uip_driver_s *dev)
*/
#warning "Missing logic"
+ /* Initialize the buffer list */
+
+ pic32mx_bufferinit(priv);
+
/* Initialize the TX descriptor list */
pic32mx_txdescinit(priv);
@@ -1827,9 +1954,26 @@ static int pic32mx_txavail(struct uip_driver_s *dev)
if (pic32mx_txdesc(priv) != NULL)
{
- /* If so, then poll uIP for new XMIT data */
+ /* If so, then poll uIP for new XMIT data. First allocate a buffer
+ * to perform the poll
+ */
- (void)uip_poll(&priv->pd_dev, pic32mx_uiptxpoll);
+ DEBUGASSERT(priv->pd_dev.d_buf == NULL);
+ priv->pd_dev.d_buf = pic32mx_allocbuffer(priv);
+ if (priv->pd_dev.d_buf)
+ {
+ /* And perform the poll */
+
+ (void)uip_poll(&priv->pd_dev, pic32mx_uiptxpoll);
+
+ /* Free any buffer left attached after the poll */
+
+ if (priv->pd_dev.d_buf != NULL)
+ {
+ pic32mx_freebuffer(priv, priv->pd_dev.d_buf);
+ priv->pd_dev.d_buf = NULL;
+ }
+ }
}
}
@@ -2222,7 +2366,7 @@ static inline int pic32mx_phyinit(struct pic32mx_driver_s *priv)
/* Enter RMII mode and select 100 MBPS support */
pic32mx_putreg(ETH_CMD_RMII, PIC32MX_ETH_CMD);
- pic32mx_putreg(EMAC1_SUPP_SPEEDRMII:, PIC32MX_ETH_SUPP);
+ pic32mx_putreg(EMAC1_SUPP_SPEEDRMII, PIC32MX_ETH_SUPP);
/* Find PHY Address. Because the controller has a pull-up and the
* PHY has pull-down resistors on RXD lines some times the PHY
@@ -2557,7 +2701,6 @@ static void pic32mx_macmode(uint8_t mode)
static void pic32mx_ethreset(struct pic32mx_driver_s *priv)
{
- uint32_t regval;
irqstate_t flags;
/* Reset the MAC */
@@ -2646,9 +2789,7 @@ static inline int pic32mx_ethinitialize(int intf)
#endif
{
struct pic32mx_driver_s *priv;
- uint32_t regval;
int ret;
- int i;
DEBUGASSERT(intf < CONFIG_PIC32MX_NINTERFACES);
priv = &g_ethdrvr[intf];
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h
index 29735f3c5..f909c5974 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h
@@ -727,8 +727,8 @@
#define PIC32MX_TXDESC_ADDRESS 0x04 /* Data buffer address (32-bits) */
#define PIC32MX_TXDESC_TSV1 0x08 /* Transmit filter status vector 1 (32-bits) */
#define PIC32MX_TXDESC_TSV2 0x0c /* Transmit filter status vector 2 (32-bits) */
-#define PIC32MX_TXDESC_NEXTED 0x10 /* Size in bytes of one Tx descriptor */
-#define PIC32MX_TXDESC_SIZE 0x14
+#define PIC32MX_TXDESC_NEXTED 0x10 /* Next Ethernet Descriptor (ED) */
+#define PIC32MX_TXDESC_SIZE 0x14 /* Size in bytes of one Tx descriptor */
/* Tx descriptor uint32_t* indices */
@@ -736,8 +736,8 @@
#define TXDESC_ADDRESS 1 /* Data buffer address (32-bits) */
#define TXDESC_TSV1 2 /* Transmit filter status vector 1 (32-bits) */
#define TXDESC_TSV2 3 /* Transmit filter status vector 2 (32-bits) */
-#define TXDESC_NEXTED 4 /* Size in bytes of one Tx descriptor */
-#define TXDESC_SIZE 5
+#define TXDESC_NEXTED 4 /* Next Ethernet Descriptor (ED) */
+#define TXDESC_SIZE 5 /* Size in 32-bit words of one Tx descriptor */
/* Rx descriptor offsets */
@@ -745,8 +745,8 @@
#define PIC32MX_RXDESC_ADDRESS 0x04 /* Data buffer address (32-bits) */
#define PIC32MX_RXDESC_RSV1 0x08 /* Receive filter status vector 1 and checksum (32-bits) */
#define PIC32MX_RXDESC_RSV2 0x0c /* Receive filter status vector 2 (32-bits) */
-#define PIC32MX_RXDESC_NEXTED 0x10 /* Size in bytes of one Tx descriptor */
-#define PIC32MX_RXDESC_SIZE 0x14
+#define PIC32MX_RXDESC_NEXTED 0x10 /* Next Ethernet Descriptor (ED) */
+#define PIC32MX_RXDESC_SIZE 0x14 /* Size in bytes of one Tx descriptor */
/* Rx descriptor offsets uint32_t* indices */
@@ -754,8 +754,8 @@
#define RXDESC_ADDRESS 1 /* Data buffer address (32-bits) */
#define RXDESC_RSV1 2 /* Receive filter status vector 1 and checksum (32-bits) */
#define RXDESC_RSV2 3 /* Receive filter status vector 2 (32-bits) */
-#define RXDESC_NEXTED 4 /* Size in bytes of one Tx descriptor */
-#define RXDESC_SIZE 5
+#define RXDESC_NEXTED 4 /* Next Ethernet Descriptor (ED) */
+#define RXDESC_SIZE 5 /* Size in 32-bit words of one Tx descriptor */
/* Descriptor Bit Definitions ***************************************************************/
/* Tx descriptor status bit definitions */
@@ -853,6 +853,26 @@
#ifndef __ASSEMBLY__
+/* Descriptors as structures */
+
+struct pic32mx_txdesc_s
+{
+ uint32_t status; /* Various status bits (32-bits) */
+ uint32_t address; /* Data buffer address (32-bits) */
+ uint32_t tsv1; /* Transmit filter status vector 1 (32-bits) */
+ uint32_t tsv2; /* Transmit filter status vector 2 (32-bits) */
+ uint32_t nexted; /* Next Ethernet Descriptor (ED) */
+};
+
+struct pic32mx_rxdesc_s
+{
+ uint32_t status; /* Various status bits (32-bits) */
+ uint32_t address; /* Data buffer address (32-bits) */
+ uint32_t rsv1; /* Receive filter status vector 1 and checksum (32-bits) */
+ uint32_t rsv2; /* Receive filter status vector 2 (32-bits) */
+ uint32_t nexted; /* Next Ethernet Descriptor (ED) */
+};
+
/********************************************************************************************
* Inline Functions
********************************************************************************************/