aboutsummaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2012-09-16 21:05:40 +0000
committerpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2012-09-16 21:05:40 +0000
commit1947d55686c1c86349b4f0bb1153c81cd04c618c (patch)
tree2a1a2b4dbc6031fcc9badb5d0570be30a0381111 /nuttx
parentc09094ccfc6e51b0de4e045a9bfe51bf1b178667 (diff)
downloadpx4-firmware-1947d55686c1c86349b4f0bb1153c81cd04c618c.tar.gz
px4-firmware-1947d55686c1c86349b4f0bb1153c81cd04c618c.tar.bz2
px4-firmware-1947d55686c1c86349b4f0bb1153c81cd04c618c.zip
Add W25 FLASH support to fire-stm32v2 and shenzhou boards; a fiew enc28j60 updates
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@5162 7fd9a85b-ad96-42d3-883c-3090e2eb8679
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/TODO9
-rw-r--r--nuttx/configs/fire-stm32v2/src/Makefile12
-rw-r--r--nuttx/configs/fire-stm32v2/src/fire-internal.h12
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_w25.c153
-rw-r--r--nuttx/configs/shenzhou/src/Makefile4
-rw-r--r--nuttx/configs/shenzhou/src/shenzhou-internal.h12
-rw-r--r--nuttx/configs/shenzhou/src/up_w25.c153
-rw-r--r--nuttx/drivers/net/Kconfig9
-rw-r--r--nuttx/drivers/net/enc28j60.c25
-rw-r--r--nuttx/drivers/net/enc28j60.h8
10 files changed, 370 insertions, 27 deletions
diff --git a/nuttx/TODO b/nuttx/TODO
index ae42d6c1c..72a94290b 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -1,4 +1,4 @@
-NuttX TODO List (Last updated August 12, 2012)
+NuttX TODO List (Last updated September 16, 2012)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
This file summarizes known NuttX bugs, limitations, inconsistencies with
@@ -548,13 +548,6 @@ o Network (net/, drivers/net)
Status: Open
Priority: Low... fix defconfig files as necessary.
- Title: UNFINISHED ENC28J60 DRIVER
- Description: So far, I have not come up with a usable hardware platform to
- verify the ENC28J60 Ethernet driver (drivers/net/enc28j60.c).
- So it is untested.
- Status: Open
- Priority: Low unless you need it.
-
o USB (drivers/usbdev, drivers/usbhost)
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
diff --git a/nuttx/configs/fire-stm32v2/src/Makefile b/nuttx/configs/fire-stm32v2/src/Makefile
index 4c4fd1d41..d605a8f3b 100644
--- a/nuttx/configs/fire-stm32v2/src/Makefile
+++ b/nuttx/configs/fire-stm32v2/src/Makefile
@@ -56,10 +56,6 @@ else
CSRCS += up_userleds.c
endif
-ifeq ($(CONFIG_ENC28J60),y)
-CSRCS += up_enc28j60.c
-endif
-
ifeq ($(CONFIG_ARCH_BUTTONS),y)
CSRCS += up_buttons.c
endif
@@ -68,6 +64,14 @@ ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
+ifeq ($(CONFIG_ENC28J60),y)
+CSRCS += up_enc28j60.c
+endif
+
+ifeq ($(CONFIG_MTD_W25),y)
+CSRCS += up_w25.c
+endif
+
ifeq ($(CONFIG_USBMSC),y)
CSRCS += up_usbmsc.c
endif
diff --git a/nuttx/configs/fire-stm32v2/src/fire-internal.h b/nuttx/configs/fire-stm32v2/src/fire-internal.h
index 0260d8e33..e9f7a8508 100644
--- a/nuttx/configs/fire-stm32v2/src/fire-internal.h
+++ b/nuttx/configs/fire-stm32v2/src/fire-internal.h
@@ -303,6 +303,18 @@ void stm32_selectlcd(void);
int stm32_sdinitialize(int minor);
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MTD_W25
+int stm32_w25initialize(int minor);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_FIRE_STM32V2_SRC_FIRE_INTERNAL_H */
diff --git a/nuttx/configs/fire-stm32v2/src/up_w25.c b/nuttx/configs/fire-stm32v2/src/up_w25.c
new file mode 100644
index 000000000..a3460a158
--- /dev/null
+++ b/nuttx/configs/fire-stm32v2/src/up_w25.c
@@ -0,0 +1,153 @@
+/****************************************************************************
+ * config/fire-stm32v2/src/up_w25.c
+ * arch/arm/src/board/up_w25.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/mount.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <errno.h>
+#include <debug.h>
+
+#ifdef CONFIG_STM32_SPI1
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+# include <nuttx/fs/nxffs.h>
+#endif
+
+#include "fire-internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+/* Can't support the W25 device if it SPI1 or W25 support is not enabled */
+
+#define HAVE_W25 1
+#if !defined(CONFIG_STM32_SPI1) || !defined(CONFIG_MTD_W25)
+# undef HAVE_W25
+#endif
+
+/* Can't support W25 features if mountpoints are disabled */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT)
+# undef HAVE_W25
+#endif
+
+/* Can't support both FAT and NXFFS */
+
+#if defined(CONFIG_FS_FAT) && defined(CONFIG_FS_NXFFS)
+# warning "Can't support both FAT and NXFFS -- using FAT"
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+int stm32_w25initialize(int minor)
+{
+#ifdef HAVE_W25
+ FAR struct spi_dev_s *spi;
+ FAR struct mtd_dev_s *mtd;
+#ifndef CONFIG_FS_NXFFS
+ uint8_t devname[12];
+#endif
+ int ret;
+
+ /* Get the SPI port */
+
+ spi = up_spiinitialize(2);
+ if (!spi)
+ {
+ fdbg("ERROR: Failed to initialize SPI port 2\n");
+ return -ENODEV;
+ }
+
+ /* Now bind the SPI interface to the SST 25 SPI FLASH driver */
+
+ mtd = sst25_initialize(spi);
+ if (!mtd)
+ {
+ fdbg("ERROR: Failed to bind SPI port 2 to the SST 25 FLASH driver\n");
+ return -ENODEV;
+ }
+
+#ifndef CONFIG_FS_NXFFS
+ /* And finally, use the FTL layer to wrap the MTD driver as a block driver */
+
+ ret = ftl_initialize(minor, mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Initialize the FTL layer\n");
+ return ret;
+ }
+#else
+ /* Initialize to provide NXFFS on the MTD interface */
+
+ ret = nxffs_initialize(mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: NXFFS initialization failed: %d\n", -ret);
+ return ret;
+ }
+
+ /* Mount the file system at /mnt/w25 */
+
+ snprintf(devname, 12, "/mnt/w25%c", a + minor);
+ ret = mount(NULL, devname, "nxffs", 0, NULL);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno);
+ return ret;
+ }
+#endif
+#endif
+ return OK;
+}
diff --git a/nuttx/configs/shenzhou/src/Makefile b/nuttx/configs/shenzhou/src/Makefile
index 11e36f136..50ddaa5ca 100644
--- a/nuttx/configs/shenzhou/src/Makefile
+++ b/nuttx/configs/shenzhou/src/Makefile
@@ -68,6 +68,10 @@ ifeq ($(CONFIG_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
+ifeq ($(CONFIG_MTD_W25),y)
+CSRCS += up_w25.c
+endif
+
ifeq ($(CONFIG_USBMSC),y)
CSRCS += up_usbmsc.c
endif
diff --git a/nuttx/configs/shenzhou/src/shenzhou-internal.h b/nuttx/configs/shenzhou/src/shenzhou-internal.h
index 6f9683a56..19460bc99 100644
--- a/nuttx/configs/shenzhou/src/shenzhou-internal.h
+++ b/nuttx/configs/shenzhou/src/shenzhou-internal.h
@@ -270,5 +270,17 @@ int stm32_usbhost_initialize(void);
int stm32_sdinitialize(int minor);
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_MTD_W25
+int stm32_w25initialize(int minor);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_SHENZHOUL_SRC_SHENZHOU_INTERNAL_H */
diff --git a/nuttx/configs/shenzhou/src/up_w25.c b/nuttx/configs/shenzhou/src/up_w25.c
new file mode 100644
index 000000000..aa547f6fe
--- /dev/null
+++ b/nuttx/configs/shenzhou/src/up_w25.c
@@ -0,0 +1,153 @@
+/****************************************************************************
+ * config/shenzhou/src/up_w25.c
+ * arch/arm/src/board/up_w25.c
+ *
+ * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/mount.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <errno.h>
+#include <debug.h>
+
+#ifdef CONFIG_STM32_SPI1
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+# include <nuttx/fs/nxffs.h>
+#endif
+
+#include "shenzhou-internal.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+/* Can't support the W25 device if it SPI1 or W25 support is not enabled */
+
+#define HAVE_W25 1
+#if !defined(CONFIG_STM32_SPI1) || !defined(CONFIG_MTD_W25)
+# undef HAVE_W25
+#endif
+
+/* Can't support W25 features if mountpoints are disabled */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT)
+# undef HAVE_W25
+#endif
+
+/* Can't support both FAT and NXFFS */
+
+#if defined(CONFIG_FS_FAT) && defined(CONFIG_FS_NXFFS)
+# warning "Can't support both FAT and NXFFS -- using FAT"
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_w25initialize
+ *
+ * Description:
+ * Initialize and register the W25 FLASH file system.
+ *
+ ****************************************************************************/
+
+int stm32_w25initialize(int minor)
+{
+#ifdef HAVE_W25
+ FAR struct spi_dev_s *spi;
+ FAR struct mtd_dev_s *mtd;
+#ifndef CONFIG_FS_NXFFS
+ uint8_t devname[12];
+#endif
+ int ret;
+
+ /* Get the SPI port */
+
+ spi = up_spiinitialize(2);
+ if (!spi)
+ {
+ fdbg("ERROR: Failed to initialize SPI port 2\n");
+ return -ENODEV;
+ }
+
+ /* Now bind the SPI interface to the SST 25 SPI FLASH driver */
+
+ mtd = sst25_initialize(spi);
+ if (!mtd)
+ {
+ fdbg("ERROR: Failed to bind SPI port 2 to the SST 25 FLASH driver\n");
+ return -ENODEV;
+ }
+
+#ifndef CONFIG_FS_NXFFS
+ /* And finally, use the FTL layer to wrap the MTD driver as a block driver */
+
+ ret = ftl_initialize(minor, mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Initialize the FTL layer\n");
+ return ret;
+ }
+#else
+ /* Initialize to provide NXFFS on the MTD interface */
+
+ ret = nxffs_initialize(mtd);
+ if (ret < 0)
+ {
+ fdbg("ERROR: NXFFS initialization failed: %d\n", -ret);
+ return ret;
+ }
+
+ /* Mount the file system at /mnt/w25 */
+
+ snprintf(devname, 12, "/mnt/w25%c", a + minor);
+ ret = mount(NULL, devname, "nxffs", 0, NULL);
+ if (ret < 0)
+ {
+ fdbg("ERROR: Failed to mount the NXFFS volume: %d\n", errno);
+ return ret;
+ }
+#endif
+#endif
+ return OK;
+}
diff --git a/nuttx/drivers/net/Kconfig b/nuttx/drivers/net/Kconfig
index b5c09bf01..a42d35fea 100644
--- a/nuttx/drivers/net/Kconfig
+++ b/nuttx/drivers/net/Kconfig
@@ -25,6 +25,7 @@ config ENC28J60
References:
ENC28J60 Data Sheet, Stand-Alone Ethernet Controller with SPI Interface,
DS39662C, 2008 Microchip Technology Inc.
+
if ENC28J60
config ENC28J60_NINTERFACES
int "Number of physical ENC28J60"
@@ -61,6 +62,14 @@ config ENC28J60_HALFDUPPLEX
default n
---help---
Default is full duplex
+
+config ENC28J60_DUMPPACKET
+ bool "Dump Packets"
+ default n
+ ---help---
+ If selected, the ENC28J60 driver will dump the contents of each
+ packet to the console.
+
endif
config NET_E1000
diff --git a/nuttx/drivers/net/enc28j60.c b/nuttx/drivers/net/enc28j60.c
index 654d0ae61..bb79910b3 100644
--- a/nuttx/drivers/net/enc28j60.c
+++ b/nuttx/drivers/net/enc28j60.c
@@ -150,7 +150,7 @@
#define ALIGNED_BUFSIZE ((CONFIG_NET_BUFSIZE + 255) & ~255)
#define PKTMEM_TX_START 0x0000 /* Start TX buffer at 0 */
-#define PKTMEM_TX_ENDP1 ALIGNED_BUFSIZE /* Allow TX buffer for one frame + */
+#define PKTMEM_TX_ENDP1 ALIGNED_BUFSIZE /* Allow TX buffer for one frame */
#define PKTMEM_RX_START PKTMEM_TX_ENDP1 /* Followed by RX buffer */
#define PKTMEM_RX_END PKTMEM_END /* RX buffer goes to the end of SRAM */
@@ -1352,7 +1352,7 @@ static void enc_pktif(FAR struct enc_driver_s *priv)
/* Copy the data data from the receive buffer to priv->dev.d_buf */
enc_rdbuffer(priv, priv->dev.d_buf, priv->dev.d_len);
- enc_dumppacket("Received Packet", priv->ld_dev.d_buf, priv->ld_dev.d_len);
+ enc_dumppacket("Received Packet", priv->dev.d_buf, priv->dev.d_len);
/* Dispatch the packet to uIP */
@@ -1419,9 +1419,12 @@ static void enc_irqworker(FAR void *arg)
while ((eir = enc_rdgreg(priv, ENC_EIR) & EIR_ALLINTS) != 0)
{
/* Handle interrupts according to interrupt register register bit
- * settings
- *
- * DMAIF: The DMA interrupt indicates that the DMA module has completed
+ * settings.
+ */
+
+ nllvdbg("EIR: %02x\n", eir);
+
+ /* DMAIF: The DMA interrupt indicates that the DMA module has completed
* its memory copy or checksum calculation. Additionally, this interrupt
* will be caused if the host controller cancels a DMA operation by
* manually clearing the DMAST bit. Once set, DMAIF can only be cleared
@@ -1538,6 +1541,8 @@ static void enc_irqworker(FAR void *arg)
uint8_t pktcnt = enc_rdbreg(priv, ENC_EPKTCNT);
if (pktcnt > 0)
{
+ nllvdbg("EPKTCNT: %02x\n", pktcnt);
+
#ifdef CONFIG_ENC28J60_STATS
if (pktcnt > priv->stats.maxpktcnt)
{
@@ -1856,11 +1861,9 @@ static int enc_ifup(struct uip_driver_s *dev)
*/
enc_wrphy(priv, ENC_PHIE, PHIE_PGEIE | PHIE_PLNKIE);
- enc_bfsgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE);
- enc_bfsgreg(priv, ENC_EIR, EIR_DMAIF | EIR_LINKIF | EIR_TXIF |
- EIR_TXERIF | EIR_RXERIF | EIR_PKTIF);
- enc_wrgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE | EIE_LINKIE |
- EIE_TXIE | EIE_TXERIE | EIE_RXERIE);
+ enc_bfcgreg(priv, ENC_EIR, EIR_ALLINTS);
+ enc_wrgreg(priv, ENC_EIE, EIE_INTIE | EIE_PKTIE | EIE_LINKIE |
+ EIE_TXIE | EIE_TXERIE | EIE_RXERIE);
/* Enable the receiver */
@@ -2289,7 +2292,7 @@ static int enc_reset(FAR struct enc_driver_s *priv)
enc_wrbreg(priv, ENC_MAIPGL, 0x12);
- /* Set ack-to-Back Inter-Packet Gap */
+ /* Set Back-to-Back Inter-Packet Gap */
enc_wrbreg(priv, ENC_MABBIPG, 0x15);
#endif
diff --git a/nuttx/drivers/net/enc28j60.h b/nuttx/drivers/net/enc28j60.h
index 3c787c533..dab9cc5cf 100644
--- a/nuttx/drivers/net/enc28j60.h
+++ b/nuttx/drivers/net/enc28j60.h
@@ -131,10 +131,10 @@
#define ECON1_BSEL_SHIFT (0) /* Bits 0-1: Bank select */
#define ECON1_BSEL_MASK (3 << ECON1_BSEL_SHIFT)
-# define ECON1_BSEL_BANK0 (0 << 0) /* Bank 0 */
-# define ECON1_BSEL_BANK1 (1 << 1) /* Bank 1 */
-# define ECON1_BSEL_BANK2 (2 << 0) /* Bank 2 */
-# define ECON1_BSEL_BANK3 (3 << 0) /* Bank 3 */
+# define ECON1_BSEL_BANK0 (0 << ECON1_BSEL_SHIFT) /* Bank 0 */
+# define ECON1_BSEL_BANK1 (1 << ECON1_BSEL_SHIFT) /* Bank 1 */
+# define ECON1_BSEL_BANK2 (2 << ECON1_BSEL_SHIFT) /* Bank 2 */
+# define ECON1_BSEL_BANK3 (3 << ECON1_BSEL_SHIFT) /* Bank 3 */
#define ECON1_RXEN (1 << 2) /* Bit 2: Receive Enable */
#define ECON1_TXRTS (1 << 3) /* Bit 3: Transmit Request to Send */
#define ECON1_CSUMEN (1 << 4) /* Bit 4: DMA Checksum Enable */