soc: renesas: Maintain the minimal support of Renesas RZ/T2M

Renesas takes over the maintainer of SoC Renesas RZ/T2M to unify with
other RZ devices

- Move soc/renesas/rzt2m to soc/renesas/rz
- Support xSPI boot mode to boot code from flash
- Change to use HAL Renesas

Signed-off-by: Hieu Nguyen <hieu.nguyen.ym@bp.renesas.com>
Signed-off-by: Nhut Nguyen <nhut.nguyen.kc@renesas.com>
Signed-off-by: Binh Nguyen <binh.nguyen.xw@renesas.com>
This commit is contained in:
Hieu Nguyen 2024-12-24 12:50:22 +07:00 committed by Benjamin Cabé
commit f961578b7d
18 changed files with 376 additions and 493 deletions

View file

@ -1,8 +1,15 @@
# Copyright (c) 2023 Antmicro <www.antmicro.com>
# Copyright (c) 2025 Renesas Electronics Corporation
# SPDX-License-Identifier: Apache-2.0
zephyr_sources(soc.c)
zephyr_sources(
soc.c
loader_param.c
../common/loader_program.S
)
zephyr_include_directories(.)
zephyr_linker_sources(SECTIONS sections.ld)
set(SOC_LINKER_SCRIPT ${ZEPHYR_BASE}/include/zephyr/arch/arm/cortex_r/scripts/linker.ld CACHE INTERNAL "")

View file

@ -1,11 +1,14 @@
# Copyright (c) 2023 Antmicro <www.antmicro.com>
# Copyright (c) 2025 Renesas Electronics Corporation
# SPDX-License-Identifier: Apache-2.0
config SOC_RENESAS_RZT2M
config SOC_SERIES_RZT2M
select ARM
select CPU_CORTEX_R52
select CPU_HAS_ARM_MPU
select GIC_SINGLE_SECURITY_STATE
select ARM_ARCH_TIMER
select SYSCON
select HAS_RENESAS_RZ_FSP
select SOC_RESET_HOOK
select SOC_EARLY_INIT_HOOK
select ARM_CUSTOM_INTERRUPT_CONTROLLER

View file

@ -0,0 +1,31 @@
# Copyright (c) 2023 Antmicro <www.antmicro.com>
# Copyright (c) 2025 Renesas Electronics Corporation
# SPDX-License-Identifier: Apache-2.0
if SOC_SERIES_RZT2M
config NUM_IRQS
default 480
config SYS_CLOCK_HW_CYCLES_PER_SEC
default 25000000
config FPU
default y
config FLASH_SIZE
default $(dt_chosen_reg_size_int,$(DT_CHOSEN_Z_FLASH),0,K)
config FLASH_BASE_ADDRESS
default $(dt_chosen_reg_addr_hex,$(DT_CHOSEN_Z_FLASH))
DT_CHOSEN_IMAGE_ZEPHYR = zephyr,code-partition
config BUILD_OUTPUT_ADJUST_LMA
default "($(dt_chosen_reg_addr_hex,$(DT_CHOSEN_IMAGE_ZEPHYR)) + \
$(dt_chosen_reg_addr_hex,$(DT_CHOSEN_Z_FLASH)))"
config BUILD_OUTPUT_ADJUST_LMA_SECTIONS
default "*;!.loader"
endif # SOC_SERIES_RZT2M

View file

@ -0,0 +1,25 @@
# Copyright (c) 2023 Antmicro <www.antmicro.com>
# Copyright (c) 2025 Renesas Electronics Corporation
# SPDX-License-Identifier: Apache-2.0
config SOC_SERIES_RZT2M
bool
select SOC_FAMILY_RENESAS_RZ
help
Renesas RZ/T2M series
config SOC_SERIES
default "rzt2m" if SOC_SERIES_RZT2M
config SOC_R9A07G075M24GBG
bool
select SOC_SERIES_RZT2M
help
R9A07G075M24GBG
config SOC_R9A07G075M24GBG_CR520
bool
select SOC_R9A07G075M24GBG
config SOC
default "r9a07g075m24gbg" if SOC_R9A07G075M24GBG

View file

