summaryrefslogtreecommitdiff
path: root/nuttx/configs/z80sim/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-12-31 23:52:53 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-12-31 23:52:53 +0000
commit768b31742994a7270a11f6b0393329b3404b2af0 (patch)
tree07225e24cd679bcd042f722dc39514fa90ba541c /nuttx/configs/z80sim/src
parente56f12fd3dbddb72e0a3996a1247d27bad227cd5 (diff)
downloadpx4-nuttx-768b31742994a7270a11f6b0393329b3404b2af0.tar.gz
px4-nuttx-768b31742994a7270a11f6b0393329b3404b2af0.tar.bz2
px4-nuttx-768b31742994a7270a11f6b0393329b3404b2af0.zip
Debug NSH on z80sim
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@474 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/z80sim/src')
-rw-r--r--nuttx/configs/z80sim/src/z80_lowputc.c3
-rw-r--r--nuttx/configs/z80sim/src/z80_serial.c60
2 files changed, 38 insertions, 25 deletions
diff --git a/nuttx/configs/z80sim/src/z80_lowputc.c b/nuttx/configs/z80sim/src/z80_lowputc.c
index ead9aa455..4996272f9 100644
--- a/nuttx/configs/z80sim/src/z80_lowputc.c
+++ b/nuttx/configs/z80sim/src/z80_lowputc.c
@@ -38,12 +38,13 @@
********************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
#include <nuttx/irq.h>
#include <nuttx/arch.h>
#include <assert.h>
#include <debug.h>
-#include "up_arch.h"
+
#include "os_internal.h"
#include "up_internal.h"
diff --git a/nuttx/configs/z80sim/src/z80_serial.c b/nuttx/configs/z80sim/src/z80_serial.c
index dbca1b78e..9a8fa0f89 100644
--- a/nuttx/configs/z80sim/src/z80_serial.c
+++ b/nuttx/configs/z80sim/src/z80_serial.c
@@ -86,41 +86,52 @@ static boolean up_txfifoempty(struct uart_dev_s *dev);
struct uart_ops_s g_uart_ops =
{
- .setup = up_setup,
- .shutdown = up_shutdown,
- .handler = up_interrupt,
- .ioctl = up_ioctl,
- .receive = up_receive,
- .rxint = up_rxint,
- .rxfifonotempty = up_rxfifonotempty,
- .send = up_send,
- .txint = up_txint,
- .txfifonotfull = up_txfifonotfull,
- .txfifoempty = up_txfifoempty,
+ up_setup, /* setup */
+ up_shutdown, /* shutdown */
+ up_interrupt, /* handler */
+ up_ioctl, /* ioctl */
+ up_receive, /* receive */
+ up_rxint, /* rxint */
+ up_rxfifonotempty, /* rxfifonotempty */
+ up_send, /* send */
+ up_txint, /* txint */
+ up_txfifonotfull, /* txfifonotfull */
+ up_txfifoempty, /* txfifoempty */
};
/* I/O buffers */
-static char g_uartrxbuffer[CONFIG_UART0_RXBUFSIZE];
-static char g_uarttxbuffer[CONFIG_UART0_TXBUFSIZE];
+static char g_uartrxbuffer[CONFIG_UART_RXBUFSIZE];
+static char g_uarttxbuffer[CONFIG_UART_TXBUFSIZE];
/* This describes the state of the fake UART port. */
static uart_dev_t g_uartport =
{
- .irq = DM320_IRQ_UART0,
- .recv =
- {
- .size = CONFIG_UART0_RXBUFSIZE,
- .buffer = g_uart0rxbuffer,
+ 0, /* open_count */
+ 0, /* irq */
+ FALSE, /* xmitwaiting */
+ FALSE, /* recvwaiting */
+ TRUE, /* isconsole */
+ { 1 }, /* closesem */
+ { 0 }, /* xmitsem */
+ { 0 }, /* recvsem */
+ { /* xmit */
+ { 1 }, /* sem */
+ 0, /* head */
+ 0, /* tail */
+ CONFIG_UART_TXBUFSIZE, /* size */
+ g_uarttxbuffer, /* buffer */
},
- .xmit =
- {
- .size = CONFIG_UART0_TXBUFSIZE,
- .buffer = g_uart0txbuffer,
+ { /* recv */
+ { 1 }, /* sem */
+ 0, /* head */
+ 0, /* tail */
+ CONFIG_UART_RXBUFSIZE, /* size */
+ g_uartrxbuffer, /* buffer */
},
- .ops = &g_uart_ops,
- .priv = NULL,
+ &g_uart_ops, /* ops */
+ NULL, /* priv */
};
/****************************************************************************
@@ -326,6 +337,7 @@ void up_serialinit(void)
int up_putc(int ch)
{
up_lowputc(ch);
+ return 0;
}