[PATCH 11/34] bsps: Use new APBUART register block API

Sebastian Huber sebastian.huber at embedded-brains.de
Wed May 31 16:30:46 UTC 2023


---
 bsps/include/grlib/apbuart_termios.h      |   4 +-
 bsps/shared/grlib/uart/apbuart_cons.c     | 136 +++++++++++++---------
 bsps/shared/grlib/uart/apbuart_polled.c   |  52 +++++----
 bsps/shared/grlib/uart/apbuart_termios.c  |  49 +++++---
 bsps/sparc/leon3/console/console.c        |   2 +-
 bsps/sparc/leon3/console/printk_support.c |  16 ++-
 bsps/sparc/leon3/include/bsp/leon3.h      |   6 +
 7 files changed, 162 insertions(+), 103 deletions(-)

diff --git a/bsps/include/grlib/apbuart_termios.h b/bsps/include/grlib/apbuart_termios.h
index 82eb4b6de4..a19b99b609 100644
--- a/bsps/include/grlib/apbuart_termios.h
+++ b/bsps/include/grlib/apbuart_termios.h
@@ -34,7 +34,7 @@
 #define APBUART_TERMIOS_H
 
 #include <rtems/termiostypes.h>
-#include "grlib.h"
+#include "apbuart.h"
 
 #ifdef __cplusplus
 extern "C" {
@@ -42,7 +42,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 5d47b7f4a1..74f9bf3e0c 100644
--- a/bsps/shared/grlib/uart/apbuart_cons.c
+++ b/bsps/shared/grlib/uart/apbuart_cons.c
@@ -47,11 +47,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
@@ -60,12 +64,6 @@
 #define DBG(x...)
 #endif
 
-/* LEON3 Low level transmit/receive functions provided by debug-uart code */
-#ifdef LEON3
-#include <leon.h>
-extern struct apbuart_regs *leon3_debug_uart; /* The debug UART */
-#endif
-
 /* Probed hardware capabilities */
 enum {
 	CAP_FIFO = 0x01, /* FIFO available */
@@ -74,7 +72,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[52];
 	volatile int sending;
@@ -213,18 +211,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;
 		}
 	}
@@ -241,6 +244,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
@@ -269,10 +273,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).
@@ -280,10 +286,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.
@@ -293,12 +299,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);
 
@@ -387,12 +393,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;
@@ -407,6 +414,8 @@ static bool first_open(
 )
 {
 	struct apbuart_priv *uart = base_get_priv(base);
+	apbuart *regs = uart->regs;
+	uint32_t ctrl;
 
 	uart->tty = tty;
 
@@ -418,7 +427,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;
@@ -435,15 +445,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;
 }
 
@@ -454,13 +464,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 ****/
@@ -468,8 +481,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 */
 		}
@@ -480,8 +493,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
 }
 
@@ -497,10 +513,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;
@@ -511,10 +528,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) {
@@ -528,9 +545,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;
 }
@@ -541,7 +560,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);
@@ -576,7 +595,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):
@@ -603,7 +622,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);
 
@@ -617,7 +636,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;
@@ -637,7 +656,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 */
@@ -673,11 +692,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) {
 		/*
@@ -685,28 +704,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;
@@ -722,21 +743,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);
@@ -749,10 +773,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 b83af56b09..f3e4997a12 100644
--- a/bsps/shared/grlib/uart/apbuart_polled.c
+++ b/bsps/shared/grlib/uart/apbuart_polled.c
@@ -1,8 +1,17 @@
 /* SPDX-License-Identifier: BSD-2-Clause */
 
+/**
+ * @file
+ *
+ * @ingroup RTEMSDeviceGRLIBAPBUART
+ *
+ * @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 & Co. KG
  *
  * Redistribution and use in source and binary forms, with or without
  * modification, are permitted provided that the following conditions
@@ -27,38 +36,37 @@
  */
 
 #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 6506b70e3d..8b5ccd67f6 100644
--- a/bsps/shared/grlib/uart/apbuart_termios.c
+++ b/bsps/shared/grlib/uart/apbuart_termios.c
@@ -32,6 +32,7 @@
 
 #include <grlib/apbuart_termios.h>
 #include <grlib/apbuart.h>
+#include <grlib/io.h>
 #include <bsp.h>
 
 static void apbuart_isr(void *arg)
@@ -42,9 +43,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);
@@ -52,7 +53,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);
@@ -67,23 +68,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;
 }
 
@@ -134,7 +139,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):
@@ -162,7 +167,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);
 
@@ -173,7 +178,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;
@@ -184,7 +189,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);
 }
@@ -197,12 +203,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;
 }
@@ -216,6 +225,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);
 
@@ -229,11 +239,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;
 }
@@ -246,10 +258,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 24484eb96f..891116b2c4 100644
--- a/bsps/sparc/leon3/console/console.c
+++ b/bsps/sparc/leon3/console/console.c
@@ -81,7 +81,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 9fd1b1a089..cb77c66a96 100644
--- a/bsps/sparc/leon3/console/printk_support.c
+++ b/bsps/sparc/leon3/console/printk_support.c
@@ -35,14 +35,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);
 
@@ -105,15 +108,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 05915a7dea..7c723de129 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
-- 
2.35.3



More information about the devel mailing list