@ -0,0 +1,53 @@
/*
* Copyright (c) 2025 Renesas Electronics Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdint.h>
#include <zephyr/linker/section_tags.h>
#define CACHE_FLG (0x00000000)
#define CS0BCR_V_WRAPCFG_V (0x00000000)
#define CS0WCR_V_COMCFG_V (0x00000000)
#define DUMMY0_BMCFG_V (0x00000000)
#define BSC_FLG_xSPI_FLG (0x00000000)
#define LDR_ADDR_NML (0x6000004C)
#define LDR_SIZE_NML (0x00006000)
#define DEST_ADDR_NML (0x00102000)
#define DUMMY1 (0x00000000)
#define DUMMY2 (0x00000000)
#define DUMMY3_CSSCTL_V (0x0000003F)
#define DUMMY4_LIOCFGCS0_V (0x00070000)
#define DUMMY5 (0x00000000)
#define DUMMY6 (0x00000000)
#define DUMMY7 (0x00000000)
#define DUMMY8 (0x00000000)
#define DUMMY9 (0x00000000)
#define DUMMY10_ACCESS_SPEED (0x00000006)
#define CHECK_SUM (0xE0A8)
#define LOADER_PARAM_MAX (19)
#define __loader_param Z_GENERIC_SECTION(.loader_param)
const uint32_t loader_param[LOADER_PARAM_MAX] __loader_param = {
CACHE_FLG,
CS0BCR_V_WRAPCFG_V,
CS0WCR_V_COMCFG_V,
DUMMY0_BMCFG_V,
BSC_FLG_xSPI_FLG,
LDR_ADDR_NML,
LDR_SIZE_NML,
DEST_ADDR_NML,
DUMMY1,
DUMMY2,
DUMMY3_CSSCTL_V,
DUMMY4_LIOCFGCS0_V,
DUMMY5,
DUMMY6,
DUMMY7,
DUMMY8,
DUMMY9,
DUMMY10_ACCESS_SPEED,
CHECK_SUM,
};

View file

@ -0,0 +1,17 @@
/*
* Copyright (c) 2025 Renesas Electronics Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/devicetree.h>
SECTION_PROLOGUE(.loader, CONFIG_FLASH_BASE_ADDRESS,)
{
__loader_param_start = .;
KEEP(*(.loader_param))
__loader_param_end = .;
. = DT_REG_ADDR(DT_NODELABEL(loader_program));
__loader_program_start = .;
KEEP(*(.loader_text.*))
__loader_program_end = .;
} GROUP_LINK_IN(FLASH)

View file

@ -0,0 +1,87 @@
/*
* Copyright (c) 2023 Antmicro <www.antmicro.com>
* Copyright (c) 2025 Renesas Electronics Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <bsp_api.h>
#include <zephyr/init.h>
#include <zephyr/sys/barrier.h>
#include <zephyr/drivers/interrupt_controller/gic.h>
#include <zephyr/irq.h>
extern void bsp_global_system_counter_init(void);
void *gp_renesas_isr_context[BSP_ICU_VECTOR_MAX_ENTRIES + BSP_CORTEX_VECTOR_TABLE_ENTRIES];
IRQn_Type g_current_interrupt_num[32];
uint8_t g_current_interrupt_pointer;
void soc_reset_hook(void)
{
/* Enable peripheral port access at EL1 and EL0 */
__asm__ volatile("mrc p15, 0, r0, c15, c0, 0\n");
__asm__ volatile("orr r0, #1\n");
__asm__ volatile("mcr p15, 0, r0, c15, c0, 0\n");
barrier_dsync_fence_full();
barrier_isync_fence_full();
}
void soc_early_init_hook(void)
{
/* Configure system clocks. */
bsp_clock_init();
/* Initialize SystemCoreClock variable. */
SystemCoreClockUpdate();
/* Initialize global system counter. The counter is enabled and is incrementing. */
bsp_global_system_counter_init();
}
unsigned int z_soc_irq_get_active(void)
{
int intid = arm_gic_get_active();
g_current_interrupt_num[g_current_interrupt_pointer++] = intid;
return intid;
}
void z_soc_irq_eoi(unsigned int intid)
{
g_current_interrupt_pointer--;
arm_gic_eoi(intid);
}
void z_soc_irq_enable(unsigned int irq)
{
arm_gic_irq_enable(irq);
}
void z_soc_irq_disable(unsigned int irq)
{
arm_gic_irq_disable(irq);
}
int z_soc_irq_is_enabled(unsigned int irq)
{
return arm_gic_irq_is_enabled(irq);
}
void z_soc_irq_priority_set(unsigned int irq, unsigned int prio, uint32_t flags)
{
arm_gic_irq_set_priority(irq, prio, flags);
}
void z_soc_irq_init(void)
{
g_current_interrupt_pointer = 0;
}
/* Porting FSP IRQ configuration by an empty function */
/* Let Zephyr handle IRQ configuration */
void bsp_irq_core_cfg(void)
{
/* Do nothing */
}

