summaryrefslogtreecommitdiff
path: root/nuttx/arch/avr/src/atmega/atmega_serial.c
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/avr/src/atmega/atmega_serial.c')
-rw-r--r--nuttx/arch/avr/src/atmega/atmega_serial.c526
1 files changed, 361 insertions, 165 deletions
diff --git a/nuttx/arch/avr/src/atmega/atmega_serial.c b/nuttx/arch/avr/src/atmega/atmega_serial.c
index 7b5e02bd9..4d3b5a23c 100644
--- a/nuttx/arch/avr/src/atmega/atmega_serial.c
+++ b/nuttx/arch/avr/src/atmega/atmega_serial.c
@@ -83,7 +83,7 @@
#if defined(CONFIG_USART0_SERIAL_CONSOLE)
# define CONSOLE_DEV g_usart0port /* USART0 is console */
# define TTYS0_DEV g_usart0port /* USART0 is ttyS0 */
-# ifdef CONFIG_AVR_USART1_RS232
+# ifdef CONFIG_AVR_USART1
# define TTYS1_DEV g_usart1port /* USART1 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
@@ -91,7 +91,7 @@
#elif defined(CONFIG_USART1_SERIAL_CONSOLE)
# define CONSOLE_DEV g_usart1port /* USART1 is console */
# define TTYS0_DEV g_usart1port /* USART1 is ttyS0 */
-# ifdef CONFIG_AVR_USART0_RS232
+# ifdef CONFIG_AVR_USART0
# define TTYS1_DEV g_usart0port /* USART0 is ttyS1 */
# else
# undef TTYS1_DEV /* No ttyS1 */
@@ -102,77 +102,69 @@
* Private Types
****************************************************************************/
-struct up_dev_s
-{
- uintptr_t usartbase; /* Base address of USART registers */
- uint32_t baud; /* Configured baud */
- uint32_t csr; /* Saved channel status register contents */
- uint8_t irq; /* IRQ associated with this USART */
- uint8_t parity; /* 0=none, 1=odd, 2=even */
- uint8_t bits; /* Number of bits (5, 6, 7 or 8) */
- bool stopbits2; /* true: Configure with 2 stop bits instead of 1 */
-};
-
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-static int up_setup(struct uart_dev_s *dev);
-static void up_shutdown(struct uart_dev_s *dev);
-static int up_attach(struct uart_dev_s *dev);
-static void up_detach(struct uart_dev_s *dev);
-static int up_interrupt(int irq, void *context);
-static int up_ioctl(struct file *filep, int cmd, unsigned long arg);
-static int up_receive(struct uart_dev_s *dev, uint32_t *status);
-static void up_rxint(struct uart_dev_s *dev, bool enable);
-static bool up_rxavailable(struct uart_dev_s *dev);
-static void up_send(struct uart_dev_s *dev, int ch);
-static void up_txint(struct uart_dev_s *dev, bool enable);
-static bool up_txready(struct uart_dev_s *dev);
+#ifdef CONFIG_AVR_USART0
+static int usart0_setup(struct uart_dev_s *dev);
+static void usart0_shutdown(struct uart_dev_s *dev);
+static int usart0_attach(struct uart_dev_s *dev);
+static void usart0_detach(struct uart_dev_s *dev);
+static int usart0_interrupt(int irq, void *context);
+static int usart0_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int usart0_receive(struct uart_dev_s *dev, uint32_t *status);
+static void usart0_rxint(struct uart_dev_s *dev, bool enable);
+static bool usart0_rxavailable(struct uart_dev_s *dev);
+static void usart0_send(struct uart_dev_s *dev, int ch);
+static void usart0_txint(struct uart_dev_s *dev, bool enable);
+static bool usart0_txready(struct uart_dev_s *dev);
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static int usart1_setup(struct uart_dev_s *dev);
+static void usart1_shutdown(struct uart_dev_s *dev);
+static int usart1_attach(struct uart_dev_s *dev);
+static void usart1_detach(struct uart_dev_s *dev);
+static int usart1_interrupt(int irq, void *context);
+static int usart1_ioctl(struct file *filep, int cmd, unsigned long arg);
+static int usart1_receive(struct uart_dev_s *dev, uint32_t *status);
+static void usart1_rxint(struct uart_dev_s *dev, bool enable);
+static bool usart1_rxavailable(struct uart_dev_s *dev);
+static void usart1_send(struct uart_dev_s *dev, int ch);
+static void usart1_txint(struct uart_dev_s *dev, bool enable);
+static bool usart1_txready(struct uart_dev_s *dev);
+#endif
/****************************************************************************
* Private Variables
****************************************************************************/
-struct uart_ops_s g_uart_ops =
-{
- .setup = up_setup,
- .shutdown = up_shutdown,
- .attach = up_attach,
- .detach = up_detach,
- .ioctl = up_ioctl,
- .receive = up_receive,
- .rxint = up_rxint,
- .rxavailable = up_rxavailable,
- .send = up_send,
- .txint = up_txint,
- .txready = up_txready,
- .txempty = up_txready,
+/* USART0 operations */
+
+#ifdef CONFIG_AVR_USART0
+struct uart_ops_s g_usart0_ops =
+{
+ .setup = usart0_setup,
+ .shutdown = usart0_shutdown,
+ .attach = usart0_attach,
+ .detach = usart0_detach,
+ .ioctl = usart0_ioctl,
+ .receive = usart0_receive,
+ .rxint = usart0_rxint,
+ .rxavailable = usart0_rxavailable,
+ .send = usart0_send,
+ .txint = usart0_txint,
+ .txready = usart0_txready,
+ .txempty = usart0_txready,
};
-/* I/O buffers */
+/* USART0 I/O buffers */
-#ifdef CONFIG_AVR_USART0_RS232
static char g_usart0rxbuffer[CONFIG_USART0_RXBUFSIZE];
static char g_usart0txbuffer[CONFIG_USART0_TXBUFSIZE];
-#endif
-#ifdef CONFIG_AVR_USART1_RS232
-static char g_usart1rxbuffer[CONFIG_USART1_RXBUFSIZE];
-static char g_usart1txbuffer[CONFIG_USART1_TXBUFSIZE];
-#endif
-/* This describes the state of the AVR32 USART0 ports. */
-
-#ifdef CONFIG_AVR_USART0_RS232
-static struct up_dev_s g_usart0priv =
-{
- .usartbase = AVR_USART0_BASE,
- .baud = CONFIG_USART0_BAUD,
- .irq = AVR_IRQ_USART0,
- .parity = CONFIG_USART0_PARITY,
- .bits = CONFIG_USART0_BITS,
- .stopbits2 = CONFIG_USART0_2STOP,
-};
+/* This describes the state of the ATMega USART0 port. */
static uart_dev_t g_usart0port =
{
@@ -186,24 +178,36 @@ static uart_dev_t g_usart0port =
.size = CONFIG_USART0_TXBUFSIZE,
.buffer = g_usart0txbuffer,
},
- .ops = &g_uart_ops,
- .priv = &g_usart0priv,
+ .ops = &g_usart0_ops,
};
#endif
-/* This describes the state of the AVR32 USART1 port. */
+/* USART1 operations */
-#ifdef CONFIG_AVR_USART1_RS232
-static struct up_dev_s g_usart1priv =
+#ifdef CONFIG_AVR_USART1
+struct uart_ops_s g_usart1_ops =
{
- .usartbase = AVR_USART1_BASE,
- .baud = CONFIG_USART1_BAUD,
- .irq = AVR_IRQ_USART1,
- .parity = CONFIG_USART1_PARITY,
- .bits = CONFIG_USART1_BITS,
- .stopbits2 = CONFIG_USART1_2STOP,
+ .setup = usart1_setup,
+ .shutdown = usart1_shutdown,
+ .attach = usart1_attach,
+ .detach = usart1_detach,
+ .ioctl = usart1_ioctl,
+ .receive = usart1_receive,
+ .rxint = usart1_rxint,
+ .rxavailable = usart1_rxavailable,
+ .send = usart1_send,
+ .txint = usart1_txint,
+ .txready = usart1_txready,
+ .txempty = usart1_txready,
};
+/* USART 1 I/O buffers */
+
+static char g_usart1rxbuffer[CONFIG_USART1_RXBUFSIZE];
+static char g_usart1txbuffer[CONFIG_USART1_TXBUFSIZE];
+
+/* This describes the state of the ATMega USART1 port. */
+
static uart_dev_t g_usart1port =
{
.recv =
@@ -216,8 +220,7 @@ static uart_dev_t g_usart1port =
.size = CONFIG_USART1_TXBUFSIZE,
.buffer = g_usart1txbuffer,
},
- .ops = &g_uart_ops,
- .priv = &g_usart1priv,
+ .ops = &g_usart1_ops,
};
#endif
@@ -226,43 +229,43 @@ static uart_dev_t g_usart1port =
****************************************************************************/
/****************************************************************************
- * Name: up_serialin
+ * Name: usart0/1_restoreusartint
****************************************************************************/
-static inline uint32_t up_serialin(struct up_dev_s *priv, int offset)
+#ifdef CONFIG_AVR_USART0
+static void usart0_restoreusartint(uint8_t imr)
{
# warning "Missing logic"
}
+#endif
-/****************************************************************************
- * Name: up_serialout
- ****************************************************************************/
-
-static inline void up_serialout(struct up_dev_s *priv, int offset, uint32_t value)
+#ifdef CONFIG_AVR_USART1
+static void usart1_restoreusartint(uint8_t imr)
{
# warning "Missing logic"
}
+#endif
/****************************************************************************
- * Name: up_restoreusartint
+ * Name: usart0/1_disableusartint
****************************************************************************/
-static void up_restoreusartint(struct up_dev_s *priv, uint32_t imr)
+#ifdef CONFIG_AVR_USART0
+static inline void usart0_disableusartint(uint8_t *imr)
{
# warning "Missing logic"
}
+#endif
-/****************************************************************************
- * Name: up_disableusartint
- ****************************************************************************/
-
-static inline void up_disableusartint(struct up_dev_s *priv, uint32_t *imr)
+#ifdef CONFIG_AVR_USART1
+static inline void usart1_disableusartint(uint8_t *imr)
{
# warning "Missing logic"
}
+#endif
/****************************************************************************
- * Name: up_setup
+ * Name: usart0/1_setup
*
* Description:
* Configure the USART baud, bits, parity, etc. This method is called the
@@ -270,22 +273,34 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint32_t *imr)
*
****************************************************************************/
-static int up_setup(struct uart_dev_s *dev)
+#ifdef CONFIG_AVR_USART0
+static int usart0_setup(struct uart_dev_s *dev)
{
#ifndef CONFIG_SUPPRESS_UART_CONFIG
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ /* Configure the USART as an RS-232 UART */
+ usart0_configure();
+#endif
+
+ return OK;
+}
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static int usart1_setup(struct uart_dev_s *dev)
+{
+#ifndef CONFIG_SUPPRESS_UART_CONFIG
/* Configure the USART as an RS-232 UART */
- usart_configure(priv->usartbase, priv->baud, priv->parity,
- priv->bits, priv->stopbits2);
+ usart1_configure();
#endif
return OK;
}
+#endif
/****************************************************************************
- * Name: up_shutdown
+ * Name: usart0/1_shutdown
*
* Description:
* Disable the USART. This method is called when the serial
@@ -293,17 +308,26 @@ static int up_setup(struct uart_dev_s *dev)
*
****************************************************************************/
-static void up_shutdown(struct uart_dev_s *dev)
+#ifdef CONFIG_AVR_USART0
+static void usart0_shutdown(struct uart_dev_s *dev)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ /* Reset, disable interrupts, and disable Rx and Tx */
+
+ usart0_reset();
+}
+#endif
+#ifdef CONFIG_AVR_USART1
+static void usart1_shutdown(struct uart_dev_s *dev)
+{
/* Reset, disable interrupts, and disable Rx and Tx */
- usart_reset(priv->usartbase);
+ usart1_reset();
}
+#endif
/****************************************************************************
- * Name: up_attach
+ * Name: usart0/1_attach
*
* Description:
* Configure the USART to operation in interrupt driven mode. This method is
@@ -317,17 +341,30 @@ static void up_shutdown(struct uart_dev_s *dev)
*
****************************************************************************/
-static int up_attach(struct uart_dev_s *dev)
+#ifdef CONFIG_AVR_USART0
+static int usart0_attach(struct uart_dev_s *dev)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ /* Attach the USART0 IRQs */
- /* Attach the IRQ */
+ return irq_attach(ATMEGA_IRQ_U0RX, usart0_interrupt);
+ return irq_attach(ATMEGA_IRQ_U0DRE, usart0_interrupt);
+ return irq_attach(ATMEGA_IRQ_U0TX, usart0_interrupt);
+}
+#endif
+
+#ifdef CONFIG_AVR_USART0
+static int usart0_attach(struct uart_dev_s *dev)
+{
+ /* Attach the USART0 IRQs */
- return irq_attach(priv->irq, up_interrupt);
+ return irq_attach(ATMEGA_IRQ_U1RX, usart1_interrupt);
+ return irq_attach(ATMEGA_IRQ_U1DRE, usart1_interrupt);
+ return irq_attach(ATMEGA_IRQ_U1TX, usart1_interrupt);
}
+#endif
/****************************************************************************
- * Name: up_detach
+ * Name: usart0/1_detach
*
* Description:
* Detach USART interrupts. This method is called when the serial port is
@@ -336,15 +373,36 @@ static int up_attach(struct uart_dev_s *dev)
*
****************************************************************************/
-static void up_detach(struct uart_dev_s *dev)
+#ifdef CONFIG_AVR_USART0
+static void usart0_detach(struct uart_dev_s *dev)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ /* Disable all USART0 interrupts */
# warning "Missing logic"
- irq_detach(priv->irq);
+
+ /* Detach the USART0 IRQs */
+
+ return irq_detach(ATMEGA_IRQ_U0RX);
+ return irq_detach(ATMEGA_IRQ_U0DRE);
+ return irq_detach(ATMEGA_IRQ_U0TX);
}
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static void usart1_detach(struct uart_dev_s *dev)
+{
+ /* Disable all USART0 interrupts */
+# warning "Missing logic"
+
+ /* Detach the USART0 IRQs */
+
+ return irq_deattach(ATMEGA_IRQ_U1RX);
+ return irq_deattach(ATMEGA_IRQ_U1DRE);
+ return irq_deattach(ATMEGA_IRQ_U1TX);
+}
+#endif
/****************************************************************************
- * Name: up_interrupt
+ * Name: usart0/1_interrupt
*
* Description:
* This is the USART interrupt handler. It will be invoked when an
@@ -355,33 +413,53 @@ static void up_detach(struct uart_dev_s *dev)
*
****************************************************************************/
-static int up_interrupt(int irq, void *context)
+#ifdef CONFIG_AVR_USART0
+static int usart0_interrupt(int irq, void *context)
{
- struct uart_dev_s *dev = NULL;
- struct up_dev_s *priv;
- uint32_t csr;
- int passes;
- bool handled;
+ uint8_t csr;
+ int passes;
+ bool handled;
-#ifdef CONFIG_AVR_USART0_RS232
- if (g_usart0priv.irq == irq)
- {
- dev = &g_usart0port;
- }
- else
-#endif
-#ifdef CONFIG_AVR_USART1_RS232
- if (g_usart1priv.irq == irq)
+ /* Loop until there are no characters to be transferred or,
+ * until we have been looping for a long time.
+ */
+
+ handled = true;
+ for (passes = 0; passes < 256 && handled; passes++)
{
- dev = &g_usart1port;
+ handled = false;
+
+# warning "Missing logic"
+ /* Handle incoming, receive bytes (with or without timeout) */
+
+# warning "Missing logic"
+ {
+ /* Received data ready... process incoming bytes */
+
+ uart_recvchars(dev);
+ handled = true;
+ }
+
+ /* Handle outgoing, transmit bytes */
+
+# warning "Missing logic"
+ {
+ /* Transmit data regiser empty ... process outgoing bytes */
+
+ uart_xmitchars(dev);
+ handled = true;
+ }
}
- else
+ return OK;
+}
#endif
- {
- PANIC(OSERR_INTERNAL);
- }
- priv = (struct up_dev_s*)dev->priv;
- DEBUGASSERT(priv);
+
+#ifdef CONFIG_AVR_USART1
+static int usart1_interrupt(int irq, void *context)
+{
+ uint8_t csr;
+ int passes;
+ bool handled;
/* Loop until there are no characters to be transferred or,
* until we have been looping for a long time.
@@ -415,29 +493,44 @@ static int up_interrupt(int irq, void *context)
}
return OK;
}
+#endif
/****************************************************************************
- * Name: up_ioctl
+ * Name: usart0/1_ioctl
*
* Description:
* All ioctl calls will be routed through this method
*
****************************************************************************/
-static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
+#ifdef CONFIG_AVR_USART0
+static int usart0_ioctl(struct file *filep, int cmd, unsigned long arg)
{
#if 0 /* Reserved for future growth */
- struct inode *inode;
- struct uart_dev_s *dev;
- struct up_dev_s *priv;
- int ret = OK;
+ int ret = OK;
+
+ switch (cmd)
+ {
+ case xxx: /* Add commands here */
+ break;
- DEBUGASSERT(filep, filep->f_inode);
- inode = filep->f_inode;
- dev = inode->i_private;
+ default:
+ ret = -ENOTTY;
+ break;
+ }
+
+ return ret;
+#else
+ return -ENOTTY;
+#endif
+}
+#endif
- DEBUGASSERT(dev, dev->priv)
- priv = (struct up_dev_s*)dev->priv;
+#ifdef CONFIG_AVR_USART1
+static int usart1_ioctl(struct file *filep, int cmd, unsigned long arg)
+{
+#if 0 /* Reserved for future growth */
+ int ret = OK;
switch (cmd)
{
@@ -454,9 +547,10 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
return -ENOTTY;
#endif
}
+#endif
/****************************************************************************
- * Name: up_receive
+ * Name: usart0/1_receive
*
* Description:
* Called (usually) from the interrupt level to receive one
@@ -465,10 +559,32 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
*
****************************************************************************/
-static int up_receive(struct uart_dev_s *dev, uint32_t *status)
+#ifdef CONFIG_AVR_USART0
+static int usart0_receive(struct uart_dev_s *dev, uint32_t *status)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ /* Get the Rx byte. The USART Rx interrupt flag is cleared by side effect
+ * when reading the received character.
+ */
+
+# warning "Missing logic"
+
+ /* Return status information */
+
+ if (status)
+ {
+# warning "Missing logic"
+ }
+ /* Then return the actual received byte */
+
+# warning "Missing logic"
+ return 0;
+}
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static int usart1_receive(struct uart_dev_s *dev, uint32_t *status)
+{
/* Get the Rx byte. The USART Rx interrupt flag is cleared by side effect
* when reading the received character.
*/
@@ -487,19 +603,39 @@ static int up_receive(struct uart_dev_s *dev, uint32_t *status)
# warning "Missing logic"
return 0;
}
+#endif
/****************************************************************************
- * Name: up_rxint
+ * Name: usart0/1_rxint
*
* Description:
* Call to enable or disable RX interrupts
*
****************************************************************************/
-static void up_rxint(struct uart_dev_s *dev, bool enable)
+#ifdef CONFIG_AVR_USART0
+static void usart0_rxint(struct uart_dev_s *dev, bool enable)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
+ if (enable)
+ {
+ /* Receive an interrupt when their is anything in the Rx data register (or an Rx
+ * timeout occurs).
+ */
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+# warning "Missing logic"
+#endif
+ }
+ else
+ {
+# warning "Missing logic"
+ }
+}
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static void usart1_rxint(struct uart_dev_s *dev, bool enable)
+{
if (enable)
{
/* Receive an interrupt when their is anything in the Rx data register (or an Rx
@@ -515,48 +651,97 @@ static void up_rxint(struct uart_dev_s *dev, bool enable)
# warning "Missing logic"
}
}
+#endif
/****************************************************************************
- * Name: up_rxavailable
+ * Name: usart0/1_rxavailable
*
* Description:
* Return true if the receive register is not empty
*
****************************************************************************/
-static bool up_rxavailable(struct uart_dev_s *dev)
+#ifdef CONFIG_AVR_USART0
+static bool usart0_rxavailable(struct uart_dev_s *dev)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
# warning "Missing logic"
return 0;
}
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static bool usart1_rxavailable(struct uart_dev_s *dev)
+{
+# warning "Missing logic"
+ return 0;
+}
+#endif
/****************************************************************************
- * Name: up_send
+ * Name: usart0/1_send
*
* Description:
* This method will send one byte on the USART.
*
****************************************************************************/
-static void up_send(struct uart_dev_s *dev, int ch)
+#ifdef CONFIG_AVR_USART0
+static void usart0_send(struct uart_dev_s *dev, int ch)
+{
+# warning "Missing logic"
+ return 0;
+}
+#endif
+
+#ifdef CONFIG_AVR_USART0
+static void usart0_send(struct uart_dev_s *dev, int ch)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
# warning "Missing logic"
return 0;
}
+#endif
/****************************************************************************
- * Name: up_txint
+ * Name: usart0/1_txint
*
* Description:
* Call to enable or disable TX interrupts
*
****************************************************************************/
-static void up_txint(struct uart_dev_s *dev, bool enable)
+#ifdef CONFIG_AVR_USART0
+static void usart0_txint(struct uart_dev_s *dev, bool enable)
+{
+ irqstate_t flags;
+
+ flags = irqsave();
+ if (enable)
+ {
+ /* Set to receive an interrupt when the TX data register is empty */
+
+#ifndef CONFIG_SUPPRESS_SERIAL_INTS
+# warning "Missing logic"
+
+ /* Fake a TX interrupt here by just calling uart_xmitchars() with
+ * interrupts disabled (note this may recurse).
+ */
+
+ uart_xmitchars(dev);
+#endif
+ }
+ else
+ {
+ /* Disable the TX interrupt */
+
+# warning "Missing logic"
+ }
+ irqrestore(flags);
+}
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static void usart1_txint(struct uart_dev_s *dev, bool enable)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
irqstate_t flags;
flags = irqsave();
@@ -582,21 +767,31 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
}
irqrestore(flags);
}
+#endif
/****************************************************************************
- * Name: up_txready
+ * Name: usart0/1_txready
*
* Description:
* Return true if the tranmsit data register is empty
*
****************************************************************************/
-static bool up_txready(struct uart_dev_s *dev)
+#ifdef CONFIG_AVR_USART0
+static bool usart0_txready(struct uart_dev_s *dev)
{
- struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
# warning "Missing logic"
return 0;
}
+#endif
+
+#ifdef CONFIG_AVR_USART1
+static bool usart1_txready(struct uart_dev_s *dev)
+{
+# warning "Missing logic"
+ return 0;
+}
+#endif
/****************************************************************************
* Public Functions
@@ -608,9 +803,7 @@ static bool up_txready(struct uart_dev_s *dev)
* Description:
* Performs the low level USART initialization early in debug so that the
* serial console will be available during bootup. This must be called
- * before up_serialinit. NOTE: This function depends on GPIO pin
- * configuration performed in up_consoleinit() and main clock iniialization
- * performed in up_clkinitialize().
+ * before up_serialinit.
*
****************************************************************************/
@@ -618,16 +811,20 @@ void up_earlyserialinit(void)
{
/* Disable all USARTS */
- up_disableusartint(TTYS0_DEV.priv, NULL);
+ usart0_disableusartint(TTYS0_DEV.priv, NULL);
#ifdef TTYS1_DEV
- up_disableusartint(TTYS1_DEV.priv, NULL);
+ usart0_disableusartint(TTYS1_DEV.priv, NULL);
#endif
/* Configuration whichever one is the console */
#ifdef HAVE_SERIAL_CONSOLE
CONSOLE_DEV.isconsole = true;
- up_setup(&CONSOLE_DEV);
+# if defined(CONFIG_USART0_SERIAL_CONSOLE)
+ usart0_setup(&CONSOLE_DEV);
+# elif defined(CONFIG_USART1_SERIAL_CONSOLE)
+ usart1_setup(&CONSOLE_DEV);
+# endif
#endif
}
@@ -667,10 +864,9 @@ void up_serialinit(void)
int up_putc(int ch)
{
#ifdef HAVE_SERIAL_CONSOLE
- struct up_dev_s *priv = (struct up_dev_s*)CONSOLE_DEV.priv;
- uint32_t imr;
+ uint8_t imr;
- up_disableusartint(priv, &imr);
+ up_disableusartint(&imr);
/* Check for LF */
@@ -682,7 +878,7 @@ int up_putc(int ch)
}
up_lowputc(ch);
- up_restoreusartint(priv, imr);
+ up_restoreusartint(imr);
#endif
return ch;
}