summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-11-28 01:04:11 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2010-11-28 01:04:11 +0000
commit66a32df5155e7669fec3544366cf23becb47de83 (patch)
tree6356e525833ed9a9e06c5c5f470d26ad1ab8a926
parent9bd21d7b274c24ac45128b104b676be295e01877 (diff)
downloadpx4-nuttx-66a32df5155e7669fec3544366cf23becb47de83.tar.gz
px4-nuttx-66a32df5155e7669fec3544366cf23becb47de83.tar.bz2
px4-nuttx-66a32df5155e7669fec3544366cf23becb47de83.zip
Files needed to make LPC17xx EMAC RAM more configurable
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3141 42af7a65-404d-4744-a932-0658087f49c3
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c7
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_emacram.h196
-rw-r--r--nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c121
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h5
-rw-r--r--nuttx/include/net/uip/uip-arp.h1
-rw-r--r--nuttx/net/send.c17
6 files changed, 219 insertions, 128 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
index 3bba12e85..46d5d9e7a 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_allocateheap.c
@@ -50,6 +50,7 @@
#include "up_internal.h"
#include "lpc17_memorymap.h"
+#include "lpc17_emacram.h"
/****************************************************************************
* Private Definitions
@@ -137,13 +138,13 @@ void up_addregion(void)
#ifdef LPC17_HAVE_BANK0
# if defined(CONFIG_NET) && defined(CONFIG_LPC17_ETHERNET) && defined(LPC17_NETHCONTROLLERS)
# ifdef LPC17_HAVE_BANK1
- mm_addregion((FAR void*)LPC17_SRAM_BANK1, 16*1024);
+ mm_addregion((FAR void*)LPC17_SRAM_BANK1, LPC17_BANK1_SIZE);
# endif
# else
# ifdef LPC17_HAVE_BANK1
- mm_addregion((FAR void*)LPC17_SRAM_BANK0, 32*1024);
+ mm_addregion((FAR void*)LPC17_SRAM_BANK0, LPC17_BANK0_SIZE+LPC17_BANK1_SIZE);
# else
- mm_addregion((FAR void*)LPC17_SRAM_BANK0, 16*1024);
+ mm_addregion((FAR void*)LPC17_SRAM_BANK0, LPC17_BANK0_SIZE);
# endif
# endif
#endif
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h b/nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h
new file mode 100755
index 000000000..75137084e
--- /dev/null
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_emacram.h
@@ -0,0 +1,196 @@
+/************************************************************************************
+ * arch/arm/src/lpc17xx/lpc17_emacram.h
+ *
+ * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_LPC17XX_LPC17_EMACRAM_H
+#define __ARCH_ARM_SRC_LPC17XX_LPC17_EMACRAM_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#if defined(CONFIG_NET) && defined(CONFIG_LPC17_ETHERNET)
+
+#include "chip.h"
+#include "lpc17_memorymap.h"
+
+/* Does this chip have and ethernet controller? */
+
+#if LPC17_NETHCONTROLLERS > 0
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+
+/* Configuration ********************************************************************/
+
+/* Number of Tx descriptors */
+
+#ifndef CONFIG_NET_NTXDESC
+# define CONFIG_NET_NTXDESC 18
+#endif
+
+/* Number of Rx descriptors */
+
+#ifndef CONFIG_NET_NRXDESC
+# define CONFIG_NET_NRXDESC 18
+#endif
+
+/* All of AHB SRAM, Bank 0 is set aside for EMAC Tx and Rx descriptors. */
+
+#define LPC17_EMACRAM_BASE LPC17_SRAM_BANK0
+#define LPC17_EMACRAM_SIZE LPC17_BANK0_SIZE
+
+/* Descriptors Memory Layout ********************************************************/
+/* EMAC DMA RAM and descriptor definitions. The configured number of descriptors
+ * will determine the organization and the size of the descriptor and status tables.
+ * There is a complex interaction between the maximum packet size (CONFIG_NET_BUFSIZE)
+ * and the number of Rx and Tx descriptors that can be suppored (CONFIG_NET_NRXDESC
+ * and CONFIG_NET_NTXDESC): Small buffers -> more packets. This is something that
+ * needs to be tuned for you system.
+ *
+ * For a 16Kb SRAM region, here is the relationship:
+ *
+ * 16384 <= ntx * (pktsize + 8 + 4) + nrx * (pktsize + 8 + 8)
+ *
+ * If ntx == nrx and pktsize == 424, then you could have
+ * ntx = nrx = 18.
+ *
+ * An example with all of the details:
+ *
+ * NTXDESC=18 NRXDESC=18 CONFIG_NET_BUFSIZE=420:
+ * LPC17_TXDESCTAB_SIZE = 18*8 = 144
+ * LPC17_TXSTATTAB_SIZE = 18*4 = 72
+ * LPC17_TXTAB_SIZE = 216
+ *
+ * LPC17_RXDESCTAB_SIZE = 16*8 = 144
+ * LPC17_RXSTATTAB_SIZE = 16*8 = 144
+ * LPC17_TXTAB_SIZE = 288
+ *
+ * LPC17_DESCTAB_SIZE = 504
+ * LPC17_DESC_BASE = LPC17_SRAM_BANK0 + 0x00004000 - 504
+ * = LPC17_SRAM_BANK0 + 0x00003e08
+ * LPC17_TXDESC_BASE = LPC17_SRAM_BANK0 + 0x00003e08
+ * LPC17_TXSTAT_BASE = LPC17_SRAM_BANK0 + 0x00003e98
+ * LPC17_RXDESC_BASE = LPC17_SRAM_BANK0 + 0x00003ee0
+ * LPC17_RXSTAT_BASE = LPC17_SRAM_BANK0 + 0x00003f70
+ *
+ * LPC17_PKTMEM_BASE = LPC17_SRAM_BANK0
+ * LPC17_PKTMEM_SIZE = 0x00004000-504 = 0x00003e40
+ * LPC17_PKTMEM_END = LPC17_SRAM_BANK0 + 0x00003e08
+
+ * LPC17_MAXPACKET_SIZE = ((420 + 3 + 2) & ~3) = 424
+ * LPC17_NTXPKTS = 18
+ * LPC17_NRXPKTS = 18
+
+ * LPC17_TXBUFFER_SIZE = 18 * 424 = 0x00001dd0
+ * LPC17_RXBUFFER_SIZE = 18 * 424 = 0x00001dd0
+ * LPC17_BUFFER_SIZE = 0x00003ba0
+
+ * LPC17_BUFFER_BASE = LPC17_SRAM_BANK0
+ * LPC17_TXBUFFER_BASE = LPC17_SRAM_BANK0
+ * LPC17_RXBUFFER_BASE = LPC17_SRAM_BANK0 + 0x00001dd0
+ * LPC17_BUFFER_END = LPC17_SRAM_BANK0 + 0x00003ba0
+ *
+ * Then the check LPC17_BUFFER_END < LPC17_PKTMEM_END passes. The amount of
+ * unused memory is small: 0x00003e08-0x00003ba0 or about 616 bytes -- not
+ * enough for two more packets.
+ *
+ * [It is also possible, with some effort, to reclaim any unused
+ * SRAM for the use in the heap. But that has not yet been pursued.]
+ */
+
+#define LPC17_TXDESCTAB_SIZE (CONFIG_NET_NTXDESC*LPC17_TXDESC_SIZE)
+#define LPC17_TXSTATTAB_SIZE (CONFIG_NET_NTXDESC*LPC17_TXSTAT_SIZE)
+#define LPC17_TXTAB_SIZE (LPC17_TXDESCTAB_SIZE+LPC17_TXSTATTAB_SIZE)
+
+#define LPC17_RXDESCTAB_SIZE (CONFIG_NET_NRXDESC*LPC17_RXDESC_SIZE)
+#define LPC17_RXSTATTAB_SIZE (CONFIG_NET_NRXDESC*LPC17_RXSTAT_SIZE)
+#define LPC17_RXTAB_SIZE (LPC17_RXDESCTAB_SIZE+LPC17_RXSTATTAB_SIZE)
+
+#define LPC17_DESCTAB_SIZE (LPC17_TXTAB_SIZE+LPC17_RXTAB_SIZE)
+
+/* Descriptor table memory organization. Descriptor tables are packed at
+ * the end of AHB SRAM, Bank 0. The beginning of bank 0 is reserved for
+ * packet memory.
+ */
+
+#define LPC17_DESC_BASE (LPC17_EMACRAM_BASE+LPC17_EMACRAM_SIZE-LPC17_DESCTAB_SIZE)
+#define LPC17_TXDESC_BASE LPC17_DESC_BASE
+#define LPC17_TXSTAT_BASE (LPC17_TXDESC_BASE+LPC17_TXDESCTAB_SIZE)
+#define LPC17_RXDESC_BASE (LPC17_TXSTAT_BASE+LPC17_TXSTATTAB_SIZE)
+#define LPC17_RXSTAT_BASE (LPC17_RXDESC_BASE + LPC17_RXDESCTAB_SIZE)
+
+/* Now carve up the beginning of SRAM for packet memory. The size of a
+ * packet buffer is related to the size of the MTU. We'll round sizes up
+ * to multiples of 256 bytes.
+ */
+
+#define LPC17_PKTMEM_BASE LPC17_EMACRAM_BASE
+#define LPC17_PKTMEM_SIZE (LPC17_EMACRAM_SIZE-LPC17_DESCTAB_SIZE)
+#define LPC17_PKTMEM_END (LPC17_EMACRAM_BASE+LPC17_PKTMEM_SIZE)
+
+#define LPC17_MAXPACKET_SIZE ((CONFIG_NET_BUFSIZE + 3 + 2) & ~3)
+#define LPC17_NTXPKTS CONFIG_NET_NTXDESC
+#define LPC17_NRXPKTS CONFIG_NET_NRXDESC
+
+#define LPC17_TXBUFFER_SIZE (LPC17_NTXPKTS * LPC17_MAXPACKET_SIZE)
+#define LPC17_RXBUFFER_SIZE (LPC17_NRXPKTS * LPC17_MAXPACKET_SIZE)
+#define LPC17_BUFFER_SIZE (LPC17_TXBUFFER_SIZE + LPC17_RXBUFFER_SIZE)
+
+#define LPC17_BUFFER_BASE LPC17_PKTMEM_BASE
+#define LPC17_TXBUFFER_BASE LPC17_BUFFER_BASE
+#define LPC17_RXBUFFER_BASE (LPC17_TXBUFFER_BASE + LPC17_TXBUFFER_SIZE)
+#define LPC17_BUFFER_END (LPC17_BUFFER_BASE + LPC17_BUFFER_SIZE)
+
+#if LPC17_BUFFER_END > LPC17_PKTMEM_END
+# error "Packet memory overlaps descriptor tables"
+#endif
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+#endif /* LPC17_NETHCONTROLLERS > 0 */
+#endif /* CONFIG_NET && CONFIG_LPC17_ETHERNET */
+#endif /* __ARCH_ARM_SRC_LPC17XX_LPC17_EMACRAM_H */
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
index fe0ac2e43..2f2e53fc7 100644
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_ethernet.c
@@ -60,6 +60,7 @@
#include "up_arch.h"
#include "lpc17_syscon.h"
#include "lpc17_ethernet.h"
+#include "lpc17_emacram.h"
#include "lpc17_internal.h"
#include <arch/board/board.h>
@@ -199,126 +200,6 @@
# endif
#endif
-/* Descriptors **************************************************************/
-/* EMAC DMA RAM and descriptor definitions. The configured number of
- * descriptors will determine the organization and the size of the
- * descriptor and status tables. There is a complex interaction between
- * the maximum packet size (CONFIG_NET_BUFSIZE) and the number of
- * Rx and Tx descriptors that can be suppored (CONFIG_NET_NRXDESC and
- * CONFIG_NET_NTXDESC): Small buffers -> more packets. This is
- * something that needs to be tuned for you system.
- *
- * For a 16Kb SRAM region, here is the relationship:
- *
- * 16384 <= ntx * (pktsize + 8 + 4) + nrx * (pktsize + 8 + 8)
- *
- * If ntx == nrx and pktsize == 424, then you could have
- * ntx = nrx = 18.
- *
- * An example with all of the details:
- *
- * NTXDESC=18 NRXDESC=18 CONFIG_NET_BUFSIZE=420:
- * LPC17_TXDESCTAB_SIZE = 18*8 = 144
- * LPC17_TXSTATTAB_SIZE = 18*4 = 72
- * LPC17_TXTAB_SIZE = 216
- *
- * LPC17_RXDESCTAB_SIZE = 16*8 = 144
- * LPC17_RXSTATTAB_SIZE = 16*8 = 144
- * LPC17_TXTAB_SIZE = 288
- *
- * LPC17_DESCTAB_SIZE = 504
- * LPC17_DESC_BASE = LPC17_SRAM_BANK0 + 0x00004000 - 504
- * = LPC17_SRAM_BANK0 + 0x00003e08
- * LPC17_TXDESC_BASE = LPC17_SRAM_BANK0 + 0x00003e08
- * LPC17_TXSTAT_BASE = LPC17_SRAM_BANK0 + 0x00003e98
- * LPC17_RXDESC_BASE = LPC17_SRAM_BANK0 + 0x00003ee0
- * LPC17_RXSTAT_BASE = LPC17_SRAM_BANK0 + 0x00003f70
- *
- * LPC17_PKTMEM_BASE = LPC17_SRAM_BANK0
- * LPC17_PKTMEM_SIZE = 0x00004000-504 = 0x00003e40
- * LPC17_PKTMEM_END = LPC17_SRAM_BANK0 + 0x00003e08
-
- * LPC17_MAXPACKET_SIZE = ((420 + 3 + 2) & ~3) = 424
- * LPC17_NTXPKTS = 18
- * LPC17_NRXPKTS = 18
-
- * LPC17_TXBUFFER_SIZE = 18 * 424 = 0x00001dd0
- * LPC17_RXBUFFER_SIZE = 18 * 424 = 0x00001dd0
- * LPC17_BUFFER_SIZE = 0x00003ba0
-
- * LPC17_BUFFER_BASE = LPC17_SRAM_BANK0
- * LPC17_TXBUFFER_BASE = LPC17_SRAM_BANK0
- * LPC17_RXBUFFER_BASE = LPC17_SRAM_BANK0 + 0x00001dd0
- * LPC17_BUFFER_END = LPC17_SRAM_BANK0 + 0x00003ba0
- *
- * Then the check LPC17_BUFFER_END < LPC17_PKTMEM_END passes. The
- * amount of unused memory is small: 0x00003e08-0x00003ba0 or about
- * 616 bytes -- not enough for two more packets.
- *
- * [It is also possible, with some effort, to reclaim any unused
- * SRAM for the use in the heap. But that has not yet been pursued.]
- */
-
-#ifndef CONFIG_NET_NTXDESC
-# define CONFIG_NET_NTXDESC 18
-#endif
-#define LPC17_TXDESCTAB_SIZE (CONFIG_NET_NTXDESC*LPC17_TXDESC_SIZE)
-#define LPC17_TXSTATTAB_SIZE (CONFIG_NET_NTXDESC*LPC17_TXSTAT_SIZE)
-#define LPC17_TXTAB_SIZE (LPC17_TXDESCTAB_SIZE+LPC17_TXSTATTAB_SIZE)
-
-#ifndef CONFIG_NET_NRXDESC
-# define CONFIG_NET_NRXDESC 18
-#endif
-#define LPC17_RXDESCTAB_SIZE (CONFIG_NET_NRXDESC*LPC17_RXDESC_SIZE)
-#define LPC17_RXSTATTAB_SIZE (CONFIG_NET_NRXDESC*LPC17_RXSTAT_SIZE)
-#define LPC17_RXTAB_SIZE (LPC17_RXDESCTAB_SIZE+LPC17_RXSTATTAB_SIZE)
-
-#define LPC17_DESCTAB_SIZE (LPC17_TXTAB_SIZE+LPC17_RXTAB_SIZE)
-
-/* All of AHB SRAM, Bank 0 is set aside for EMAC Tx and Rx descriptors. */
-
-#define LPC17_BANK0_SIZE 0x00004000
-
-#define LPC17_EMACRAM_BASE LPC17_SRAM_BANK0
-#define LPC17_EMACRAM_SIZE LPC17_BANK0_SIZE
-
-/* Descriptor table memory organization. Descriptor tables are packed at
- * the end of AHB SRAM, Bank 0. The beginning of bank 0 is reserved for
- * packet memory.
- */
-
-#define LPC17_DESC_BASE (LPC17_EMACRAM_BASE+LPC17_EMACRAM_SIZE-LPC17_DESCTAB_SIZE)
-#define LPC17_TXDESC_BASE LPC17_DESC_BASE
-#define LPC17_TXSTAT_BASE (LPC17_TXDESC_BASE+LPC17_TXDESCTAB_SIZE)
-#define LPC17_RXDESC_BASE (LPC17_TXSTAT_BASE+LPC17_TXSTATTAB_SIZE)
-#define LPC17_RXSTAT_BASE (LPC17_RXDESC_BASE + LPC17_RXDESCTAB_SIZE)
-
-/* Now carve up the beginning of SRAM for packet memory. The size of a
- * packet buffer is related to the size of the MTU. We'll round sizes up
- * to multiples of 256 bytes.
- */
-
-#define LPC17_PKTMEM_BASE LPC17_EMACRAM_BASE
-#define LPC17_PKTMEM_SIZE (LPC17_EMACRAM_SIZE-LPC17_DESCTAB_SIZE)
-#define LPC17_PKTMEM_END (LPC17_EMACRAM_BASE+LPC17_PKTMEM_SIZE)
-
-#define LPC17_MAXPACKET_SIZE ((CONFIG_NET_BUFSIZE + 3 + 2) & ~3)
-#define LPC17_NTXPKTS CONFIG_NET_NTXDESC
-#define LPC17_NRXPKTS CONFIG_NET_NRXDESC
-
-#define LPC17_TXBUFFER_SIZE (LPC17_NTXPKTS * LPC17_MAXPACKET_SIZE)
-#define LPC17_RXBUFFER_SIZE (LPC17_NRXPKTS * LPC17_MAXPACKET_SIZE)
-#define LPC17_BUFFER_SIZE (LPC17_TXBUFFER_SIZE + LPC17_RXBUFFER_SIZE)
-
-#define LPC17_BUFFER_BASE LPC17_PKTMEM_BASE
-#define LPC17_TXBUFFER_BASE LPC17_BUFFER_BASE
-#define LPC17_RXBUFFER_BASE (LPC17_TXBUFFER_BASE + LPC17_TXBUFFER_SIZE)
-#define LPC17_BUFFER_END (LPC17_BUFFER_BASE + LPC17_BUFFER_SIZE)
-
-#if LPC17_BUFFER_END > LPC17_PKTMEM_END
-# error "Packet memory overlaps descriptor tables"
-#endif
-
/****************************************************************************
* Private Types
****************************************************************************/
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h b/nuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h
index f331c958c..59a6fd51e 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_memorymap.h
@@ -65,6 +65,11 @@
#define LPC17_SCS_BASE 0xe000e000
#define LPC17_DEBUGMCU_BASE 0xe0042000
+/* AHB SRAM Bank sizes **************************************************************/
+
+#define LPC17_BANK0_SIZE (16*1024) /* Size of AHB SRAM Bank0 (if present) */
+#define LPC17_BANK1_SIZE (16*1024) /* Size of AHB SRAM Bank1 (if present) */
+
/* APB0 Peripherals *****************************************************************/
#define LPC17_WDT_BASE 0x40000000 /* -0x40003fff: Watchdog timer */
diff --git a/nuttx/include/net/uip/uip-arp.h b/nuttx/include/net/uip/uip-arp.h
index cf8d19d30..439960e9a 100644
--- a/nuttx/include/net/uip/uip-arp.h
+++ b/nuttx/include/net/uip/uip-arp.h
@@ -213,7 +213,6 @@ EXTERN void uip_arp_update(uint16_t *pipaddr, uint8_t *ethaddr);
EXTERN struct arp_entry *uip_arp_find(in_addr_t ipaddr);
-
/****************************************************************************
* Name: uip_arp_delete
*
diff --git a/nuttx/net/send.c b/nuttx/net/send.c
index 515c350e4..14b9cea99 100644
--- a/nuttx/net/send.c
+++ b/nuttx/net/send.c
@@ -184,7 +184,6 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
* actually sent.
*/
- conn->unacked = 0;
goto end_wait;
}
@@ -292,7 +291,7 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
}
}
- /* All data has been send and we are just waiting for ACK or re-tranmist
+ /* All data has been send and we are just waiting for ACK or re-transmit
* indications to complete the send. Check for a timeout.
*/
@@ -301,8 +300,8 @@ static uint16_t send_interrupt(struct uip_driver_s *dev, void *pvconn,
{
/* Yes.. report the timeout */
- nllvdbg("TCP timeout\n");
- pstate->snd_sent = -EAGAIN;
+ nlldbg("SEND timeout\n");
+ pstate->snd_sent = -ETIMEDOUT;
goto end_wait;
}
#endif /* CONFIG_NET_SOCKOPTS && !CONFIG_DISABLE_CLOCK */
@@ -318,6 +317,10 @@ end_wait:
pstate->snd_cb->priv = NULL;
pstate->snd_cb->event = NULL;
+ /* There are no outstanding, unacknowledged bytes */
+
+ conn->unacked = 0;
+
/* Wake up the waiting thread */
sem_post(&pstate->snd_sem);
@@ -447,6 +450,12 @@ ssize_t send(int sockfd, const void *buf, size_t len, int flags)
state.snd_isn = uip_tcpgetsequence(conn->sndseq);
+ /* There is no outstanding, unacknowledged data after this
+ * initial sequence number.
+ */
+
+ conn->unacked = 0;
+
/* Update the initial time for calculating timeouts */
#if defined(CONFIG_NET_SOCKOPTS) && !defined(CONFIG_DISABLE_CLOCK)