summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-11-16 09:22:38 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-11-16 09:22:38 -0600
commitb6112c5ca3f1d5b8b929ae64e0b256d26374fc7c (patch)
tree3b3d1d454f1894a9dba926abbba6b8a44c467825
parent656e3c5bebfa925d8eaa77519a3c2f4ea453c1ea (diff)
downloadpx4-nuttx-b6112c5ca3f1d5b8b929ae64e0b256d26374fc7c.tar.gz
px4-nuttx-b6112c5ca3f1d5b8b929ae64e0b256d26374fc7c.tar.bz2
px4-nuttx-b6112c5ca3f1d5b8b929ae64e0b256d26374fc7c.zip
Completes conversion of CONFIG_NET_BUFIZE to CONFIG_NET_ETH/SLIP_MTU
-rw-r--r--misc/drivers/rtl8187x/rtl8187x.c8
-rw-r--r--nuttx/include/nuttx/net/netconfig.h33
-rw-r--r--nuttx/include/nuttx/net/netdev.h2
-rw-r--r--nuttx/net/Kconfig37
-rw-r--r--nuttx/net/devif/devif_input.c2
-rw-r--r--nuttx/net/devif/devif_iobsend.c2
-rw-r--r--nuttx/net/devif/devif_pktsend.c2
-rw-r--r--nuttx/net/devif/devif_send.c2
-rw-r--r--nuttx/net/netdev/netdev_ioctl.c8
-rw-r--r--nuttx/net/tcp/Kconfig2
-rw-r--r--nuttx/net/utils/net_chksum.c2
11 files changed, 60 insertions, 40 deletions
diff --git a/misc/drivers/rtl8187x/rtl8187x.c b/misc/drivers/rtl8187x/rtl8187x.c
index c7706a6c4..e2c25e4bb 100644
--- a/misc/drivers/rtl8187x/rtl8187x.c
+++ b/misc/drivers/rtl8187x/rtl8187x.c
@@ -1185,7 +1185,7 @@ static inline int rtl8187x_allocbuffers(FAR struct rtl8187x_state_s *priv)
* the TX descriptor.
*/
- buflen = CONFIG_NET_BUFSIZE + 2 + SIZEOF_TXDESC;
+ buflen = CONFIG_NET_ETH_MTU + 2 + SIZEOF_TXDESC;
ret = DRVR_IOALLOC(priv->hcd, &priv->txbuffer, buflen);
if (ret != OK)
{
@@ -1196,7 +1196,7 @@ static inline int rtl8187x_allocbuffers(FAR struct rtl8187x_state_s *priv)
* the RX descriptor.
*/
- buflen = CONFIG_NET_BUFSIZE + 2 + SIZEOF_RXDESC;
+ buflen = CONFIG_NET_ETH_MTU + 2 + SIZEOF_RXDESC;
ret = DRVR_IOALLOC(priv->hcd, &priv->rxbuffer, buflen);
if (ret != OK)
{
@@ -2188,7 +2188,7 @@ static inline int rtl8187x_receive(FAR struct rtl8187x_state_s *priv,
/* Check if uIP is configured to handle a packet of this size */
- if (iolen > CONFIG_NET_BUFSIZE + SIZEOF_RXDESC + 2)
+ if (iolen > CONFIG_NET_ETH_MTU + SIZEOF_RXDESC + 2)
{
RTL8187X_STATS(priv, rxtoobig);
RTL8187X_STATS(priv, rxdropped);
@@ -2319,7 +2319,7 @@ static void rtl8187x_rxpollwork(FAR void *arg)
/* Attempt to read from the bulkin endpoint */
ret = DRVR_TRANSFER(priv->hcd, priv->epin, priv->rxbuffer,
- CONFIG_NET_BUFSIZE + SIZEOF_RXDESC + 2);
+ CONFIG_NET_ETH_MTU + SIZEOF_RXDESC + 2);
/* How dow we get the length of the transfer? */
#warning "Missing logic"
diff --git a/nuttx/include/nuttx/net/netconfig.h b/nuttx/include/nuttx/net/netconfig.h
index 5e987cf65..793dd0cb5 100644
--- a/nuttx/include/nuttx/net/netconfig.h
+++ b/nuttx/include/nuttx/net/netconfig.h
@@ -81,11 +81,29 @@
* can be found. For Ethernet, this should be set to 14. For SLIP, this
* should be set to 0.
*
- * If CONFIG_NET_MULTILINK is defined, then mutliple link protocols are
+ * If CONFIG_NET_MULTILINK is defined, then multiple link protocols are
* supported concurrently. In this case, the size of link layer header
* varies and is obtained from the network device structure.
+ *
+ * Support is also provided to select different MTU sizes for each different
+ * link layer protocol. A better solution would be to support device-by-
+ * device MTU sizes. This minimum support is require to support the
+ * optimal SLIP MTU of 296 bytes and the standard Ethernet MTU of 1500
+ * bytes.
*/
+#ifdef CONFIG_NET_SLIP
+# ifndef CONFIG_NET_SLIP_MTU
+# define CONFIG_NET_SLIP_MTU 590
+# endif
+#endif
+
+#ifdef CONFIG_NET_ETHERNET
+# ifndef CONFIG_NET_ETH_MTU
+# define CONFIG_NET_ETH_MTU 590
+# endif
+#endif
+
#if defined(CONFIG_NET_MULTILINK)
/* We are supporting multiple network devices using different link layer
* protocols. Get the size of the link layer header from the device
@@ -188,7 +206,7 @@
#endif
/* The UDP maximum packet size. This is should not be to set to more
- * than CONFIG_NET_BUFSIZE - NET_LL_HDRLEN(dev) - IPUDP_HDRLEN.
+ * than NET_LL_MTU(d) - NET_LL_HDRLEN(dev) - IPUDP_HDRLEN.
*/
#define UDP_MSS(d) (CONFIG_NET_ETH_MTU - NET_LL_HDRLEN(d) - IPUDP_HDRLEN)
@@ -332,17 +350,6 @@
/* General configuration options */
-/* The size of the uIP packet buffer.
- *
- * The uIP packet buffer should not be smaller than 60 bytes, and does
- * not need to be larger than 1500 bytes. Lower size results in lower
- * TCP throughput, larger size results in higher TCP throughput.
- */
-
-#ifndef CONFIG_NET_BUFSIZE
-# define CONFIG_NET_BUFSIZE 400
-#endif
-
/* Delay after receive to catch a following packet. No delay should be
* required if TCP/IP read-ahead buffering is enabled.
*/
diff --git a/nuttx/include/nuttx/net/netdev.h b/nuttx/include/nuttx/net/netdev.h
index 8e6f1b6eb..d5135738d 100644
--- a/nuttx/include/nuttx/net/netdev.h
+++ b/nuttx/include/nuttx/net/netdev.h
@@ -131,7 +131,7 @@ struct net_driver_s
#ifdef CONFIG_NET_MULTIBUFFER
uint8_t *d_buf;
#else
- uint8_t d_buf[CONFIG_NET_BUFSIZE + CONFIG_NET_GUARDSIZE];
+ uint8_t d_buf[MAX_NET_LL_MTU + CONFIG_NET_GUARDSIZE];
#endif
/* d_appdata points to the location where application data can be read from
diff --git a/nuttx/net/Kconfig b/nuttx/net/Kconfig
index 526eb3722..53f2f93e6 100644
--- a/nuttx/net/Kconfig
+++ b/nuttx/net/Kconfig
@@ -47,25 +47,38 @@ config NET_PROMISCUOUS
Force the Ethernet driver to operate in promiscuous mode (if supported
by the Ethernet driver).
-config NET_BUFSIZE
- int "Network packet buffer size (MTU)"
- default 1294 if !NET_SLIP && NET_IPv6
- default 590 if !NET_SLIP && !NET_IPv6
- default 296 if NET_SLIP && !NET_IPv6
+config NET_ETH_MTU
+ int "Ethernet packet buffer size (MTU)"
+ default 1294 if NET_IPv6
+ default 590 if !NET_IPv6
+ depends on NET_ETHERNET
+ range 590 1518
---help---
Packet buffer size. This size includes the TCP/UDP payload plus the
- size of TCP/UDP header, the IP header, and the Ethernet header
- (assuming that the Ethernet transport is used). This value is
- normally referred to as the MTU (Maximum Transmission Unit); the
- payload is the MSS (Maximum Segment Size).
+ size of TCP/UDP header, the IP header, and the Ethernet header.
+ This value is normally referred to as the MTU (Maximum Transmission
+ Unit); the payload is the MSS (Maximum Segment Size).
IPv4 hosts are required to be able to handle an MSS of at least
536 octets, resulting in a minimum buffer size of 536+20+20+14 =
- 590 (For SLIP 256+20+20 = 296).
+ 590.
IPv6 hosts are required to be able to handle an MSS of 1220 octets,
resulting in a minimum buffer size of of 1220+20+40+14 = 1294
+config NET_SLIP_MTU
+ int # "SLIP packet buffer size (MTU)"
+ default 296
+ depends on NET_SLIP
+ range 296 1518
+ ---help---
+ Packet buffer size. This size includes the TCP/UDP payload plus the
+ size of TCP/UDP header and the IP header. This value is normally
+ referred to as the MTU (Maximum Transmission Unit); the payload
+ payload is the MSS (Maximum Segment Size). SLIP is required to
+ support at lest 256+20+20 = 296. Values other than 296 are not
+ recommended.
+
config NET_RECEIVE_WINDOW
int "Receive window size"
default 1220 if !NET_SLIP && NET_IPv6
@@ -115,10 +128,6 @@ config NET_SLIP
at least one IP protocol selected and the following additional
network settings: NET_NOINTS and NET_MULTIBUFFER.
- NET_BUFSIZE *must* be set to 296. Other optional configuration
- settings that affect the SLIP driver: NET_STATISTICS.
- Default: Ethernet
-
SLIP supports point-to-point IP communications over a serial port.
The default data link layer for uIP is Ethernet. If NET_SLIP is
defined in the NuttX configuration file, then SLIP will be supported.
diff --git a/nuttx/net/devif/devif_input.c b/nuttx/net/devif/devif_input.c
index 03b5f64ca..c60140562 100644
--- a/nuttx/net/devif/devif_input.c
+++ b/nuttx/net/devif/devif_input.c
@@ -113,7 +113,7 @@
/* IP fragment re-assembly */
#define IP_MF 0x20
-#define TCP_REASS_BUFSIZE (CONFIG_NET_BUFSIZE - NET_LL_HDRLEN(dev))
+#define TCP_REASS_BUFSIZE (NET_LL_MTU(dev) - NET_LL_HDRLEN(dev))
#define TCP_REASS_LASTFRAG 0x01
/****************************************************************************
diff --git a/nuttx/net/devif/devif_iobsend.c b/nuttx/net/devif/devif_iobsend.c
index 424cd94ec..6d00ebcf4 100644
--- a/nuttx/net/devif/devif_iobsend.c
+++ b/nuttx/net/devif/devif_iobsend.c
@@ -99,7 +99,7 @@
void devif_iob_send(FAR struct net_driver_s *dev, FAR struct iob_s *iob,
unsigned int len, unsigned int offset)
{
- DEBUGASSERT(dev && len > 0 && len < CONFIG_NET_BUFSIZE);
+ DEBUGASSERT(dev && len > 0 && len < NET_LL_MTU(dev));
/* Copy the data from the I/O buffer chain to the device buffer */
diff --git a/nuttx/net/devif/devif_pktsend.c b/nuttx/net/devif/devif_pktsend.c
index 5c453fb4d..ef8e33523 100644
--- a/nuttx/net/devif/devif_pktsend.c
+++ b/nuttx/net/devif/devif_pktsend.c
@@ -99,7 +99,7 @@
void devif_pkt_send(FAR struct net_driver_s *dev, FAR const void *buf,
unsigned int len)
{
- DEBUGASSERT(dev && len > 0 && len < CONFIG_NET_BUFSIZE);
+ DEBUGASSERT(dev && len > 0 && len < NET_LL_MTU(dev));
/* Copy the data into the device packet buffer */
diff --git a/nuttx/net/devif/devif_send.c b/nuttx/net/devif/devif_send.c
index 41ecd3361..60eaadd1e 100644
--- a/nuttx/net/devif/devif_send.c
+++ b/nuttx/net/devif/devif_send.c
@@ -94,7 +94,7 @@
void devif_send(struct net_driver_s *dev, const void *buf, int len)
{
- DEBUGASSERT(dev && len > 0 && len < CONFIG_NET_BUFSIZE);
+ DEBUGASSERT(dev && len > 0 && len < NET_LL_MTU(dev));
memcpy(dev->d_snddata, buf, len);
dev->d_sndlen = len;
diff --git a/nuttx/net/netdev/netdev_ioctl.c b/nuttx/net/netdev/netdev_ioctl.c
index 1af66029b..a70358478 100644
--- a/nuttx/net/netdev/netdev_ioctl.c
+++ b/nuttx/net/netdev/netdev_ioctl.c
@@ -316,8 +316,12 @@ static int netdev_ifrioctl(FAR struct socket *psock, int cmd,
case SIOCGIFMTU: /* Get MTU size */
{
- req->ifr_mtu = CONFIG_NET_BUFSIZE;
- ret = OK;
+ dev = netdev_ifrdev(req);
+ if (dev)
+ {
+ req->ifr_mtu = NET_LL_MTU(dev);
+ ret = OK;
+ }
}
break;
diff --git a/nuttx/net/tcp/Kconfig b/nuttx/net/tcp/Kconfig
index c148a44b0..2f513654d 100644
--- a/nuttx/net/tcp/Kconfig
+++ b/nuttx/net/tcp/Kconfig
@@ -31,7 +31,7 @@ config NET_TCP_REASSEMBLY
This features requires an additional amount of RAM to hold the
reassembly buffer and the reassembly code size is approximately 700
bytes. The reassembly buffer is of the same size as the d_buf buffer
- (configured by CONFIG_NET_BUFSIZE).
+ (configured by CONFIG_NET_xxx_MTU).
Note: IP packet reassembly is not heavily tested (and, hence,
EXPERIMENTAL).
diff --git a/nuttx/net/utils/net_chksum.c b/nuttx/net/utils/net_chksum.c
index 1fc85a7c2..c32c7ade5 100644
--- a/nuttx/net/utils/net_chksum.c
+++ b/nuttx/net/utils/net_chksum.c
@@ -128,7 +128,7 @@ static uint16_t upper_layer_chksum(FAR struct net_driver_s *dev, uint8_t proto)
/* Verify some minimal assumptions */
- if (upper_layer_len > CONFIG_NET_BUFSIZE)
+ if (upper_layer_len > NET_LL_MTU(dev))
{
return 0;
}