summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/ChangeLog1
-rw-r--r--nuttx/Documentation/NuttX.html13
-rw-r--r--nuttx/Documentation/NuttxPortingGuide.html254
-rw-r--r--nuttx/arch/arm/src/arm/up_doirq.c39
-rw-r--r--nuttx/arch/arm/src/cortexm3/up_doirq.c51
-rw-r--r--nuttx/arch/arm/src/lm3s/chip.h24
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_ethernet.c357
-rw-r--r--nuttx/arch/arm/src/lm3s/lm3s_internal.h26
-rw-r--r--nuttx/arch/z80/src/ez80/ez80_emac.c6
-rw-r--r--nuttx/configs/eagle100/README.txt55
10 files changed, 684 insertions, 142 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index f7224b673..f0e37fe0d 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -727,4 +727,5 @@
* arch/arm/src/lm2s: Added an Ethernet driver for the LM3S6918
* configs/eagle100/nettest: Added an examples/nettest configuration for the
Micromint Eagle100 board.
+ * Documentation/NuttxPortingGuide.html: Added a section on NuttX device drivers.
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 6bc942e93..f2717ad04 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: May 19, 2009</p>
+ <p>Last Updated: May 21, 2009</p>
</td>
</tr>
</table>
@@ -696,7 +696,8 @@
These unreleased changes are listed <a href="#pendingchanges">here</a>.
</p>
<p>
- The release features support for the Micromint Eagle-100 development board.
+ The release features support for the <a href=" http://www.micromint.com/">Micromint</a>
+ Eagle-100 development board.
This board is based around, the Luminary LM3S6918 MCU.
This is the first ARM Cortex-M3 architecture supported by Nuttx.
This initial, basic port includes timer and serial console with configurations to execute the NuttX OS test and to run the <a href="NuttShell.html">NuttShell (NSH)</a>.
@@ -860,8 +861,8 @@
<td>
<p>
<b>Luminary LM3S6918</b>.
- This port uses the Micromint Eagle-100 development board with a GNU arm-elf toolchain*
- under either Linux or Cygwin.
+ This port uses the <a href=" http://www.micromint.com/">Micromint</a> Eagle-100 development
+ board with a GNU arm-elf toolchain* under either Linux or Cygwin.
</p>
<p>
<b>STATUS:</b>
@@ -1416,6 +1417,7 @@ nuttx-0.4.7 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
* arch/arm/src/lm2s: Added an Ethernet driver for the LM3S6918
* configs/eagle100/nettest: Added an examples/nettest configuration for the
Micromint Eagle100 board.
+ * Documentation/NuttxPortingGuide.html: Added a section on NuttX device drivers.
pascal-0.1.3 2009-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
@@ -1487,9 +1489,10 @@ buildroot-0.1.6 2009-xx-xx &lt;spudmonkey@racsa.co.cr&gt;
</tr>
</table>
<ul>
- <li>ARM, ARM7 ARM7TDMI, ARM9, ARM920T, ARM926EJS are trademarks of Advanced RISC Machines, Limited.</li>
+ <li>ARM, ARM7 ARM7TDMI, ARM9, ARM920T, ARM926EJS Cortex-M3 are trademarks of Advanced RISC Machines, Limited.</li>
<li>Cygwin is a trademark of Red Hat, Incorporated.</li>
<li>Linux is a registered trademark of Linus Torvalds.</li>
+ <li>Eagle-100 is a trademark of <a href=" http://www.micromint.com/">Micromint USA, LLC</a>.
<li>LPC2148 is a trademark of NXP Semiconductors.</li>
<li>TI is a tradename of Texas Instruments Incorporated.</li>
<li>UNIX is a registered trademark of The Open Group.</li>
diff --git a/nuttx/Documentation/NuttxPortingGuide.html b/nuttx/Documentation/NuttxPortingGuide.html
index 1934e9bb6..eea76434f 100644
--- a/nuttx/Documentation/NuttxPortingGuide.html
+++ b/nuttx/Documentation/NuttxPortingGuide.html
@@ -12,7 +12,7 @@
<h1><big><font color="#3c34ec">
<i>NuttX RTOS Porting Guide</i>
</font></big></h1>
- <p>Last Updated: May 9, 2009</p>
+ <p>Last Updated: May 21, 2009</p>
</td>
</tr>
</table>
@@ -104,6 +104,18 @@
</ul>
</ul>
<a href="#NxFileSystem">5.0 NuttX File System</a><br>
+ <a href="#DeviceDrivers">6.0 NuttX Device Drivers</a><br>
+ <ul>
+ <a href="#chardrivers">6.1 Character Device Drivers</a><br>
+ <a href="#blockdrivers">6.2 Block Device Drivers</a><br>
+ <a href="#blockdrivers">6.3 Specialized Device Drivers</a>
+ <ul>
+ <a href="#ethdrivers">6.3.1 Ethernet Device Drivers</a><br>
+ <a href="#spidrivers">6.3.2 SPI Device Drivers</a><br>
+ <a href="#i2cdrivers">6.3.3 I2C Device Drivers</a><br>
+ <a href="#serialdrivers">6.3.4 Serial Device Drivers</a>
+ </ul>
+ </ul>
<a href="#apndxconfigs">Appendix A: NuttX Configuration Settings</a><br>
<a href="#apndxtrademarks">Appendix B: Trademarks</a>
</ul>
@@ -1624,6 +1636,243 @@ extern void up_ledoff(int led);
<table width ="100%">
<tr bgcolor="#e4e4e4">
<td>
+ <h1><a name="DeviceDrivers">6.0 NuttX Device Drivers</a></h1>
+ </td>
+ </tr>
+</table>
+
+<p>
+ NuttX supports a variety of device drivers including:
+ <ul>
+ <li><i>Character</i> Device Drivers,</li>
+ <li><i>Block</i> Device Drivers, and</li>
+ <li>Other <i>Specialized</i> Drivers.</li>
+ </ul>
+ As discussed in the following paragraphs.
+</p>
+
+<h2><a name="chardrivers">6.1 Character Device Drivers</a></h2>
+
+<p>
+ Character device drivers have these properties:
+</p>
+<ul>
+ <li>
+ <b><code>include/nuttx/fs.h</code></b>.
+ All structures and APIs needed to work with character drivers are provided in this header file.
+ </li>
+ <li>
+ <b><code>struct file_operations</code></b>.
+ Each character device driver must implement an instance of <code>struct file_operations</code>.
+ That structure defines a call table with the following methods:
+ <ul>
+ <p><code>int open(FAR struct file *filp);</code></p>
+ <p><code>int close(FAR struct file *filp);</code></p>
+ <p><code>ssize_t read(FAR struct file *filp, FAR char *buffer, size_t buflen);</code></p>
+ <p><code>ssize_t write(FAR struct file *filp, FAR const char *buffer, size_t buflen);</code></p>
+ <p><code>off_t seek(FAR struct file *filp, off_t offset, int whence);</code></p>
+ <p><code>int ioctl(FAR struct file *filp, int cmd, unsigned long arg);</code></p>
+ <p><code>int poll(FAR struct file *filp, struct pollfd *fds, boolean setup);</code></p>
+ </ul>
+ </li>
+ <li>
+ <b><code>int register_driver(const char *path, const struct file_operations *fops, mode_t mode, void *priv);</code></b>.
+ Each character driver registers itself by calling <code>register_driver()</code>, passing it the
+ <code>path</code> where it will appear in the <a href="#NxFileSystem">pseudo-file-system</a> and it's
+ initialized instance of <code>struct file_operations</code>.
+ </li>
+ <li>
+ <b>User Access</b>.
+ After it has been registered, the character driver can be accessed by user code using the standard functions <code>open()</code>, <code>close()</code>, <code>read()</code>, <code>write()</code>, etc.
+ </li>
+ <li>
+ <b>Examples</b>.
+ <code>drivers/dev_null.c</code>, <code>drivers/fifo.c</code>, <code>drivers/serial.c</code>, etc.
+ </li>
+</ul>
+
+<h2><a name="blockdrivers">6.2 Block Device Drivers</a></h2>
+
+<p>
+ Block device drivers have these properties:
+</p>
+<ul>
+ <li>
+ <b><code>include/nuttx/fs.h</code></b>.
+ All structures and APIs needed to work with block drivers are provided in this header file.
+ </li>
+ <li>
+ <b><code>struct block_operations</code></b>.
+ Each block device driver must implement an instance of <code>struct block_operations</code>.
+ That structure defines a call table with the following methods:
+ <ul>
+ <p><code>int open(FAR struct inode *inode);</code></p>
+ <p><code>int close(FAR struct inode *inode);</code></p>
+ <p><code>ssize_t read(FAR struct inode *inode, FAR unsigned char *buffer, size_t start_sector, unsigned int nsectors);</code></p>
+ <p><code>ssize_t write(FAR struct inode *inode, FAR const unsigned char *buffer, size_t start_sector, unsigned int nsectors);</code></p>
+ <p><code>int geometry(FAR struct inode *inode, FAR struct geometry *geometry);</code></p>
+ <p><code>int ioctl(FAR struct inode *inode, int cmd, unsigned long arg);</code></p>
+ </ul>
+ </li>
+ <li>
+ <b><code>int register_blockdriver(const char *path, const struct block_operations *bops, mode_t mode, void *priv);</code></b>.
+ Each block driver registers itself by calling <code>register_blockdriver()</code>, passing it the
+ <code>path</code> where it will appear in the <a href="#NxFileSystem">pseudo-file-system</a> and it's
+ initialized instance of <code>struct block_operations</code>.
+ </li>
+ <li>
+ <b>User Access</b>.
+ Users do not normally access block drivers directly, rather, they access block drivers
+ indirectly through the <code>mount()</code> API.
+ The <code>mount()</code> API binds a block driver instance with a file system and with a mountpoint.
+ Then the user may use the block driver to access the file system on the underlying media.
+ <b>Example:</b> See the <code>cmd_mount()</code> implementation in <code>examples/nsh/nsh_fscmds.c</code>.
+ </li>
+ <li>
+ <b>Accessing a Character Driver as a Block Device</b>.
+ See the loop device at <code>drivers/loop.c</code>.
+ <b>Example:</b> See the <code>cmd_losetup()</code> implementation in <code>examples/nsh/nsh_fscmds.c</code>.
+ </li>
+ <li>
+ <b>Accessing a Block Driver as Character Device</b>.
+ See the Block-to-Character (BCH) conversion logic in <code>drivers/bch/</code>.
+ <b>Example:</b> See the <code>cmd_dd()</code> implementation in <code>examples/nsh/nsh_ddcmd.c</code>.
+ </li>
+ <li>
+ <b>Examples</b>.
+ <code>drivers/loop.c</code>, <code>drivers/mmcds/mmcsd_spi.c</code>, <code>drivers/ramdisk.c</code>, etc.
+ </li>
+</ul>
+
+<h2><a name="blockdrivers">6.3 Specialized Device Drivers</a></h2>
+
+<h3><a name="ethdrivers">6.3.1 Ethernet Device Drivers</a></h3>
+
+<ul>
+ <li>
+ <b><code>include/net/uip/uip-arch.h</code></b>.
+ All structures and APIs needed to work with Ethernet drivers are provided in this header file.
+ The structure <code>struct uip_driver_s</code> defines the interface and is passed to uIP via
+ <code>netdev_register()</code>.
+ </li>
+ <li>
+ <b><code>int netdev_register(FAR struct uip_driver_s *dev);</code></b>.
+ Each Eterhenet driver registers itself by calling <code>netdev_register()</code>.
+ </li>
+ <li>
+ <b>Examples</b>.
+ <code>drivers/net/dm90x0.c</code>, <code>arch/drivers/arm/src/c5471/c5471_ethernet.c</code>, <code>arch/z80/src/ez80/ez80_emac.c</code>, etc.
+ </li>
+</ul>
+
+<h3><a name="spidrivers">6.3.2 SPI Device Drivers</a></h3>
+
+<ul>
+ <li>
+ <b><code>include/nuttx/spi.h</code></b>.
+ All structures and APIs needed to work with SPI drivers are provided in this header file.
+ </li>
+ <li>
+ <b><code>struct spi_ops_s</code></b>.
+ Each SPI device driver must implement an instance of <code>struct spi_ops_s</code>.
+ That structure defines a call table with the following methods:
+ <ul>
+ <p><code>void select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, boolean selected);</code></p>
+ <p><code>uint32 setfrequency(FAR struct spi_dev_s *dev, uint32 frequency);</code></p>
+ <p><code>void setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode);</code></p>
+ <p><code>void setbits(FAR struct spi_dev_s *dev, int nbits);</code></p>
+ <p><code>ubyte status(FAR struct spi_dev_s *dev, enum spi_dev_e devid);</code></p>
+ <p><code>uint16 send(FAR struct spi_dev_s *dev, uint16 wd);</code></p>
+ <p><code>void exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer, FAR void *rxbuffer, size_t nwords);</code></p>
+ <p><codei>nt registercallback(FAR struct spi_dev_s *dev, mediachange_t callback, void *arg);</code></p>
+ </ul>
+ <li>
+ <b>Binding SPI Drivers</b>.
+ SPI drivers are not normally directly accessed by user code, but are usually bound to another,
+ higher level device driver.
+ See for example, <code>int mmcsd_spislotinitialize(int minor, int slotno, FAR struct spi_dev_s *spi)</code> in <code>drivers/mmcsd/mmcsd_spi.c</code>.
+ </li>
+ <li>
+ <b>Examples</b>.
+ <code>drivers/loop.c</code>, <code>drivers/mmcds/mmcsd_spi.c</code>, <code>drivers/ramdisk.c</code>, etc.
+ </li>
+</ul>
+
+<h3><a name="i2cdrivers">6.3.3 I2C Device Drivers</a></h3>
+
+<ul>
+ <li>
+ <b><code>include/nuttx/i2c.h</code></b>.
+ All structures and APIs needed to work with I2C drivers are provided in this header file.
+ </li>
+ <li>
+ <b><code>struct i2c_ops_s</code></b>.
+ Each I2C device driver must implement an instance of <code>struct i2c_ops_s</code>.
+ That structure defines a call table with the following methods:
+ <ul>
+ <p><code>uint32 setfrequency(FAR struct i2c_dev_s *dev, uint32 frequency);</code></p>
+ <p><code>int setaddress(FAR struct i2c_dev_s *dev, int addr, int nbits);</code></p>
+ <p><code>int write(FAR struct i2c_dev_s *dev, const ubyte *buffer, int buflen);</code></p>
+ <p><code>int read(FAR struct i2c_dev_s *dev, ubyte *buffer, int buflen);</code></p>
+ </ul>
+ <li>
+ <b>Binding I2C Drivers</b>.
+ SPI drivers are not normally directly accessed by user code, but are usually bound to another,
+ higher level device driver.
+ </li>
+ <li>
+ <b>Examples</b>.
+ <code>arch/z80/src/ez80/ez80_i2c.c</code>, <code>arch/z80/src/z8/z8_i2c.c</code>, etc.
+ </li>
+</ul>
+
+<h3><a name="serialdrivers">6.3.4 Serial Device Drivers</a></h3>
+
+<ul>
+ <li>
+ <b><code>include/nuttx/serial.h</code></b>.
+ All structures and APIs needed to work with serial drivers are provided in this header file.
+ </li>
+ <li>
+ <b><code>struct uart_ops_s</code></b>.
+ Each serial device driver must implement an instance of <code>struct uart_ops_s</code>.
+ That structure defines a call table with the following methods:
+ <ul>
+ <p><code>int setup(FAR struct uart_dev_s *dev);</code></p>
+ <p><code>void shutdown(FAR struct uart_dev_s *dev);</code></p>
+ <p><code>int attach(FAR struct uart_dev_s *dev);</code></p>
+ <p><code>void detach(FAR struct uart_dev_s *dev);</code></p>
+ <p><code>int ioctl(FAR struct file *filep, int cmd, unsigned long arg);</code></p>
+ <p><code>int receive(FAR struct uart_dev_s *dev, unsigned int *status);</code></p>
+ <p><code>void rxint(FAR struct uart_dev_s *dev, boolean enable);</code></p>
+ <p><code>boolean rxavailable(FAR struct uart_dev_s *dev);</code></p>
+ <p><code>void send(FAR struct uart_dev_s *dev, int ch);</code></p>
+ <p><code>void txint(FAR struct uart_dev_s *dev, boolean enable);</code></p>
+ <p><code>boolean txready(FAR struct uart_dev_s *dev);</code></p>
+ <p><code>boolean txempty(FAR struct uart_dev_s *dev);</code></p>
+ </ul>
+ </li>
+ <li>
+ <b><code>int uart_register(FAR const char *path, FAR uart_dev_t *dev);</code></b>.
+ A serial driver may register itself by calling <code>uart_register()</code>, passing it the
+ <code>path</code> where it will appear in the <a href="#NxFileSystem">pseudo-file-system</a> and it's
+ initialized instance of <code>struct uart_ops_s</code>.
+ By convention, serial device drivers are registered at pathes like <code>/dev/ttyS0</code>, <code>/dev/ttyS1</code>, etc.
+ See the <code>uart_register()</code> implementation in <code>drivers/serial.c</code>.
+ </li>
+ <li>
+ <b>User Access</b>.
+ Serial drivers are, ultimately, normal <a href="#chardrivers">character drivers</a> and are accessed as other character drivers.
+ </li>
+ <li>
+ <b>Examples</b>.
+ <code>arch/arm/src/chip/lm3s_serial.c</code>, <code>arch/arm/src/lpc214x/lpc214x_serial.c</code>, <code>arch/z16/src/z16f/z16f_serial.c</code>, etc.
+ </li>
+</ul>
+
+<table width ="100%">
+ <tr bgcolor="#e4e4e4">
+ <td>
<h1><a name="apndxconfigs">Appendix A: NuttX Configuration Settings</a></h1>
</td>
</tr>
@@ -2255,9 +2504,10 @@ extern void up_ledoff(int led);
</tr>
</table>
- <li>ARM, ARM7 ARM7TDMI, ARM9, ARM926EJS are trademarks of Advanced RISC Machines, Limited.</li>
+ <li>ARM, ARM7 ARM7TDMI, ARM9, ARM920T, ARM926EJS, Cortex-M3 are trademarks of Advanced RISC Machines, Limited.</li>
<li>Cygwin is a trademark of Red Hat, Incorporated.</li>
<li>Linux is a registered trademark of Linus Torvalds.</li>
+ <li>Eagle-100 is a trademark of <a href=" http://www.micromint.com/">Micromint USA, LLC</a>.
<li>LPC2148 is a trademark of NXP Semiconductors.</li>
<li>TI is a tradename of Texas Instruments Incorporated.</li>
<li>UNIX is a registered trademark of The Open Group.</li>
diff --git a/nuttx/arch/arm/src/arm/up_doirq.c b/nuttx/arch/arm/src/arm/up_doirq.c
index 948550904..ef5e7e1ee 100644
--- a/nuttx/arch/arm/src/arm/up_doirq.c
+++ b/nuttx/arch/arm/src/arm/up_doirq.c
@@ -72,33 +72,34 @@ void up_doirq(int irq, uint32 *regs)
#ifdef CONFIG_SUPPRESS_INTERRUPTS
PANIC(OSERR_ERREXCEPTION);
#else
- if ((unsigned)irq < NR_IRQS)
- {
- /* Current regs non-zero indicates that we are processing
- * an interrupt; current_regs is also used to manage
- * interrupt level context switches.
- */
+ /* Nested interrupts are not supported in this implementation. If you want
+ * implemented nested interrupts, you would have to (1) change the way that
+ * current regs is handled and (2) the design associated with
+ * CONFIG_ARCH_INTERRUPTSTACK.
+ */
- current_regs = regs;
+ /* Current regs non-zero indicates that we are processing an interrupt;
+ * current_regs is also used to manage interrupt level context switches.
+ */
- /* Mask and acknowledge the interrupt */
+ DEBUGASSERT(current_regs == NULL);
+ current_regs = regs;
- up_maskack_irq(irq);
+ /* Mask and acknowledge the interrupt */
- /* Deliver the IRQ */
+ up_maskack_irq(irq);
- irq_dispatch(irq, regs);
+ /* Deliver the IRQ */
- /* Indicate that we are no long in an interrupt handler */
+ irq_dispatch(irq, regs);
- current_regs = NULL;
+ /* Indicate that we are no long in an interrupt handler */
- /* Unmask the last interrupt (global interrupts are still
- * disabled.
- */
+ current_regs = NULL;
- up_enable_irq(irq);
- }
- up_ledoff(LED_INIRQ);
+ /* Unmask the last interrupt (global interrupts are still disabled) */
+
+ up_enable_irq(irq);
#endif
+ up_ledoff(LED_INIRQ);
}
diff --git a/nuttx/arch/arm/src/cortexm3/up_doirq.c b/nuttx/arch/arm/src/cortexm3/up_doirq.c
index 8c749ce5f..d6551153c 100644
--- a/nuttx/arch/arm/src/cortexm3/up_doirq.c
+++ b/nuttx/arch/arm/src/cortexm3/up_doirq.c
@@ -72,42 +72,43 @@ uint32 *up_doirq(int irq, uint32 *regs)
#ifdef CONFIG_SUPPRESS_INTERRUPTS
PANIC(OSERR_ERREXCEPTION);
#else
- if ((unsigned)irq < NR_IRQS)
- {
- /* Current regs non-zero indicates that we are processing
- * an interrupt; current_regs is also used to manage
- * interrupt level context switches.
- */
+ /* Nested interrupts are not supported in this implementation. If you want
+ * implemented nested interrupts, you would have to (1) change the way that
+ * current regs is handled and (2) the design associated with
+ * CONFIG_ARCH_INTERRUPTSTACK.
+ */
- current_regs = regs;
+ /* Current regs non-zero indicates that we are processing an interrupt;
+ * current_regs is also used to manage interrupt level context switches.
+ */
- /* Mask and acknowledge the interrupt */
+ DEBUGASSERT(current_regs == NULL);
+ current_regs = regs;
- up_maskack_irq(irq);
+ /* Mask and acknowledge the interrupt */
- /* Deliver the IRQ */
+ up_maskack_irq(irq);
- irq_dispatch(irq, regs);
+ /* Deliver the IRQ */
- /* If a context switch occurred while processing the interrupt
- * then current_regs may have change value. If we return any value
- * different from the input regs, then the lower level will know
- * that a context switch occurred during interrupt processing.
- */
+ irq_dispatch(irq, regs);
- regs = current_regs;
+ /* If a context switch occurred while processing the interrupt then
+ * current_regs may have change value. If we return any value different
+ * from the input regs, then the lower level will know that a context
+ * switch occurred during interrupt processing.
+ */
- /* Indicate that we are no long in an interrupt handler */
+ regs = current_regs;
- current_regs = NULL;
+ /* Indicate that we are no long in an interrupt handler */
- /* Unmask the last interrupt (global interrupts are still
- * disabled.
- */
+ current_regs = NULL;
- up_enable_irq(irq);
- }
- up_ledoff(LED_INIRQ);
+ /* Unmask the last interrupt (global interrupts are still disabled) */
+
+ up_enable_irq(irq);
#endif
+ up_ledoff(LED_INIRQ);
return regs;
}
diff --git a/nuttx/arch/arm/src/lm3s/chip.h b/nuttx/arch/arm/src/lm3s/chip.h
index 84e603d81..fc183575b 100644
--- a/nuttx/arch/arm/src/lm3s/chip.h
+++ b/nuttx/arch/arm/src/lm3s/chip.h
@@ -43,17 +43,27 @@
#include <nuttx/config.h>
#include <sys/types.h>
-#include "lm3s_memorymap.h" /* Memory map */
-#include "lm3s_syscontrol.h" /* System control module */
-#include "lm3s_gpio.h" /* GPIO module */
-#include "lm3s_uart.h" /* UART peripherals */
-#include "lm3s_ethernet.h" /* Ethernet MAC and PHY */
-#include "lm3s_flash.h" /* FLASH */
-
/************************************************************************************
* Definitions
************************************************************************************/
+/* Get customizations for each supported chip (only the LM3S6918 right now) */
+
+#ifdef CONFIG_ARCH_CHIP_LM3S6918
+# define LMS_NETHCONTROLLERS 1 /* One ethenet controller */
+#else
+# error "No Ethernet support for this LM3S chip"
+#endif
+
+/* Then get all of the register definitions */
+
+#include "lm3s_memorymap.h" /* Memory map */
+#include "lm3s_syscontrol.h" /* System control module */
+#include "lm3s_gpio.h" /* GPIO module */
+#include "lm3s_uart.h" /* UART peripherals */
+#include "lm3s_ethernet.h" /* Ethernet MAC and PHY */
+#include "lm3s_flash.h" /* FLASH */
+
/************************************************************************************
* Public Types
************************************************************************************/
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
index 84dadc700..cc8e3be37 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
+++ b/nuttx/arch/arm/src/lm3s/lm3s_ethernet.c
@@ -61,12 +61,6 @@
* Definitions
****************************************************************************/
-#ifdef CONFIG_ARCH_CHIP_LM3S6918
-# define LM3S_NINTERFACES 1
-#else
-# error "No Ethernet support for this LM3S chip"
-#endif
-
/* TX poll deley = 1 seconds. CLK_TCK is the number of clock ticks per second */
#define LM3S_WDDELAY (1*CLK_TCK)
@@ -78,12 +72,37 @@
/* This is a helper pointer for accessing the contents of the Ethernet header */
-#define BUF ((struct uip_eth_hdr *)priv->ld_dev.d_buf)
+#define ETHBUF ((struct uip_eth_hdr *)priv->ld_dev.d_buf)
+
+#define LM32S_MAX_MDCCLK 2500000
/****************************************************************************
* Private Types
****************************************************************************/
+/* EMAC statistics (debug only) */
+
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
+struct ez80mac_statistics_s
+{
+ uint32 rx_int; /* Number of Rx interrupts received */
+ uint32 rx_packets; /* Number of packets received (sum of the following): */
+ uint32 rx_ip; /* Number of Rx IP packets received */
+ uint32 rx_arp; /* Number of Rx ARP packets received */
+ uint32 rx_dropped; /* Number of dropped, unsupported Rx packets */
+ uint32 rx_pktsize; /* Number of dropped, too small or too bigr */
+ uint32 rx_errors; /* Number of Rx errors (reception error) */
+ uint32 rx_ovrerrors; /* Number of Rx FIFO overrun errors */
+ uint32 tx_int; /* Number of Tx interrupts received */
+ uint32 tx_packets; /* Number of Tx packets queued */
+ uint32 tx_errors; /* Number of Tx errors (transmission error)*/
+ uint32 tx_timeouts; /* Number of Tx timeout errors */
+};
+# define EMAC_STAT(priv,name) priv->ld_stat.name++
+#else
+# define EMAC_STAT(priv,name)
+#endif
+
/* The lm3s_driver_s encapsulates all state information for a single hardware
* interface
*/
@@ -94,7 +113,7 @@ struct lm3s_driver_s
* multiple Ethernet controllers.
*/
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
uint32 ld_base; /* Ethernet controller base address */
int ld-irq; /* Ethernet controller IRQ */
#endif
@@ -103,6 +122,10 @@ struct lm3s_driver_s
WDOG_ID ld_txpoll; /* TX poll timer */
WDOG_ID ld_txtimeout; /* TX timeout timer */
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
+ struct ez80mac_statistics_s ld_stat;
+#endif
+
/* This holds the information visible to uIP/NuttX */
struct uip_driver_s ld_dev; /* Interface understood by uIP */
@@ -112,7 +135,7 @@ struct lm3s_driver_s
* Private Data
****************************************************************************/
-static struct lm3s_driver_s g_lm3sdev[LM3S_NINTERFACES];
+static struct lm3s_driver_s g_lm3sdev[LMS_NETHCONTROLLERS];
/****************************************************************************
* Private Function Prototypes
@@ -120,38 +143,38 @@ static struct lm3s_driver_s g_lm3sdev[LM3S_NINTERFACES];
/* Miscellaneous low level helpers */
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
static uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset);
static void lm3s_ethout(struct lm3s_driver_s *priv, int offset, uint32 value);
#else
static inline uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset);
static inline void lm3s_ethout(struct lm3s_driver_s *priv, int offset, uint32 value);
#endif
-static void lm3s_ethreset(struct lm3s_driver_s *priv);
-static void lm3s_phywrite(struct lm3s_driver_s *priv, int regaddr, uint16 value);
+static void lm3s_ethreset(struct lm3s_driver_s *priv);
+static void lm3s_phywrite(struct lm3s_driver_s *priv, int regaddr, uint16 value);
static uint16 lm3s_phyread(struct lm3s_driver_s *priv, int regaddr);
/* Common TX logic */
-static int lm3s_transmit(struct lm3s_driver_s *priv);
-static int lm3s_uiptxpoll(struct uip_driver_s *dev);
+static int lm3s_transmit(struct lm3s_driver_s *priv);
+static int lm3s_uiptxpoll(struct uip_driver_s *dev);
/* Interrupt handling */
-static void lm3s_receive(struct lm3s_driver_s *priv);
-static void lm3s_txdone(struct lm3s_driver_s *priv);
-static int lm3s_interrupt(int irq, FAR void *context);
+static void lm3s_receive(struct lm3s_driver_s *priv);
+static void lm3s_txdone(struct lm3s_driver_s *priv);
+static int lm3s_interrupt(int irq, FAR void *context);
/* Watchdog timer expirations */
-static void lm3s_polltimer(int argc, uint32 arg, ...);
-static void lm3s_txtimeout(int argc, uint32 arg, ...);
+static void lm3s_polltimer(int argc, uint32 arg, ...);
+static void lm3s_txtimeout(int argc, uint32 arg, ...);
/* NuttX callback functions */
-static int lm3s_ifup(struct uip_driver_s *dev);
-static int lm3s_ifdown(struct uip_driver_s *dev);
-static int lm3s_txavail(struct uip_driver_s *dev);
+static int lm3s_ifup(struct uip_driver_s *dev);
+static int lm3s_ifdown(struct uip_driver_s *dev);
+static int lm3s_txavail(struct uip_driver_s *dev);
/****************************************************************************
* Private Functions
@@ -172,7 +195,7 @@ static int lm3s_txavail(struct uip_driver_s *dev);
*
****************************************************************************/
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
static uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset)
{
return getreg32(priv->ld_base + offset);
@@ -200,7 +223,7 @@ static inline uint32 lm3s_ethin(struct lm3s_driver_s *priv, int offset)
*
****************************************************************************/
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
static void lm3s_ethout(struct lm3s_driver_s *priv, int offset, uint32 value)
{
putreg32(value, priv->ld_base + offset);
@@ -233,9 +256,8 @@ static void lm3s_ethreset(struct lm3s_driver_s *priv)
irqstate_t flags;
uint32 regval;
volatile uint32 delay;
- uint32 div;
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
# error "If multiple interfaces are supported, this function would have to be redesigned"
#endif
@@ -282,20 +304,6 @@ static void lm3s_ethreset(struct lm3s_driver_s *priv)
regval = lm3s_ethin(priv, LM3S_MAC_RIS_OFFSET);
lm3s_ethout(priv, LM3S_MAC_IACK_OFFSET, regval);
-
- /* Set the management clock divider register for access to the PHY
- * register set. The MDC clock is divided down from the system clock per:
- *
- * MCLK_FREQUENCY = SYSCLK_FREQUENCY / (2 * (div + 1))
- * div = (SYSCLK_FREQUENCY / 2 / MCLK_FREQUENCY) - 1
- *
- * Where MCLK_FREQUENCY is 2,500,000. We will add 1 to assure the max
- * MCLK_FREQUENCY is not exceeded.
- */
-
- div = SYSCLK_FREQUENCY / 2 / 2500000;
- lm3s_ethout(priv, LM3S_MAC_MDV_OFFSET, div);
- nvdbg("MDV: %08x\n", div);
irqrestore(flags);
}
@@ -440,25 +448,119 @@ static int lm3s_uiptxpoll(struct uip_driver_s *dev)
static void lm3s_receive(struct lm3s_driver_s *priv)
{
- do
+ uint32 regval;
+ ubyte *dbuf;
+ int pktlen;
+ int bytesleft;
+
+ /* Loop while there are incoming packets to be processed */
+
+ while ((lm3s_ethin(priv, LM3S_MAC_NP_OFFSET) & MAC_NP_MASK) != 0)
{
- /* Check for errors and update statistics */
-#warning "Missing logic"
+ /* Update statistics */
- /* Check if the packet is a valid size for the uIP buffer configuration */
+ EMAC_STAT(priv, rx_packets);
/* Copy the data data from the hardware to priv->ld_dev.d_buf. Set
* amount of data in priv->ld_dev.d_len
*/
+ dbuf = priv->ld_dev.d_buf;
+
+ /* The packet frame length begins in the LS 16-bits of the first
+ * word from the FIFO followed by the Ethernet header beginning
+ * in the MS 16-bits of the first word.
+ *
+ * Pick off the packet length from the first word.
+ */
+
+ regval = lm3s_ethin(priv, LM3S_MAC_DATA_OFFSET);
+ pktlen = (int)(regval & 0x0000ffff);
+
+ /* Check if the pktlen is valid. It should be large enough to
+ * hold an Ethernet header and small enough to fit entirely in
+ * the I/O buffer.
+ */
+
+ if (pktlen > CONFIG_NET_BUFSIZE || pktlen <= UIP_LLH_LEN)
+ {
+ int wordlen;
+
+ /* We will have to drop this packet */
+
+ EMAC_STAT(priv, rx_pktsize);
+
+ /* This is the number of bytes and words left to read (including,
+ * the final, possibly partial word).
+ */
+
+ wordlen = (pktlen + 1) >> 4;
+
+ /* Read and discard the remaining words in the FIFO */
+
+ while (wordlen--)
+ {
+ (void)lm3s_ethin(priv, LM3S_MAC_DATA_OFFSET);
+ }
+
+ /* Check for another packet */
+
+ continue;
+ }
+
+ /* Save the first two bytes from the first word */
+
+ *dbuf++ = (ubyte)((regval >> 16) & 0xff);
+ *dbuf++ = (ubyte)((regval >> 24) & 0xff);
+ bytesleft = pktlen - 2;
+
+ /* Read all of the whole, 32-bit values in the middle of the packet */
+
+ for (; bytesleft > 3; bytesleft -= 4, dbuf += 4)
+ {
+ /* Read a whole word */
+
+ *(uint32*)dbuf = lm3s_ethin(priv, LM3S_MAC_DATA_OFFSET);
+ }
+
+ /* Handle the last, partial word in the FIFO */
+
+ if (bytesleft > 0)
+ {
+ /* Read the last word */
+
+ regval = lm3s_ethin(priv, LM3S_MAC_DATA_OFFSET);
+ switch (bytesleft)
+ {
+ case 0:
+ default:
+ break;
+
+ case 3:
+ dbuf[2] = (regval >> 16) & 0xff;
+ case 2:
+ dbuf[1] = (regval >> 8) & 0xff;
+ case 1:
+ dbuf[0] = regval & 0xff;
+ break;
+ }
+ }
+
+ /* Pass the packet length to uIP */
+
+ priv->ld_dev.d_len = pktlen;
+
/* We only accept IP packets of the configured type and ARP packets */
#ifdef CONFIG_NET_IPv6
- if (BUF->type == HTONS(UIP_ETHTYPE_IP6))
+ if (ETHBUF->type == HTONS(UIP_ETHTYPE_IP6))
#else
- if (BUF->type == HTONS(UIP_ETHTYPE_IP))
+ if (ETHBUF->type == HTONS(UIP_ETHTYPE_IP))
#endif
{
+ nvdbg("IP packet received (%02x)\n", ETHBUF->type);
+ EMAC_STAT(priv, rx_ip);
+
uip_arp_ipin();
uip_input(&priv->ld_dev);
@@ -472,8 +574,11 @@ static void lm3s_receive(struct lm3s_driver_s *priv)
lm3s_transmit(priv);
}
}
- else if (BUF->type == htons(UIP_ETHTYPE_ARP))
+ else if (ETHBUF->type == htons(UIP_ETHTYPE_ARP))
{
+ nvdbg("ARP packet received (%02x)\n", ETHBUF->type);
+ EMAC_STAT(priv, rx_arp);
+
uip_arp_arpin(&priv->ld_dev);
/* If the above function invocation resulted in data that should be
@@ -485,6 +590,13 @@ static void lm3s_receive(struct lm3s_driver_s *priv)
lm3s_transmit(priv);
}
}
+#ifdef CONFIG_DEBUG
+ else
+ {
+ ndbg("Unsupported packet type dropped (%02x)\n", ETHBUF->type);
+ EMAC_STAT(priv, rx_dropped);
+ }
+#endif
}
while ( /* FIX ME */ TRUE /* FIX ME */); /* While there are more packets to be processed */
}
@@ -539,27 +651,64 @@ static void lm3s_txdone(struct lm3s_driver_s *priv)
static int lm3s_interrupt(int irq, FAR void *context)
{
register struct lm3s_driver_s *priv;
+ uint32 ris;
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
# error "A mechanism to associate and interface with an IRQ is needed"
#else
priv = &g_lm3sdev[0];
#endif
- /* Disable Ethernet interrupts */
-#warning "Missing logic"
+ /* Read the raw interrupt status register */
- /* Get and clear interrupt status bits */
+ ris = lm3s_ethin(priv, LM3S_MAC_RIS_OFFSET);
- /* Handle interrupts according to status bit settings */
+ /* Clear all pending interrupts */
- /* Check if we received an incoming packet, if so, call lm3s_receive() */
+ lm3s_ethout(priv, LM3S_MAC_IACK_OFFSET, ris);
- lm3s_receive(priv);
+ /* Check for errors */
- /* Check is a packet transmission just completed. If so, call lm3s_txdone */
+#if defined(CONFIG_DEBUG) && defined(CONFIG_DEBUG_NET)
+ if ((ris & MAC_RIS_TXER) != 0)
+ {
+ EMAC_STAT(priv, tx_errors); /* Number of Tx errors */
+ }
- lm3s_txdone(priv);
+ if ((ris & MAC_RIS_FOV) != 0)
+ {
+ EMAC_STAT(priv, rx_ovrerrors); /* Number of Rx FIFO overrun errors */
+ }
+
+ if ((ris & MAC_RIS_RXER) != 0)
+ {
+ EMAC_STAT(priv, rx_errors); /* Number of Rx errors */
+ }
+#endif
+
+ /* Handle (unmasked) interrupts according to status bit settings */
+
+ ris &= lm3s_ethin(priv, LM3S_MAC_IM_OFFSET);
+
+ /* Is this an Rx interrupt (meaning that a packet has been received)? */
+
+ if ((ris & MAC_RIS_RXINT) != 0)
+ {
+ /* Handle the incoming packet */
+
+ EMAC_STAT(priv, rx_int);
+ lm3s_receive(priv);
+ }
+
+ /* Is this an Tx interrupt (meaning that the Tx FIFO is empty)? */
+
+ if ((ris & MAC_RIS_TXEMP) != 0)
+ {
+ /* Handle the complete of the transmission */
+
+ EMAC_STAT(priv, tx_int);
+ lm3s_txdone(priv);
+ }
/* Enable Ethernet interrupts (perhaps excluding the TX done interrupt if
* there are no pending transmissions.
@@ -591,7 +740,8 @@ static void lm3s_txtimeout(int argc, uint32 arg, ...)
struct lm3s_driver_s *priv = (struct lm3s_driver_s *)arg;
/* Increment statistics and dump debug info */
-#warning "Missing logic"
+
+ EMAC_STAT(priv, tx_timeouts);
/* Then reset the hardware */
@@ -655,6 +805,7 @@ static int lm3s_ifup(struct uip_driver_s *dev)
struct lm3s_driver_s *priv = (struct lm3s_driver_s *)dev->d_private;
irqstate_t flags;
uint32 regval;
+ uint32 div;
uint16 phyreg;
ndbg("Bringing up: %d.%d.%d.%d\n",
@@ -666,6 +817,20 @@ static int lm3s_ifup(struct uip_driver_s *dev)
flags = irqsave();
lm3s_ethreset(priv);
+ /* Set the management clock divider register for access to the PHY
+ * register set. The MDC clock is divided down from the system clock per:
+ *
+ * MDCCLK_FREQUENCY = SYSCLK_FREQUENCY / (2 * (div + 1))
+ * div = (SYSCLK_FREQUENCY / 2 / MDCCLK_FREQUENCY) - 1
+ *
+ * Where the maximum value for MDCCLK_FREQUENCY is 2,500,000. We will
+ * add 1 to assure the max LM32S_MAX_MDCCLK is not exceeded.
+ */
+
+ div = SYSCLK_FREQUENCY / 2 / LM32S_MAX_MDCCLK;
+ lm3s_ethout(priv, LM3S_MAC_MDV_OFFSET, div);
+ nvdbg("MDV: %08x\n", div);
+
/* Then configure the Ethernet Controller for normal operation
*
* Setup the transmit control register (Full duplex, TX CRC Auto Generation,
@@ -721,8 +886,8 @@ static int lm3s_ifup(struct uip_driver_s *dev)
/* Enable the Ethernet receiver */
- regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET);
- regval |= MAC_RCTL_RXEN;
+ regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET);
+ regval |= MAC_RCTL_RXEN;
lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval);
/* Enable the Ethernet transmitter */
@@ -739,7 +904,7 @@ static int lm3s_ifup(struct uip_driver_s *dev)
/* Enable the Ethernet interrupt */
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
up_enable_irq(priv->irq);
#else
up_enable_irq(LM3S_IRQ_ETHCON);
@@ -776,7 +941,8 @@ static int lm3s_ifup(struct uip_driver_s *dev)
* Function: lm3s_ifdown
*
* Description:
- * NuttX Callback: Stop the interface.
+ * NuttX Callback: Stop the interface. The only way to restore normal
+ * behavior is to call lm3s_ifup().
*
* Parameters:
* dev - Reference to the NuttX driver state structure
@@ -792,22 +958,58 @@ static int lm3s_ifdown(struct uip_driver_s *dev)
{
struct lm3s_driver_s *priv = (struct lm3s_driver_s *)dev->d_private;
irqstate_t flags;
+ uint32 regval;
- /* Disable the Ethernet interrupt */
+ /* Cancel the TX poll timer and TX timeout timers */
flags = irqsave();
-#if LM3S_NINTERFACES > 1
+ wd_cancel(priv->ld_txpoll);
+ wd_cancel(priv->ld_txtimeout);
+
+ /* Disable the Ethernet interrupt */
+
+#if LMS_NETHCONTROLLERS > 1
up_disable_irq(priv->irq);
#else
up_disable_irq(LM3S_IRQ_ETHCON);
#endif
- /* Cancel the TX poll timer and TX timeout timers */
+ /* Disable all Ethernet controller interrupt sources */
- wd_cancel(priv->ld_txpoll);
- wd_cancel(priv->ld_txtimeout);
+ regval = lm3s_ethin(priv, LM3S_MAC_IM_OFFSET);
+ regval &= ~MAC_IM_ALLINTS;
+ lm3s_ethout(priv, LM3S_MAC_IM_OFFSET, regval);
- /* Reset the device */
+ /* Reset the receive FIFO */
+
+ regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET);
+ regval |= MAC_RCTL_RSTFIFO;
+ lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval);
+
+ /* Disable the Ethernet receiver */
+
+ regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET);
+ regval &= ~MAC_RCTL_RXEN;
+ lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval);
+
+ /* Disable the Ethernet transmitter */
+
+ regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET);
+ regval &= ~MAC_TCTL_TXEN;
+ lm3s_ethout(priv, LM3S_MAC_TCTL_OFFSET, regval);
+
+ /* Reset the receive FIFO (again) */
+
+ regval = lm3s_ethin(priv, LM3S_MAC_RCTL_OFFSET);
+ regval |= MAC_RCTL_RSTFIFO;
+ lm3s_ethout(priv, LM3S_MAC_RCTL_OFFSET, regval);
+
+ /* Clear any pending interrupts */
+
+ regval = lm3s_ethin(priv, LM3S_MAC_RIS_OFFSET);
+ lm3s_ethout(priv, LM3S_MAC_IACK_OFFSET, regval);
+
+ /* The interface is now DOWN */
priv->ld_bifup = FALSE;
irqrestore(flags);
@@ -876,9 +1078,7 @@ static int lm3s_txavail(struct uip_driver_s *dev)
*
****************************************************************************/
-/* Initialize the Ethernet controller and driver */
-
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
int lm3s_initialize(int intf)
#else
static inline int lm3s_initialize(int intf)
@@ -889,12 +1089,12 @@ static inline int lm3s_initialize(int intf)
/* Check if the Ethernet module is present */
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
# error "This debug check only works with one interface"
#else
DEBUGASSERT((getreg32(LM3S_SYSCON_DC4) & (SYSCON_DC4_EMAC0|SYSCON_DC4_EPHY0)) == (SYSCON_DC4_EMAC0|SYSCON_DC4_EPHY0));
#endif
- DEBUGASSERT((unsigned)intf < LM3S_NINTERFACES);
+ DEBUGASSERT((unsigned)intf < LMS_NETHCONTROLLERS);
/* Initialize the driver structure */
@@ -902,11 +1102,11 @@ static inline int lm3s_initialize(int intf)
priv->ld_dev.d_ifup = lm3s_ifup; /* I/F down callback */
priv->ld_dev.d_ifdown = lm3s_ifdown; /* I/F up (new IP address) callback */
priv->ld_dev.d_txavail = lm3s_txavail; /* New TX data callback */
- priv->ld_dev.d_private = (void*)&g_lm3sdev[0]; /* Used to recover private state from dev */
+ priv->ld_dev.d_private = (void*)priv; /* Used to recover private state from dev */
/* Create a watchdog for timing polling for and timing of transmisstions */
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
# error "A mechanism to associate base address an IRQ with an interface is needed"
priv->ld_base = ??; /* Ethernet controller base address */
priv->ld_irq = ??; /* Ethernet controller IRQ number */
@@ -929,10 +1129,11 @@ static inline int lm3s_initialize(int intf)
*/
lm3s_ethreset(priv);
+ lm3s_ifdown(&priv->ld_dev);
/* Attach the IRQ to the driver */
-#if LM3S_NINTERFACES > 1
+#if LMS_NETHCONTROLLERS > 1
ret = irq_attach(priv->irq, lm3s_interrupt);
#else
ret = irq_attach(LM3S_IRQ_ETHCON, lm3s_interrupt);
@@ -955,14 +1156,18 @@ static inline int lm3s_initialize(int intf)
* Name: up_netinitialize
*
* Description:
- * Initialize the first network interface
+ * Initialize the first network interface. If there are more than one interface
+ * in the chip, then board-specific logic will have to provide this function to
+ * determine which, if any, Ethernet controllers should be initialized.
*
************************************************************************************/
+#if LMS_NETHCONTROLLERS == 1
void up_netinitialize(void)
{
(void)lm3s_initialize(0);
}
+#endif
#endif /* CONFIG_NET && CONFIG_LM3S_ETHERNET */
diff --git a/nuttx/arch/arm/src/lm3s/lm3s_internal.h b/nuttx/arch/arm/src/lm3s/lm3s_internal.h
index 0408fe81d..6640241e6 100644
--- a/nuttx/arch/arm/src/lm3s/lm3s_internal.h
+++ b/nuttx/arch/arm/src/lm3s/lm3s_internal.h
@@ -44,8 +44,7 @@
#include <sys/types.h>
#include "up_internal.h"
-#include "lm3s_memorymap.h"
-#include "lm3s_gpio.h"
+#include "chip.h"
/************************************************************************************
* Definitions
@@ -290,6 +289,29 @@ EXTERN boolean lm3s_gpioread(uint32 pinset, boolean value);
EXTERN int weak_function gpio_irqinitialize(void);
+/****************************************************************************
+ * Function: lm3s_initialize
+ *
+ * Description:
+ * Initialize the Ethernet driver for one interface. If the LM3S chip
+ * supports multiple Ethernet controllers, then bould specific logic
+ * must implement up_netinitialize() and call this function to initialize
+ * the desiresed interfaces.
+ *
+ * Parameters:
+ * None
+ *
+ * Returned Value:
+ * OK on success; Negated errno on failure.
+ *
+ * Assumptions:
+ *
+ ****************************************************************************/
+
+#if LMS_NETHCONTROLLERS > 1
+EXTERN int lm3s_initialize(int intf);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/arch/z80/src/ez80/ez80_emac.c b/nuttx/arch/z80/src/ez80/ez80_emac.c
index df550b715..4aff6f553 100644
--- a/nuttx/arch/z80/src/ez80/ez80_emac.c
+++ b/nuttx/arch/z80/src/ez80/ez80_emac.c
@@ -1179,7 +1179,7 @@ static int ez80emac_receive(struct ez80emac_driver_s *priv)
EMAC_STAT(priv, rx_packets);
/* Skip over bad packers */
-
+
if ((rxdesc->stat & EMAC_RXDESC_OK) == 0)
{
nvdbg("Skipping bad RX pkt: %04x\n", rxdesc->stat);
@@ -1381,7 +1381,7 @@ static int ez80emac_txinterrupt(int irq, FAR void *context)
if (!priv->txhead)
{
nvdbg("No pending Tx.. Stopping XMIT function.\n");
-
+
/* Stop the Tx poll timer. (It will get restarted when we have
* something to send
*/
@@ -1406,7 +1406,7 @@ static int ez80emac_txinterrupt(int irq, FAR void *context)
wd_cancel(priv->txtimeout);
}
-
+
return OK;
}
diff --git a/nuttx/configs/eagle100/README.txt b/nuttx/configs/eagle100/README.txt
index 5ca6e05e5..61cbf3d85 100644
--- a/nuttx/configs/eagle100/README.txt
+++ b/nuttx/configs/eagle100/README.txt
@@ -1,6 +1,21 @@
README
^^^^^^
+References:
+^^^^^^^^^^
+
+ Micromint: http://www.micromint.com/
+ Luminary: http://www.luminarymicro.com/
+
+Development Environment
+^^^^^^^^^^^^^^^^^^^^^^^
+
+ Either Linux or Cygwin on Windows can be used for the development environment.
+ The source has been built only using the GNU toolchain (see below). Other
+ toolchains will likely cause problems. Testing was performed using the Cygwin
+ environment because the Luminary FLASH programming application was used for
+ writing to FLASH and this application works only under Windows.
+
Toolchain
^^^^^^^^^
@@ -43,8 +58,10 @@ Ethernet-Bootloader
Here are some notes about using the Luminary Ethernet boot-loader built
into the Eagle-100 board.
+ Built-In Application:
+
- The board has no fixed IP address but uses DHCP to get an address.
- I use a D-link router; I can use a web browser to surf to the D-link
+ I used a D-link router; I can use a web browser to surf to the D-link
web page to get the address assigned by
- Then you can use this IP address in your browser to surf to the Eagle-100
@@ -52,15 +69,22 @@ Ethernet-Bootloader
the page called "Firmware Update". That page includes instructions on
how to download code to the Eagle-100.
+ - After you burn the first program, you lose this application. Then you
+ will probably be better off connected directly to the Eagle-100 board
+ or through a switch (The router caused problems for me during downloads).
+
+ Using the Ethernet Bootloader:
+
- You will need the "LM Flash Programmer application". You can get that
program from the Luminary web site. There is a link on the LM3S6918 page.
- Is there any documentation for using the bootloader? Yes and No: There
is an application note covering the bootloader on the Luminary site, but
- it is not very informative.
+ it is not very informative. The Eagle100 User's Manual has the best
+ information.
- Are there any special things I have to do in my code, other than setting
- the origin to 0x0000:2000 (APP_START_ADDRESS)? No. The bootload assumes
+ the origin to 0x0000:2000 (APP_START_ADDRESS)? No. The bootloader assumes
that you have a vector table at that address . The bootloader does the
following each time it boots (after you have downloaded the first valid
application):
@@ -75,6 +99,16 @@ Ethernet-Bootloader
Eagle-100 board while resetting the board. The user button is GPIOA, pin 6
(call FORCED_UPDATE_PIN in the bootloader code).
+ - Note 1: I had to remove my D-Link router from the configuration in order
+ to use the LM Flash Programmer (the Bootloader issues BOOTP requests to
+ communicate with the LM Flash Programmer, my router was responding to
+ these BOOTP requests and hosing the download). It is safer to connect
+ via a switch or via an Ethernet switch.
+
+ - Note 2: You don't need the router's DHCPD server in the download
+ configuration; the Luminary Flash Programmer has the capability of
+ temporarily assigning the IP address to the Eagle-100 via BOOTP.
+
Eagle100-specific Configuration Options
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
@@ -185,8 +219,23 @@ can be selected as follow:
Where <subdir> is one of the following:
+nettest
+^^^^^^^
+
+This configuration directory may be used to enable networking using the
+LM3S6918's Ethernet controller. It uses examples/nettest to excercise the
+TCP/IP network.
+
+nsh
+^^^
+
+Configures the NuttShell (nsh) located at examples/nsh. The
+Configuration enables both the serial and telnetd NSH interfaces.
+
ostest
^^^^^^
This configuration directory, performs a simple OS test using
examples/ostest.
+
+