summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-22 19:01:57 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-02-22 19:01:57 +0000
commit50daab3f16fd9822ff8ebf28e088581981db03f1 (patch)
tree10dcdfc8bef6051bbcea9690381c701e5c88a175 /nuttx
parent8acb89e0800041b91f88c01e241d60d2c19ae852 (diff)
downloadpx4-nuttx-50daab3f16fd9822ff8ebf28e088581981db03f1.tar.gz
px4-nuttx-50daab3f16fd9822ff8ebf28e088581981db03f1.tar.bz2
px4-nuttx-50daab3f16fd9822ff8ebf28e088581981db03f1.zip
Changes for a clean NuvoTon NuTiny-SDK-NUC120 build
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5662 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/Make.defs2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c3
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_serial.c32
4 files changed, 15 insertions, 24 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 6101cef24..b0fd52728 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -4200,3 +4200,5 @@
for the Cortex-M0
* configs/nutiny-nuc120, arch/arm/include/nu1xx, and arch/arm/src/nuc1xx:
Support for Nuvoton NuTiny NUC120.
+ * 2013-02-22: the Cortex-M0, NuvoTron NUC1xx, and NuTiny-SDK-NUC120 port is
+ code complete and ready for testing. \ No newline at end of file
diff --git a/nuttx/arch/arm/src/nuc1xx/Make.defs b/nuttx/arch/arm/src/nuc1xx/Make.defs
index 354152af8..c2361fd70 100644
--- a/nuttx/arch/arm/src/nuc1xx/Make.defs
+++ b/nuttx/arch/arm/src/nuc1xx/Make.defs
@@ -57,4 +57,4 @@ endif
CHIP_ASRCS =
CHIP_CSRCS = nuc_clockconfig.c nuc_gpio.c nuc_idle.c nuc_irq.c nuc_lowputc.c
-CHIP_CSRCS += nuc_start.c nuc_timerisr.c
+CHIP_CSRCS += nuc_serial.c nuc_start.c nuc_timerisr.c
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c
index 4eec8fb54..b383e6fbf 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_lowputc.c
@@ -66,7 +66,7 @@
# define NUC_CONSOLE_BITS CONFIG_UART0_BITS
# define NUC_CONSOLE_PARITY CONFIG_UART0_PARITY
# define NUC_CONSOLE_2STOP CONFIG_UART0_2STOP
-# if defined(CONFIG_UART1_SERIAL_CONSOLE)
+# elif defined(CONFIG_UART1_SERIAL_CONSOLE)
# define NUC_CONSOLE_BASE NUC_UART1_BASE
# define NUC_CONSOLE_BAUD CONFIG_UART1_BAUD
# define NUC_CONSOLE_BITS CONFIG_UART1_BITS
@@ -79,6 +79,7 @@
# define NUC_CONSOLE_PARITY CONFIG_UART2_PARITY
# define NUC_CONSOLE_2STOP CONFIG_UART2_2STOP
# endif
+#endif
/****************************************************************************
* Private Functions
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_serial.c b/nuttx/arch/arm/src/nuc1xx/nuc_serial.c
index 0528fe8fe..b0b6aa67f 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_serial.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_serial.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/nuc1xx/nuc_serial.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -77,8 +77,6 @@
#if defined(USE_SERIALDRIVER) && defined(HAVE_UART)
-/* Configuration ************************************************************/
-
/****************************************************************************
* Private Types
****************************************************************************/
@@ -150,11 +148,6 @@ static char g_uart2rxbuffer[CONFIG_UART2_RXBUFSIZE];
static char g_uart2txbuffer[CONFIG_UART2_TXBUFSIZE];
#endif
-#ifdef CONFIG_NUC_UART3
-static char g_uart3rxbuffer[CONFIG_UART3_RXBUFSIZE];
-static char g_uart3txbuffer[CONFIG_UART3_TXBUFSIZE];
-#endif
-
/* This describes the state of the LPC17xx uart0 port. */
#ifdef CONFIG_NUC_UART0
@@ -184,7 +177,7 @@ static uart_dev_t g_uart0port =
.ops = &g_uart_ops,
.priv = &g_uart0priv,
};
-#endif
+#endif /* CONFIG_NUC_UART0 */
/* This describes the state of the LPC17xx uart1 port. */
@@ -215,7 +208,7 @@ static uart_dev_t g_uart1port =
.ops = &g_uart_ops,
.priv = &g_uart1priv,
};
-#endif
+#endif /* CONFIG_NUC_UART1 */
/* This describes the state of the LPC17xx uart1 port. */
@@ -246,7 +239,7 @@ static uart_dev_t g_uart2port =
.ops = &g_uart_ops,
.priv = &g_uart2priv,
};
-#endif
+#endif /* CONFIG_NUC_UART2 */
/* Which UART with be tty0/console and which tty1? tty2? */
@@ -308,6 +301,7 @@ static uart_dev_t g_uart2port =
# undef TTYS2_DEV /* No ttyS2 */
# endif
# endif
+# endif
#else /* No console */
# define TTYS0_DEV g_uart0port /* UART0=ttyS0 */
# ifdef CONFIG_NUC_UART1
@@ -433,7 +427,6 @@ static int up_setup(struct uart_dev_s *dev)
regval |= (UART_LCR_PBE | UART_LCR_EPE);
#endif
-
#if NUC_CONSOLE_2STOP != 0
revgval |= UART_LCR_NSB;
#endif
@@ -456,6 +449,7 @@ static int up_setup(struct uart_dev_s *dev)
/* Enable Flow Control in the Modem Control Register */
/* Not implemented */
+#endif /* CONFIG_SUPPRESS_NUC_UART_CONFIG */
return OK;
}
@@ -565,13 +559,6 @@ static int up_interrupt(int irq, void *context)
}
else
#endif
-#ifdef CONFIG_NUC_UART3
- if (g_uart3priv.irq == irq)
- {
- dev = &g_uart3port;
- }
- else
-#endif
{
PANIC(OSERR_INTERNAL);
}
@@ -720,7 +707,8 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
nuc_setbaud(priv->base, priv->baud);
}
break;
-#endif
+
+#endif /* CONFIG_SERIAL_TERMIOS */
default:
ret = -ENOTTY;
@@ -958,7 +946,7 @@ int up_putc(int ch)
return ch;
}
-#else /* USE_SERIALDRIVER */
+#else /* USE_SERIALDRIVER && HAVE_UART */
/****************************************************************************
* Name: up_putc
@@ -985,4 +973,4 @@ int up_putc(int ch)
return ch;
}
-#endif /* USE_SERIALDRIVER */
+#endif /* USE_SERIALDRIVER && HAVE_UART */