summaryrefslogtreecommitdiff
path: root/nuttx/arch/sh
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-02-15 23:28:10 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2009-02-15 23:28:10 +0000
commit34f65599a3508531cd068f70b7e4350c9c72158e (patch)
tree935f366d5ae28cfc0664ad6cdb4971603efa19a5 /nuttx/arch/sh
parentef7ab3bf2bd90d5971cb0d3371c20e5d8ad671b3 (diff)
downloadpx4-nuttx-34f65599a3508531cd068f70b7e4350c9c72158e.tar.gz
px4-nuttx-34f65599a3508531cd068f70b7e4350c9c72158e.tar.bz2
px4-nuttx-34f65599a3508531cd068f70b7e4350c9c72158e.zip
Add low level UART support for M16C
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@1508 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/arch/sh')
-rw-r--r--nuttx/arch/sh/src/m16c/Make.defs2
-rw-r--r--nuttx/arch/sh/src/m16c/chip.h46
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_lowputc.c293
-rw-r--r--nuttx/arch/sh/src/m16c/m16c_uart.h146
4 files changed, 463 insertions, 24 deletions
diff --git a/nuttx/arch/sh/src/m16c/Make.defs b/nuttx/arch/sh/src/m16c/Make.defs
index 7c18d4c60..a9a1c21bf 100644
--- a/nuttx/arch/sh/src/m16c/Make.defs
+++ b/nuttx/arch/sh/src/m16c/Make.defs
@@ -45,7 +45,7 @@ CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c \
CHIP_ASRCS = m16c_vectors.S
#CHIP_CSRCS = m16c_initialstate.c m16c_copystate.c m16c_lowputc.c m16c_irq.c \
# m16c_timerisr.c m16c_serial.c m16c_dumpstate.c
-CHIP_CSRCS = m16c_initialstate.c m16c_copystate.c m16c_irq.c \
+CHIP_CSRCS = m16c_initialstate.c m16c_copystate.c m16c_lowputc.c m16c_irq.c \
m16c_timerisr.c m16c_dumpstate.c
ifneq ($(CONFIG_DISABLE_SIGNALS),y)
diff --git a/nuttx/arch/sh/src/m16c/chip.h b/nuttx/arch/sh/src/m16c/chip.h
index 4c1c20b47..fccd771a5 100644
--- a/nuttx/arch/sh/src/m16c/chip.h
+++ b/nuttx/arch/sh/src/m16c/chip.h
@@ -132,16 +132,16 @@
#define M16C_DAR1 0x00034 /* DMA1 destination pointer */
#define M16C_TCR1 0x00038 /* DMA1 transfer counter */
#define M16C_DM1CON 0x0003c /* DMA1 control */
-#define M16C_INT3IC 0x00044 /* INT3 interrupt control */
+#define M16C_INT3IC 0x00044 /* INT3 interrupt control */
#define M16C_INT5IC 0x00048 /* INT5 interrupt control */
#define M16C_INT4IC 0x00049 /* INT4 interrupt control */
-#define M16C_BCNIC 0x0004a /* Bus collision detection interrupt control */
+#define M16C_BCNIC 0x0004a /* Bus collision detection interrupt control */
#define M16C_DM0IC 0x0004b /* DMA0 interrupt control */
#define M16C_DM1IC 0x0004c /* DMA1 interrupt control */
#define M16C_KUPIC 0x0004d /* Key input interrupt control */
#define M16C_ADIC 0x0004e /* A-D conversion interrupt control */
-#define M16C_S2TIC 0x0004f /* UART2 transmit interrupt control */
-#define M16C_S2RIC 0x00050 /* UART2 receive interrupt control */
+#define M16C_S2TIC 0x0004f /* UART2 transmit interrupt control */
+#define M16C_S2RIC 0x00050 /* UART2 receive interrupt control */
#define M16C_S0TIC 0x00051 /* UART0 transmit interrupt control */
#define M16C_S0RIC 0x00052 /* UART0 receive interrupt control */
#define M16C_S1TIC 0x00053 /* UART1 transmit interrupt control */
@@ -160,26 +160,26 @@
#define M16C_FMR1 0x001b5 /* Flash Control 1 */
#define M16C_FMR0 0x001b7 /* Flash Control 0 */
#define M16C_PCLKR 0x0025e /* Peripheral Clock Select */
-#define M16C_TA11 0x00342 /* Timer A1-1 */
-#define M16C_TA21 0x00344 /* Timer A2-1 */
-#define M16C_TA41 0x00346 /* Timer A4-1 */
-#define M16C_INVC0 0x00348 /* Three-phase PWM control 0 */
-#define M16C_INVC1 0x00349 /* Three-phase PWM control 1 */
-#define M16C_IDB0 0x0034a /* Three-phase output buffer 0 */
-#define M16C_IDB1 0x0034b /* Three-phase output buffer 1 */
+#define M16C_TA11 0x00342 /* Timer A1-1 */
+#define M16C_TA21 0x00344 /* Timer A2-1 */
+#define M16C_TA41 0x00346 /* Timer A4-1 */
+#define M16C_INVC0 0x00348 /* Three-phase PWM control 0 */
+#define M16C_INVC1 0x00349 /* Three-phase PWM control 1 */
+#define M16C_IDB0 0x0034a /* Three-phase output buffer 0 */
+#define M16C_IDB1 0x0034b /* Three-phase output buffer 1 */
#define M16C_DTT 0x0034c /* Dead time timer */
#define M16C_ICTB2 0x0034d /* Timer B2 interrupt occurences frequency set counter */
-#define M16C_IFSR 0x0035f /* Interrupt request cause select */
-#define M16C_U2SMR4 0x00374 /* UART2 special mode register4 */
-#define M16C_U2SMR3 0x00375 /* UART2 special mode register3 */
-#define M16C_U2SMR2 0x00376 /* UART2 special mode register2 */
-#define M16C_U2SMR 0x00377 /* UART2 special mode */
-#define M16C_U2MR 0x00378 /* UART2 transmit/receive mode */
-#define M16C_U2BRG 0x00379 /* UART2 bit rate generator */
-#define M16C_U2TB 0x0037a /* UART2 transmit buffer */
-#define M16C_U2C0 0x0037c /* UART2 transmit/receive control 0 */
-#define M16C_U2C1 0x0037d /* UART2 transmit/receive control 1 */
-#define M16C_U2RB 0x0037e /* UART2 receive buffer */
+#define M16C_IFSR 0x0035f /* Interrupt request cause select */
+#define M16C_U2SMR4 0x00374 /* UART2 special mode register4 */
+#define M16C_U2SMR3 0x00375 /* UART2 special mode register3 */
+#define M16C_U2SMR2 0x00376 /* UART2 special mode register2 */
+#define M16C_U2SMR 0x00377 /* UART2 special mode */
+#define M16C_U2MR 0x00378 /* UART2 transmit/receive mode */
+#define M16C_U2BRG 0x00379 /* UART2 bit rate generator */
+#define M16C_U2TB 0x0037a /* UART2 transmit buffer */
+#define M16C_U2C0 0x0037c /* UART2 transmit/receive control 0 */
+#define M16C_U2C1 0x0037d /* UART2 transmit/receive control 1 */
+#define M16C_U2RB 0x0037e /* UART2 receive buffer */
#define M16C_TABSR 0x00380 /* Count start flag */
#define M16C_CPSRF 0x00381 /* Clock prescaler reset flag */
#define M16C_ONSF 0x00382 /* One-shot start flag */
@@ -201,7 +201,7 @@
#define M16C_TB0MR 0x0039b /* Timer B0 mode */
#define M16C_TB1MR 0x0039c /* Timer B1 mode */
#define M16C_TB2MR 0x0039d /* Timer B2 mode */
-#define M16C_TB2SC 0x0039e /* Timer B2 special mode */
+#define M16C_TB2SC 0x0039e /* Timer B2 special mode */
#define M16C_U0MR 0x003a0 /* UART0 transmit/receive mode */
#define M16C_U0BRG 0x003a1 /* UART0 bit rate generator */
#define M16C_U0TB 0x003a2 /* UART0 transmit buffer */
diff --git a/nuttx/arch/sh/src/m16c/m16c_lowputc.c b/nuttx/arch/sh/src/m16c/m16c_lowputc.c
new file mode 100644
index 000000000..78b2a68af
--- /dev/null
+++ b/nuttx/arch/sh/src/m16c/m16c_lowputc.c
@@ -0,0 +1,293 @@
+/**************************************************************************
+ * arch/sh/src/m16c/m16c_lowputc.c
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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/types.h>
+
+#include <nuttx/arch.h>
+
+#include "up_internal.h"
+#include "up_arch.h"
+
+#include "chip.h"
+#include "up_internal.h"
+#include "m16c_uart.h"
+
+/**************************************************************************
+ * Private Definitions
+ **************************************************************************/
+
+/* Configuration **********************************************************/
+
+#ifndef M16C_XIN_PRESCALER
+# define M16C_XIN_PRESCALER 1
+#endif
+
+/* Is there a serial console? */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE) && !defined(CONFIG_UART0_DISABLE)
+# define HAVE_CONSOLE 1
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE) && !defined(CONFIG_UART1_DISABLE)
+# define HAVE_CONSOLE 1
+# undef CONFIG_UART0_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+#elif defined(CONFIG_UART2_SERIAL_CONSOLE) && !defined(CONFIG_UART2_DISABLE)
+# define HAVE_CONSOLE 1
+# undef CONFIG_UART1_SERIAL_CONSOLE
+# undef CONFIG_UART2_SERIAL_CONSOLE
+#else
+# if defined(CONFIG_UART0_SERIAL_CONSOLE) || defined(CONFIG_UART1_SERIAL_CONSOLE)|| defined(CONFIG_UART2_SERIAL_CONSOLE)
+# error "Serial console selected, but corresponding UART not enabled"
+# endif
+# undef HAVE_CONSOLE
+#endif
+
+/* Select UART parameters for the selected console */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+# define M16C_UART_BASE M16C_UART0_BASE
+# define M16C_UART_BAUD CONFIG_UART0_BAUD
+# define M16C_UART_BITS CONFIG_UART0_BITS
+# define M16C_UART_PARITY CONFIG_UART0_PARITY
+# define M16C_UART_2STOP CONFIG_UART0_2STOP
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+# define M16C_UART_BASE M16C_UART1_BASE
+# define M16C_UART_BAUD CONFIG_UART1_BAUD
+# define M16C_UART_BITS CONFIG_UART1_BITS
+# define M16C_UART_PARITY CONFIG_UART1_PARITY
+# define M16C_UART_2STOP CONFIG_UART1_2STOP
+#elif defined(CONFIG_UART2_SERIAL_CONSOLE)
+# define M16C_UART_BASE M16C_UART2_BASE
+# define M16C_UART_BAUD CONFIG_UART2_BAUD
+# define M16C_UART_BITS CONFIG_UART2_BITS
+# define M16C_UART_PARITY CONFIG_UART2_PARITY
+# define M16C_UART_2STOP CONFIG_UART2_2STOP
+#else
+# error "No CONFIG_UARTn_SERIAL_CONSOLE Setting"
+#endif
+
+/* Get mode setting */
+
+#if M16C_UART_BITS == 7
+# define M16C_MR_SMDBITS UART_MR_SMD7BITS
+#elif M16C_UART_BITS == 8
+# define M16C_MR_SMDBITS UART_MR_SMD8BITS
+#elif M16C_UART_BITS == 8
+# define M16C_MR_SMDBITS UART_MR_SMD9BITS
+#else
+# error "Number of bits not supported"
+#endif
+
+#if M16C_UART_PARITY == 0
+# define M16C_MR_PARITY (0)
+#elif M16C_UART_PARITY == 1
+# define M16C_MR_PARITY UART_MR_PRYE
+#elif M16C_UART_PARITY == 2
+# define M16C_MR_PARITY (UART_MR_PRYE|UART_MR_PRY)
+#else
+# error "Invalid parity selection"
+#endif
+
+#if M16C_UART_2STOP != 0
+# define M16C_MR_STOPBITS UART_MR_STPS
+#else
+# define M16C_MR_STOPBITS (0)
+#endif
+
+/* The full MR setting: */
+
+#define M16C_MR_VALUE (M16C_MR_SMDBITS|M16C_MR_PARITY|M16C_MR_STOPBITS)
+
+/* Clocking ***************************************************************/
+
+/* The Bit Rate Generator (BRG) value can be calculated by:
+ *
+ * BRG = source-frequency / prescaler / 16 / baud rate - 1
+ *
+ * Example:
+ * source-frequency = 20,000,000 (20MHz)
+ * prescaler = 1
+ * baud rate = 19200
+ * BRG = 20,000,000/1/16/19200 - 1 = 64
+ */
+
+#define M16C_UART_BRG_VALUE \
+ ((M16C_XIN_FREQ / (16 * M16C_XIN_PRESCALER * M16C_UART_BAUD)) - 1)
+
+/**************************************************************************
+ * Private Types
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Function Prototypes
+ **************************************************************************/
+
+/**************************************************************************
+ * Global Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Variables
+ **************************************************************************/
+
+/**************************************************************************
+ * Private Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_txready
+ *
+ * Description:
+ * Return TRUE of the Transmit Data Register is empty
+ *
+ **************************************************************************/
+
+#ifdef HAVE_CONSOLE
+static inline int up_txready(void)
+{
+ /* Check the TI bit in the CI register. 1=Transmit buffer emptyy */
+
+ return ((getreg8(M16C_UART_BASE + M16C_UART_C1) & UART_C1_TI) != 0);
+}
+#endif
+
+/**************************************************************************
+ * Public Functions
+ **************************************************************************/
+
+/**************************************************************************
+ * Name: up_lowputc
+ *
+ * Description:
+ * Output one byte on the serial console
+ *
+ **************************************************************************/
+
+void up_lowputc(char ch)
+{
+#ifdef HAVE_CONSOLE
+ /* Wait until the transmit buffer is empty */
+
+ while (!up_txready());
+
+ /* Write the data to the transmit buffer */
+
+ putreg16((uint16)ch, M16C_UART_BASE + M16C_UART_TB);
+#endif
+}
+
+/**************************************************************************
+ * Name: up_lowsetup
+ *
+ * Description:
+ * This performs basic initialization of the UART used for the serial
+ * console. Its purpose is to get the console output availabe as soon
+ * as possible.
+ *
+ **************************************************************************/
+
+void up_lowsetup(void)
+{
+#if defined(HAVE_CONSOLE) && !defined(CONFIG_SUPPRESS_UART_CONFIG)
+ ubyte regval;
+
+ /* Set the baud rate generator */
+
+ putreg8(M16C_UART_BRG_VALUE, M16C_UART_BASE + M16C_UART_BRG);
+
+ /* Disable CTS/RTS */
+
+ putreg8(UART_C0_CRD, M16C_UART_BASE + M16C_UART_C0);
+
+ /* Disable RX/TX interrupts */
+
+#if 0
+ putreg8(0, M16C_UCON);
+#endif
+
+/* Set interrupt cause=TX complete and continuous receive mode */
+
+#if defined(CONFIG_UART0_SERIAL_CONSOLE)
+ regval = getreg8(M16C_UCON);
+ regval |= (UART_CON_U0IRS|UART_CON_U0RRM);
+ putreg8(regval, M16C_UCON);
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+ regval = getreg8(M16C_UCON);
+ regval |= (UART_CON_U1IRS|UART_CON_U1RRM);
+ putreg8(regval, M16C_UCON);
+#else
+ regval = getreg8(M16C_U2C1);
+ regval |= (UART_C1_U2IRS|UART_C1_U2RRM);
+ putreg8(regval, M16C_U2C1);
+#endif
+
+ /* Set UART transmit/receive control register 1 to enable transmit and receive */
+
+ putreg8(UART_C1_TE|UART_C1_RE, M16C_UART_BASE + M16C_UART_C1);
+
+ /* Set UART transmit/receive mode register data bits, stop bits, parity */
+
+ putreg8(M16C_MR_VALUE, M16C_UART_BASE + M16C_UART_MR);
+
+ /* Set port direction registers for Rx/TX pins */
+
+ #if defined(CONFIG_UART0_SERIAL_CONSOLE)
+ regval = getreg8(M16C_PD6);
+ regval &= ~(1 << 2); /* PD6-2:RxD1 */
+ regval |= (1 << 3); /* PD6-3:TxD1 */
+ putreg8(regval, M16C_PD6);
+#elif defined(CONFIG_UART1_SERIAL_CONSOLE)
+ regval = getreg8(M16C_PD6);
+ regval &= ~(1 << 6); /* PD6-6:RxD1 */
+ regval |= (1 << 7); /* PD6-7:TxD1 */
+ putreg8(regval, M16C_PD6);
+#else
+ regval = getreg8(M16C_PD7);
+ regval &= ~(1 << 1); /* PD7-1:RxD1 */
+ regval &= (1 << 0); /* PD7-0:TxD1 */
+ putreg8(regval, M16C_PD7);
+#endif
+
+ /* Read any data left in the RX fifo */
+
+ regval = (ubyte)getreg16(M16C_UART_BASE + M16C_UART_RB);
+#endif
+}
diff --git a/nuttx/arch/sh/src/m16c/m16c_uart.h b/nuttx/arch/sh/src/m16c/m16c_uart.h
new file mode 100644
index 000000000..8f9b1a005
--- /dev/null
+++ b/nuttx/arch/sh/src/m16c/m16c_uart.h
@@ -0,0 +1,146 @@
+/************************************************************************************
+ * arch/sh/src/m16c/m16c_uart.h
+ *
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_SH_SRC_M16C_M16C_UART_H
+#define __ARCH_SH_SRC_M16C_M16C_UART_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* UART Register Block Base Addresses ***********************************************/
+
+#define M16C_UART0_BASE 0x003a0 /* First UART0 register */
+#define M16C_UART1_BASE 0x003a8 /* First UART1 register */
+#define M16C_UART2_BASE 0x00378 /* First UART2 register (ignoring special regs) */
+
+/* UART Register Offsets ************************************************************/
+
+#define M16C_UART_MR 0x00 /* 8-bit UART transmit/receive mode */
+#define M16C_UART_BRG 0x01 /* 8-bit UART bit rate generator */
+#define M16C_UART_TB 0x02 /* 16-bit UART transmit buffer */
+#define M16C_UART_C0 0x04 /* 8-bit UART transmit/receive control 0 */
+#define M16C_UART_C1 0x05 /* 8-bit UART transmit/receive control 1 */
+#define M16C_UART_RB 0x06 /* 16-bit UART receive buffer */
+
+/* UART Register Bit Definitions ****************************************************/
+
+/* UART transmit/receive mode */
+
+#define UART_MR_SMDMASK 0x07 /* Serial I/O mode select */
+#define UART_MR_SMDINVALID 0x00 /* 000: Serial I/O invalid */
+#define UART_MR_SMDSYNCH 0x01 /* 001: Required in Sync Mode (UART0/1) Serial I/O (UART2) */
+#define UART_MR_SMDINHIB1 0x02 /* 010: Inhibited (UART0/1) I2C mode (UART2) */
+#define UART_MR_SMDINHIB2 0x03 /* 011: Inhibited */
+#define UART_MR_SMD7BITS 0x04 /* 100: Transfer data 7 bits long */
+#define UART_MR_SMD8BITS 0x05 /* 101: Transfer data 8 bits long */
+#define UART_MR_SMD9BITS 0x06 /* 110: Transfer data 9 bits long */
+#define UART_MR_SMDINHIB3 0x07 /* 111: Inhibited */
+#define UART_MR_CKDIR 0x08 /* Bit 3: Internal/external clock select 1=external */
+#define UART_MR_STPS 0x10 /* Bit 4: Stop bit length select 1=2 stop bits */
+#define UART_MR_PRY 0x20 /* Bit 5: Odd/even parity select bit 1=Even parity */
+#define UART_MR_PRYE 0x40 /* Bit 6: Parity enable 1=enabled */
+#define UART_MR_IOPOL 0x80 /* Bit 7: Reserved (UART0/1) Tx/Rx polarity reverse (UART2) */
+
+/* UART receive buffer register (16-bit) */
+
+#define UART_RB_DATAMASK 0x01ff /* Bits 0-8: Receive data */
+ /* Bits 9-10: Reserved */
+#define UART_RB_ABT 0x0800 /* Bit 11: Arbitration lost detecting flag */
+#define UART_RB_OER 0x1000 /* Bit 12: Overrun error flag */
+#define UART_RB_FER 0x2000 /* Bit 13: Framing error flag */
+#define UART_RB_PER 0x4000 /* Bit 14: Parity error flag */
+#define UART_RB_SUM 0x8000 /* Bit 15: Error sum flag */
+
+/* UART Transmit/Receive Control 0 */
+
+#define UART_C0_CLKMASK 0x02 /* Bits 0-1: BRG count source select */
+#define UART_C0_F1SIO 0x00 /* 00 : f1SIO or f2SIO is selected */
+#define UART_C0_F8SIO 0x01 /* 01 : f8SIO is selected */
+#define UART_C0_F32SIO 0x02 /* 10 : f32SIO is selected */
+#define UART_C0_INHIB 0x03 /* 11 : Inhibited */
+#define UART_C0_CRS 0x04 /* Bit 2: CTS/RTS function select 1=RTS */
+#define UART_C0_TXEPT 0x08 /* Bit 3: Transmit register empty 1=empty */
+#define UART_C0_CRD 0x10 /* Bit 4: CTS/RTS disable bit 1=CTS/RTS disabled */
+#define UART_C0_NCH 0x20 /* Bit 5: Data output select 1=TxDi is N-channel open drain output */
+#define UART_C0_CKPOL 0x40 /* Bit 6: CLK polarity select 1=XMT rising, recieve falling */
+#define UART_C0_UFORM 0x80 /* Bit 7: Transfer format select 1=MSB first */
+
+/* UART Transmit/Receive Control 1 */
+
+#define UART_C1_TE 0x01 /* Bit 0: Transmit enable 1=enable */
+#define UART_C1_TI 0x02 /* Bit 1: Transmit buffer empty 1=empty */
+#define UART_C1_RE 0x04 /* Bit 2: Receive enable 1=enable */
+#define UART_C1_RI 0x08 /* Bit 3: Receive complete 1=data in read buffer */
+ /* The following are only defined for UART2: */
+#define UART_C1_U2IRS 0x10 /* Bit 4: UART2 transmit interrupt cause select */
+#define UART_C1_U2RRM 0x20 /* Bit 5: UART2 continuous receive mode enable */
+#define UART_C1_U2LCH 0x40 /* Bit 6: UART2 Data logic select */
+#define UART_C1_U2ERE 0x80 /* Bit 7: UART2 Error signal output enable */
+
+/* UART2 Transmit/Receive Control 2 */
+
+#define UART_CON_U0IRS 0x01 /* Bit 0: UART0 transmit interrupt cause select */
+#define UART_CON_U1IRS 0x02 /* Bit 1: UART1 transmit interrupt cause select */
+#define UART_CON_U0RRM 0x04 /* Bit 2: UART0 continuous receive mode enable */
+#define UART_CON_U1RRM 0x08 /* Bit 3: UART1 continuous receive mode enable */
+#define UART_CON_CLKMD0 0x10 /* Bit 4: CLK/CLKS select bit 0 */
+#define UART_CON_CLKMD1 0x20 /* Bit 5: CLK/CLKS select bit */
+#define UART_CON_RCSP 0x40 /* Bit 6: Separate CTS/RTS bit */
+ /* Bit 7: Reserved */
+/* UART2 special mode register 1 (to be provided) */
+
+/* UART2 special mode register 2 (to be provided) */
+
+/* UART2 special mode register 3 (to be provided) */
+
+/* UART2 special mode register 4 (to be provided) */
+
+/************************************************************************************
+ * Global Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#endif /* __ASSEMBLY__ */
+
+#endif /* __ARCH_SH_SRC_M16C_M16C_UART_H */