summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/TODO11
-rw-r--r--nuttx/arch/z16/src/z16f/z16f_serial.c55
-rw-r--r--nuttx/include/nuttx/arch.h6
-rw-r--r--nuttx/lib/lib_fflush.c56
4 files changed, 66 insertions, 62 deletions
diff --git a/nuttx/TODO b/nuttx/TODO
index 4ef87b23c..e5a4b51d1 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -21,7 +21,7 @@ NuttX TODO List (Last updated January 6, 2008)
(2) ARM/LPC214x (arch/arm/src/lpc214x/)
(4) pjrc-8052 / MCS51 (arch/pjrc-8051/)
(2) z80 (arch/z80/)
- (1) z16 (arch/z16/)
+ (2) z16 (arch/z16/)
o Task/Scheduler (sched/)
^^^^^^^^^^^^^^^^^^^^^^^
@@ -373,3 +373,12 @@ o z16 (arch/z16)
Status: Open
Priority: Low, thought to be cosmetic. I think this is a consequence of
replacing vs. inserting the library.
+
+ Description: When the interrupt-driven serial driver is used, the system
+ hangs. This is because of TX ready (TRDE) interrupts that
+ get lost while interrupts are disabled. The existing
+ serial driver appears to be limited to hardware with a
+ latching, level-sensitive TX ready interrupt.
+ Status: Open
+ Priority: Medium. A polled, write-only serial driver is used in the
+ interim for system testing.
diff --git a/nuttx/arch/z16/src/z16f/z16f_serial.c b/nuttx/arch/z16/src/z16f/z16f_serial.c
index cf44618f4..ce40a497f 100644
--- a/nuttx/arch/z16/src/z16f/z16f_serial.c
+++ b/nuttx/arch/z16/src/z16f/z16f_serial.c
@@ -68,6 +68,10 @@
extern _Erom unsigned long SYS_CLK_FREQ;
#define _DEFCLK ((unsigned long)&SYS_CLK_FREQ)
+#define STATE_DISABLED 0
+#define STATE_RXENABLED 1
+#define STATE_TXENABLED 2
+
/****************************************************************************
* Private Types
****************************************************************************/
@@ -246,7 +250,8 @@ static ubyte z16f_disableuartirq(struct uart_dev_s *dev)
{
struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv;
irqstate_t flags = irqsave();
- ubyte state = priv->rxenabled ? 1 : 0 | priv->txenabled ? 2 : 0;
+ ubyte state = priv->rxenabled ? STATE_RXENABLED : STATE_DISABLED | \
+ priv->txenabled ? STATE_TXENABLED : STATE_DISABLED;
z16f_txint(dev, FALSE);
z16f_rxint(dev, FALSE);
@@ -264,27 +269,29 @@ static void z16f_restoreuartirq(struct uart_dev_s *dev, ubyte state)
struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv;
irqstate_t flags = irqsave();
- z16f_txint(dev, (state & 2) ? TRUE : FALSE);
- z16f_rxint(dev, (state & 1) ? TRUE : FALSE);
+ z16f_txint(dev, (state & STATE_TXENABLED) ? TRUE : FALSE);
+ z16f_rxint(dev, (state & STATE_RXENABLED) ? TRUE : FALSE);
irqrestore(flags);
}
/****************************************************************************
- * Name: z16f_waittx
+ * Name: z16f_consoleput
****************************************************************************/
-static void z16f_waittx(struct uart_dev_s *dev, boolean (*status)(struct uart_dev_s *))
+static void z16f_consoleput(ubyte ch)
{
+ struct z16f_uart_s *priv = (struct z16f_uart_s*)CONSOLE_DEV.priv;
int tmp;
for (tmp = 1000 ; tmp > 0 ; tmp--)
{
- if (status(dev))
+ if (z16f_txready(&CONSOLE_DEV))
{
break;
}
}
+ putreg8(ch, priv->uartbase + Z16F_UART_TXD);
}
/****************************************************************************
@@ -379,23 +386,16 @@ static int z16f_attach(struct uart_dev_s *dev)
/* Attach the RX IRQ */
ret = irq_attach(priv->rxirq, z16f_rxinterrupt);
- if (ret != OK)
+ if (ret == OK)
{
- goto errout;
- }
+ /* Attach the TX IRQ */
- /* Attach the TX IRQ */
-
- ret = irq_attach(priv->txirq, z16f_txinterrupt);
- if (ret != OK)
- {
- goto errout_with_rxirq;
+ ret = irq_attach(priv->txirq, z16f_txinterrupt);
+ if (ret != OK)
+ {
+ irq_detach(priv->rxirq);
+ }
}
- return OK;
-
-errout_with_rxirq:
- irq_detach(priv->rxirq);
-errout:
return ret;
}
@@ -598,7 +598,7 @@ static boolean z16f_rxavailable(struct uart_dev_s *dev)
static void z16f_send(struct uart_dev_s *dev, int ch)
{
struct z16f_uart_s *priv = (struct z16f_uart_s*)dev->priv;
- putreg8(ch, priv->uartbase + Z16F_UART1_TXD);
+ putreg8(ch, priv->uartbase + Z16F_UART_TXD);
}
/****************************************************************************
@@ -707,7 +707,6 @@ void up_serialinit(void)
int up_putc(int ch)
{
- struct z16f_uart_s *priv = (struct z16f_uart_s*)CONSOLE_DEV.priv;
ubyte state;
/* Keep interrupts disabled so that we do not interfere with normal
@@ -722,20 +721,18 @@ int up_putc(int ch)
{
/* Add CR before LF */
- z16f_waittx(&CONSOLE_DEV, z16f_txready);
- putreg8('\r', priv->uartbase + Z16F_UART_TXD);
+ z16f_consoleput('\r');
}
/* Output the character */
- z16f_waittx(&CONSOLE_DEV, z16f_txready);
- putreg8((ubyte)ch, priv->uartbase + Z16F_UART_TXD);
+ z16f_consoleput((ubyte)ch);
- /* Now wait for all queue TX data to drain before restoring interrupts. The
- * driver should receive one txdone interrupt which it may or may not ignore.
+ /* It is important to restore the TX interrupt while the send is pending.
+ * otherwise, TRDE interrupts can be lost since they do not pend after the
+ * TRDE false->true transition.
*/
- z16f_waittx(&CONSOLE_DEV, z16f_txempty);
z16f_restoreuartirq(&CONSOLE_DEV, state);
return ch;
}
diff --git a/nuttx/include/nuttx/arch.h b/nuttx/include/nuttx/arch.h
index aca7c299b..3eef7b15d 100644
--- a/nuttx/include/nuttx/arch.h
+++ b/nuttx/include/nuttx/arch.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -460,9 +460,7 @@ EXTERN void up_udelay(unsigned int microseconds);
*
****************************************************************************/
-# ifdef CONFIG_ARCH_LOWPUTC
EXTERN int up_putc(int ch);
-#endif
#undef EXTERN
#ifdef __cplusplus
diff --git a/nuttx/lib/lib_fflush.c b/nuttx/lib/lib_fflush.c
index 1af9305fb..c9751df61 100644
--- a/nuttx/lib/lib_fflush.c
+++ b/nuttx/lib/lib_fflush.c
@@ -1,7 +1,7 @@
-/************************************************************
+/****************************************************************************
* lib_fflush.c
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -14,7 +14,7 @@
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
- * 3. Neither the name Gregory Nutt nor the names of its contributors may be
+ * 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.
*
@@ -31,15 +31,15 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Compilation Switches
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h> /* for CONFIG_STDIO_BUFFER_SIZE */
#include <stdio.h>
@@ -49,44 +49,44 @@
#include <nuttx/fs.h>
#include "lib_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Type Declarations
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Constant Data
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Constant Data
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Name: lib_fflushall
*
* Description:
* Called by the OS when a task exits
- ************************************************************/
+ ****************************************************************************/
void lib_flushall(FAR struct streamlist *list)
{
@@ -115,9 +115,9 @@ void lib_flushall(FAR struct streamlist *list)
}
}
-/************************************************************
+/****************************************************************************
* Name: fflush
- ************************************************************/
+ ****************************************************************************/
int fflush(FILE *stream)
{