View file

@ -0,0 +1,47 @@
/*
* Copyright (c) 2023 Antmicro <www.antmicro.com>
* Copyright (c) 2025 Renesas Electronics Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_SOC_RENESAS_RZT2M_SOC_H_
#define ZEPHYR_SOC_RENESAS_RZT2M_SOC_H_
typedef enum IRQn {
SoftwareGeneratedInt0 = 0,
SoftwareGeneratedInt1,
SoftwareGeneratedInt2,
SoftwareGeneratedInt3,
SoftwareGeneratedInt4,
SoftwareGeneratedInt5,
SoftwareGeneratedInt6,
SoftwareGeneratedInt7,
SoftwareGeneratedInt8,
SoftwareGeneratedInt9,
SoftwareGeneratedInt10,
SoftwareGeneratedInt11,
SoftwareGeneratedInt12,
SoftwareGeneratedInt13,
SoftwareGeneratedInt14,
SoftwareGeneratedInt15,
DebugCommunicationsChannelInt = 22,
PerformanceMonitorCounterOverflowInt = 23,
CrossTriggerInterfaceInt = 24,
VritualCPUInterfaceMaintenanceInt = 25,
HypervisorTimerInt = 26,
VirtualTimerInt = 27,
NonSecurePhysicalTimerInt = 30,
SHARED_PERIPHERAL_INTERRUPTS_MAX_ENTRIES = CONFIG_NUM_IRQS
} IRQn_Type;
/* Do not let CMSIS to handle GIC and Timer */
#define __GIC_PRESENT 0
#define __TIM_PRESENT 0
#define __FPU_PRESENT 1
/* Porting FSP IRQ configuration by an empty function */
/* Let Zephyr handle IRQ configuration */
void bsp_irq_core_cfg(void);
#endif /* ZEPHYR_SOC_RENESAS_RZT2M_SOC_H_ */

View file

@ -20,3 +20,8 @@ family:
- name: rzt2l
socs:
- name: r9a07g074m04gbg
- name: rzt2m
socs:
- name: r9a07g075m24gbg
cpuclusters:
- name: cr520

View file

@ -1,21 +0,0 @@
# Copyright (c) 2023 Antmicro <www.antmicro.com>
# SPDX-License-Identifier: Apache-2.0
if SOC_RENESAS_RZT2M
config NUM_IRQS
default 994
config SYS_CLOCK_HW_CYCLES_PER_SEC
default 20000000
config FPU
default y
config FLASH_SIZE
default 0
config FLASH_BASE_ADDRESS
default 0
endif # SOC_RENESAS_RZT2M

View file

@ -1,14 +0,0 @@
# Copyright (c) 2023 Antmicro <www.antmicro.com>
# SPDX-License-Identifier: Apache-2.0
config SOC_RENESAS_RZT2M
bool
config SOC_PART_NUMBER_R9A07G075
bool
config SOC
default "renesas_rzt2m" if SOC_RENESAS_RZT2M
config SOC_PART_NUMBER
default "R9A07G075" if SOC_PART_NUMBER_R9A07G075

View file

