summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-09 17:47:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-03-09 17:47:25 +0000
commitdcc5105f03ad04aa6e36a2ff7331a019303a88a4 (patch)
tree6359cf6bec3ebb6ca3fcc4c32144c1f16e46c4f3
parent08f1693659735a722f6de74e300010ce97616416 (diff)
downloadpx4-nuttx-dcc5105f03ad04aa6e36a2ff7331a019303a88a4.tar.gz
px4-nuttx-dcc5105f03ad04aa6e36a2ff7331a019303a88a4.tar.bz2
px4-nuttx-dcc5105f03ad04aa6e36a2ff7331a019303a88a4.zip
Fix several bugs related to PIC32 Ethernet driver
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4468 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c153
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h38
-rw-r--r--nuttx/arch/mips/src/pic32mx/pic32mx-exception.c2
-rw-r--r--nuttx/configs/pic32-starterkit/nsh/defconfig6
-rw-r--r--nuttx/configs/pic32-starterkit/ostest/defconfig6
5 files changed, 160 insertions, 45 deletions
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
index b7ca6f42f..210a85bbf 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.c
@@ -132,10 +132,13 @@
#define PIC32MX_NBUFFERS (CONFIG_NET_NRXDESC + CONFIG_NET_NTXDESC + 1)
/* Debug Configuration *****************************************************/
-/* Register debug -- can only happen of CONFIG_DEBUG is selected */
+/* Register/Descriptor debug -- can only happen of CONFIG_DEBUG is selected.
+ * This will probably generate much more output than you care to see.
+ */
#ifndef CONFIG_DEBUG
-# undef CONFIG_NET_REGDEBUG
+# undef CONFIG_NET_REGDEBUG
+# undef CONFIG_NET_DESCDEBUG
#endif
/* CONFIG_NET_DUMPPACKET will dump the contents of each packet to the
@@ -378,6 +381,14 @@ static void pic32mx_putreg(uint32_t val, uint32_t addr);
/* Buffer and descriptor management */
+#ifdef CONFIG_NET_DESCDEBUG
+static void pic32mx_dumptxdesc(struct pic32mx_txdesc_s *txdesc, const char *msg);
+static void pic32mx_dumprxdesc(struct pic32mx_rxdesc_s *rxdesc, const char *msg);
+#else
+# define pic32mx_dumptxdesc(txdesc,msg)
+# define pic32mx_dumprxdesc(rxdesc,msg)
+#endif
+
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);
@@ -385,6 +396,7 @@ 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 struct pic32mx_txdesc_s *pic32mx_txdesc(struct pic32mx_driver_s *priv);
+static inline void pic32mx_rxreturn(struct pic32mx_rxdesc_s *rxdesc);
static struct pic32mx_rxdesc_s *pic32mx_rxdesc(struct pic32mx_driver_s *priv);
/* Common TX logic */
@@ -569,6 +581,60 @@ static void pic32mx_putreg(uint32_t val, uint32_t addr)
#endif
/****************************************************************************
+ * Function: pic32mx_dumptxdesc
+ *
+ * Description:
+ * Dump the contents of the specified TX descriptor
+ *
+ * Parameters:
+ * txdesc - Pointer to the TX descriptor to dump
+ * msg - Annotation for the TX descriptor
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_DESCDEBUG
+static void pic32mx_dumptxdesc(struct pic32mx_txdesc_s *txdesc, const char *msg)
+{
+ dbg("TX Descriptor [%p]: %s\n", txdesc, msg);
+ dbg(" status: %08x\n", txdesc->status);
+ dbg(" address: %08x [%08x]\n", txdesc->address, VIRT_ADDR(txdesc->address));
+ dbg(" tsv1: %08x\n", txdesc->tsv1);
+ dbg(" tsv2: %08x\n", txdesc->tsv2);
+ dbg(" nexted: %08x [%08x]\n", txdesc->nexted, VIRT_ADDR(txdesc->nexted));
+}
+#endif
+
+/****************************************************************************
+ * Function: pic32mx_dumprxdesc
+ *
+ * Description:
+ * Dump the contents of the specified RX descriptor
+ *
+ * Parameters:
+ * txdesc - Pointer to the RX descriptor to dump
+ * msg - Annotation for the RX descriptor
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_NET_DESCDEBUG
+static void pic32mx_dumprxdesc(struct pic32mx_rxdesc_s *rxdesc, const char *msg)
+{
+ dbg("RX Descriptor [%p]: %s\n", rxdesc, msg);
+ dbg(" status: %08x\n", rxdesc->status);
+ dbg(" address: %08x [%08x]\n", rxdesc->address, VIRT_ADDR(rxdesc->address));
+ dbg(" rsv1: %08x\n", rxdesc->rsv1);
+ dbg(" rsv2: %08x\n", rxdesc->rsv2);
+ dbg(" nexted: %08x [%08x]\n", rxdesc->nexted, VIRT_ADDR(rxdesc->nexted));
+}
+#endif
+
+/****************************************************************************
* Function: pic32mx_bufferinit
*
* Description:
@@ -679,12 +745,14 @@ static inline void pic32mx_txdescinit(struct pic32mx_driver_s *priv)
if (i == (CONFIG_NET_NRXDESC-1))
{
- txdesc->nexted = (uint32_t)priv->pd_txdesc;
+ txdesc->nexted = PHYS_ADDR(priv->pd_txdesc);
}
else
{
- txdesc->nexted = (uint32_t)&priv->pd_txdesc[i+1];
+ txdesc->nexted = PHYS_ADDR(&priv->pd_txdesc[i+1]);
}
+
+ pic32mx_dumptxdesc(txdesc, "Initial");
}
/* Update the ETHTXST register with the physical address of the head of
@@ -732,10 +800,10 @@ static inline void pic32mx_rxdescinit(struct pic32mx_driver_s *priv)
* for reception.
*/
- rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
- rxdesc->address = PHYS_ADDR(pic32mx_allocbuffer(priv));
rxdesc->rsv1 = 0;
rxdesc->rsv2 = 0;
+ rxdesc->address = PHYS_ADDR(pic32mx_allocbuffer(priv));
+ rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
/* Set the NEXTED pointer. If this is the last descriptor in the
* list, then set the NEXTED pointer back to the first entry,
@@ -744,12 +812,14 @@ static inline void pic32mx_rxdescinit(struct pic32mx_driver_s *priv)
if (i == (CONFIG_NET_NRXDESC-1))
{
- rxdesc->nexted = (uint32_t)priv->pd_rxdesc;
+ rxdesc->nexted = PHYS_ADDR(priv->pd_rxdesc);
}
else
{
- rxdesc->nexted = (uint32_t)&priv->pd_rxdesc[i+1];
+ rxdesc->nexted = PHYS_ADDR(&priv->pd_rxdesc[i+1]);
}
+
+ pic32mx_dumprxdesc(rxdesc, "Initial");
}
/* Update the ETHRXST register with the physical address of the head of the
@@ -807,6 +877,30 @@ static struct pic32mx_txdesc_s *pic32mx_txdesc(struct pic32mx_driver_s *priv)
}
/****************************************************************************
+ * Function: pic32mx_rxreturn
+ *
+ * Description:
+ * Return an RX descriptor to the hardware.
+ *
+ * Parameters:
+ * rxdesc - Reference to the RX descriptor to be returned
+ *
+ * Returned Value:
+ * None
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+static inline void pic32mx_rxreturn(struct pic32mx_rxdesc_s *rxdesc)
+{
+ rxdesc->rsv1 = 0;
+ rxdesc->rsv2 = 0;
+ rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
+ pic32mx_dumprxdesc(rxdesc, "Returned to hardware");
+}
+
+/****************************************************************************
* Function: pic32mx_rxdesc
*
* Description:
@@ -877,6 +971,7 @@ static struct pic32mx_rxdesc_s *pic32mx_rxdesc(struct pic32mx_driver_s *priv)
static int pic32mx_transmit(struct pic32mx_driver_s *priv)
{
struct pic32mx_txdesc_s *txdesc;
+ uint32_t status;
/* 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
@@ -885,7 +980,7 @@ static int pic32mx_transmit(struct pic32mx_driver_s *priv)
DEBUGASSERT(priv->pd_dev.d_buf && priv->pd_dev.d_len < CONFIG_NET_BUFSIZE);
- /* Increment statistics and dump the packet *if so configured) */
+ /* 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);
@@ -906,6 +1001,7 @@ static int pic32mx_transmit(struct pic32mx_driver_s *priv)
txdesc = pic32mx_txdesc(priv);
DEBUGASSERT(txdesc != NULL);
+ pic32mx_dumptxdesc(txdesc, "Before transmit setup");
/* Remove the transmit buffer from the device structure and assign it to
* the TX descriptor.
@@ -918,8 +1014,7 @@ static int pic32mx_transmit(struct pic32mx_driver_s *priv)
* contained in the buffer.
*/
- txdesc->tsv2 &= TXDESC_TSV2_BYTECOUNT_MASK;
- txdesc->tsv2 |= ((uint32_t)priv->pd_dev.d_len << TXDESC_TSV2_BYTECOUNT_SHIFT);
+ status = ((uint32_t)priv->pd_dev.d_len << TXDESC_STATUS_BYTECOUNT_SHIFT);
priv->pd_dev.d_len = 0;
/* Set EOWN = 1 to indicate that the packet belongs to Ethernet and set both
@@ -927,7 +1022,10 @@ static int pic32mx_transmit(struct pic32mx_driver_s *priv)
* frame.
*/
- txdesc->status |= (TXDESC_STATUS_EOWN | TXDESC_STATUS_EOP | TXDESC_STATUS_SOP);
+ status |= (TXDESC_STATUS_EOWN | TXDESC_STATUS_NPV |
+ TXDESC_STATUS_EOP | TXDESC_STATUS_SOP);
+ txdesc->status = status;
+ pic32mx_dumptxdesc(txdesc, "After transmit setup");
/* Enable the transmission of the message by setting the TXRTS bit (ETHCON1:9). */
@@ -942,6 +1040,7 @@ static int pic32mx_transmit(struct pic32mx_driver_s *priv)
(void)wd_start(priv->pd_txtimeout, PIC32MX_TXTIMEOUT, pic32mx_txtimeout,
1, (uint32_t)priv);
+
return OK;
}
@@ -1097,6 +1196,7 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
return;
}
+ pic32mx_dumprxdesc(rxdesc, "RX Complete");
/* Update statistics */
@@ -1104,14 +1204,15 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
/* Get the packet length */
- priv->pd_dev.d_len = (rxdesc->rsv1 & RXDESC_RSV1_BYTECOUNT_MASK) >> RXDESC_RSV1_BYTECOUNT_SHIFT;
+ priv->pd_dev.d_len = (rxdesc->rsv2 & RXDESC_RSV2_BYTECOUNT_MASK) >> RXDESC_RSV2_BYTECOUNT_SHIFT;
/* Check for errors */
- if ((rxdesc->status & RXDESC_RSV1_OK) == 0)
+ if ((rxdesc->rsv2 & RXDESC_RSV2_OK) == 0)
{
- nlldbg("Error. rxdesc: %08x\n", rxdesc->status);
+ nlldbg("ERROR. rsv1: %08x rsv2: %08x\n", rxdesc->rsv1, rxdesc->rsv2);
EMAC_STAT(priv, rx_pkterr);
+ pic32mx_rxreturn(rxdesc);
}
/* If the packet length is greater then the buffer, then we cannot accept
@@ -1124,6 +1225,7 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
{
nlldbg("Too big. packet length: %d rxdesc: %08x\n", priv->pd_dev.d_len, rxdesc->status);
EMAC_STAT(priv, rx_pktsize);
+ pic32mx_rxreturn(rxdesc);
}
/* We don't have any logic here for reassembling packets from fragments. */
@@ -1132,6 +1234,7 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
{
nlldbg("Fragment. packet length: %d rxdesc: %08x\n", priv->pd_dev.d_len, rxdesc->status);
EMAC_STAT(priv, rx_fragment);
+ pic32mx_rxreturn(rxdesc);
}
else
{
@@ -1149,12 +1252,9 @@ static void pic32mx_rxdone(struct pic32mx_driver_s *priv)
/* And give the RX descriptor back to the hardware */
- rxdesc->status = RXDESC_STATUS_EOWN | TXDESC_STATUS_NPV;
- rxdesc->rsv1 = 0;
- rxdesc->rsv1 = 0;
-
+ pic32mx_rxreturn(rxdesc);
pic32mx_dumppacket("Received packet",
- priv->pd_dev.d_buf, priv->pd_dev.d_len);
+ priv->pd_dev.d_buf, priv->pd_dev.d_len);
/* We only accept IP packets of the configured type and ARP packets */
@@ -1271,16 +1371,19 @@ static void pic32mx_txdone(struct pic32mx_driver_s *priv)
if (txdesc->address != 0)
{
- /* Reset status */
-
- txdesc->status = TXDESC_STATUS_SOWN | TXDESC_STATUS_NPV;
- txdesc->tsv1 = 0;
- txdesc->tsv2 = 0;
+ pic32mx_dumptxdesc(txdesc, "Freeing TX buffer");
/* Free the TX buffer */
pic32mx_freebuffer(priv, (uint8_t *)VIRT_ADDR(txdesc->address));
txdesc->address = 0;
+
+ /* Reset status */
+
+ txdesc->tsv1 = 0;
+ txdesc->tsv2 = 0;
+ txdesc->status = TXDESC_STATUS_SOWN | TXDESC_STATUS_NPV;
+ pic32mx_dumptxdesc(txdesc, "TX buffer freed");
}
}
}
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h
index f8232c6d3..eb293ad31 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-ethernet.h
@@ -432,7 +432,7 @@
#define ETH_INT_RXBUFNA (1 << 1) /* Bit 1: Receive buffer not available interrupt */
#define ETH_INT_TXABORT (1 << 2) /* Bit 2: Transmitter abort interrupt */
#define ETH_INT_TXDONE (1 << 3) /* Bit 3: Transmitter done interrupt */
- /* Bit 4: Reserved */
+ /* Bit 4: Reserved */
#define ETH_INT_RXACT (1 << 5) /* Bit 5: RX activity interrupt */
#define ETH_INT_PKTPEND (1 << 6) /* Bit 6: Packet pending interrupt */
#define ETH_INT_RXDONE (1 << 7) /* Bit 7: Receiver done interrupt */
@@ -440,7 +440,7 @@
#define ETH_INT_EWMARK (1 << 9) /* Bit 9: Empty watermark interrupt */
/* Bits 10-12: Reserved */
#define ETH_INT_RXBUSE (1 << 13) /* Bit 13: Receive BVCI bus error interrupt */
-#define ETH_INT_TXBUSE (1 << 14) /* Bit 14: TXBUSEIE: Transmit BVCI bus error interrupt */
+#define ETH_INT_TXBUSE (1 << 14) /* Bit 14: Transmit BVCI bus error interrupt */
/* Bits 15-31: Reserved */
#define ETH_INT_ALLINTS (0x000063ef)
@@ -837,23 +837,23 @@
#define RXDESC_RSV1_BCASTMATCH (1 << 30) /* Bit 30: RXF_RSV6 Broadcast match */
#define RXDESC_RSV1_MCASTMATCH (1 << 31) /* Bit 31: RXF_RSV7 Multicast match */
-#define RXDESC_RSV1_BYTECOUNT_SHIFT (0) /* Bits 0-15: RSV0-15 Received Byte Count */
-#define RXDESC_RSV1_BYTECOUNT_MASK (0xffff << RXDESC_RSV1_BYTECOUNT_SHIFT)
-#define RXDESC_RSV1_LONGDROP (1 << 16) /* Bit 16: RSV16 Long Event/Drop Event */
-#define RXDESC_RSV1_RXDVSEEN (1 << 17) /* Bit 17: RSV17 RXDV Event Previously Seen */
-#define RXDESC_RSV1_CARSEEN (1 << 18) /* Bit 18: RSV18 Carrier Event Previously Seen */
-#define RXDESC_RSV1_CODE (1 << 19) /* Bit 19: RSV19 Receive Code Violation */
-#define RXDESC_RSV1_CRCERR (1 << 20) /* Bit 20: RSV20 CRC Error */
-#define RXDESC_RSV1_LENCHK (1 << 21) /* Bit 21: RSV21 Length Check Error */
-#define RXDESC_RSV1_OOR (1 << 22) /* Bit 22: RSV22 Length Out of Range */
-#define RXDESC_RSV1_OK (1 << 23) /* Bit 23: RSV23 Received Ok */
-#define RXDESC_RSV1_MCAST (1 << 24) /* Bit 24: RSV24 Receive Multicast Packet */
-#define RXDESC_RSV1_BCAST (1 << 25) /* Bit 25: RSV25 Receive Broadcast Packet */
-#define RXDESC_RSV1_DRIBBLE (1 << 26) /* Bit 26: RSV26 Dribble Nibble */
-#define RXDESC_RSV1_CONTROL (1 << 27) /* Bit 27: RSV27 Receive Control Frame */
-#define RXDESC_RSV1_PAUSE (1 << 28) /* Bit 28: RSV28 Receive Pause Control Frame */
-#define RXDESC_RSV1_UNKNOWNOP (1 << 29) /* Bit 29: RSV29 Receive Unknown Op code */
-#define RXDESC_RSV1_VLAN (1 << 30) /* Bit 30: RSV30 Receive VLAN Type Detected */
+#define RXDESC_RSV2_BYTECOUNT_SHIFT (0) /* Bits 0-15: RSV0-15 Received Byte Count */
+#define RXDESC_RSV2_BYTECOUNT_MASK (0xffff << RXDESC_RSV2_BYTECOUNT_SHIFT)
+#define RXDESC_RSV2_LONGDROP (1 << 16) /* Bit 16: RSV16 Long Event/Drop Event */
+#define RXDESC_RSV2_RXDVSEEN (1 << 17) /* Bit 17: RSV17 RXDV Event Previously Seen */
+#define RXDESC_RSV2_CARSEEN (1 << 18) /* Bit 18: RSV18 Carrier Event Previously Seen */
+#define RXDESC_RSV2_CODE (1 << 19) /* Bit 19: RSV19 Receive Code Violation */
+#define RXDESC_RSV2_CRCERR (1 << 20) /* Bit 20: RSV20 CRC Error */
+#define RXDESC_RSV2_LENCHK (1 << 21) /* Bit 21: RSV21 Length Check Error */
+#define RXDESC_RSV2_OOR (1 << 22) /* Bit 22: RSV22 Length Out of Range */
+#define RXDESC_RSV2_OK (1 << 23) /* Bit 23: RSV23 Received Ok */
+#define RXDESC_RSV2_MCAST (1 << 24) /* Bit 24: RSV24 Receive Multicast Packet */
+#define RXDESC_RSV2_BCAST (1 << 25) /* Bit 25: RSV25 Receive Broadcast Packet */
+#define RXDESC_RSV2_DRIBBLE (1 << 26) /* Bit 26: RSV26 Dribble Nibble */
+#define RXDESC_RSV2_CONTROL (1 << 27) /* Bit 27: RSV27 Receive Control Frame */
+#define RXDESC_RSV2_PAUSE (1 << 28) /* Bit 28: RSV28 Receive Pause Control Frame */
+#define RXDESC_RSV2_UNKNOWNOP (1 << 29) /* Bit 29: RSV29 Receive Unknown Op code */
+#define RXDESC_RSV2_VLAN (1 << 30) /* Bit 30: RSV30 Receive VLAN Type Detected */
/* Bit 31: RSV31 Reserved */
/********************************************************************************************
diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c b/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c
index bd43e9dda..dd3b88b14 100644
--- a/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c
+++ b/nuttx/arch/mips/src/pic32mx/pic32mx-exception.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/mips/src/pic32mx/pic32mx-exception.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
diff --git a/nuttx/configs/pic32-starterkit/nsh/defconfig b/nuttx/configs/pic32-starterkit/nsh/defconfig
index 615140a83..24c909824 100644
--- a/nuttx/configs/pic32-starterkit/nsh/defconfig
+++ b/nuttx/configs/pic32-starterkit/nsh/defconfig
@@ -284,7 +284,11 @@ CONFIG_UART6_2STOP=0
# CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
# Also needs CONFIG_DEBUG.
# CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
+# CONFIG_DEBUG. Automatically enables CONFIG_NET_DESCDEBUG as well.
+# CONFIG_NET_DESCDEBUG - Enabled low level descriptor debug. Also needs
# CONFIG_DEBUG.
+# CONFIG_NET_DUMPPACKET - Dump all incoming and output packet contents.
+# Also needs CONFIG_DEBUG.
# CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
# CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
# Automatically set if CONFIG_NET_IGMP is selected.
@@ -304,6 +308,8 @@ CONFIG_PHY_FDUPLEX=y
CONFIG_NET_NTXDESC=7
CONFIG_NET_NRXDESC=7
CONFIG_NET_REGDEBUG=n
+CONFIG_NET_DESCDEBUG=n
+CONFIG_NET_DUMPPACKET=n
#
# PIC32MX-specific USB device setup
diff --git a/nuttx/configs/pic32-starterkit/ostest/defconfig b/nuttx/configs/pic32-starterkit/ostest/defconfig
index cd968afc7..941408745 100644
--- a/nuttx/configs/pic32-starterkit/ostest/defconfig
+++ b/nuttx/configs/pic32-starterkit/ostest/defconfig
@@ -284,7 +284,11 @@ CONFIG_UART6_2STOP=0
# CONFIG_NET_DUMPPACKET - Dump all received and transmitted packets.
# Also needs CONFIG_DEBUG.
# CONFIG_NET_REGDEBUG - Enabled low level register debug. Also needs
+# CONFIG_DEBUG. Automatically enables CONFIG_NET_DESCDEBUG as well.
+# CONFIG_NET_DESCDEBUG - Enabled low level descriptor debug. Also needs
# CONFIG_DEBUG.
+# CONFIG_NET_DUMPPACKET - Dump all incoming and output packet contents.
+# Also needs CONFIG_DEBUG.
# CONFIG_NET_HASH - Enable receipt of near-perfect match frames.
# CONFIG_NET_MULTICAST - Enable receipt of multicast (and unicast) frames.
# Automatically set if CONFIG_NET_IGMP is selected.
@@ -304,6 +308,8 @@ CONFIG_PHY_FDUPLEX=y
CONFIG_NET_NTXDESC=7
CONFIG_NET_NRXDESC=7
CONFIG_NET_REGDEBUG=n
+CONFIG_NET_DESCDEBUG=n
+CONFIG_NET_DUMPPACKET=n
#
# PIC32MX-specific USB device setup