This patch adds support for running RTEMS on the RPU (cortex R5) cores of
the ZynqMP.  This is only a basic BSP and does not yet support the
following:
- SMP
- Cache
- MPU

Also, everything except for the startup and exception vectors runs out of
DRAM, which is slow without cache.  At some point in the future, I plan to
move some of the fast memory sections to ATCM and BTCM and enable cache.

Lastly, credit to Stanislav (s.pankev...@gmail.com, also on this mailing
list), for internal reviews and feedback.

The steps done to implement this BSP are as follows:
- to xilinx_zynqmp_ultra96 bsp (spec/build/bsps/arm/xilinx-zynqmp/*)
  - Added optprocunitapu.yml to pass C define ZYNQMP_PROC_UNIT_APU
- Copied xilinx_zynqmp_ultra96 bsp to xilinx_zynqmp_mercuryxu5_rpu in
spec/build/bsps/arm/xilinx-zynqmp-rpu/*
- In new BSP
  - changed optprocunitapu.yml to optprocunitrpu.yml to pass C define
ZYNQMP_PROC_UNIT_RPU
  - Removed all things regarding MMU, and SMP
  - Changed source: bsps/arm/shared/cache/cache-cp15.c to
bsps/shared/cache/nocache.c
  - Removed all other references to cache
  - Changed abi flags
  - Updated the linkcmds to remove MMU and cache sections.
  - Updated optint0len, optint0ori, optint1len, and optint1ori to target
ATCM and BTCM.
  - Updated linkcmds to place START and VECTOR regions in ATCM
- In BSP C sources
  - Used ZYNQMP_PROC_UNIT_APU and ZYNQMP_PROC_UNIT_RPU to enable/disable
MPU, SMP, and cache.
  - Used PROC_UNIT flags to control GIC address.
  - Added hook0 code for RPU code to make sure SCTLR[M, I, A, C, V] are
cleared
  - Created a timer driver for the Triple Timer Counter (TTC) module since
the RPU doesn't have an ARM generic timer

---
diff --git a/bsps/arm/xilinx-zynqmp/clock/clock-ttc.c
b/bsps/arm/xilinx-zynqmp/clock/clock-ttc.c
new file mode 100644
index 0000000000..dd0bc3a3c9
--- /dev/null
+++ b/bsps/arm/xilinx-zynqmp/clock/clock-ttc.c
@@ -0,0 +1,219 @@
+/**
+ * @file
+ *
+ * @ingroup RTEMSBSPsARMZynqMP
+ *
+ * @brief Triple Timer Counter clock functions definitions.
+ */
+
+/*
+ * SPDX-License-Identifier: BSD-2-Clause
+ *
+ * Copyright (C) 2023 Reflex Aerospace GmbH
+ *
+ * Written by Philip Kirkpatrick <p.kirkpatr...@reflexaerospace.com>
+ *
+ * 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.
+ */
+
+#include <stdlib.h>
+
+#include <rtems.h>
+#include <bsp.h>
+#include <bsp/irq.h>
+#include <bsp/zynqmp.h>
+#include <bsp/xttcps_hw.h>
+#include <rtems/timecounter.h>
+
+static struct timecounter zynqmp_ttc_tc;
+
+#define TTC_REFERENCE_CLOCK 100000000
+
+/* This is defined in dev/clock/clockimpl.h */
+void Clock_isr(rtems_irq_hdl_param arg);
+
+static uint32_t irq_match_interval;
+
+static uint32_t zynqmp_ttc_get_timecount(struct timecounter *tc)
+{
+  uint32_t time;
+  time = XTtcPs_ReadReg(ZYNQMP_TTC0, XTTCPS_COUNT_VALUE_OFFSET);
+  return time;
+}
+
+/**
+ *  @brief Initialize the HW peripheral for clock driver
+ *
+ *  Clock driver is implemented by RTI module
+ *
+ * @retval Void
+ */
+static void zynqmp_ttc_clock_driver_support_initialize_hardware( void )
+{
+
+  uint32_t microsec_per_tick;
+  uint16_t clock_ratio;
+  uint8_t  index;
+  uint32_t frequency;
+  uint32_t prescaler;
+  uint32_t tmp_reg_val;
+
+  microsec_per_tick = rtems_configuration_get_microseconds_per_tick();
+
+  /* Check the TTC is OFF before reconfiguring */
+  XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_CNT_CNTRL_OFFSET,
XTTCPS_CNT_CNTRL_DIS_MASK |
+        XTTCPS_CNT_CNTRL_EN_WAVE_MASK);  // Don't enable waveform output
(active low)
+
+  /* Prescaler value is 2^(N + 1) */
+  /* Divide down the clock as much as possible while still retaining a */
+  /* frequency that is an integer multiple of 1MHz.  This maximizes time
to */
+  /* overflow while minimizing rounding errors in 1us periods */
+  clock_ratio = TTC_REFERENCE_CLOCK / 1000000;
+  /* Search for the highest set bit.  This is effectively
min(log2(ratio))*/
+  for(index = sizeof(clock_ratio) * 8 - 1; index > 0; index--)
+  {
+    if((clock_ratio >> (index)) & 0x01)
+    {
+        break;
+    }
+  }
+  if(index == 0 && (clock_ratio & 0x01 == 0))
+  {
+    // No prescaler
+    frequency = TTC_REFERENCE_CLOCK;
+    XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_CLK_CNTRL_OFFSET, 0);
+  }
+  else
+  {
+    prescaler = index - 1;
+    frequency = TTC_REFERENCE_CLOCK / (1 << (prescaler + 1));
+    XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_CLK_CNTRL_OFFSET,
+        prescaler << XTTCPS_CLK_CNTRL_PS_VAL_SHIFT |
+        XTTCPS_CLK_CNTRL_PS_EN_MASK);
+  }
+
+  /* Max out the counter interval */
+  tmp_reg_val = XTTCPS_INTERVAL_VAL_MASK;
+  XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_INTERVAL_VAL_OFFSET, tmp_reg_val);
+
+  /* Setup match register to generate tick IRQ */
+  irq_match_interval = (uint32_t) ((frequency * microsec_per_tick) /
1000000);
+  XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_MATCH_0_OFFSET, irq_match_interval);
+  /* Clear interupts (clear on read) */
+  XTtcPs_ReadReg(ZYNQMP_TTC0, XTTCPS_ISR_OFFSET);
+  /* Enable interupt for match register */
+  XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_IER_OFFSET, XTTCPS_IXR_MATCH_0_MASK);
+  /* Configure, reset, and enable counter */
+  XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_CNT_CNTRL_OFFSET,
+        XTTCPS_CNT_CNTRL_EN_WAVE_MASK |  /* Don't enable waveform output
(active low) */
+        XTTCPS_CNT_CNTRL_RST_MASK |      /* Reset count and start counter
*/
+        XTTCPS_CNT_CNTRL_MATCH_MASK      /* Enable match mode */
+        /* Increment mode */
+        /* Overflow mode */
+        /* Not disabled */
+        );
+
+  /* set timecounter */
+  zynqmp_ttc_tc.tc_get_timecount = zynqmp_ttc_get_timecount;
+  zynqmp_ttc_tc.tc_counter_mask = XTTCPS_COUNT_VALUE_MASK;
+  zynqmp_ttc_tc.tc_frequency = frequency;
+  zynqmp_ttc_tc.tc_quality = RTEMS_TIMECOUNTER_QUALITY_CLOCK_DRIVER;
+  rtems_timecounter_install(&zynqmp_ttc_tc);
+}
+
+/**
+ * @brief Clears interrupt source
+ *
+ * @retval Void
+ */
+static uint32_t tick_miss = 0;
+static void zynqmp_ttc_clock_driver_support_at_tick( void )
+{
+  uint32_t irq_flags;
+  uint32_t cval;
+  uint32_t now;
+  uint32_t delta;
+
+  /* Get and clear interupts (clear on read) */
+  irq_flags = XTtcPs_ReadReg(ZYNQMP_TTC0, XTTCPS_ISR_OFFSET);
+
+  if(irq_flags & XTTCPS_IXR_MATCH_0_MASK)
+  {
+    /* Update match */
+    cval = XTtcPs_ReadReg(ZYNQMP_TTC0, XTTCPS_MATCH_0_OFFSET);
+    /* Check that the match for the next tick is in the future */
+    /* If no, then set the match for one irq interval from now */
+    /*   This will have the effect that your timebase will slip but */
+    /*   won't hang waiting for the counter to wrap around. */
+    /* If this happens durring normal opteration, there is a problem */
+    /*   causing this interrupt to not be serviced quickly enough */
+    /* If this happens during debugging, that is normal and expected */
+    /*   becaue the TTC does NOT pause when the CPU is halted on a
breakpoint */
+    now = XTtcPs_ReadReg(ZYNQMP_TTC0, XTTCPS_COUNT_VALUE_OFFSET);
+    delta = now - cval;
+    if(delta > irq_match_interval)
+    {
+     cval = now;
+     tick_miss++;
+    }
+    cval += irq_match_interval;
+    XTtcPs_WriteReg(ZYNQMP_TTC0, XTTCPS_MATCH_0_OFFSET, cval);
+  }
+  /* Else, something is set up wrong, only match should be enabled */
+}
+
+/**
+ * @brief registers RTI interrupt handler
+ *
+ * @param[in] Clock_isr new ISR handler
+ * @param[in] Old_ticker old ISR handler (unused and type broken)
+ *
+ * @retval Void
+ */
+static void zynqmp_ttc_clock_driver_support_install_isr(
+  rtems_isr_entry Clock_isr
+)
+{
+  rtems_status_code sc = RTEMS_SUCCESSFUL;
+
+  sc = rtems_interrupt_handler_install(
+    ZYNQMP_IRQ_TTC_0_0,
+    "Clock",
+    RTEMS_INTERRUPT_UNIQUE,
+    (rtems_interrupt_handler) Clock_isr,
+    NULL
+  );
+  if ( sc != RTEMS_SUCCESSFUL ) {
+    rtems_fatal_error_occurred(0xdeadbeef);
+  }
+}
+
+#define Clock_driver_support_at_tick \
+                        zynqmp_ttc_clock_driver_support_at_tick
+
+#define Clock_driver_support_initialize_hardware \
+                        zynqmp_ttc_clock_driver_support_initialize_hardware
+
+#define Clock_driver_support_install_isr(Clock_isr) \
+              zynqmp_ttc_clock_driver_support_install_isr( Clock_isr )
+
+#include "../../../shared/dev/clock/clockimpl.h"
diff --git a/bsps/arm/xilinx-zynqmp/config/xilinx_zynqmp_rpu.inc
b/bsps/arm/xilinx-zynqmp/config/xilinx_zynqmp_rpu.inc
new file mode 100644
index 0000000000..f97f4d5018
--- /dev/null
+++ b/bsps/arm/xilinx-zynqmp/config/xilinx_zynqmp_rpu.inc
@@ -0,0 +1,10 @@
+include $(RTEMS_ROOT)/make/custom/default.cfg
+
+RTEMS_CPU = arm
+
+CPU_CFLAGS = -march=armv7-r -mthumb -mfpu=vfpv3-d16 -mfloat-abi=hard
+
+CFLAGS_OPTIMIZE_V ?= -O2 -g
+CFLAGS_OPTIMIZE_V += -ffunction-sections -fdata-sections
+
+LDFLAGS = -Wl,--gc-sections
diff --git a/bsps/arm/xilinx-zynqmp/include/bsp.h
b/bsps/arm/xilinx-zynqmp/include/bsp.h
index 9d33cf6134..d0b4b9d644 100644
--- a/bsps/arm/xilinx-zynqmp/include/bsp.h
+++ b/bsps/arm/xilinx-zynqmp/include/bsp.h
@@ -64,9 +64,17 @@
 extern "C" {
 #endif /* __cplusplus */

+#ifdef ZYNQMP_PROC_UNIT_APU
 #define BSP_ARM_GIC_CPUIF_BASE 0xf9020000

 #define BSP_ARM_GIC_DIST_BASE 0xf9010000
+#endif
+
+#ifdef ZYNQMP_PROC_UNIT_RPU
+#define BSP_ARM_GIC_CPUIF_BASE 0x00F9001000
+
+#define BSP_ARM_GIC_DIST_BASE 0xF9000000
+#endif

 #define BSP_ARM_A9MPCORE_SCU_BASE 0

diff --git a/bsps/arm/xilinx-zynqmp/include/bsp/irq.h
b/bsps/arm/xilinx-zynqmp/include/bsp/irq.h
index 9aae8168db..a8271bebb5 100644
--- a/bsps/arm/xilinx-zynqmp/include/bsp/irq.h
+++ b/bsps/arm/xilinx-zynqmp/include/bsp/irq.h
@@ -56,17 +56,32 @@ extern "C" {
  * @brief Interrupt Support
  * @{
  */
-
 /* PPIs */
+#ifdef ZYNQMP_PROC_UNIT_APU
 #define ZYNQMP_IRQ_HYP_TIMER 26
 #define ZYNQMP_IRQ_VIRT_TIMER 27
 #define ZYNQMP_IRQ_S_PHYS_TIMER 29
 #define ZYNQMP_IRQ_NS_PHYS_TIMER 30
+#endif

 /* SPIs */
 #define ZYNQMP_IRQ_UART_0 53
 #define ZYNQMP_IRQ_UART_1 54

+#define ZYNQMP_IRQ_TTC_0_0 68
+#define ZYNQMP_IRQ_TTC_0_1 69
+#define ZYNQMP_IRQ_TTC_0_2 70
+#define ZYNQMP_IRQ_TTC_1_0 71
+#define ZYNQMP_IRQ_TTC_1_1 72
+#define ZYNQMP_IRQ_TTC_1_2 73
+#define ZYNQMP_IRQ_TTC_2_0 74
+#define ZYNQMP_IRQ_TTC_2_1 75
+#define ZYNQMP_IRQ_TTC_2_2 76
+#define ZYNQMP_IRQ_TTC_3_0 77
+#define ZYNQMP_IRQ_TTC_3_1 78
+#define ZYNQMP_IRQ_TTC_3_2 79
+
+
 #define BSP_INTERRUPT_VECTOR_COUNT 188

 /** @} */
diff --git a/bsps/arm/xilinx-zynqmp/include/bsp/xttcps_hw.h
b/bsps/arm/xilinx-zynqmp/include/bsp/xttcps_hw.h
new file mode 100644
index 0000000000..ba0d559b07
--- /dev/null
+++ b/bsps/arm/xilinx-zynqmp/include/bsp/xttcps_hw.h
@@ -0,0 +1,223 @@
+/******************************************************************************
+* Copyright (C) 2010 - 2021 Xilinx, Inc.  All rights reserved.
+* SPDX-License-Identifier: MIT
+******************************************************************************/
+
+/*****************************************************************************/
+/**
+*
+* @file xttcps_hw.h
+* @addtogroup ttcps_v3_14
+* @{
+*
+* This file defines the hardware interface to one of the three timer
counters
+* in the Ps block.
+*
+*
+* <pre>
+* MODIFICATION HISTORY:
+*
+* Ver   Who    Date     Changes
+* ----- ------ -------- -------------------------------------------------
+* 1.00a drg/jz 01/21/10 First release
+* 3.00  kvn    02/13/15 Modified code for MISRA-C:2012 compliance.
+* 3.5   srm    10/06/17 Updated XTTCPS_COUNT_VALUE_MASK,
+*                       XTTCPS_INTERVAL_VAL_MASK, XTTCPS_MATCH_MASK macros
to
+*                       mask 16 bit values for zynq and 32 bit values for
+*                       zynq ultrascale+mpsoc "
+* </pre>
+*
+******************************************************************************/
+
+#ifndef XTTCPS_HW_H /* prevent circular inclusions */
+#define XTTCPS_HW_H /* by using protection macros */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/***************************** Include Files
*********************************/
+
+
+#ifndef __rtems__
+#include "xil_types.h"
+#include "xil_assert.h"
+#include "xil_io.h"
+#else
+#include "xil_types.h"
+static inline u32 Xil_In32(UINTPTR Addr)
+{
+ return *(volatile u32 *) Addr;
+}
+static inline void Xil_Out32(UINTPTR Addr, u32 Value)
+{
+ volatile u32 *LocalAddr = (volatile u32 *)Addr;
+ *LocalAddr = Value;
+}
+#endif /* __rtems__ */
+
+/************************** Constant Definitions
*****************************/
+/*
+ * Flag for a9 processor
+ */
+#if 0
+ #if !defined (ARMR5) && !defined (__aarch64__) && !defined (ARMA53_32)
+ #define ARMA9
+ #endif
+#endif
+
+/** @name Register Map
+ *
+ * Register offsets from the base address of the device.
+ *
+ * @{
+ */
+#define XTTCPS_CLK_CNTRL_OFFSET 0x00000000U  /**< Clock Control Register */
+#define XTTCPS_CNT_CNTRL_OFFSET 0x0000000CU  /**< Counter Control
Register*/
+#define XTTCPS_COUNT_VALUE_OFFSET 0x00000018U  /**< Current Counter Value
*/
+#define XTTCPS_INTERVAL_VAL_OFFSET 0x00000024U  /**< Interval Count Value
*/
+#define XTTCPS_MATCH_0_OFFSET 0x00000030U  /**< Match 1 value */
+#define XTTCPS_MATCH_1_OFFSET 0x0000003CU  /**< Match 2 value */
+#define XTTCPS_MATCH_2_OFFSET 0x00000048U  /**< Match 3 value */
+#define XTTCPS_ISR_OFFSET 0x00000054U  /**< Interrupt Status Register */
+#define XTTCPS_IER_OFFSET 0x00000060U  /**< Interrupt Enable Register */
+/* @} */
+
+/** @name Clock Control Register
+ * Clock Control Register definitions
+ * @{
+ */
+#define XTTCPS_CLK_CNTRL_PS_EN_MASK 0x00000001U  /**< Prescale enable */
+#define XTTCPS_CLK_CNTRL_PS_VAL_MASK 0x0000001EU  /**< Prescale value */
+#define XTTCPS_CLK_CNTRL_PS_VAL_SHIFT 1U  /**< Prescale shift */
+#define XTTCPS_CLK_CNTRL_PS_DISABLE 16U  /**< Prescale disable */
+#define XTTCPS_CLK_CNTRL_SRC_MASK 0x00000020U  /**< Clock source */
+#define XTTCPS_CLK_CNTRL_EXT_EDGE_MASK 0x00000040U  /**< External Clock
edge */
+/* @} */
+
+/** @name Counter Control Register
+ * Counter Control Register definitions
+ * @{
+ */
+#define XTTCPS_CNT_CNTRL_DIS_MASK 0x00000001U /**< Disable the counter */
+#define XTTCPS_CNT_CNTRL_INT_MASK 0x00000002U /**< Interval mode */
+#define XTTCPS_CNT_CNTRL_DECR_MASK 0x00000004U /**< Decrement mode */
+#define XTTCPS_CNT_CNTRL_MATCH_MASK 0x00000008U /**< Match mode */
+#define XTTCPS_CNT_CNTRL_RST_MASK 0x00000010U /**< Reset counter */
+#define XTTCPS_CNT_CNTRL_EN_WAVE_MASK 0x00000020U /**< Enable waveform */
+#define XTTCPS_CNT_CNTRL_POL_WAVE_MASK 0x00000040U /**< Waveform polarity
*/
+#define XTTCPS_CNT_CNTRL_RESET_VALUE 0x00000021U /**< Reset value */
+/* @} */
+
+/** @name Current Counter Value Register
+ * Current Counter Value Register definitions
+ * @{
+ */
+#if defined(ARMA9)
+#define XTTCPS_COUNT_VALUE_MASK 0x0000FFFFU /**< 16-bit counter value */
+#else
+#define XTTCPS_COUNT_VALUE_MASK 0xFFFFFFFFU /**< 32-bit counter value */
+#endif
+/* @} */
+
+/** @name Interval Value Register
+ * Interval Value Register is the maximum value the counter will count up
or
+ * down to.
+ * @{
+ */
+#if defined(ARMA9)
+#define XTTCPS_INTERVAL_VAL_MASK (u32)(0x0000FFFF) /**< 16-bit Interval
value*/
+#else
+#define XTTCPS_INTERVAL_VAL_MASK (u32)(0xFFFFFFFF) /**< 32-bit Interval
value*/
+#endif
+/* @} */
+
+/** @name Match Registers
+ * Definitions for Match registers, each timer counter has three match
+ * registers.
+ * @{
+ */
+#if defined(ARMA9)
+#define XTTCPS_MATCH_MASK 0x0000FFFFU /**< 16-bit Match value */
+#else
+#define XTTCPS_MATCH_MASK 0xFFFFFFFFU /**< 32-bit Match value */
+#endif
+#define XTTCPS_NUM_MATCH_REG 3U /**< Num of Match reg */
+/* @} */
+
+/** @name Interrupt Registers
+ * Following register bit mask is for all interrupt registers.
+ *
+ * @{
+ */
+#define XTTCPS_IXR_INTERVAL_MASK 0x00000001U  /**< Interval Interrupt */
+#define XTTCPS_IXR_MATCH_0_MASK 0x00000002U  /**< Match 1 Interrupt */
+#define XTTCPS_IXR_MATCH_1_MASK 0x00000004U  /**< Match 2 Interrupt */
+#define XTTCPS_IXR_MATCH_2_MASK 0x00000008U  /**< Match 3 Interrupt */
+#define XTTCPS_IXR_CNT_OVR_MASK 0x00000010U  /**< Counter Overflow */
+#define XTTCPS_IXR_ALL_MASK 0x0000001FU  /**< All valid Interrupts */
+/* @} */
+
+
+/***************** Macros (Inline Functions) Definitions
*********************/
+
+/****************************************************************************/
+/**
+*
+* Read the given Timer Counter register.
+*
+* @param BaseAddress is the base address of the timer counter device.
+* @param RegOffset is the register offset to be read
+*
+* @return The 32-bit value of the register
+*
+* @note C-style signature:
+* u32 XTtcPs_ReadReg(u32 BaseAddress, u32 RegOffset)
+*
+*****************************************************************************/
+#define XTtcPs_ReadReg(BaseAddress, RegOffset) \
+    (Xil_In32((BaseAddress) + (u32)(RegOffset)))
+
+/****************************************************************************/
+/**
+*
+* Write the given Timer Counter register.
+*
+* @param BaseAddress is the base address of the timer counter device.
+* @param RegOffset is the register offset to be written
+* @param Data is the 32-bit value to write to the register
+*
+* @return None.
+*
+* @note C-style signature:
+* void XTtcPs_WriteReg(XTtcPs BaseAddress, u32 RegOffset,
+* u32 Data)
+*
+*****************************************************************************/
+#define XTtcPs_WriteReg(BaseAddress, RegOffset, Data) \
+    (Xil_Out32((BaseAddress) + (u32)(RegOffset), (u32)(Data)))
+
+/****************************************************************************/
+/**
+*
+* Calculate a match register offset using the Match Register index.
+*
+* @param MatchIndex is the 0-2 value of the match register
+*
+* @return MATCH_N_OFFSET.
+*
+* @note C-style signature:
+* u32 XTtcPs_Match_N_Offset(u8 MatchIndex)
+*
+*****************************************************************************/
+#define XTtcPs_Match_N_Offset(MatchIndex) \
+ ((u32)XTTCPS_MATCH_0_OFFSET + ((u32)(12U) * (u32)(MatchIndex)))
+
+/************************** Function Prototypes
******************************/
+
+/************************** Variable Definitions
*****************************/
+#ifdef __cplusplus
+}
+#endif
+#endif /* end of protection macro */
+/** @} */
diff --git a/bsps/arm/xilinx-zynqmp/include/bsp/zynqmp.h
b/bsps/arm/xilinx-zynqmp/include/bsp/zynqmp.h
new file mode 100644
index 0000000000..7a48810490
--- /dev/null
+++ b/bsps/arm/xilinx-zynqmp/include/bsp/zynqmp.h
@@ -0,0 +1,92 @@
+/*
+ * SPDX-License-Identifier: BSD-2-Clause
+ *
+ * Copyright (C) 2023 Reflex Aerospace GmbH
+ *
+ * Written by Philip Kirkpatrick <p.kirkpatr...@reflexaerospace.com>
+ *
+ * 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 LIBBSP_ARM_ZYNQMP
+#define LIBBSP_ARM_ZYNQMP
+
+/* Data derived from
https://docs.xilinx.com/r/en-US/ug1085-zynq-ultrascale-trm/PS-I/O-Peripherals-Registers
*/
+
+/* LPD IO Peripherals */
+#define ZYNQMP_UART0 (0xFF000000)
+#define ZYNQMP_UART1 (0xFF010000)
+#define ZYNQMP_I2C0 (0xFF020000)
+#define ZYNQMP_I2C1 (0xFF030000)
+#define ZYNQMP_SPI0 (0xFF040000)
+#define ZYNQMP_SPI1 (0xFF050000)
+#define ZYNQMP_CAN0 (0xFF060000)
+#define ZYNQMP_CAN1 (0xFF070000)
+#define ZYNQMP_GPIO (0xFF0A0000)
+#define ZYNQMP_GEM0 (0xFF0B0000)
+#define ZYNQMP_GEM1 (0xFF0C0000)
+#define ZYNQMP_GEM2 (0xFF0D0000)
+#define ZYNQMP_GEM3 (0xFF0E0000)
+#define ZYNQMP_QSPI (0xFF0F0000)
+#define ZYNQMP_NAND (0xFF100000)
+#define ZYNQMP_SD0 (0xFF160000)
+#define ZYNQMP_SD1 (0xFF170000)
+#define ZYNQMP_IPI_MSG (0xFF990000)
+#define ZYNQMP_USB0 (0xFF9D0000)
+#define ZYNQMP_USB1 (0xFF9E0000)
+#define ZYNQMP_AMS (0xFFA50000)
+#define ZYNQMP_PSSYSMON (0xFFA50800)
+#define ZYNQMP_PLSYSMON (0xFFA50C00)
+#define ZYNQMP_CSU_SWDT (0xFFCB0000)
+
+/* FPD IO Peripherals */
+#define ZYNQMP_SATA (0xFD0C0000)
+#define ZYNQMP_PCIE (0xFD0E0000)
+#define ZYNQMP_PCIE_IN (0xFD0E0800)
+#define ZYNQMP_PCIE_EG (0xFD0E0C00)
+#define ZYNQMP_PCIE_DMA (0xFD0F0000)
+#define ZYNQMP_SIOU (0xFD3D0000)
+#define ZYNQMP_GTR (0xFD400000)
+#define ZYNQMP_PCIE_ATTR (0xFD480000)
+#define ZYNQMP_DP (0xFD4A0000)
+#define ZYNQMP_GPU (0xFD4B0000)
+#define ZYNQMP_DP_DMA (0xFD4C0000)
+
+/* LPD System Registers */
+#define ZYNQMP_IPI (0xFF300000)
+#define ZYNQMP_TTC0 (0xFF110000)
+#define ZYNQMP_TTC1 (0xFF120000)
+#define ZYNQMP_TTC2 (0xFF130000)
+#define ZYNQMP_TTC3 (0xFF140000)
+#define ZYNQMP_LPD_SWDT (0xFF150000)
+#define ZYNQMP_XPPU (0xFF980000)
+#define ZYNQMP_XPPU_SINK (0xFF9C0000)
+#define ZYNQMP_PL_LPD (0xFF9B0000)
+#define ZYNQMP_OCM (0xFFA00000)
+#define ZYNQMP_LPD_FPD (0xFFA10000)
+#define ZYNQMP_RTC (0xFFA60000)
+#define ZYNQMP_OCM_XMPU (0xFFA70000)
+#define ZYNQMP_LPD_DMA (0xFFA80000)
+#define ZYNQMP_CSU_DMA (0xFFC80000)
+#define ZYNQMP_CSU (0xFFCA0000)
+#define ZYNQMP_BBRAM (0xFFCD0000)
+
+#endif /* LIBBSP_ARM_ZYNQMP */
diff --git a/bsps/arm/xilinx-zynqmp/start/bspsmp.c
b/bsps/arm/xilinx-zynqmp/start/bspsmp.c
index 28a4b6d54d..4129e6dd59 100644
--- a/bsps/arm/xilinx-zynqmp/start/bspsmp.c
+++ b/bsps/arm/xilinx-zynqmp/start/bspsmp.c
@@ -34,6 +34,7 @@

 #include <bsp/start.h>

+#ifdef ZYNQMP_PROC_UNIT_APU
 bool _CPU_SMP_Start_processor(uint32_t cpu_index)
 {
   /*
@@ -55,3 +56,11 @@ bool _CPU_SMP_Start_processor(uint32_t cpu_index)
    */
   return _Per_CPU_State_wait_for_non_initial_state(cpu_index, 0);
 }
+
+#ifdef ZYNQMP_PROC_UNIT_RPU
+
+/*
+ * SMP not currently supported on RPU
+ */
+
+#endif
\ No newline at end of file
diff --git a/bsps/arm/xilinx-zynqmp/start/bspstart.c
b/bsps/arm/xilinx-zynqmp/start/bspstart.c
index fe04ef4f8f..2825653557 100644
--- a/bsps/arm/xilinx-zynqmp/start/bspstart.c
+++ b/bsps/arm/xilinx-zynqmp/start/bspstart.c
@@ -38,6 +38,7 @@

 #include <libcpu/arm-cp15.h>

+#ifdef ZYNQMP_PROC_UNIT_APU
 void arm_generic_timer_get_config(uint32_t *frequency, uint32_t *irq)
 {
 #ifdef ARM_GENERIC_TIMER_FREQ
@@ -53,12 +54,15 @@ void arm_generic_timer_get_config(uint32_t *frequency,
uint32_t *irq)
   *irq = ZYNQMP_IRQ_NS_PHYS_TIMER;
 #endif
 }
+#endif

 void bsp_start(void)
 {
   bsp_interrupt_initialize();
+#ifdef ZYNQMP_PROC_UNIT_APU
   rtems_cache_coherent_add_area(
     bsp_section_nocacheheap_begin,
     (uintptr_t) bsp_section_nocacheheap_size
   );
+#endif
 }
diff --git a/bsps/arm/xilinx-zynqmp/start/bspstarthooks.c
b/bsps/arm/xilinx-zynqmp/start/bspstarthooks.c
index ef76563a38..07f97fb5fd 100644
--- a/bsps/arm/xilinx-zynqmp/start/bspstarthooks.c
+++ b/bsps/arm/xilinx-zynqmp/start/bspstarthooks.c
@@ -35,12 +35,34 @@

 BSP_START_TEXT_SECTION void bsp_start_hook_0(void)
 {
-  /* Nothing to do */
+  #ifdef ZYNQMP_PROC_UNIT_RPU
+ /*
+     * On reset, V will be set.  This points the exceptions to the FSBL's
vectors.  The FSBL
+     * should clear this bit before booting RTEMS but in some debugging
+     * configurations the bit may not be.  The other bits should already
be clear
+     * on reset.  Since the correct settings in these bits are critical,
+ * make sure SCTLR[M, I, A, C, V] are cleared.  Afterwards, exceptions are
+ * handled by RTEMS.
+     * Note 1: The APU also does these steps in start.S in _start in the
#if block at line 401
+     * Note 2: Not all Arm R cores need this (like the TMS570).  So, this
probably should
+     *         be in this hook and not in start.S
+ */
+
+    __asm__ volatile(
+      "mrc p15, 0, r0, c1, c0, 0 \n"
+      "bic r1, r0, #0x2800 \n"
+      "bic r1, r1, #0x7 \n"
+      "mcr p15, 0, r1, c1, c0, 0 \n"
+        : :);
+
+  #endif
 }

 BSP_START_TEXT_SECTION void bsp_start_hook_1(void)
 {
   bsp_start_copy_sections();
+#ifdef ZYNQMP_PROC_UNIT_APU
   zynqmp_setup_mmu_and_cache();
+#endif
   bsp_start_clear_bss();
 }
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/abi.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/abi.yml
new file mode 100644
index 0000000000..829e9c9297
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/abi.yml
@@ -0,0 +1,21 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-string: null
+- split: null
+- env-append: null
+build-type: option
+copyrights:
+- Copyright (C) 2023 Reflex Aerospace GmbH (
https://www.reflexaerospace.com/)
+default:
+- enabled-by: true
+  value:
+  - -march=armv7-r
+  - -mthumb
+  - -mfpu=vfpv3-d16
+  - -mfloat-abi=hard
+description: |
+  ABI flags
+enabled-by: true
+links: []
+name: ABI_FLAGS
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/bspmercureyxu5.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/bspmercureyxu5.yml
new file mode 100644
index 0000000000..1b8b16796a
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/bspmercureyxu5.yml
@@ -0,0 +1,94 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+arch: arm
+bsp: xilinx_zynqmp_mercuryxu5_rpu
+build-type: bsp
+cflags: []
+copyrights:
+- Copyright (C) 2023 Reflex Aerospace GmbH (
https://www.reflexaerospace.com/)
+cppflags: []
+enabled-by: true
+family: xilinx-zynqmp
+includes:
+- bsps/include/xil/
+install:
+- destination: ${BSP_INCLUDEDIR}
+  source:
+  - bsps/arm/xilinx-zynqmp/include/bsp.h
+  - bsps/include/xil/xil_types.h
+  - bsps/include/xil/xil_assert.h
+  - bsps/include/xil/xil_io.h
+- destination: ${BSP_INCLUDEDIR}/bsp
+  source:
+  - bsps/arm/xilinx-zynqmp/include/bsp/irq.h
+  - bsps/arm/xilinx-zynqmp/include/bsp/xttcps_hw.h
+  - bsps/arm/xilinx-zynqmp/include/bsp/zynqmp.h
+links:
+- role: build-dependency
+  uid: ../grp
+- role: build-dependency
+  uid: ../start
+- role: build-dependency
+  uid: abi
+- role: build-dependency
+  uid: optclkfastidle
+- role: build-dependency
+  uid: optclkuart
+- role: build-dependency
+  uid: optconirq
+- role: build-dependency
+  uid: ../../optconminor
+- role: build-dependency
+  uid: optint0len
+- role: build-dependency
+  uid: optint0ori
+- role: build-dependency
+  uid: optint1len
+- role: build-dependency
+  uid: optint1ori
+- role: build-dependency
+  uid: optramlen
+- role: build-dependency
+  uid: optramori
+- role: build-dependency
+  uid: optresetvec
+- role: build-dependency
+  uid: optprocunitrpu
+- role: build-dependency
+  uid: ../../obj
+- role: build-dependency
+  uid: ../../objirq
+- role: build-dependency
+  uid: ../../objdevserialzynq
+- role: build-dependency
+  uid: ../../objdevspizynq
+- role: build-dependency
+  uid: ../../objdevspixil
+- role: build-dependency
+  uid: ../../objmem
+- role: build-dependency
+  uid: ../../opto0
+- role: build-dependency
+  uid: linkcmds
+- role: build-dependency
+  uid: ../../bspopts
+source:
+- bsps/shared/cache/nocache.c
+- bsps/arm/shared/cp15/arm-cp15-set-exception-handler.c
+- bsps/arm/shared/cp15/arm-cp15-set-ttb-entries.c
+- bsps/arm/shared/start/bsp-start-memcpy.S
+- bsps/arm/xilinx-zynqmp/console/console-config.c
+- bsps/arm/xilinx-zynqmp/start/bspreset.c
+- bsps/arm/xilinx-zynqmp/start/bspstart.c
+- bsps/arm/xilinx-zynqmp/start/bspstarthooks.c
+- bsps/arm/xilinx-zynqmp/clock/clock-ttc.c
+- bsps/shared/dev/btimer/btimer-cpucounter.c
+- bsps/shared/dev/getentropy/getentropy-cpucounter.c
+- bsps/shared/dev/irq/arm-gicv2.c
+- bsps/shared/dev/irq/arm-gicv2-zynqmp.c
+- bsps/shared/dev/serial/console-termios.c
+- bsps/shared/irq/irq-default-handler.c
+- bsps/shared/start/bspfatal-default.c
+- bsps/shared/start/gettargethash-default.c
+- bsps/shared/start/sbrk.c
+- bsps/shared/start/stackalloc.c
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/linkcmds.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/linkcmds.yml
new file mode 100644
index 0000000000..6208dc4b12
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/linkcmds.yml
@@ -0,0 +1,41 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+build-type: config-file
+content: |
+  MEMORY {
+    RAM_INT_0 : ORIGIN = ${ZYNQMP_RAM_INT_0_ORIGIN:#010x}, LENGTH =
${ZYNQMP_RAM_INT_0_LENGTH:#010x}
+    RAM_INT_1 : ORIGIN = ${ZYNQMP_RAM_INT_1_ORIGIN:#010x}, LENGTH =
${ZYNQMP_RAM_INT_1_LENGTH:#010x}
+    RAM       : ORIGIN = ${ZYNQMP_RAM_ORIGIN:#010x}, LENGTH =
${ZYNQMP_RAM_LENGTH:#010x} - ${ZYNQMP_RAM_ORIGIN:#010x}
+  }
+
+  REGION_ALIAS ("REGION_START",          RAM_INT_0);
+  REGION_ALIAS ("REGION_VECTOR",         RAM_INT_0);
+  REGION_ALIAS ("REGION_TEXT",           RAM);
+  REGION_ALIAS ("REGION_TEXT_LOAD",      RAM);
+  REGION_ALIAS ("REGION_RODATA",         RAM);
+  REGION_ALIAS ("REGION_RODATA_LOAD",    RAM);
+  REGION_ALIAS ("REGION_DATA",           RAM);
+  REGION_ALIAS ("REGION_DATA_LOAD",      RAM);
+  REGION_ALIAS ("REGION_FAST_TEXT",      RAM);
+  REGION_ALIAS ("REGION_FAST_TEXT_LOAD", RAM);
+  REGION_ALIAS ("REGION_FAST_DATA",      RAM);
+  REGION_ALIAS ("REGION_FAST_DATA_LOAD", RAM);
+  REGION_ALIAS ("REGION_BSS",            RAM);
+  REGION_ALIAS ("REGION_WORK",           RAM);
+  REGION_ALIAS ("REGION_STACK",          RAM);
+  REGION_ALIAS ("REGION_NOCACHE",        RAM);
+  REGION_ALIAS ("REGION_NOCACHE_LOAD",   RAM);
+
+  bsp_stack_abt_size = DEFINED (bsp_stack_abt_size) ? bsp_stack_abt_size :
1024;
+
+  bsp_section_rwbarrier_align = DEFINED (bsp_section_rwbarrier_align) ?
bsp_section_rwbarrier_align : 1M;
+
+  bsp_vector_table_in_start_section = 1;
+
+  INCLUDE linkcmds.armv4
+copyrights:
+- Copyright (C) 2023 Reflex Aerospace GmbH (
https://www.reflexaerospace.com/)
+enabled-by: true
+install-path: ${BSP_LIBDIR}
+links: []
+target: linkcmds
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optclkfastidle.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optclkfastidle.yml
new file mode 100644
index 0000000000..e303a8bf9f
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optclkfastidle.yml
@@ -0,0 +1,21 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-boolean: null
+- define-condition: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by:
+  - arm/lm3s6965_qemu
+  - arm/realview_pbx_a9_qemu
+  - arm/xilinx_zynq_a9_qemu
+  value: true
+- enabled-by: true
+  value: false
+description: |
+  This sets a mode where the time runs as fast as possible when a clock
ISR occurs while the IDLE thread is executing.  This can significantly
reduce simulation times.
+enabled-by: true
+links: []
+name: CLOCK_DRIVER_USE_FAST_IDLE
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optclkuart.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optclkuart.yml
new file mode 100644
index 0000000000..77c8f30fff
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optclkuart.yml
@@ -0,0 +1,17 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-integer: null
+- define: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: 100000000
+description: |
+  Zynq UART clock frequency in Hz
+enabled-by: true
+format: '{}'
+links: []
+name: ZYNQ_CLOCK_UART
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optconirq.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optconirq.yml
new file mode 100644
index 0000000000..ea13fa4561
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optconirq.yml
@@ -0,0 +1,16 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-boolean: null
+- define-condition: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: true
+description: |
+  use interrupt driven mode for console devices (used by default)
+enabled-by: true
+links: []
+name: ZYNQ_CONSOLE_USE_INTERRUPTS
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint0len.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint0len.yml
new file mode 100644
index 0000000000..774d2c9269
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint0len.yml
@@ -0,0 +1,18 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-integer: null
+- assert-uint32: null
+- env-assign: null
+- format-and-define: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: 0x00010000
+description: ''
+enabled-by: true
+format: '{:#010x}'
+links: []
+name: ZYNQMP_RAM_INT_0_LENGTH
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint0ori.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint0ori.yml
new file mode 100644
index 0000000000..3fa03d3129
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint0ori.yml
@@ -0,0 +1,18 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-integer: null
+- assert-uint32: null
+- env-assign: null
+- format-and-define: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: 0x00000000
+description: ''
+enabled-by: true
+format: '{:#010x}'
+links: []
+name: ZYNQMP_RAM_INT_0_ORIGIN
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint1len.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint1len.yml
new file mode 100644
index 0000000000..f179142ed4
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint1len.yml
@@ -0,0 +1,18 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-integer: null
+- assert-uint32: null
+- env-assign: null
+- format-and-define: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: 0x00010000
+description: ''
+enabled-by: true
+format: '{:#010x}'
+links: []
+name: ZYNQMP_RAM_INT_1_LENGTH
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint1ori.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint1ori.yml
new file mode 100644
index 0000000000..37bbf4fcd0
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optint1ori.yml
@@ -0,0 +1,18 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-integer: null
+- assert-uint32: null
+- env-assign: null
+- format-and-define: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: 0x00020000
+description: ''
+enabled-by: true
+format: '{:#010x}'
+links: []
+name: ZYNQMP_RAM_INT_1_ORIGIN
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optprocunitrpu.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optprocunitrpu.yml
new file mode 100644
index 0000000000..9298808b2a
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optprocunitrpu.yml
@@ -0,0 +1,17 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-boolean: null
+- define-condition: null
+build-type: option
+copyrights:
+- Copyright (C) 2023 Reflex Aerospace GmbH (
https://www.reflexaerospace.com/)
+default:
+- enabled-by: true
+  value: true
+description: |
+  Sets the target processing unit to the RPU (R5F) cores.
+enabled-by: true
+format: '{}'
+links: []
+name: ZYNQMP_PROC_UNIT_RPU
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optramlen.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optramlen.yml
new file mode 100644
index 0000000000..5cb5e805cf
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optramlen.yml
@@ -0,0 +1,21 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-integer: null
+- assert-uint32: null
+- env-assign: null
+- format-and-define: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: arm/xilinx_zynqmp_ultra96
+  value: 0x80000000
+- enabled-by: true
+  value: 0x10000000
+description: |
+  override a BSP's default RAM length
+enabled-by: true
+format: '{:#010x}'
+links: []
+name: ZYNQMP_RAM_LENGTH
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optramori.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optramori.yml
new file mode 100644
index 0000000000..6269b662e0
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optramori.yml
@@ -0,0 +1,19 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-integer: null
+- assert-uint32: null
+- assert-aligned: 1048576
+- env-assign: null
+- format-and-define: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: 0x00100000
+description: ''
+enabled-by: true
+format: '{:#010x}'
+links: []
+name: ZYNQMP_RAM_ORIGIN
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp-rpu/optresetvec.yml
b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optresetvec.yml
new file mode 100644
index 0000000000..bac5c79627
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp-rpu/optresetvec.yml
@@ -0,0 +1,16 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-boolean: null
+- define-condition: null
+build-type: option
+copyrights:
+- Copyright (C) 2020 embedded brains GmbH (http://www.embedded-brains.de)
+default:
+- enabled-by: true
+  value: false
+description: |
+  reset vector address for BSP start
+enabled-by: true
+links: []
+name: BSP_START_RESET_VECTOR
+type: build
diff --git a/spec/build/bsps/arm/xilinx-zynqmp/bspxilinxzynqmp.yml
b/spec/build/bsps/arm/xilinx-zynqmp/bspxilinxzynqmp.yml
index 216cc88360..f14efc2957 100644
--- a/spec/build/bsps/arm/xilinx-zynqmp/bspxilinxzynqmp.yml
+++ b/spec/build/bsps/arm/xilinx-zynqmp/bspxilinxzynqmp.yml
@@ -62,6 +62,8 @@ links:
   uid: optramori
 - role: build-dependency
   uid: optresetvec
+- role: build-dependency
+  uid: optprocunitapu
 - role: build-dependency
   uid: ../../obj
 - role: build-dependency
diff --git a/spec/build/bsps/arm/xilinx-zynqmp/optprocunitapu.yml
b/spec/build/bsps/arm/xilinx-zynqmp/optprocunitapu.yml
new file mode 100644
index 0000000000..6040891123
--- /dev/null
+++ b/spec/build/bsps/arm/xilinx-zynqmp/optprocunitapu.yml
@@ -0,0 +1,17 @@
+SPDX-License-Identifier: CC-BY-SA-4.0 OR BSD-2-Clause
+actions:
+- get-boolean: null
+- define-condition: null
+build-type: option
+copyrights:
+- Copyright (C) 2023 Reflex Aerospace GmbH (
https://www.reflexaerospace.com/)
+default:
+- enabled-by: true
+  value: true
+description: |
+  Sets the target processing unit to the APU (A53) cores.
+enabled-by: true
+format: '{}'
+links: []
+name: ZYNQMP_PROC_UNIT_APU
+type: build
_______________________________________________
devel mailing list
devel@rtems.org
http://lists.rtems.org/mailman/listinfo/devel

Reply via email to