@ -1,57 +0,0 @@
/*
* Copyright (c) 2023 Antmicro <www.antmicro.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_SOC_ARM_RENESAS_RZT2M_PINCTRL_H_
#define ZEPHYR_SOC_ARM_RENESAS_RZT2M_PINCTRL_H_
#include <zephyr/types.h>
#ifdef __cplusplus
extern "C" {
#endif
typedef struct pinctrl_soc_pin_t {
uint32_t port;
uint32_t pin;
uint32_t func;
uint32_t input_enable: 1;
uint32_t output_enable: 1;
uint32_t pull_up: 1;
uint32_t pull_down: 1;
uint32_t high_impedance: 1;
uint32_t slew_rate: 2;
uint8_t drive_strength;
uint32_t schmitt_enable: 1;
} pinctrl_soc_pin_t;
#define RZT2M_GET_PORT(pinctrl) ((pinctrl >> 16) & 0xff)
#define RZT2M_GET_PIN(pinctrl) ((pinctrl >> 8) & 0xff)
#define RZT2M_GET_FUNC(pinctrl) (pinctrl & 0xff)
#define Z_PINCTRL_STATE_PIN_INIT(node_id, prop, idx) \
{ \
.port = RZT2M_GET_PORT(DT_PROP_BY_IDX(node_id, prop, idx)), \
.pin = RZT2M_GET_PIN(DT_PROP_BY_IDX(node_id, prop, idx)), \
.func = RZT2M_GET_FUNC(DT_PROP_BY_IDX(node_id, prop, idx)), \
.input_enable = DT_PROP(node_id, input_enable), \
.pull_up = DT_PROP(node_id, bias_pull_up), \
.pull_down = DT_PROP(node_id, bias_pull_down), \
.high_impedance = DT_PROP(node_id, bias_high_impedance), \
.slew_rate = DT_ENUM_IDX(node_id, slew_rate), \
.drive_strength = DT_ENUM_IDX(node_id, drive_strength), \
.schmitt_enable = DT_PROP(node_id, input_schmitt_enable), \
},
#define Z_PINCTRL_STATE_PINS_INIT(node_id, prop) \
{DT_FOREACH_CHILD_VARGS(DT_PHANDLE(node_id, prop), \
DT_FOREACH_PROP_ELEM, pinmux, \
Z_PINCTRL_STATE_PIN_INIT)}
#ifdef __cplusplus
}
#endif
#endif /* ZEPHYR_SOC_ARM_RENESAS_RZT2M_PINCTRL_H_ */

View file

@ -1,118 +0,0 @@
/*
* Copyright (c) 2023 Antmicro <www.antmicro.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/init.h>
#include <stdint.h>
#include <zephyr/drivers/syscon.h>
#include "soc.h"
#include <zephyr/sys/util_macro.h>
static const struct device *const prcrn_dev = DEVICE_DT_GET(DT_NODELABEL(prcrn));
static const struct device *const prcrs_dev = DEVICE_DT_GET(DT_NODELABEL(prcrs));
static const struct device *const sckcr_dev = DEVICE_DT_GET(DT_NODELABEL(sckcr));
static const struct device *const sckcr2_dev = DEVICE_DT_GET(DT_NODELABEL(sckcr2));
void rzt2m_unlock_prcrn(uint32_t mask)
{
uint32_t prcrn;
syscon_read_reg(prcrn_dev, 0, &prcrn);
prcrn |= PRC_KEY_CODE | mask;
syscon_write_reg(prcrn_dev, 0, prcrn);
}
void rzt2m_lock_prcrn(uint32_t mask)
{
uint32_t prcrn;
syscon_read_reg(prcrn_dev, 0, &prcrn);
prcrn &= ~mask;
prcrn |= PRC_KEY_CODE;
syscon_write_reg(prcrn_dev, 0, prcrn);
}
void rzt2m_unlock_prcrs(uint32_t mask)
{
uint32_t prcrs;
syscon_read_reg(prcrs_dev, 0, &prcrs);
prcrs |= PRC_KEY_CODE | mask;
syscon_write_reg(prcrs_dev, 0, prcrs);
}
void rzt2m_lock_prcrs(uint32_t mask)
{
uint32_t prcrs;
syscon_read_reg(prcrs_dev, 0, &prcrs);
prcrs &= ~mask;
prcrs |= PRC_KEY_CODE;
syscon_write_reg(prcrs_dev, 0, prcrs);
}
void rzt2m_set_sckcr2(uint32_t mask)
{
syscon_write_reg(sckcr2_dev, 0, mask);
}
uint32_t rzt2m_get_sckcr2(void)
{
uint32_t reg;
syscon_read_reg(sckcr2_dev, 0, &reg);
return reg;
}
void rzt2m_set_sckcr(uint32_t mask)
{
syscon_write_reg(sckcr_dev, 0, mask);
}
uint32_t rzt2m_get_sckcr(void)
{
uint32_t reg;
syscon_read_reg(sckcr_dev, 0, &reg);
return reg;
}
void rzt2m_enable_counters(void)
{
const struct device *const dev = DEVICE_DT_GET(DT_NODELABEL(gsc));
syscon_write_reg(dev, 0, CNTCR_EN);
}
void soc_early_init_hook(void)
{
/* Unlock the Protect Registers
* so that device drivers can access configuration registers of peripherals.
*/
/* After the device drivers are done, lock the Protect Registers. */
rzt2m_unlock_prcrs(PRCRS_GPIO | PRCRS_CLK);
rzt2m_unlock_prcrn(PRCRN_PRC1 | PRCRN_PRC2 | PRCRN_PRC0);
/* Reset the System Clock Control Registers to default values */
rzt2m_set_sckcr(
CLMASEL |
PHYSEL |
FSELCANFD |
FSELXSPI0_DEFAULT |
FSELXSPI1_DEFAULT |
CKIO_DEFAULT
);
rzt2m_set_sckcr2(FSELCPU0_DEFAULT | FSELCPU1_DEFAULT);
rzt2m_lock_prcrs(PRCRS_GPIO | PRCRS_CLK);
rzt2m_lock_prcrn(PRCRN_PRC1 | PRCRN_PRC2 | PRCRN_PRC0);
rzt2m_enable_counters();
}

