summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorSebastian Huber <sebastian.huber@embedded-brains.de>2021-07-19 15:21:26 +0200
committerSebastian Huber <sebastian.huber@embedded-brains.de>2021-12-08 17:25:16 +0100
commit250eed3c7df150a27d31cd74c9c5e14666f9f09d (patch)
tree983e49b6e7e9190bc6537e821384915a599fce99
parentdc94bcdfd7f1d041a6fde70fd540ba4f60d187ce (diff)
bsps: Use new APBUART register block API
-rw-r--r--bsps/include/grlib/apbuart.h131
-rw-r--r--bsps/include/grlib/apbuart_termios.h4
-rw-r--r--bsps/shared/grlib/uart/apbuart_cons.c135
-rw-r--r--bsps/shared/grlib/uart/apbuart_polled.c77
-rw-r--r--bsps/shared/grlib/uart/apbuart_termios.c49
-rw-r--r--bsps/sparc/leon3/console/console.c2
-rw-r--r--bsps/sparc/leon3/console/printk_support.c16
-rw-r--r--bsps/sparc/leon3/include/bsp/leon3.h6
8 files changed, 266 insertions, 154 deletions
diff --git a/bsps/include/grlib/apbuart.h b/bsps/include/grlib/apbuart.h
index f54689abc2..d2b7b12a41 100644
--- a/bsps/include/grlib/apbuart.h
+++ b/bsps/include/grlib/apbuart.h
@@ -1,77 +1,110 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
/**
* @file
- * @ingroup uart
+ *
+ * @ingroup RTEMSDeviceGRLIBAPBUART
+ *
+ * @brief This header file defines the APBUART interface.
*/
/*
- * COPYRIGHT (c) 2007.
- * Gaisler Research
+ * Copyright (C) 2021 embedded brains GmbH (http://www.embedded-brains.de)
*
- * The license and distribution terms for this file may be
- * found in the file LICENSE in this distribution or at
- * http://www.rtems.org/license/LICENSE.
+ * 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.
*
+ * 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 __APBUART_H__
-#define __APBUART_H__
-
-/**
- * @defgroup uart UART
+/*
+ * This file is part of the RTEMS quality process and was automatically
+ * generated. If you find something that needs to be fixed or
+ * worded better please post a report or patch to an RTEMS mailing list
+ * or raise a bug report:
*
- * @ingroup RTEMSBSPsSharedGRLIB
+ * https://www.rtems.org/bugs.html
*
- * @brief Driver interface for APBUART
+ * For information on updating and regenerating please refer to the How-To
+ * section in the Software Requirements Engineering chapter of the
+ * RTEMS Software Engineering manual. The manual is provided as a part of
+ * a release. For development sources please refer to the online
+ * documentation at:
*
- * @{
+ * https://docs.rtems.org
*/
-#include "ambapp.h"
-#include "grlib.h"
+/* Generated from spec:/dev/grlib/if/apbuart-header-2 */
+
+#ifndef _GRLIB_APBUART_H
+#define _GRLIB_APBUART_H
+
+#include <grlib/apbuart-regs.h>
#ifdef __cplusplus
extern "C" {
#endif
-#define APBUART_CTRL_RE 0x1
-#define APBUART_CTRL_TE 0x2
-#define APBUART_CTRL_RI 0x4
-#define APBUART_CTRL_TI 0x8
-#define APBUART_CTRL_PS 0x10
-#define APBUART_CTRL_PE 0x20
-#define APBUART_CTRL_FL 0x40
-#define APBUART_CTRL_LB 0x80
-#define APBUART_CTRL_EC 0x100
-#define APBUART_CTRL_TF 0x200
-#define APBUART_CTRL_RF 0x400
-#define APBUART_CTRL_DB 0x800
-#define APBUART_CTRL_BI 0x1000
-#define APBUART_CTRL_DI 0x2000
-#define APBUART_CTRL_FA 0x80000000
+/* Generated from spec:/dev/grlib/if/apbuart-inbyte-nonblocking */
-#define APBUART_STATUS_DR 0x1
-#define APBUART_STATUS_TS 0x2
-#define APBUART_STATUS_TE 0x4
-#define APBUART_STATUS_BR 0x8
-#define APBUART_STATUS_OV 0x10
-#define APBUART_STATUS_PE 0x20
-#define APBUART_STATUS_FE 0x40
-#define APBUART_STATUS_ERR 0x78
-#define APBUART_STATUS_TH 0x80
-#define APBUART_STATUS_RH 0x100
-#define APBUART_STATUS_TF 0x200
-#define APBUART_STATUS_RF 0x400
+/**
+ * @ingroup RTEMSDeviceGRLIBAPBUART
+ *
+ * @brief Clears all errors and tries to get one character from the receiver
+ * FIFO.
+ *
+ * @param regs is the pointer to the APBUART register block.
+ *
+ * @retval -1 The receiver FIFO was empty.
+ *
+ * @return Returns the first character of the receiver FIFO if it was
+ * non-empty.
+ */
+int apbuart_inbyte_nonblocking( apbuart *regs );
+
+/* Generated from spec:/dev/grlib/if/apbuart-outbyte-polled */
-void apbuart_outbyte_wait(const struct apbuart_regs *regs);
+/**
+ * @ingroup RTEMSDeviceGRLIBAPBUART
+ *
+ * @brief Waits until an empty transmitter FIFO was observed and then stores
+ * the character to the data register.
+ *
+ * @param regs is the pointer to the APBUART register block.
+ *
+ * @param ch is the character to output.
+ */
+void apbuart_outbyte_polled( apbuart *regs, char ch );
-void apbuart_outbyte_polled(struct apbuart_regs *regs, char ch);
+/* Generated from spec:/dev/grlib/if/apbuart-outbyte-wait */
-int apbuart_inbyte_nonblocking(struct apbuart_regs *regs);
+/**
+ * @ingroup RTEMSDeviceGRLIBAPBUART
+ *
+ * @brief Ensures that at least once an empty transmitter FIFO was observed.
+ *
+ * @param regs is the pointer to the APBUART register block.
+ */
+void apbuart_outbyte_wait( const apbuart *regs );
#ifdef __cplusplus
}
#endif
-/** @} */
-
-#endif /* __APBUART_H__ */
+#endif /* _GRLIB_APBUART_H */
diff --git a/bsps/include/grlib/apbuart_termios.h b/bsps/include/grlib/apbuart_termios.h
index ca6b5d3b3e..0e94cf05d2 100644
--- a/bsps/include/grlib/apbuart_termios.h
+++ b/bsps/include/grlib/apbuart_termios.h
@@ -15,7 +15,7 @@
#define APBUART_TERMIOS_H
#include <rtems/termiostypes.h>
-#include "grlib.h"
+#include "apbuart.h"
#ifdef __cplusplus
extern "C" {
@@ -23,7 +23,7 @@ extern "C" {
struct apbuart_context {
rtems_termios_device_context base;
- struct apbuart_regs *regs;
+ apbuart *regs;
unsigned int freq_hz;
rtems_vector_number irq;
volatile int sending;
diff --git a/bsps/shared/grlib/uart/apbuart_cons.c b/bsps/shared/grlib/uart/apbuart_cons.c
index a0a265ab31..936deb3b9f 100644
--- a/bsps/shared/grlib/uart/apbuart_cons.c
+++ b/bsps/shared/grlib/uart/apbuart_cons.c
@@ -28,11 +28,15 @@
#include <grlib/ambapp_bus.h>
#include <grlib/apbuart.h>
#include <grlib/ambapp.h>
-#include <grlib/grlib.h>
+#include <grlib/io.h>
#include <grlib/cons.h>
#include <rtems/termiostypes.h>
#include <grlib/apbuart_cons.h>
+#ifdef LEON3
+#include <bsp/leon3.h>
+#endif
+
/*#define DEBUG 1 */
#ifdef DEBUG
@@ -41,11 +45,6 @@
#define DBG(x...)
#endif
-/* LEON3 Low level transmit/receive functions provided by debug-uart code */
-#ifdef LEON3
-extern struct apbuart_regs *leon3_debug_uart; /* The debug UART */
-#endif
-
/* Probed hardware capabilities */
enum {
CAP_FIFO = 0x01, /* FIFO available */
@@ -54,7 +53,7 @@ enum {
struct apbuart_priv {
struct console_dev condev;
struct drvmgr_dev *dev;
- struct apbuart_regs *regs;
+ apbuart *regs;
struct rtems_termios_tty *tty;
char devName[32];
volatile int sending;
@@ -193,18 +192,23 @@ static const rtems_termios_device_handler handler_polled = {
* can select appropriate routines for the hardware. probecap() return value
* is a CAP_ bitmask.
*/
-static int probecap(struct apbuart_regs *regs)
+static int probecap(apbuart *regs)
{
int cap = 0;
+ uint32_t ctrl;
/* Probe FIFO */
- if (regs->ctrl & APBUART_CTRL_FA) {
+ ctrl = grlib_load_32(&regs->ctrl);
+ if (ctrl & APBUART_CTRL_FA) {
cap |= CAP_FIFO;
/* Probe RX delayed interrupt */
- regs->ctrl |= APBUART_CTRL_DI;
- if (regs->ctrl & APBUART_CTRL_DI) {
- regs->ctrl &= ~APBUART_CTRL_DI;
+ ctrl |= APBUART_CTRL_DI;
+ grlib_store_32(&regs->ctrl, ctrl);
+ ctrl = grlib_load_32(&regs->ctrl);
+ if (ctrl & APBUART_CTRL_DI) {
+ ctrl &= ~APBUART_CTRL_DI;
+ grlib_store_32(&regs->ctrl, ctrl);
cap |= CAP_DI;
}
}
@@ -221,6 +225,7 @@ int apbuart_init1(struct drvmgr_dev *dev)
char prefix[32];
unsigned int db;
static int first_uart = 1;
+ uint32_t ctrl;
/* The default operation in AMP is to use APBUART[0] for CPU[0],
* APBUART[1] for CPU[1] and so on. The remaining UARTs is not used
@@ -249,10 +254,12 @@ int apbuart_init1(struct drvmgr_dev *dev)
if (ambadev == NULL)
return -1;
pnpinfo = &ambadev->info;
- priv->regs = (struct apbuart_regs *)pnpinfo->apb_slv->start;
+ priv->regs = (apbuart *)pnpinfo->apb_slv->start;
/* Clear HW regs, leave baudrate register as it is */
- priv->regs->status = 0;
+ grlib_store_32(&priv->regs->status, 0);
+
+ ctrl = grlib_load_32(&priv->regs->ctrl);
/* leave Transmitter/receiver if this is the RTEMS debug UART (assume
* it has been setup by boot loader).
@@ -260,10 +267,10 @@ int apbuart_init1(struct drvmgr_dev *dev)
db = 0;
#ifdef LEON3
if (priv->regs == leon3_debug_uart) {
- db = priv->regs->ctrl & (APBUART_CTRL_RE |
- APBUART_CTRL_TE |
- APBUART_CTRL_PE |
- APBUART_CTRL_PS);
+ db = ctrl & (APBUART_CTRL_RE |
+ APBUART_CTRL_TE |
+ APBUART_CTRL_PE |
+ APBUART_CTRL_PS);
}
#endif
/* Let UART debug tunnelling be untouched if Flow-control is set.
@@ -273,12 +280,12 @@ int apbuart_init1(struct drvmgr_dev *dev)
* guess that we are debugging if FL is already set, the debugger set
* either LB or DB depending on UART capabilities.
*/
- if (priv->regs->ctrl & APBUART_CTRL_FL) {
- db |= priv->regs->ctrl & (APBUART_CTRL_DB |
+ if (ctrl & APBUART_CTRL_FL) {
+ db |= ctrl & (APBUART_CTRL_DB |
APBUART_CTRL_LB | APBUART_CTRL_FL);
}
- priv->regs->ctrl = db;
+ grlib_store_32(&priv->regs->ctrl, db);
priv->cap = probecap(priv->regs);
@@ -367,12 +374,13 @@ static int apbuart_info(
sprintf(buf, "FS Name: %s", priv->condev.fsname);
print_line(p, buf);
}
- sprintf(buf, "STATUS REG: 0x%x", priv->regs->status);
+ sprintf(buf, "STATUS REG: 0x%x", grlib_load_32(&priv->regs->status));
print_line(p, buf);
- sprintf(buf, "CTRL REG: 0x%x", priv->regs->ctrl);
+ sprintf(buf, "CTRL REG: 0x%x", grlib_load_32(&priv->regs->ctrl));
print_line(p, buf);
sprintf(buf, "SCALER REG: 0x%x baud rate %d",
- priv->regs->scaler, apbuart_get_baud(priv));
+ grlib_load_32(&priv->regs->scaler),
+ apbuart_get_baud(priv));
print_line(p, buf);
return DRVMGR_OK;
@@ -387,6 +395,8 @@ static bool first_open(
)
{
struct apbuart_priv *uart = base_get_priv(base);
+ apbuart *regs = uart->regs;
+ uint32_t ctrl;
uart->tty = tty;
@@ -398,7 +408,8 @@ static bool first_open(
}
/* Enable TX/RX */
- uart->regs->ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
+ ctrl = grlib_load_32(&regs->ctrl);
+ ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
if (uart->mode != TERMIOS_POLLED) {
int ret;
@@ -415,15 +426,15 @@ static bool first_open(
uart->sending = 0;
/* Turn on RX interrupts */
- ctrl = uart->regs->ctrl;
ctrl |= APBUART_CTRL_RI;
if (uart->cap & CAP_DI) {
/* Use RX FIFO interrupt only if delayed interrupt available. */
ctrl |= (APBUART_CTRL_DI | APBUART_CTRL_RF);
}
- uart->regs->ctrl = ctrl;
}
+ grlib_store_32(&regs->ctrl, ctrl);
+
return true;
}
@@ -434,13 +445,16 @@ static void last_close(
)
{
struct apbuart_priv *uart = base_get_priv(base);
+ apbuart *regs = uart->regs;
rtems_interrupt_lock_context lock_context;
+ uint32_t ctrl;
if (uart->mode != TERMIOS_POLLED) {
/* Turn off RX interrupts */
rtems_termios_device_lock_acquire(base, &lock_context);
- uart->regs->ctrl &=
- ~(APBUART_CTRL_DI | APBUART_CTRL_RI | APBUART_CTRL_RF);
+ ctrl = grlib_load_32(&regs->ctrl);
+ ctrl &= ~(APBUART_CTRL_DI | APBUART_CTRL_RI | APBUART_CTRL_RF);
+ grlib_store_32(&regs->ctrl, ctrl);
rtems_termios_device_lock_release(base, &lock_context);
/**** Flush device ****/
@@ -448,8 +462,8 @@ static void last_close(
/* Wait until all data has been sent */
}
while (
- (uart->regs->ctrl & APBUART_CTRL_TE) &&
- !(uart->regs->status & APBUART_STATUS_TS)
+ (grlib_load_32(&regs->ctrl) & APBUART_CTRL_TE) &&
+ !(grlib_load_32(&regs->status) & APBUART_STATUS_TS)
) {
/* Wait until all data has left shift register */
}
@@ -460,8 +474,11 @@ static void last_close(
#ifdef LEON3
/* Disable TX/RX if not used for DEBUG */
- if (uart->regs != leon3_debug_uart)
- uart->regs->ctrl &= ~(APBUART_CTRL_RE | APBUART_CTRL_TE);
+ if (regs != leon3_debug_uart) {
+ ctrl = grlib_load_32(&regs->ctrl);
+ ctrl &= ~(APBUART_CTRL_RE | APBUART_CTRL_TE);
+ grlib_store_32(&regs->ctrl, ctrl);
+ }
#endif
}
@@ -477,10 +494,11 @@ static int read_task(rtems_termios_device_context *base)
{
rtems_interrupt_lock_context lock_context;
struct apbuart_priv *uart = base_get_priv(base);
- struct apbuart_regs *regs = uart->regs;
+ apbuart *regs = uart->regs;
int cnt;
char buf[33];
struct rtems_termios_tty *tty;
+ uint32_t ctrl;
uint32_t ctrl_add;
ctrl_add = APBUART_CTRL_RI;
@@ -491,10 +509,10 @@ static int read_task(rtems_termios_device_context *base)
do {
cnt = 0;
while (
- (regs->status & APBUART_STATUS_DR) &&
+ (grlib_load_32(&regs->status) & APBUART_STATUS_DR) &&
(cnt < sizeof(buf))
) {
- buf[cnt] = regs->data;
+ buf[cnt] = grlib_load_32(&regs->data);
cnt++;
}
if (0 < cnt) {
@@ -508,9 +526,11 @@ static int read_task(rtems_termios_device_context *base)
* afterwards.
*/
rtems_termios_device_lock_acquire(base, &lock_context);
- regs->ctrl |= ctrl_add;
+ ctrl = grlib_load_32(&regs->ctrl);
+ ctrl |= ctrl_add;
+ grlib_store_32(&regs->ctrl, ctrl);
rtems_termios_device_lock_release(base, &lock_context);
- } while (regs->status & APBUART_STATUS_DR);
+ } while (grlib_load_32(&regs->status) & APBUART_STATUS_DR);
return EOF;
}
@@ -521,7 +541,7 @@ int apbuart_get_baud(struct apbuart_priv *uart)
unsigned int scaler;
/* Get current scaler setting */
- scaler = uart->regs->scaler;
+ scaler = grlib_load_32(&uart->regs->scaler);
/* Get APBUART core frequency */
drvmgr_freq_get(uart->dev, DEV_APB_SLV, &core_clk_hz);
@@ -556,7 +576,7 @@ static bool set_attributes(
rtems_termios_device_lock_acquire(base, &lock_context);
/* Read out current value */
- ctrl = uart->regs->ctrl;
+ ctrl = grlib_load_32(&uart->regs->ctrl);
switch(t->c_cflag & (PARENB|PARODD)){
case (PARENB|PARODD):
@@ -583,7 +603,7 @@ static bool set_attributes(
ctrl &= ~APBUART_CTRL_FL;
/* Update new settings */
- uart->regs->ctrl = ctrl;
+ grlib_store_32(&uart->regs->ctrl, ctrl);
rtems_termios_device_lock_release(base, &lock_context);
@@ -597,7 +617,7 @@ static bool set_attributes(
scaler = (((core_clk_hz*10)/(baud*8))-5)/10;
/* Set new baud rate by setting scaler */
- uart->regs->scaler = scaler;
+ grlib_store_32(&uart->regs->scaler, scaler);
}
return true;
@@ -617,7 +637,7 @@ static void get_attributes(
t->c_cflag |= CS8;
/* Read out current parity */
- ctrl = uart->regs->ctrl;
+ ctrl = grlib_load_32(&uart->regs->ctrl);
if (ctrl & APBUART_CTRL_PE) {
if (ctrl & APBUART_CTRL_PS)
t->c_cflag |= PARENB|PARODD; /* Odd parity */
@@ -653,11 +673,11 @@ static void write_interrupt(
)
{
struct apbuart_priv *uart = base_get_priv(base);
- struct apbuart_regs *regs = uart->regs;
+ apbuart *regs = uart->regs;
int sending;
unsigned int ctrl;
- ctrl = regs->ctrl;
+ ctrl = grlib_load_32(&regs->ctrl);
if (len > 0) {
/*
@@ -665,28 +685,30 @@ static void write_interrupt(
* we can tell termios later.
*/
/* Enable TX interrupt (interrupt is edge-triggered) */
- regs->ctrl = ctrl | APBUART_CTRL_TI;
+ ctrl |= APBUART_CTRL_TI;
+ grlib_store_32(&regs->ctrl, ctrl);
if (ctrl & APBUART_CTRL_FA) {
/* APBUART with FIFO.. Fill as many as FIFO allows */
sending = 0;
while (
- ((regs->status & APBUART_STATUS_TF) == 0) &&
+ ((grlib_load_32(&regs->status) & APBUART_STATUS_TF) == 0) &&
(sending < len)
) {
- regs->data = *buf;
+ grlib_store_32(&regs->data, *buf);
buf++;
sending++;
}
} else {
/* start UART TX, this will result in an interrupt when done */
- regs->data = *buf;
+ grlib_store_32(&regs->data, *buf);
sending = 1;
}
} else {
/* No more to send, disable TX interrupts */
- regs->ctrl = ctrl & ~APBUART_CTRL_TI;
+ ctrl &= ~APBUART_CTRL_TI;
+ grlib_store_32(&regs->ctrl, ctrl);
/* Tell close that we sent everything */
sending = 0;
@@ -702,21 +724,24 @@ static void apbuart_cons_isr(void *arg)
rtems_termios_device_context *base;
struct console_dev *condev = rtems_termios_get_device_context(tty);
struct apbuart_priv *uart = condev_get_priv(condev);
- struct apbuart_regs *regs = uart->regs;
+ apbuart *regs = uart->regs;
unsigned int status;
char buf[33];
int cnt;
if (uart->mode == TERMIOS_TASK_DRIVEN) {
- if ((status = regs->status) & APBUART_STATUS_DR) {
+ if ((status = grlib_load_32(&regs->status)) & APBUART_STATUS_DR) {
rtems_interrupt_lock_context lock_context;
+ uint32_t ctrl;
/* Turn off RX interrupts */
base = rtems_termios_get_device_context(tty);
rtems_termios_device_lock_acquire(base, &lock_context);
- regs->ctrl &=
+ ctrl = grlib_load_32(&regs->ctrl);
+ ctrl &=
~(APBUART_CTRL_DI | APBUART_CTRL_RI |
APBUART_CTRL_RF);
+ grlib_store_32(&regs->ctrl, ctrl);
rtems_termios_device_lock_release(base, &lock_context);
/* Activate termios RX daemon task */
rtems_termios_rxirq_occured(tty);
@@ -729,10 +754,10 @@ static void apbuart_cons_isr(void *arg)
*/
cnt = 0;
while (
- ((status=regs->status) & APBUART_STATUS_DR) &&
+ ((status=grlib_load_32(&regs->status)) & APBUART_STATUS_DR) &&
(cnt < sizeof(buf))
) {
- buf[cnt] = regs->data;
+ buf[cnt] = grlib_load_32(&regs->data);
cnt++;
}
if (0 < cnt) {
diff --git a/bsps/shared/grlib/uart/apbuart_polled.c b/bsps/shared/grlib/uart/apbuart_polled.c
index 87325d8951..f877d00cb0 100644
--- a/bsps/shared/grlib/uart/apbuart_polled.c
+++ b/bsps/shared/grlib/uart/apbuart_polled.c
@@ -1,45 +1,72 @@
+/* SPDX-License-Identifier: BSD-2-Clause */
+
+/**
+ * @file
+ *
+ * @ingroup DevGrlibIfApbuart
+ *
+ * @brief This source file contains the implementation of
+ * apbuart_outbyte_wait(), apbuart_outbyte_polled(), and
+ * apbuart_inbyte_nonblocking().
+ */
+
/*
- * COPYRIGHT (c) 2010.
- * Cobham Gaisler AB.
+ * Copyright (C) 2021 embedded brains GmbH (http://www.embedded-brains.de)
+ *
+ * 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.
*
- * The license and distribution terms for this file may be
- * found in the file LICENSE in this distribution or at
- * http://www.rtems.org/license/LICENSE.
+ * 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.
*/
#include <grlib/apbuart.h>
+#include <grlib/io.h>
-#include <rtems/score/cpuimpl.h>
+#include <rtems/score/io.h>
-void apbuart_outbyte_wait(const struct apbuart_regs *regs)
+void apbuart_outbyte_wait( const apbuart *regs )
{
- while ( (regs->status & APBUART_STATUS_TE) == 0 ) {
- /* Lower bus utilization while waiting for UART */
- _CPU_Instruction_no_operation();
- _CPU_Instruction_no_operation();
- _CPU_Instruction_no_operation();
- _CPU_Instruction_no_operation();
- _CPU_Instruction_no_operation();
- _CPU_Instruction_no_operation();
- _CPU_Instruction_no_operation();
- _CPU_Instruction_no_operation();
+ while ( ( grlib_load_32( &regs->status ) & APBUART_STATUS_TE ) == 0 ) {
+ _IO_Relax();
}
}
-void apbuart_outbyte_polled(struct apbuart_regs *regs, char ch)
+void apbuart_outbyte_polled( apbuart *regs, char ch)
{
- apbuart_outbyte_wait(regs);
- regs->data = (uint8_t) ch;
+ apbuart_outbyte_wait( regs );
+ grlib_store_32( &regs->data, (uint8_t) ch );
}
-int apbuart_inbyte_nonblocking(struct apbuart_regs *regs)
+int apbuart_inbyte_nonblocking( apbuart *regs )
{
- /* Clear errors */
- regs->status = ~APBUART_STATUS_ERR;
+ uint32_t status;
+
+ status = grlib_load_32( &regs->status );
+
+ /* Clear errors, writes to non-error flags are ignored */
+ status &= ~( APBUART_STATUS_FE | APBUART_STATUS_PE | APBUART_STATUS_OV |
+ APBUART_STATUS_BR );
+ grlib_store_32( &regs->status, status );
- if ((regs->status & APBUART_STATUS_DR) == 0) {
+ if ( ( status & APBUART_STATUS_DR ) == 0 ) {
return -1;
}
- return (uint8_t) regs->data;
+ return (int) APBUART_DATA_DATA_GET( grlib_load_32( &regs->data ) );
}
diff --git a/bsps/shared/grlib/uart/apbuart_termios.c b/bsps/shared/grlib/uart/apbuart_termios.c
index 9014a1c735..d71335f221 100644
--- a/bsps/shared/grlib/uart/apbuart_termios.c
+++ b/bsps/shared/grlib/uart/apbuart_termios.c
@@ -13,6 +13,7 @@
#include <grlib/apbuart_termios.h>
#include <grlib/apbuart.h>
+#include <grlib/io.h>
#include <bsp.h>
static void apbuart_isr(void *arg)
@@ -23,9 +24,9 @@ static void apbuart_isr(void *arg)
char data;
/* Get all received characters */
- while ((status=uart->regs->status) & APBUART_STATUS_DR) {
+ while ((status=grlib_load_32(&uart->regs->status)) & APBUART_STATUS_DR) {
/* Data has arrived, get new data */
- data = uart->regs->data;
+ data = (char)grlib_load_32(&uart->regs->data);
/* Tell termios layer about new character */
rtems_termios_enqueue_raw_characters(tty, &data, 1);
@@ -33,7 +34,7 @@ static void apbuart_isr(void *arg)
if (
(status & APBUART_STATUS_TE)
- && (uart->regs->ctrl & APBUART_CTRL_TI) != 0
+ && (grlib_load_32(&uart->regs->ctrl) & APBUART_CTRL_TI) != 0
) {
/* write_interrupt will get called from this function */
rtems_termios_dequeue_characters(tty, 1);
@@ -48,23 +49,27 @@ static void apbuart_write_support(
{
struct apbuart_context *uart = (struct apbuart_context *) base;
int sending;
+ uint32_t ctrl;
+
+ ctrl = grlib_load_32(&uart->regs->ctrl);
if (len > 0) {
/* Enable TX interrupt (interrupt is edge-triggered) */
- uart->regs->ctrl |= APBUART_CTRL_TI;
+ ctrl |= APBUART_CTRL_TI;
/* start UART TX, this will result in an interrupt when done */
- uart->regs->data = *buf;
+ grlib_store_32(&uart->regs->data, (uint8_t)*buf);
sending = 1;
} else {
/* No more to send, disable TX interrupts */
- uart->regs->ctrl &= ~APBUART_CTRL_TI;
+ ctrl &= ~APBUART_CTRL_TI;
/* Tell close that we sent everything */
sending = 0;
}
+ grlib_store_32(&uart->regs->ctrl, ctrl);
uart->sending = sending;
}
@@ -115,7 +120,7 @@ static bool apbuart_set_attributes(
rtems_termios_device_lock_acquire(base, &lock_context);
/* Read out current value */
- ctrl = uart->regs->ctrl;
+ ctrl = grlib_load_32(&uart->regs->ctrl);
switch (t->c_cflag & (PARENB|PARODD)) {
case (PARENB|PARODD):
@@ -143,7 +148,7 @@ static bool apbuart_set_attributes(
}
/* Update new settings */
- uart->regs->ctrl = ctrl;
+ grlib_store_32(&uart->regs->ctrl, ctrl);
rtems_termios_device_lock_release(base, &lock_context);
@@ -154,7 +159,7 @@ static bool apbuart_set_attributes(
scaler = (((uart->freq_hz * 10) / (baud * 8)) - 5) / 10;
/* Set new baud rate by setting scaler */
- uart->regs->scaler = scaler;
+ grlib_store_32(&uart->regs->scaler, scaler);
}
return true;
@@ -165,7 +170,8 @@ static void apbuart_set_best_baud(
struct termios *term
)
{
- uint32_t baud = (uart->freq_hz * 10) / ((uart->regs->scaler * 10 + 5) * 8);
+ uint32_t baud = (uart->freq_hz * 10) /
+ ((grlib_load_32(&uart->regs->scaler) * 10 + 5) * 8);
rtems_termios_set_best_baud(term, baud);
}
@@ -178,12 +184,15 @@ static bool apbuart_first_open_polled(
)
{
struct apbuart_context *uart = (struct apbuart_context *) base;
+ uint32_t ctrl;
apbuart_set_best_baud(uart, term);
/* Initialize UART on opening */
- uart->regs->ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
- uart->regs->status = 0;
+ ctrl = grlib_load_32(&uart->regs->ctrl);
+ ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
+ grlib_store_32(&uart->regs->ctrl, ctrl);
+ grlib_store_32(&uart->regs->status, 0);
return true;
}
@@ -197,6 +206,7 @@ static bool apbuart_first_open_interrupt(
{
struct apbuart_context *uart = (struct apbuart_context *) base;
rtems_status_code sc;
+ uint32_t ctrl;
apbuart_set_best_baud(uart, term);
@@ -210,11 +220,13 @@ static bool apbuart_first_open_interrupt(
uart->sending = 0;
/* Enable Receiver and transmitter and Turn on RX interrupts */
- uart->regs->ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE |
- APBUART_CTRL_RI;
+ ctrl = grlib_load_32(&uart->regs->ctrl);
+ ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE | APBUART_CTRL_RI;
+ grlib_store_32(&uart->regs->ctrl, ctrl);
/* Initialize UART on opening */
- uart->regs->ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
- uart->regs->status = 0;
+ ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
+ grlib_store_32(&uart->regs->ctrl, ctrl);
+ grlib_store_32(&uart->regs->status, 0);
return true;
}
@@ -227,10 +239,13 @@ static void apbuart_last_close_interrupt(
{
struct apbuart_context *uart = (struct apbuart_context *) base;
rtems_interrupt_lock_context lock_context;
+ uint32_t ctrl;
/* Turn off RX interrupts */
rtems_termios_device_lock_acquire(base, &lock_context);
- uart->regs->ctrl &= ~(APBUART_CTRL_RI);
+ ctrl = grlib_load_32(&uart->regs->ctrl);
+ ctrl &= ~APBUART_CTRL_RI;
+ grlib_store_32(&uart->regs->ctrl, ctrl);
rtems_termios_device_lock_release(base, &lock_context);
/**** Flush device ****/
diff --git a/bsps/sparc/leon3/console/console.c b/bsps/sparc/leon3/console/console.c
index 153907840f..afa15e028b 100644
--- a/bsps/sparc/leon3/console/console.c
+++ b/bsps/sparc/leon3/console/console.c
@@ -62,7 +62,7 @@ static int find_matching_apbuart(struct ambapp_dev *dev, int index, void *arg)
struct ambapp_apb_info *apb = (struct ambapp_apb_info *)dev->devinfo;
/* Extract needed information of one APBUART */
- apbuarts[uarts].regs = (struct apbuart_regs *)apb->start;
+ apbuarts[uarts].regs = (apbuart *)apb->start;
apbuarts[uarts].irq = apb->common.irq;
/* Get APBUART core frequency, it is assumed that it is the same
* as Bus frequency where the UART is situated
diff --git a/bsps/sparc/leon3/console/printk_support.c b/bsps/sparc/leon3/console/printk_support.c
index f9cf0b7520..d540e75911 100644
--- a/bsps/sparc/leon3/console/printk_support.c
+++ b/bsps/sparc/leon3/console/printk_support.c
@@ -16,14 +16,17 @@
*/
#include <bsp.h>
-#include <leon.h>
+#include <bsp/leon3.h>
#include <rtems/bspIo.h>
#include <rtems/sysinit.h>
#include <rtems/score/thread.h>
#include <grlib/apbuart.h>
+#include <grlib/io.h>
+
+#include <grlib/ambapp.h>
int leon3_debug_uart_index __attribute__((weak)) = 0;
-struct apbuart_regs *leon3_debug_uart = NULL;
+apbuart *leon3_debug_uart = NULL;
static void bsp_debug_uart_init(void);
@@ -86,15 +89,18 @@ static void bsp_debug_uart_init(void)
ambapp_find_by_idx, (void *)&i);
if (adev != NULL) {
struct ambapp_apb_info *apb;
+ uint32_t ctrl;
/*
* Found a matching debug console, initialize debug UART if present for
* printk().
*/
apb = (struct ambapp_apb_info *)adev->devinfo;
- leon3_debug_uart = (struct apbuart_regs *)apb->start;
- leon3_debug_uart->ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
- leon3_debug_uart->status = 0;
+ leon3_debug_uart = (apbuart *)apb->start;
+ ctrl = grlib_load_32(&leon3_debug_uart->ctrl);
+ ctrl |= APBUART_CTRL_RE | APBUART_CTRL_TE;
+ grlib_store_32(&leon3_debug_uart->ctrl, ctrl);
+ grlib_store_32(&leon3_debug_uart->status, 0);
BSP_poll_char = bsp_debug_uart_poll_char;
BSP_output_char = bsp_debug_uart_output_char;
diff --git a/bsps/sparc/leon3/include/bsp/leon3.h b/bsps/sparc/leon3/include/bsp/leon3.h
index 32d18be14b..c0359937f9 100644
--- a/bsps/sparc/leon3/include/bsp/leon3.h
+++ b/bsps/sparc/leon3/include/bsp/leon3.h
@@ -38,6 +38,7 @@
#include <rtems.h>
#include <grlib/grlib.h>
+#include <grlib/apbuart-regs.h>
struct ambapp_dev;
@@ -104,6 +105,11 @@ static inline uint32_t bsp_irq_fixup( uint32_t irq )
return eirq;
}
+/**
+ * @brief This pointer provides the debug APBUART register block address.
+ */
+extern apbuart *leon3_debug_uart;
+
/** @} */
#ifdef __cplusplus