summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-17 14:28:10 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-11-17 14:28:10 +0000
commit8bc9aa48a6c10260d599cff7cca8fa89322c3ea5 (patch)
tree59be18d4347e5cfa2d8e0bb87f8c2fb3a6ba333a /nuttx
parenta80ff427530ab32907f0d3858b05a8d4fbf13be2 (diff)
downloadpx4-nuttx-8bc9aa48a6c10260d599cff7cca8fa89322c3ea5.tar.gz
px4-nuttx-8bc9aa48a6c10260d599cff7cca8fa89322c3ea5.tar.bz2
px4-nuttx-8bc9aa48a6c10260d599cff7cca8fa89322c3ea5.zip
Fix DM90x0 driver problem that caused TX overruns
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@384 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/Documentation/NuttX.html1
-rw-r--r--nuttx/drivers/net/dm90x0.c68
-rw-r--r--nuttx/examples/nettest/nettest-server.c1
-rw-r--r--nuttx/net/net-timeo.c5
-rw-r--r--nuttx/net/uip/uip-tcpinput.c6
6 files changed, 48 insertions, 37 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 565c35cba..6f59da81e 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -224,6 +224,4 @@
recv() in place but the packet was being ACKed. There are still TCP
recv buffering issues, but this is part of a larger buffering issue.
* Basic server functionality verified: listen(), accept()
-
-
-
+ * Fix DM90x0 driver problem that caused TX overruns
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 65a4a6e49..c8079ed1d 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -680,6 +680,7 @@ Other memory:
recv() in place but the packet was being ACKed. There are still TCP
recv buffering issues, but this is part of a larger buffering issue.
* Basic server functionality verified: listen(), accept()
+ * Fix DM90x0 driver problem that caused TX overruns
</pre></ul>
<table width ="100%">
diff --git a/nuttx/drivers/net/dm90x0.c b/nuttx/drivers/net/dm90x0.c
index 67b20427e..5efca07f4 100644
--- a/nuttx/drivers/net/dm90x0.c
+++ b/nuttx/drivers/net/dm90x0.c
@@ -298,7 +298,7 @@ struct dm9x_driver_s
WDOG_ID dm_txpoll; /* TX poll timer */
WDOG_ID dm_txtimeout; /* TX timeout timer */
uint8 dm_ntxpending; /* Count of packets pending transmission */
- uint8 ncrxpackets; /* Number of continuous rx packets */
+ uint8 ncrxpackets; /* Number of continuous rx packets */
/* Mode-dependent function to move data in 8/16/32 I/O modes */
@@ -763,46 +763,54 @@ static inline boolean dm9x_rxchecksumready(uint8 rxbyte)
static int dm9x_transmit(struct dm9x_driver_s *dm9x)
{
- /* Increment count of packets transmitted */
+ /* Check if there is room in the DM90x0 to hold another packet. In 100M mode,
+ * that can be 2 packets, otherwise it is a single packet.
+ */
+
+ if (dm9x->dm_ntxpending < 1 || (dm9x->dm_b100M && dm9x->dm_ntxpending < 2))
+ {
+ /* Increment count of packets transmitted */
- dm9x->dm_ntxpending++;
+ dm9x->dm_ntxpending++;
#if defined(CONFIG_DM9X_STATS)
- dm9x->dm_ntxpackets++;
- dm9x->dm_ntxbytes += dm9x->dm_dev.d_len;
+ dm9x->dm_ntxpackets++;
+ dm9x->dm_ntxbytes += dm9x->dm_dev.d_len;
#endif
- /* Disable all DM90x0 interrupts */
+ /* Disable all DM90x0 interrupts */
- putreg(DM9X_IMR, DM9X_IMRDISABLE);
+ putreg(DM9X_IMR, DM9X_IMRDISABLE);
- /* Set the TX length */
+ /* Set the TX length */
- putreg(DM9X_TXPLL, (dm9x->dm_dev.d_len & 0xff));
- putreg(DM9X_TXPLH, (dm9x->dm_dev.d_len >> 8) & 0xff);
+ putreg(DM9X_TXPLL, (dm9x->dm_dev.d_len & 0xff));
+ putreg(DM9X_TXPLH, (dm9x->dm_dev.d_len >> 8) & 0xff);
- /* Move the data to be sent into TX SRAM */
+ /* Move the data to be sent into TX SRAM */
- DM9X_INDEX = DM9X_MWCMD;
- dm9x->dm_write(dm9x->dm_dev.d_buf, dm9x->dm_dev.d_len);
+ DM9X_INDEX = DM9X_MWCMD;
+ dm9x->dm_write(dm9x->dm_dev.d_buf, dm9x->dm_dev.d_len);
#if !defined(CONFIG_DM9X_ETRANS)
- /* Issue TX polling command */
+ /* Issue TX polling command */
- putreg(DM9X_TXC, 0x1); /* Cleared after TX complete*/
+ putreg(DM9X_TXC, 0x1); /* Cleared after TX complete*/
#endif
- /* Clear count of back-to-back RX packet transfers */
+ /* Clear count of back-to-back RX packet transfers */
- dm9x->ncrxpackets = 0;
+ dm9x->ncrxpackets = 0;
- /* Re-enable DM90x0 interrupts */
+ /* Re-enable DM90x0 interrupts */
- putreg(DM9X_IMR, DM9X_IMRENABLE);
+ putreg(DM9X_IMR, DM9X_IMRENABLE);
- /* Setup the TX timeout watchdog (perhaps restarting the timer) */
+ /* Setup the TX timeout watchdog (perhaps restarting the timer) */
- (void)wd_start(dm9x->dm_txtimeout, DM6X_TXTIMEOUT, dm9x_txtimeout, 1, (uint32)dm9x);
- return OK;
+ (void)wd_start(dm9x->dm_txtimeout, DM6X_TXTIMEOUT, dm9x_txtimeout, 1, (uint32)dm9x);
+ return OK;
+ }
+ return -EBUSY;
}
/****************************************************************************
@@ -978,9 +986,8 @@ static void dm9x_receive(struct dm9x_driver_s *dm9x)
uip_arp_ipin();
uip_input(&dm9x->dm_dev);
- /* If the above function invocation resulted in data that
- * should be sent out on the network, the global variable
- * d_len is set to a value > 0.
+ /* 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 (dm9x->dm_dev.d_len > 0)
@@ -993,10 +1000,9 @@ static void dm9x_receive(struct dm9x_driver_s *dm9x)
{
uip_arp_arpin(&dm9x->dm_dev);
- /* If the above function invocation resulted in data that
- * should be sent out on the network, the global variable
- * d_len is set to a value > 0.
- */
+ /* 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 (dm9x->dm_dev.d_len > 0)
{
@@ -1525,8 +1531,8 @@ static void dm9x_bringup(struct dm9x_driver_s *dm9x)
/* Initialize statistics */
- dm9x->ncrxpackets = 0; /* Number of continuous RX packets */
- dm9x->dm_ntxpending = 0; /* Number of pending TX packets */
+ dm9x->ncrxpackets = 0; /* Number of continuous RX packets */
+ dm9x->dm_ntxpending = 0; /* Number of pending TX packets */
dm9x_resetstatistics(dm9x);
/* Activate DM9000A/DM9010 */
diff --git a/nuttx/examples/nettest/nettest-server.c b/nuttx/examples/nettest/nettest-server.c
index d00498f4e..984dee6b3 100644
--- a/nuttx/examples/nettest/nettest-server.c
+++ b/nuttx/examples/nettest/nettest-server.c
@@ -207,6 +207,7 @@ void recv_server(void)
/* Then send the same data back to the client */
+ message("server: Sending %d bytes\n", totalbytesread);
nbytessent = send(acceptsd, buffer, totalbytesread, 0);
if (nbytessent <= 0)
{
diff --git a/nuttx/net/net-timeo.c b/nuttx/net/net-timeo.c
index 65161ca1d..0bc25c030 100644
--- a/nuttx/net/net-timeo.c
+++ b/nuttx/net/net-timeo.c
@@ -41,7 +41,10 @@
#if defined(CONFIG_NET) && defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)
#include <sys/types.h>
+#include <debug.h>
+
#include <nuttx/clock.h>
+
#include "net-internal.h"
/****************************************************************************
@@ -70,6 +73,7 @@ int net_timeo(uint32 start_time, socktimeo_t timeo)
{
uint32 timeo_ticks = DSEC2TICK(timeo);
uint32 elapsed = g_system_timer - start_time;
+
if (elapsed >= timeo_ticks)
{
return TRUE;
@@ -78,3 +82,4 @@ int net_timeo(uint32 start_time, socktimeo_t timeo)
}
#endif /* CONFIG_NET && CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
+
diff --git a/nuttx/net/uip/uip-tcpinput.c b/nuttx/net/uip/uip-tcpinput.c
index 2ecd23d98..5ce3e2df6 100644
--- a/nuttx/net/uip/uip-tcpinput.c
+++ b/nuttx/net/uip/uip-tcpinput.c
@@ -276,7 +276,7 @@ found:
if (BUF->flags & TCP_RST)
{
conn->tcpstateflags = UIP_CLOSED;
- dbg("Recvd reset - TCP state: UIP_CLOSED\n");
+ dbg("RESET - TCP state: UIP_CLOSED\n");
(void)uip_tcpcallback(dev, conn, UIP_ABORT);
goto drop;
@@ -496,7 +496,7 @@ found:
/* The connection is closed after we send the RST */
conn->tcpstateflags = UIP_CLOSED;
- vdbg("TCP state: UIP_CLOSED\n");
+ vdbg("Connection failed - TCP state: UIP_CLOSED\n");
/* We do not send resets in response to resets. */
@@ -643,7 +643,7 @@ found:
if (flags & UIP_ACKDATA)
{
conn->tcpstateflags = UIP_CLOSED;
- vdbg("TCP state: UIP_CLOSED\n");
+ vdbg("UIP_LAST_ACK TCP state: UIP_CLOSED\n");
(void)uip_tcpcallback(dev, conn, UIP_CLOSE);
}