View file

@ -1,70 +0,0 @@
/*
* Copyright (c) 2023 Antmicro <www.antmicro.com>
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef _SOC__H_
#define _SOC__H_
/* Do not let CMSIS to handle GIC and Timer */
#include <stdint.h>
#define __GIC_PRESENT 0
#define __TIM_PRESENT 0
/* Global system counter */
#define CNTCR_EN BIT(0)
#define CNTCR_HDBG BIT(1)
/* Safety area protect register */
#define PRCRS_CLK BIT(0)
#define PRCRS_LPC_RESET BIT(1)
#define PRCRS_GPIO BIT(2)
#define PRCRS_SYS_CTRL BIT(3)
/* Non-safety area protect register */
#define PRCRN_PRC0 BIT(0)
#define PRCRN_PRC1 BIT(1)
#define PRCRN_PRC2 BIT(2)
#define SCI4ASYNCSEL BIT(31)
#define SCI3ASYNCSEL BIT(30)
#define SCI2ASYNCSEL BIT(29)
#define SCI1ASYNCSEL BIT(28)
#define SCI0ASYNCSEL BIT(27)
#define SPI2ASYNCSEL BIT(26)
#define SPI1ASYNCSEL BIT(25)
#define SPI0ASYNCSEL BIT(24)
#define CLMASEL BIT(22)
#define PHYSEL BIT(21)
#define FSELCANFD BIT(20)
#define DIVSELXSPI1 BIT(14)
#define DIVSELXSPI0 BIT(6)
#define CKIO_DEFAULT BIT(17)
#define FSELXSPI1_DEFAULT GENMASK(10, 9)
#define FSELXSPI0_DEFAULT GENMASK(2, 1)
#define SCI5ASYNCSEL BIT(25)
#define SPI3ASYNCSEL BIT(24)
#define DIVSELSUB BIT(5)
#define FSELCPU1_DEFAULT 0b10 << 2
#define FSELCPU0_DEFAULT 0b10 << 0
/* PRC Key Code - this value is required to allow any write operation
* to the PRCRS / PRCRN registers.
* See section 10.2 of the RZ/T2M User's Manual: Hardware.
*/
#define PRC_KEY_CODE 0xa500
void rzt2m_unlock_prcrn(uint32_t mask);
void rzt2m_lock_prcrn(uint32_t mask);
void rzt2m_unlock_prcrs(uint32_t mask);
void rzt2m_lock_prcrs(uint32_t mask);
void rzt2m_set_sckcr2(uint32_t mask);
uint32_t rzt2m_get_sckcr2(void);
void rzt2m_set_sckcr(uint32_t mask);
uint32_t rzt2m_get_sckcr(void);
#endif /* _SOC__H_ */

View file

@ -1,2 +0,0 @@
socs:
- name: renesas_rzt2m