From 198d61918b831890b932702d4c6e6b223562f638 Mon Sep 17 00:00:00 2001 From: Wang_Weigen Date: Mon, 30 Aug 2021 14:05:12 +0800 Subject: [PATCH] add gap8 board of riscv for xiuos --- Ubiquitous/XiUOS/Makefile | 2 +- Ubiquitous/XiUOS/arch/risc-v/Makefile | 4 + Ubiquitous/XiUOS/arch/risc-v/gap8/Makefile | 3 + .../XiUOS/arch/risc-v/gap8/arch_interrupt.h | 287 +++ Ubiquitous/XiUOS/arch/risc-v/gap8/boot.S | 382 +++ Ubiquitous/XiUOS/arch/risc-v/gap8/chip.h | 57 + Ubiquitous/XiUOS/arch/risc-v/gap8/gap8.h | 2045 +++++++++++++++++ .../arch/risc-v/gap8/gap8_allocateheap.c | 98 + Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_idle.c | 84 + .../arch/risc-v/gap8/gap8_schedulesigaction.c | 199 ++ Ubiquitous/XiUOS/arch/risc-v/gap8/interrupt.c | 361 +++ Ubiquitous/XiUOS/arch/risc-v/gap8/tick.c | 19 + Ubiquitous/XiUOS/board/gapuino/Kconfig | 69 + Ubiquitous/XiUOS/board/gapuino/Makefile | 6 + Ubiquitous/XiUOS/board/gapuino/README.txt | 89 + Ubiquitous/XiUOS/board/gapuino/board.c | 69 + Ubiquitous/XiUOS/board/gapuino/board.h | 85 + Ubiquitous/XiUOS/board/gapuino/config.mk | 38 + Ubiquitous/XiUOS/board/gapuino/link.lds | 175 ++ .../board/gapuino/third_party_driver/Kconfig | 33 + .../board/gapuino/third_party_driver/Makefile | 28 + .../gapuino/third_party_driver/gpio/Kconfig | 11 + .../gapuino/third_party_driver/gpio/Makefile | 3 + .../third_party_driver/gpio/hardware_gpio.c | 218 ++ .../third_party_driver/include/connect_uart.h | 38 + .../third_party_driver/include/gap8_fll.h | 75 + .../third_party_driver/include/gap8_tim.h | 87 + .../third_party_driver/include/gap8_uart.h | 70 + .../include/hardware_gpio.h | 305 +++ .../include/hardware_udma.h | 234 ++ .../third_party_driver/sys_clock/Kconfig | 1 + .../third_party_driver/sys_clock/Makefile | 3 + .../third_party_driver/sys_clock/gap8_fll.c | 128 ++ .../sys_clock/gapuino_sysinit.c | 119 + .../gapuino/third_party_driver/timer/Kconfig | 19 + .../gapuino/third_party_driver/timer/Makefile | 3 + .../timer/hardware_hwtimer.c | 116 + .../gapuino/third_party_driver/uart/Kconfig | 14 + .../gapuino/third_party_driver/uart/Makefile | 4 + .../third_party_driver/uart/connect_uart.c | 326 +++ .../third_party_driver/uart/hardware_udma.c | 387 ++++ Ubiquitous/XiUOS/path_kernel.mk | 10 + 42 files changed, 6303 insertions(+), 1 deletion(-) mode change 100644 => 100755 Ubiquitous/XiUOS/Makefile mode change 100644 => 100755 Ubiquitous/XiUOS/arch/risc-v/Makefile create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/Makefile create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/arch_interrupt.h create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/boot.S create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/chip.h create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/gap8.h create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_allocateheap.c create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_idle.c create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_schedulesigaction.c create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/interrupt.c create mode 100755 Ubiquitous/XiUOS/arch/risc-v/gap8/tick.c create mode 100755 Ubiquitous/XiUOS/board/gapuino/Kconfig create mode 100755 Ubiquitous/XiUOS/board/gapuino/Makefile create mode 100755 Ubiquitous/XiUOS/board/gapuino/README.txt create mode 100755 Ubiquitous/XiUOS/board/gapuino/board.c create mode 100755 Ubiquitous/XiUOS/board/gapuino/board.h create mode 100755 Ubiquitous/XiUOS/board/gapuino/config.mk create mode 100755 Ubiquitous/XiUOS/board/gapuino/link.lds create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/Kconfig create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/Makefile create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Kconfig create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Makefile create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/hardware_gpio.c create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/connect_uart.h create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_fll.h create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_tim.h create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_uart.h create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_gpio.h create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_udma.h create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Kconfig create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Makefile create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gap8_fll.c create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gapuino_sysinit.c create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Kconfig create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Makefile create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/hardware_hwtimer.c create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Kconfig create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Makefile create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/connect_uart.c create mode 100755 Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/hardware_udma.c mode change 100644 => 100755 Ubiquitous/XiUOS/path_kernel.mk diff --git a/Ubiquitous/XiUOS/Makefile b/Ubiquitous/XiUOS/Makefile old mode 100644 new mode 100755 index e3a9c6f5..15a0e53e --- a/Ubiquitous/XiUOS/Makefile +++ b/Ubiquitous/XiUOS/Makefile @@ -5,7 +5,7 @@ MAKEFLAGS += --no-print-directory .PHONY:COMPILE_APP COMPILE_KERNEL -support :=kd233 stm32f407-st-discovery maix-go stm32f407zgt6 aiit-riscv64-board aiit-arm32-board hifive1-rev-B hifive1-emulator k210-emulator cortex-m3-emulator ok1052-c +support :=kd233 stm32f407-st-discovery maix-go stm32f407zgt6 aiit-riscv64-board aiit-arm32-board hifive1-rev-B hifive1-emulator k210-emulator cortex-m3-emulator ok1052-c gapuino SRC_DIR:= export BOARD ?=kd233 diff --git a/Ubiquitous/XiUOS/arch/risc-v/Makefile b/Ubiquitous/XiUOS/arch/risc-v/Makefile old mode 100644 new mode 100755 index 0fa301e4..5c86eb8b --- a/Ubiquitous/XiUOS/arch/risc-v/Makefile +++ b/Ubiquitous/XiUOS/arch/risc-v/Makefile @@ -16,4 +16,8 @@ ifeq ($(CONFIG_BOARD_AIIT_RISCV_EVB),y) SRC_DIR +=k210 endif +ifeq ($(CONFIG_BOARD_GAPUINO),y) +SRC_DIR +=gap8 +endif + include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/Makefile b/Ubiquitous/XiUOS/arch/risc-v/gap8/Makefile new file mode 100755 index 00000000..6ab88edd --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/Makefile @@ -0,0 +1,3 @@ +SRC_FILES := boot.S interrupt.c tick.c + +include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/arch_interrupt.h b/Ubiquitous/XiUOS/arch/risc-v/gap8/arch_interrupt.h new file mode 100755 index 00000000..142c1181 --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/arch_interrupt.h @@ -0,0 +1,287 @@ +/**************************************************************************** + * arch/risc-v/include/gap8/irq.h + * GAP8 event system + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * GAP8 features a FC controller and a 8-core cluster. IRQ from peripherals + * have unique ID, which are dispatched to the FC or cluster by the SOC + * event unit, and then by the FC event unit or cluster event unit, and + * finally to FC or cluster. Peripherals share the same IRQ entry. + ****************************************************************************/ + +#ifndef ARCH_INTERRUPT_H__ +#define ARCH_INTERRUPT_H__ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +/**************************************************************************** + * Pre-Processor Definitions + ****************************************************************************/ + +/* Unique ID in SOC domain */ + +/* uDMA data events. + * Each peripheral has a uDMA_ID. + * Each peripheral also has RX and TX event ID, which happen to be 2*uDMA_ID + * and 2*uDMA_ID+1. + */ + +#define GAP8_EVENT_UDMA_LVDS_RX 0 +#define GAP8_EVENT_UDMA_LVDS_TX 1 +#define GAP8_EVENT_UDMA_SPIM0_RX 2 +#define GAP8_EVENT_UDMA_SPIM0_TX 3 +#define GAP8_EVENT_UDMA_SPIM1_RX 4 +#define GAP8_EVENT_UDMA_SPIM1_TX 5 +#define GAP8_EVENT_UDMA_HYPERBUS_RX 6 +#define GAP8_EVENT_UDMA_HYPERBUS_TX 7 +#define GAP8_EVENT_UDMA_UART_RX 8 +#define GAP8_EVENT_UDMA_UART_TX 9 +#define GAP8_EVENT_UDMA_I2C0_RX 10 +#define GAP8_EVENT_UDMA_I2C0_TX 11 +#define GAP8_EVENT_UDMA_I2C1_RX 12 +#define GAP8_EVENT_UDMA_I2C1_TX 13 +#define GAP8_EVENT_UDMA_TCDM_RX 14 +#define GAP8_EVENT_UDMA_TCDM_TX 15 +#define GAP8_EVENT_UDMA_SAI_CH0 16 +#define GAP8_EVENT_UDMA_SAI_CH1 17 +#define GAP8_EVENT_UDMA_CPI_RX 18 + +#define GAP8_UDMA_MAX_EVENT 18 + +/* Other events of uDMA peripherals */ + +#define GAP8_EVENT_LVDS_GEN0 20 +#define GAP8_EVENT_LVDS_GEN1 21 +#define GAP8_EVENT_SPIM0_EOT 22 +#define GAP8_EVENT_SPIM1_EOT 23 +#define GAP8_EVENT_HYPERBUS_RESERVED 24 +#define GAP8_EVENT_UART_RESERVED 25 +#define GAP8_EVENT_I2C0_ERROR 26 +#define GAP8_EVENT_I2C1_ERROR 27 +#define GAP8_EVENT_I2S_RESERVED 28 +#define GAP8_EVENT_CAM_RESERVED 29 + +/* PMU events */ + +#define GAP8_EVENT_PMU_CLUSTER_POWER_ON 31 +#define GAP8_EVENT_PMU_CLUSTER_RESERVED0 32 +#define GAP8_EVENT_PMU_CLUSTER_RESERVED1 33 +#define GAP8_EVENT_PMU_CLUSTER_RESERVED2 34 +#define GAP8_EVENT_PMU_CLUSTER_CLOCK_GATING 35 +#define GAP8_EVENT_PMU_DLC_BRIDGE_PICL_OK 36 +#define GAP8_EVENT_PMU_DLC_BRIDGE_SCU_OK 37 + +/* Other SOC domain peripheral events */ + +#define GAP8_EVENT_PWM0 38 +#define GAP8_EVENT_PWM1 39 +#define GAP8_EVENT_PWM2 40 +#define GAP8_EVENT_PWM3 41 +#define GAP8_EVENT_GPIO 42 /* GPIO group interrupt */ +#define GAP8_EVENT_RTC_APB 43 +#define GAP8_EVENT_RTC 44 +#define GAP8_EVENT_RESERVED0 45 +#define GAP8_EVENT_RESERVED1 46 +#define GAP8_EVENT_RESERVED2 47 +#define GAP8_EVENT_SOC_SW_0 48 /* GAP8 SOC SW Event0 */ +#define GAP8_EVENT_SOC_SW_1 49 /* GAP8 SOC SW Event1 */ +#define GAP8_EVENT_SOC_SW_2 50 /* GAP8 SOC SW Event2 */ +#define GAP8_EVENT_SOC_SW_3 51 /* GAP8 SOC SW Event3 */ +#define GAP8_EVENT_SOC_SW_4 52 /* GAP8 SOC SW Event4 */ +#define GAP8_EVENT_SOC_SW_5 53 /* GAP8 SOC SW Event5 */ +#define GAP8_EVENT_SOC_SW_6 54 /* GAP8 SOC SW Event6 */ +#define GAP8_EVENT_SOC_SW_7 55 /* GAP8 SOC SW Event7 */ +#define GAP8_EVENT_REF32K_CLK_RISE 56 /* Reference 32K Clock event */ + +/* FC domain IRQ ID */ + +#define GAP8_IRQ_FC_SW_0 0 +#define GAP8_IRQ_FC_SW_1 1 +#define GAP8_IRQ_FC_SW_2 2 +#define GAP8_IRQ_FC_SW_3 3 +#define GAP8_IRQ_FC_SW_4 4 +#define GAP8_IRQ_FC_SW_5 5 +#define GAP8_IRQ_FC_SW_6 6 +#define GAP8_IRQ_FC_SW_7 7 +#define GAP8_IRQ_FC_TIMER_LO 10 +#define GAP8_IRQ_FC_TIMER_HI 11 +#define GAP8_IRQ_FC_UDMA 27 +#define GAP8_IRQ_FC_MPU 28 +#define GAP8_IRQ_FC_UDMA_ERR 29 +#define GAP8_IRQ_FC_HP_0 30 +#define GAP8_IRQ_FC_HP_1 31 + +#define GAP8_IRQ_RESERVED 60 + +/* Cluster domain IRQ ID */ + +/* TODO */ + +/* RISCY core exception vectors */ + +#define GAP8_IRQ_RST 32 +#define GAP8_IRQ_ILLEGAL 33 +#define GAP8_IRQ_SYSCALL 34 + +/* Total number of IRQs. + * 32 ISRs + reset-handler + illegal-instruction-handler + + * system-call-handler + */ + +#define NR_IRQS 35 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* SOC_EU - SOC domain event unit */ + +typedef struct +{ + volatile uint32_t EVENT; /* event register */ + volatile uint32_t FC_MASK_MSB; /* fc mask MSB register */ + volatile uint32_t FC_MASK_LSB; /* fc mask LSB register */ + volatile uint32_t CL_MASK_MSB; /* cluster mask MSB register */ + volatile uint32_t CL_MASK_LSB; /* cluster mask LSB register */ + volatile uint32_t PR_MASK_MSB; /* propagate mask MSB register */ + volatile uint32_t PR_MASK_LSB; /* propagate mask LSB register */ + volatile uint32_t ERR_MASK_MSB; /* error mask MSB register */ + volatile uint32_t ERR_MASK_LSB; /* error mask LSB register */ + volatile uint32_t TIMER_SEL_HI; /* timer high register */ + volatile uint32_t TIMER_SEL_LO; /* timer low register */ +} soc_eu_reg_t; + +#define SOC_EU ((soc_eu_reg_t *)0x1A106000U) + +/* FCEU - FC domain event unit */ + +typedef struct +{ + volatile uint32_t MASK; /* mask register */ + volatile uint32_t MASK_AND; /* mask-and(clr) register */ + volatile uint32_t MASK_OR; /* mask-or(set) register */ + volatile uint32_t MASK_IRQ; /* irq mask register */ + volatile uint32_t MASK_IRQ_AND; /* irq mask-and(clr) register */ + volatile uint32_t MASK_IRQ_OR; /* irq mask-or(set) register */ + volatile uint32_t STATUS; /* clock Status register */ + volatile uint32_t BUFFER; /* irq pending register */ + volatile uint32_t BUFFER_MASKED; /* buffer masked register */ + volatile uint32_t BUFFER_IRQ_MASKED; /* buffer irq masked register */ + volatile uint32_t BUFFER_CLEAR; /* clear irq pending */ + volatile uint32_t SW_EVENTS_MASK; /* software event mask register */ + volatile uint32_t SW_EVENTS_MASK_AND; /* software event mask and register */ + volatile uint32_t SW_EVENTS_MASK_OR; /* software event mask or register */ + volatile uint32_t EVENT_WAIT; /* event wait register */ + volatile uint32_t EVENT_WAIT_CLEAR; /* event wait clear register */ + volatile uint32_t MASK_SEC_IRQ; /* mask sec irq register */ +} fceu_reg_t; + +#define FCEU ((fceu_reg_t*)0x00204000U) + +/* Current interrupt event ID */ + +typedef struct +{ + volatile uint32_t CURRENT_EVENT; /* current event register */ +} soc_event_reg_t; + +#define SOC_EVENTS ((soc_event_reg_t*)0x00200F00UL) + +/* event trigger and mask */ + +typedef struct +{ + volatile uint32_t TRIGGER_SET[8]; /* trigger set register */ + volatile uint32_t _reserved0[8]; /* Offset: 0x20 (R/W) Empty Registers */ + volatile uint32_t TRIGGER_WAIT[8]; /* trigger wait register */ + volatile uint32_t _reserved1[8]; /* Offset: 0x60 (R/W) Empty Registers */ + volatile uint32_t TRIGGER_CLR[8]; /* trigger clear register */ +} eu_sw_events_trigger_reg_t; + +#define EU_SW_EVNT_TRIG ((eu_sw_events_trigger_reg_t*)0x00204100UL) + +#define ARCH_MAX_IRQ_NUM NR_IRQS + +int ArchEnableHwIrq(uint32_t irq_num); +int ArchDisableHwIrq(uint32_t irq_num); + + +/**************************************************************************** + * Name: up_disable_event + * + * Description: + * Disable the specific event. Note that setting 1 means to disable an + * event... + * + ****************************************************************************/ + +static inline void up_disable_event(int event) +{ + if (event >= 32) + { + SOC_EU->FC_MASK_MSB |= (1 << (event - 32)); + } + else + { + SOC_EU->FC_MASK_LSB |= (1 << event); + } +} + +/**************************************************************************** + * Name: up_enable_event + * + * Description: + * Enable the specific event. Note that setting 0 means to enable an + * event... + * + ****************************************************************************/ + +static inline void up_enable_event(int event) +{ + if (event >= 32) + { + SOC_EU->FC_MASK_MSB &= ~(1 << (event - 32)); + } + else + { + SOC_EU->FC_MASK_LSB &= ~(1 << event); + } +} + +#endif diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/boot.S b/Ubiquitous/XiUOS/arch/risc-v/gap8/boot.S new file mode 100755 index 00000000..7202b85d --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/boot.S @@ -0,0 +1,382 @@ +/**************************************************************************** + * arch/risc-v/src/gapuino/gap8_head.S + * Startup file for FC of GAP8 + * Interrupt vector and reset handler + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* Exception context size: EPC + 31 common regs + 6 loop regs */ + +#define EXCEPTION_STACK_SIZE 4*38 + +/**************************************************************************** + * Assembler Macro Definitions + ****************************************************************************/ + +/* save all the registers on interrupt entry */ + + .macro SAVE_REGS + addi sp, sp, -EXCEPTION_STACK_SIZE + sw x1, 1*4(sp) /* ra */ + sw x3, 3*4(sp) /* gp */ + sw x4, 4*4(sp) /* tp */ + sw x5, 5*4(sp) /* t0 */ + sw x6, 6*4(sp) /* t1 */ + sw x7, 7*4(sp) /* t2 */ + sw x8, 8*4(sp) /* s0 */ + sw x9, 9*4(sp) /* s1 */ + sw x10, 10*4(sp) /* a0 */ + sw x11, 11*4(sp) /* a1 */ + sw x12, 12*4(sp) /* a2 */ + sw x13, 13*4(sp) /* a3 */ + sw x14, 14*4(sp) /* a4 */ + sw x15, 15*4(sp) /* a5 */ + sw x16, 16*4(sp) /* a6 */ + sw x17, 17*4(sp) /* a7 */ + sw x18, 18*4(sp) /* s2 */ + sw x19, 19*4(sp) /* s3 */ + sw x20, 20*4(sp) /* s4 */ + sw x21, 21*4(sp) /* s5 */ + sw x22, 22*4(sp) /* s6 */ + sw x23, 23*4(sp) /* s7 */ + sw x24, 24*4(sp) /* s8 */ + sw x25, 25*4(sp) /* s9 */ + sw x26, 26*4(sp) /* s10 */ + sw x27, 27*4(sp) /* s11 */ + sw x28, 28*4(sp) /* t3 */ + sw x29, 29*4(sp) /* t4 */ + sw x30, 30*4(sp) /* t5 */ + sw x31, 31*4(sp) /* t6 */ + csrr x28, 0x7B0 + csrr x29, 0x7B1 + csrr x30, 0x7B2 + sw x28, 32*4(sp) /* lpstart[0] */ + sw x29, 33*4(sp) /* lpend[0] */ + sw x30, 34*4(sp) /* lpcount[0] */ + csrr x28, 0x7B4 + csrr x29, 0x7B5 + csrr x30, 0x7B6 + sw x28, 35*4(sp) /* lpstart[1] */ + sw x29, 36*4(sp) /* lpend[1] */ + sw x30, 37*4(sp) /* lpcount[1] */ + addi s0, sp, EXCEPTION_STACK_SIZE + sw s0, 2*4(sp) /* original SP */ + .endm + +/* restore regs and `mret` */ + + .macro RESTORE_REGS + lw x28, 35*4(sp) /* lpstart[1] */ + lw x29, 36*4(sp) /* lpend[1] */ + lw x30, 37*4(sp) /* lpcount[1] */ + csrrw x0, 0x7B4, x28 + csrrw x0, 0x7B5, x29 + csrrw x0, 0x7B6, x30 + lw x28, 32*4(sp) /* lpstart[0] */ + lw x29, 33*4(sp) /* lpend[0] */ + lw x30, 34*4(sp) /* lpcount[0] */ + csrrw x0, 0x7B0, x28 + csrrw x0, 0x7B1, x29 + csrrw x0, 0x7B2, x30 + li s0, 0x1890 /* machine mode, UPIE & MPIE enabled */ + csrrw x0, mstatus, s0 + lw x3, 3*4(sp) /* gp */ + lw x4, 4*4(sp) /* tp */ + lw x5, 5*4(sp) /* t0 */ + lw x6, 6*4(sp) /* t1 */ + lw x7, 7*4(sp) /* t2 */ + lw x8, 8*4(sp) /* s0 */ + lw x9, 9*4(sp) /* s1 */ + lw x10, 10*4(sp) /* a0 */ + lw x11, 11*4(sp) /* a1 */ + lw x12, 12*4(sp) /* a2 */ + lw x13, 13*4(sp) /* a3 */ + lw x14, 14*4(sp) /* a4 */ + lw x15, 15*4(sp) /* a5 */ + lw x16, 16*4(sp) /* a6 */ + lw x17, 17*4(sp) /* a7 */ + lw x18, 18*4(sp) /* s2 */ + lw x19, 19*4(sp) /* s3 */ + lw x20, 20*4(sp) /* s4 */ + lw x21, 21*4(sp) /* s5 */ + lw x22, 22*4(sp) /* s6 */ + lw x23, 23*4(sp) /* s7 */ + lw x24, 24*4(sp) /* s8 */ + lw x25, 25*4(sp) /* s9 */ + lw x26, 26*4(sp) /* s10 */ + lw x27, 27*4(sp) /* s11 */ + lw x28, 28*4(sp) /* t3 */ + lw x29, 29*4(sp) /* t4 */ + lw x30, 30*4(sp) /* t5 */ + lw x31, 31*4(sp) /* t6 */ + + lw x1, 1*4(sp) /* ra */ + + lw sp, 2*4(sp) /* restore original sp */ + .endm + +/* wrapper for IRQ vector */ + + .macro WRAP_IRQ Routine, IRQn + wrap_irq_\Routine : + SAVE_REGS + + csrr s0, mepc + sw s0, 0(sp) /* exception PC */ + + li a0, \IRQn /* irq = IRQn */ + mv a1, sp /* context = sp */ + jal x1, gap8_dispatch_irq + + /* If context switch is needed, return + * a new sp + */ + + mv sp, a0 + + lw s0, 0(sp) /* restore ePC */ + csrw mepc, s0 + + RESTORE_REGS + + mret + .endm + + +/******************************************************************************* + * External Variables and Functions + *******************************************************************************/ + + # .extern _sbss + # .extern _ebss + .extern __bss_start + .extern __bss_end + .extern _idle_stack_end + .extern __data_start__ + + .extern gap8_dispatch_irq + .extern entry + .extern gapuino_sysinit + .extern GapuinoStart + +.globl reset_handler +/******************************************************************************* + * Reset handler + *******************************************************************************/ +reset_handler: +#if 0 + csrr a0, 0xf14 /* Cluster ID */ + andi a1, a0, 0x1f /* Core ID */ + srli a0, a0, 5 +#endif + # la gp, __data_start__ + li a0, 0x1800 /* Set MSTATUS : Machine Mode */ + csrw mstatus, a0 + + li a0, 0x1C000000 /* Set MTVEC */ + csrw mtvec, a0 + + /* Stack initialization */ + + la x2, _idle_stack_end + + /* Clear BSS */ + + la x26, __bss_start + la x27, __bss_end + + bge x26, x27, zero_loop_end + +zero_loop: + sw x0, 0(x26) + addi x26, x26, 4 + ble x26, x27, zero_loop + +zero_loop_end: + + /* TODO: initialize data section */ + + /* Initialize cache and clock */ + + + # jal x1, gapuino_sysinit + + /* Directly call NuttX nx_start() */ + csrr a0, 0xf14 /* Cluster ID */ + andi a1, a0, 0x1f /* Core ID */ + + j GapuinoStart + + /* If it ever returns, spin here forever... */ + +dead_loop: + jal x0, dead_loop + + +/* IRQ wrappers + * IRQn are identical to gap8_interrupt.h + */ + +WRAP_IRQ sw_evt0, 0 +WRAP_IRQ sw_evt1, 1 +WRAP_IRQ sw_evt2, 2 +WRAP_IRQ sw_evt3, 3 +WRAP_IRQ sw_evt4, 4 +WRAP_IRQ sw_evt5, 5 +WRAP_IRQ sw_evt6, 6 +WRAP_IRQ sw_evt7, 7 + +WRAP_IRQ timer_lo, 10 +WRAP_IRQ timer_hi, 11 + +WRAP_IRQ udma, 27 +WRAP_IRQ mpu, 28 +WRAP_IRQ udma_err, 29 +WRAP_IRQ fc_hp0, 30 +WRAP_IRQ fc_hp1, 31 + +WRAP_IRQ reserved, 60 + +/* RISCV exceptions */ + +illegal_insn_handler: + csrr s0, mepc + sw s0, 0*4(sp) /* exception PC */ + + /* Spin here so that debugger would read `s0` */ + +1: + j 1b + +/* Systemcall handler */ + +ecall_insn_handler: + SAVE_REGS + + /* Point to the next instruction of `ecall` */ + + csrr s0, mepc + addi s0, s0, 4 + sw s0, 0(sp) /* exception PC */ + + li a0, 34 /* irq = 34 */ + mv a1, sp /* context = sp */ + jal x1, gap8_dispatch_irq + + /* If context switch is needed, return + * a new sp + */ + + mv sp, a0 + + lw s0, 0(sp) /* restore ePC */ + csrw mepc, s0 + + RESTORE_REGS + + mret + +/******************************************************************************* + * INTERRUPT VECTOR TABLE + *******************************************************************************/ +/* This section has to be down here, since we have to disable rvc for it */ + + .section .vectors_M, "ax" + .option norvc; + + j wrap_irq_sw_evt0 /* 0 */ + j wrap_irq_sw_evt1 /* 1 */ + j wrap_irq_sw_evt2 /* 2 */ + j wrap_irq_sw_evt3 /* 3 */ + j wrap_irq_sw_evt4 /* 4 */ + j wrap_irq_sw_evt5 /* 5 */ + j wrap_irq_sw_evt6 /* 6 */ + j wrap_irq_sw_evt7 /* 7 */ + j wrap_irq_reserved /* 8 */ + j wrap_irq_reserved /* 9 */ + j wrap_irq_timer_lo /* 10 */ + j wrap_irq_timer_hi /* 11 */ + j wrap_irq_reserved /* 12 */ + j wrap_irq_reserved /* 13 */ + j wrap_irq_reserved /* 14 */ + j wrap_irq_reserved /* 15 */ + j wrap_irq_reserved /* 16 */ + j wrap_irq_reserved /* 17 */ + j wrap_irq_reserved /* 18 */ + j wrap_irq_reserved /* 19 */ + j wrap_irq_reserved /* 20 */ + j wrap_irq_reserved /* 21 */ + j wrap_irq_reserved /* 22 */ + j wrap_irq_reserved /* 23 */ + j wrap_irq_reserved /* 24 */ + j wrap_irq_reserved /* 25 */ + j wrap_irq_reserved /* 26 */ + j wrap_irq_udma /* 27 */ + j wrap_irq_mpu /* 28 */ + j wrap_irq_udma_err /* 29 */ + j wrap_irq_fc_hp0 /* 30 */ + j wrap_irq_fc_hp1 /* 31 */ + + j reset_handler /* 32 */ + j illegal_insn_handler/* 33 */ + j ecall_insn_handler /* 34 */ + + + +/**************************************************************************** + * This variable is pointed to the structure containing all information + * exchanged with the platform loader. It is using a fixed address so that + * the loader can also find it and then knows the address of the debug + * structure. + ****************************************************************************/ + + .section .dbg_struct, "ax" + .option norvc; + .org 0x90 + .global __rt_debug_struct_ptr +__rt_debug_struct_ptr: + .word Debug_Struct + +/**************************************************************************** + * This global variable is unsigned int g_idle_topstack and is exported here + * only because of its coupling to idle thread stack. + ****************************************************************************/ + + .section .data + .global g_idle_topstack +g_idle_topstack: + .word _idle_stack_end diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/chip.h b/Ubiquitous/XiUOS/arch/risc-v/gap8/chip.h new file mode 100755 index 00000000..eff9f00b --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/chip.h @@ -0,0 +1,57 @@ +/**************************************************************************** + * arch/risc-v/include/gap8/chip.h + * Gapuino chip features + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * + ****************************************************************************/ + +/* This file should never be included directly but, rather, only indirectly + * through nuttx/irq.h + */ + +#ifndef __ARCH_RISCV_INCLUDE_GAP8_CHIP_H +#define __ARCH_RISCV_INCLUDE_GAP8_CHIP_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#endif /* __ARCH_RISCV_INCLUDE_GAP8_CHIP_H */ diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8.h b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8.h new file mode 100755 index 00000000..fdef6c1b --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8.h @@ -0,0 +1,2045 @@ +/************************************************************************************ + * arch/risc-v/src/gap8/gap8.h + * Peripheral registers on GAP8 + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.com> + * Modified from gap_sdk + * + * 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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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 __ARCH_RISC_V_SRC_GAP8_GAP8_H +#define __ARCH_RISC_V_SRC_GAP8_GAP8_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +#define SOC_PERI_BASE (0x1A100000UL) /* SOC Peripherals Base Address */ +#define CORE_PERI_BASE (0x00200000UL) /* RISC Core Peripheral Base Address */ +#define CONFIG_CORE_CLOCK_FREQ 200000000 +/* 2 basic timer */ + +typedef struct +{ + volatile uint32_t CFG_REG_LO; /* Configuration Register for lower 32-bits */ + volatile uint32_t CFG_REG_HI; /* Configuration Register for high 32-bits */ + volatile uint32_t VALUE_LO; /* Timer Value Register for low 32-bits */ + volatile uint32_t VALUE_HI; /* Timer Value Register for high 32-bits */ + volatile uint32_t CMP_LO; /* Timer comparator Register for low 32-bits */ + volatile uint32_t CMP_HI; /* Timer comparator Register for high 32-bits */ + volatile uint32_t START_LO; /* Timer start Register for low 32-bits */ + volatile uint32_t START_HI; /* Timer start Register for high 32-bits */ + volatile uint32_t RESET_LO; /* Timer reset Register for low 32-bits */ + volatile uint32_t RESET_HI; /* Timer reset Register for high 32-bits */ +} basic_tim_reg_t; + +#define BASIC_TIM ((basic_tim_reg_t*)(CORE_PERI_BASE + 0x0400UL)) + +#define BASIC_TIM_CASC_ENABLE (1L << 31) +#define BASIC_TIM_CASC_DISABLE (0L << 31) +#define BASIC_TIM_CLKSRC_FLL (0L << 7) +#define BASIC_TIM_CLKSRC_32K (1L << 7) +#define BASIC_TIM_PRESC_ENABLE (1L << 6) +#define BASIC_TIM_PRESC_DISABLE (0L << 6) +#define BASIC_TIM_ONE_SHOT (1L << 5) +#define BASIC_TIM_MODE_CONT (0L << 4) +#define BASIC_TIM_MODE_CYCL (1L << 4) +#define BASIC_TIM_IRQ_ENABLE (1L << 2) +#define BASIC_TIM_IRQ_DISABLE (0L << 2) +#define BASIC_TIM_RESET (1L << 1) +#define BASIC_TIM_ENABLE (1L << 0) + +typedef struct +{ + volatile uint32_t ICACHE_ENABLE; /* Cluster Icache Enable Register */ + volatile uint32_t ICACHE_FLUSH; /* Cluster Icache Flush Register */ + volatile uint32_t ICACHE_LX_SEL_FLUSH; /* Cluster Icache Level-X Flush Register or FC Flush Selected Address Register */ + volatile uint32_t ICACHE_SEL_FLUSH_STATUS; /* Cluster Icache Flush Selected Address Register or FC ICACHE status */ + volatile uint32_t ICACHE_IS_PRI; /* Cluster Icache is private Icache */ +} scbc_reg_t; + +#define CORE_SCBC_BASE (CORE_PERI_BASE + 0x1400UL) /* RISC Core System Control Block Cache Base Address */ +#define SCBC ((scbc_reg_t*)CORE_SCBC_BASE) /* Icache SCBC configuration struct */ + +/* FLL_CTRL */ + +typedef struct +{ + volatile uint32_t SOC_FLL_STATUS; /* Status register */ + volatile uint32_t SOC_CONF1; /* Configuration1 register */ + volatile uint32_t SOC_CONF2; /* Configuration2 register */ + volatile uint32_t SOC_INTEGRATOR; /* INTEGRATOR register */ + volatile uint32_t CLUSTER_FLL_STATUS; /* Status register */ + volatile uint32_t CLUSTER_CONF1; /* Configuration1 register */ + volatile uint32_t CLUSTER_CONF2; /* Configuration2 register */ + volatile uint32_t CLUSTER_INTEGRATOR; /* INTEGRATOR register */ + volatile uint32_t FLL_CONVERGE; /* Fll Converge register */ +} fll_ctrl_reg_t; + +#define FLL_CTRL ((fll_ctrl_reg_t *)SOC_PERI_BASE) + +/* FLL_STATUS - FLL_CTRL status register */ + +#define FLL_CTRL_STATUS_MULTI_FACTOR_MASK (0xFFFFU) +#define FLL_CTRL_STATUS_MULTI_FACTOR_SHIFT (0U) + +#define FLL_CTRL_STATUS_MULTI_FACTOR(x) (((uint32_t)(x) /* << FLL_CTRL_STATUS_MULTI_FACTOR_SHIFT */) & FLL_CTRL_STATUS_MULTI_FACTOR_MASK) + +#define READ_FLL_CTRL_STATUS_MULTI_FACTOR(x) (((uint32_t)(x) & FLL_CTRL_STATUS_MULTI_FACTOR_MASK) /* >> FLL_CTRL_STATUS_MULTI_FACTOR_SHIFT */) + +/* SOC_CONF1 - FLL_CTRL configuration 1 register */ + +#define FLL_CTRL_CONF1_MULTI_FACTOR_MASK (0xFFFFU) +#define FLL_CTRL_CONF1_MULTI_FACTOR_SHIFT (0U) + +#define FLL_CTRL_CONF1_MULTI_FACTOR(x) (((uint32_t)(x) /* << FLL_CTRL_CONF1_MULTI_FACTOR_SHIFT */) & FLL_CTRL_CONF1_MULTI_FACTOR_MASK) + +#define READ_FLL_CTRL_CONF1_MULTI_FACTOR(x) (((uint32_t)(x) & FLL_CTRL_CONF1_MULTI_FACTOR_MASK) /* >> FLL_CTRL_CONF1_MULTI_FACTOR_SHIFT */) + +#define FLL_CTRL_CONF1_DCO_INPUT_MASK (0x3FF0000U) +#define FLL_CTRL_CONF1_DCO_INPUT_SHIFT (16U) +#define FLL_CTRL_CONF1_DCO_INPUT(x) (((uint32_t)(x) << FLL_CTRL_CONF1_DCO_INPUT_SHIFT) & FLL_CTRL_CONF1_DCO_INPUT_MASK) +#define READ_FLL_CTRL_CONF1_DCO_INPUT(x) (((uint32_t)(x) & FLL_CTRL_CONF1_DCO_INPUT_MASK) >> FLL_CTRL_CONF1_DCO_INPUT_SHIFT) + +#define FLL_CTRL_CONF1_CLK_OUT_DIV_MASK (0x3C000000U) +#define FLL_CTRL_CONF1_CLK_OUT_DIV_SHIFT (26U) +#define FLL_CTRL_CONF1_CLK_OUT_DIV(x) (((uint32_t)(x) << FLL_CTRL_CONF1_CLK_OUT_DIV_SHIFT) & FLL_CTRL_CONF1_CLK_OUT_DIV_MASK) +#define READ_FLL_CTRL_CONF1_CLK_OUT_DIV(x) (((uint32_t)(x) & FLL_CTRL_CONF1_CLK_OUT_DIV_MASK) >> FLL_CTRL_CONF1_CLK_OUT_DIV_SHIFT) + +#define FLL_CTRL_CONF1_OUTPUT_LOCK_EN_MASK (0x40000000U) +#define FLL_CTRL_CONF1_OUTPUT_LOCK_EN_SHIFT (30U) +#define FLL_CTRL_CONF1_OUTPUT_LOCK_EN(x) (((uint32_t)(x) << FLL_CTRL_CONF1_OUTPUT_LOCK_EN_SHIFT) & FLL_CTRL_CONF1_OUTPUT_LOCK_EN_MASK) +#define READ_FLL_CTRL_CONF1_OUTPUT_LOCK_EN(x) (((uint32_t)(x) & FLL_CTRL_CONF1_OUTPUT_LOCK_EN_MASK) >> FLL_CTRL_CONF1_OUTPUT_LOCK_EN_SHIFT) + +#define FLL_CTRL_CONF1_MODE_MASK (0x80000000U) +#define FLL_CTRL_CONF1_MODE_SHIFT (31U) +#define FLL_CTRL_CONF1_MODE(x) (((uint32_t)(x) << FLL_CTRL_CONF1_MODE_SHIFT) & FLL_CTRL_CONF1_MODE_MASK) +#define READ_FLL_CTRL_CONF1_MODE(x) (((uint32_t)(x) & FLL_CTRL_CONF1_MODE_MASK) >> FLL_CTRL_CONF1_MODE_SHIFT) + +/* SOC_CONF2 - FLL_CTRL configuration 2 register */ + +#define FLL_CTRL_CONF2_LOOPGAIN_MASK (0xFU) +#define FLL_CTRL_CONF2_LOOPGAIN_SHIF T (0U) + +#define FLL_CTRL_CONF2_LOOPGAIN(x) (((uint32_t)(x) /* << FLL_CTRL_CONF2_LOOPGAIN_SHIFT */) & FLL_CTRL_CONF2_LOOPGAIN_MASK) + +#define READ_FLL_CTRL_CONF2_LOOPGAIN(x) (((uint32_t)(x) & FLL_CTRL_CONF2_LOOPGAIN_MASK)/* >> FLL_CTRL_CONF2_LOOPGAIN_SHIFT */) + +#define FLL_CTRL_CONF2_DEASSERT_CYCLES_MASK (0x3F0U) +#define FLL_CTRL_CONF2_DEASSERT_CYCLES_SHIFT (4U) +#define FLL_CTRL_CONF2_DEASSERT_CYCLES(x) (((uint32_t)(x) << FLL_CTRL_CONF2_DEASSERT_CYCLES_SHIFT) & FLL_CTRL_CONF2_DEASSERT_CYCLES_MASK) +#define READ_FLL_CTRL_CONF2_DEASSERT_CYCLES(x) (((uint32_t)(x) & FLL_CTRL_CONF2_DEASSERT_CYCLES_MASK) >> FLL_CTRL_CONF2_DEASSERT_CYCLES_SHIFT) + +#define FLL_CTRL_CONF2_ASSERT_CYCLES_MASK (0xFC00U) +#define FLL_CTRL_CONF2_ASSERT_CYCLES_SHIFT (10U) +#define FLL_CTRL_CONF2_ASSERT_CYCLES(x) (((uint32_t)(x) << FLL_CTRL_CONF2_ASSERT_CYCLES_SHIFT) & FLL_CTRL_CONF2_ASSERT_CYCLES_MASK) +#define READ_FLL_CTRL_CONF2_ASSERT_CYCLES(x) (((uint32_t)(x) & FLL_CTRL_CONF2_ASSERT_CYCLES_MASK) >> FLL_CTRL_CONF2_ASSERT_CYCLES_SHIFT) + +#define FLL_CTRL_CONF2_LOCK_TOLERANCE_MASK (0xFFF0000U) +#define FLL_CTRL_CONF2_LOCK_TOLERANCE_SHIFT (16U) +#define FLL_CTRL_CONF2_LOCK_TOLERANCE(x) (((uint32_t)(x) << FLL_CTRL_CONF2_LOCK_TOLERANCE_SHIFT) & FLL_CTRL_CONF2_LOCK_TOLERANCE_MASK) +#define READ_FLL_CTRL_CONF2_LOCK_TOLERANCE(x) (((uint32_t)(x) & FLL_CTRL_CONF2_LOCK_TOLERANCE_MASK) >> FLL_CTRL_CONF2_LOCK_TOLERANCE_SHIFT) + +#define FLL_CTRL_CONF2_CONF_CLK_SEL_MASK (0x20000000U) +#define FLL_CTRL_CONF2_CONF_CLK_SEL_SHIFT (29U) +#define FLL_CTRL_CONF2_CONF_CLK_SEL(x) (((uint32_t)(x) << FLL_CTRL_CONF2_CONF_CLK_SEL_SHIFT) & FLL_CTRL_CONF2_CONF_CLK_SEL_MASK) +#define READ_FLL_CTRL_CONF2_CONF_CLK_SEL(x) (((uint32_t)(x) & FLL_CTRL_CONF2_CONF_CLK_SEL_MASK) >> FLL_CTRL_CONF2_CONF_CLK_SEL_SHIFT) + +#define FLL_CTRL_CONF2_OPEN_LOOP_MASK (0x40000000U) +#define FLL_CTRL_CONF2_OPEN_LOOP_SHIFT (30U) +#define FLL_CTRL_CONF2_OPEN_LOOP(x) (((uint32_t)(x) << FLL_CTRL_CONF2_OPEN_LOOP_SHIFT) & FLL_CTRL_CONF2_OPEN_LOOP_MASK) +#define READ_FLL_CTRL_CONF2_OPEN_LOOP(x) (((uint32_t)(x) & FLL_CTRL_CONF2_OPEN_LOOP_MASK) >> FLL_CTRL_CONF2_OPEN_LOOP_SHIFT) + +#define FLL_CTRL_CONF2_DITHERING_MASK (0x80000000U) +#define FLL_CTRL_CONF2_DITHERING_SHIFT (31U) +#define FLL_CTRL_CONF2_DITHERING(x) (((uint32_t)(x) << FLL_CTRL_CONF2_DITHERING_SHIFT) & FLL_CTRL_CONF2_DITHERING_MASK) +#define READ_FLL_CTRL_CONF2_DITHERING(x) (((uint32_t)(x) & FLL_CTRL_CONF2_DITHERING_MASK) >> FLL_CTRL_CONF2_DITHERING_SHIFT) + +/* SOC_INTEGRATOR - FLL_CTRL configuration 2 register */ + +#define FLL_CTRL_INTEGRATOR_FRACT_PART_MASK (0xFFC0U) +#define FLL_CTRL_INTEGRATOR_FRACT_PART_SHIFT (6U) +#define FLL_CTRL_INTEGRATOR_FRACT_PART(x) (((uint32_t)(x) << FLL_CTRL_INTEGRATOR_FRACT_PART_SHIFT) & FLL_CTRL_INTEGRATOR_FRACT_PART_MASK) +#define READ_FLL_CTRL_INTEGRATOR_FRACT_PART(x) (((uint32_t)(x) & FLL_CTRL_INTEGRATOR_FRACT_PART_MASK) >> FLL_CTRL_INTEGRATOR_FRACT_PART_SHIFT) + +#define FLL_CTRL_INTEGRATOR_INT_PART_MASK (0x3FF0000U) +#define FLL_CTRL_INTEGRATOR_INT_PART_SHIFT (16U) +#define FLL_CTRL_INTEGRATOR_INT_PART(x) (((uint32_t)(x) << FLL_CTRL_INTEGRATOR_INT_PART_SHIFT) & FLL_CTRL_INTEGRATOR_INT_PART_MASK) +#define READ_FLL_CTRL_INTEGRATOR_INT_PART(x) (((uint32_t)(x) & FLL_CTRL_INTEGRATOR_INT_PART_MASK) >> FLL_CTRL_INTEGRATOR_INT_PART_SHIFT) + +/* FLL_CONVERGE - FLL_CTRL configuration 2 register */ + +#define FLL_CTRL_SOC_FLL_CONV_MASK (0x1U) +#define FLL_CTRL_SOC_FLL_CONV_SHIFT (0U) + +#define FLL_CTRL_SOC_FLL_CONV(x) (((uint32_t)(x) /* << FLL_CTRL_SOC_FLL_CONV_SHIFT */) & FLL_CTRL_SOC_FLL_CONV_MASK) + +#define READ_FLL_CTRL_SOC_FLL_CONV(x) (((uint32_t)(x) & FLL_CTRL_SOC_FLL_CONV_MASK) /* >> FLL_CTRL_SOC_FLL_CONV_SHIFT */) + +#define FLL_CTRL_CLUSTER_FLL_CONV_MASK (0x2U) +#define FLL_CTRL_CLUSTER_FLL_CONV_SHIFT (1U) +#define FLL_CTRL_CLUSTER_FLL_CONV(x) (((uint32_t)(x) << FLL_CTRL_CLUSTER_FLL_CONV_SHIFT) & FLL_CTRL_CLUSTER_FLL_CONV_MASK) +#define READ_FLL_CTRL_CLUSTER_FLL_CONV(x) (((uint32_t)(x) & FLL_CTRL_CLUSTER_FLL_CONV_MASK) >> FLL_CTRL_CLUSTER_FLL_CONV_SHIFT) + +/* The number of FLL */ + +#define FLL_NUM 2 + +/* The FLL reference frequency */ + +#define FLL_REF_CLK 32768 + +/* GPIO - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t DIR; /* gpio direction register */ + volatile uint32_t IN; /* gpio in register */ + volatile uint32_t OUT; /* gpio out register */ + volatile uint32_t INTEN; /* gpio inten register */ + volatile uint32_t INTCFG[2]; /* gpio int configuration registers */ + volatile uint32_t INTSTATUS; /* gpio int status register */ + volatile uint32_t EN; /* gpio enable register */ + volatile uint32_t PADCFG[8]; /* pad configuration registers */ +} gpio_reg_t; + +#define GPIO_INTCFG_TYPE_MASK (0x3U) +#define GPIO_INTCFG_TYPE_SHIFT (0U) +#define GPIO_INTCFG_TYPE(x) (((uint32_t)(x) << GPIO_INTCFG_TYPE_SHIFT) & GPIO_INTCFG_TYPE_MASK) + +#define GPIO_INTCFG_TYPE_BITS_WIDTH_MASK (0x3U) + +/* Peripheral GPIOA base pointer */ + +#define GPIOA ((gpio_reg_t *)(SOC_PERI_BASE + 0x1000u)) + +/* UDMA - General Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t RX_SADDR; /* RX UDMA buffer transfer address register */ + volatile uint32_t RX_SIZE; /* RX UDMA buffer transfer size register */ + volatile uint32_t RX_CFG; /* RX UDMA transfer configuration register */ + volatile uint32_t RX_INITCFG; /* Reserved */ + volatile uint32_t TX_SADDR; /* TX UDMA buffer transfer address register */ + volatile uint32_t TX_SIZE; /* TX UDMA buffer transfer size register */ + volatile uint32_t TX_CFG; /* TX UDMA transfer configuration register */ + volatile uint32_t TX_INITCFG; /* Reserved */ +} udma_reg_t; + +/* RX_SADDR - RX TX UDMA buffer transfer address register */ + +#define UDMA_SADDR_ADDR_MASK (0xFFFFU) +#define UDMA_SADDR_ADDR_SHIFT (0U) +#define UDMA_SADDR_ADDR(x) (((uint32_t)(x) /* << UDMA_SADDR_ADDR_SHIFT */) & UDMA_SADDR_ADDR_MASK) + +/* RX_SIZE - RX TX UDMA buffer transfer size register */ + +#define UDMA_SIZE_SIZE_MASK (0x1FFFFU) +#define UDMA_SIZE_SIZE_SHIFT (0U) +#define UDMA_SIZE_SIZE(x) (((uint32_t)(x) << UDMA_SIZE_SIZE_SHIFT) & UDMA_SIZE_SIZE_MASK) + +/* RX_CFG - RX TX UDMA transfer configuration register */ + +#define UDMA_CFG_CONTINOUS_MASK (0x1U) +#define UDMA_CFG_CONTINOUS_SHIFT (0U) +#define UDMA_CFG_CONTINOUS(x) (((uint32_t)(x) /* << UDMA_CFG_CONTINOUS_SHIFT */) & UDMA_CFG_CONTINOUS_MASK) +#define UDMA_CFG_DATA_SIZE_MASK (0x6U) +#define UDMA_CFG_DATA_SIZE_SHIFT (1U) +#define UDMA_CFG_DATA_SIZE(x) (((uint32_t)(x) << UDMA_CFG_DATA_SIZE_SHIFT) & UDMA_CFG_DATA_SIZE_MASK) +#define UDMA_CFG_EN_MASK (0x10U) +#define UDMA_CFG_EN_SHIFT (4U) +#define UDMA_CFG_EN(x) (((uint32_t)(x) << UDMA_CFG_EN_SHIFT) & UDMA_CFG_EN_MASK) +#define UDMA_CFG_CLR_MASK (0x20U) +#define UDMA_CFG_CLR_SHIFT (5U) +#define UDMA_CFG_CLR(x) (((uint32_t)(x) << UDMA_CFG_CLR_SHIFT) & UDMA_CFG_CLR_MASK) + +/* Peripheral UDMA base address 0x1A102000 */ + +#define UDMA_BASE (0x1A102000) + +/* UDMA Global configuration - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t CG; /* clock gating register */ + volatile uint32_t EVTIN; /* input event register */ +} udma_gc_reg_t; + +#define UDMA_GC_BASE (UDMA_BASE + 0x780u) +#define UDMA_GC ((udma_gc_reg_t *)UDMA_GC_BASE) + +/* UDMA_GC - UDMA event in register, User chooses which events can come to + * UDMA as reference events, support up to 4 choices + */ + +#define UDMA_GC_EVTIN_CHOICE0_MASK (0xFFU) +#define UDMA_GC_EVTIN_CHOICE0_SHIFT (0U) +#define UDMA_GC_EVTIN_CHOICE0(x) (((uint32_t)(x) << UDMA_GC_EVTIN_CHOICE0_SHIFT) & UDMA_GC_EVTIN_CHOICE0_MASK) + +#define UDMA_GC_EVTIN_CHOICE1_MASK (0xFF00U) +#define UDMA_GC_EVTIN_CHOICE1_SHIFT (8U) +#define UDMA_GC_EVTIN_CHOICE1(x) (((uint32_t)(x) << UDMA_GC_EVTIN_CHOICE1_SHIFT) & UDMA_GC_EVTIN_CHOICE1_MASK) + +#define UDMA_GC_EVTIN_CHOICE2_MASK (0xFF0000U) +#define UDMA_GC_EVTIN_CHOICE2_SHIFT (16U) +#define UDMA_GC_EVTIN_CHOICE2(x) (((uint32_t)(x) << UDMA_GC_EVTIN_CHOICE2_SHIFT) & UDMA_GC_EVTIN_CHOICE2_MASK) + +#define UDMA_GC_EVTIN_CHOICE3_MASK (0xFF000000) +#define UDMA_GC_EVTIN_CHOICE3_SHIFT (24U) +#define UDMA_GC_EVTIN_CHOICE3(x) (((uint32_t)(x) << UDMA_GC_EVTIN_CHOICE3_SHIFT) & UDMA_GC_EVTIN_CHOICE3_MASK) + +/* LVDS - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_LVDS; /* UDMA general register */ + volatile uint32_t RF_CFG; /* configuration register */ + volatile uint32_t RF_GPIO; /* Reserved */ + volatile uint32_t RF_STATUS; /* Status register */ +} lvds_reg_t; + +#define LVDS_BASE (UDMA_BASE + 0 * 128U) +#define LVDS ((lvds_reg_t *)LVDS_BASE) + +/* RF_CFG - LVDS configuration register */ + +#define LVDS_RF_CFG_TX_ENB_MASK (0x1U) +#define LVDS_RF_CFG_TX_ENB_SHIFT (0U) +#define LVDS_RF_CFG_TX_ENB(x) (((uint32_t)(x) << /* LVDS_RF_CFG_TX_ENB_SHIFT */) & LVDS_RF_CFG_TX_ENB_MASK) + +#define LVDS_RF_CFG_TX_OEB_MASK (0x2U) +#define LVDS_RF_CFG_TX_OEB_SHIFT (1U) +#define LVDS_RF_CFG_TX_OEB(x) (((uint32_t)(x) << LVDS_RF_CFG_TX_OEB_SHIFT) & LVDS_RF_CFG_TX_OEB_MASK) + +#define LVDS_RF_CFG_TX_MODE_MASK (0x4U) +#define LVDS_RF_CFG_TX_MODE_SHIFT (2U) +#define LVDS_RF_CFG_TX_MODE(x) (((uint32_t)(x) << LVDS_RF_CFG_TX_MODE_SHIFT) & LVDS_RF_CFG_TX_MODE_MASK) + +#define LVDS_RF_CFG_TX_VSEL_MASK (0x8U) +#define LVDS_RF_CFG_TX_VSEL_SHIFT (3U) +#define LVDS_RF_CFG_TX_VSEL(x) (((uint32_t)(x) << LVDS_RF_CFG_TX_VSEL_SHIFT) & LVDS_RF_CFG_TX_VSEL_MASK) + +#define LVDS_RF_CFG_RX_ENB_MASK (0x10U) +#define LVDS_RF_CFG_RX_ENB_SHIFT (4U) +#define LVDS_RF_CFG_RX_ENB(x) (((uint32_t)(x) << LVDS_RF_CFG_RX_ENB_SHIFT) & LVDS_RF_CFG_RX_ENB_MASK) + +#define LVDS_RF_CFG_SD_RX_EN_MASK (0x20U) +#define LVDS_RF_CFG_SD_RX_EN_SHIFT (5U) +#define LVDS_RF_CFG_SD_RX_EN(x) (((uint32_t)(x) << LVDS_RF_CFG_SD_RX_EN_SHIFT) & LVDS_RF_CFG_SD_RX_EN_MASK) + +#define LVDS_RF_CFG_SD_TX_EN_MASK (0x40U) +#define LVDS_RF_CFG_SD_TX_EN_SHIFT (6U) +#define LVDS_RF_CFG_SD_TX_EN(x) (((uint32_t)(x) << LVDS_RF_CFG_SD_TX_EN_SHIFT) & LVDS_RF_CFG_SD_TX_EN_MASK) + +#define LVDS_RF_CFG_DDR_RX_EN_MASK (0x80U) +#define LVDS_RF_CFG_DDR_RX_EN_SHIFT (7U) +#define LVDS_RF_CFG_DDR_RX_EN(x) (((uint32_t)(x) << LVDS_RF_CFG_DDR_RX_EN_SHIFT) & LVDS_RF_CFG_DDR_RX_EN_MASK) + +#define LVDS_RF_CFG_DDR_TX_EN_MASK (0x100U) +#define LVDS_RF_CFG_DDR_TX_EN_SHIFT (8U) +#define LVDS_RF_CFG_DDR_TX_EN(x) (((uint32_t)(x) << LVDS_RF_CFG_DDR_TX_EN_SHIFT) & LVDS_RF_CFG_DDR_TX_EN_MASK) + +#define LVDS_RF_CFG_CLKSEL_MASK (0x200U) +#define LVDS_RF_CFG_CLKSEL_SHIFT (9U) +#define LVDS_RF_CFG_CLKSEL(x) (((uint32_t)(x) << LVDS_RF_CFG_CLKSEL_SHIFT) & LVDS_RF_CFG_CLKSEL_MASK) + +#define LVDS_RF_CFG_MODE_MASK (0x400U) +#define LVDS_RF_CFG_MODE_SHIFT (10U) +#define LVDS_RF_CFG_MODE(x) (((uint32_t)(x) << LVDS_RF_CFG_MODE_SHIFT) & LVDS_RF_CFG_MODE_MASK) + +#define LVDS_RF_CFG_MODE_VAL_MASK (0x800U) +#define LVDS_RF_CFG_MODE_VAL_SHIFT (11U) +#define LVDS_RF_CFG_MODE_VAL(x) (((uint32_t)(x) << LVDS_RF_CFG_MODE_VAL_SHIFT) & LVDS_RF_CFG_MODE_VAL_MASK) + +#define LVDS_RF_CFG_MODE_RX_MASK (0x1000U) +#define LVDS_RF_CFG_MODE_RX_SHIFT (12U) +#define LVDS_RF_CFG_MODE_RX(x) (((uint32_t)(x) << LVDS_RF_CFG_MODE_RX_SHIFT) & LVDS_RF_CFG_MODE_RX_MASK) + +/* RF_STATUS - LVDS Status register */ + +#define LVDS_RF_STATUS_SYNC_FLAG_MASK (0x1U) +#define LVDS_RF_STATUS_SYNC_FLAG_SHIFT (0U) +#define LVDS_RF_STATUS_SYNC_FLAG(x) (((uint32_t)(x) /* << LVDS_RF_STATUS_SYNC_FLAG_SHIFT */) & LVDS_RF_STATUS_SYNC_FLAG_MASK) + +/* ORCA - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_ORCA; /* ORCA UDMA general register */ + volatile uint32_t RF_CFG; /* ORCA configuration register */ + volatile uint32_t RF_GPIO; /* Reserved */ + volatile uint32_t RF_STATUS; /* ORCA Status register */ + volatile uint32_t PAD; /* ORCA reserved */ + volatile uint32_t CLKDIV_EN; /* ORCA uDMA clock divider enable register */ + volatile uint32_t CLKDIV_CFG; /* ORCA uDMA clock divider configuration register */ + volatile uint32_t CLKDIV_UPD; /* ORCA uDMA clock divider data register */ + volatile uint32_t ORCA_CFG; /* ORCA configuration register */ + volatile uint32_t CNT_EVENT; /* ORCA Status register */ +} orca_reg_t; + +#define ORCA_BASE (UDMA_BASE + 0 * 128U) +#define ORCA ((orca_reg_t *)ORCA_BASE) + +/* RF_CFG - ORCA configuration register */ + +#define ORCA_RF_CFG_TX_ENB_MASK (0x1U) +#define ORCA_RF_CFG_TX_ENB_SHIFT (0U) +#define ORCA_RF_CFG_TX_ENB(x) (((uint32_t)(x) /* << ORCA_RF_CFG_TX_ENB_SHIFT */) & ORCA_RF_CFG_TX_ENB_MASK) + +#define ORCA_RF_CFG_TX_OEB_MASK (0x2U) +#define ORCA_RF_CFG_TX_OEB_SHIFT (1U) +#define ORCA_RF_CFG_TX_OEB(x) (((uint32_t)(x) << ORCA_RF_CFG_TX_OEB_SHIFT) & ORCA_RF_CFG_TX_OEB_MASK) + +#define ORCA_RF_CFG_TX_MODE_MASK (0x4U) +#define ORCA_RF_CFG_TX_MODE_SHIFT (2U) +#define ORCA_RF_CFG_TX_MODE(x) (((uint32_t)(x) << ORCA_RF_CFG_TX_MODE_SHIFT) & ORCA_RF_CFG_TX_MODE_MASK) + +#define ORCA_RF_CFG_TX_VSEL_MASK (0x8U) +#define ORCA_RF_CFG_TX_VSEL_SHIFT (3U) +#define ORCA_RF_CFG_TX_VSEL(x) (((uint32_t)(x) << ORCA_RF_CFG_TX_VSEL_SHIFT) & ORCA_RF_CFG_TX_VSEL_MASK) + +#define ORCA_RF_CFG_RX_ENB_MASK (0x10U) +#define ORCA_RF_CFG_RX_ENB_SHIFT (4U) +#define ORCA_RF_CFG_RX_ENB(x) (((uint32_t)(x) << ORCA_RF_CFG_RX_ENB_SHIFT) & ORCA_RF_CFG_RX_ENB_MASK) + +#define ORCA_RF_CFG_SD_RX_EN_MASK (0x20U) +#define ORCA_RF_CFG_SD_RX_EN_SHIFT (5U) +#define ORCA_RF_CFG_SD_RX_EN(x) (((uint32_t)(x) << ORCA_RF_CFG_SD_RX_EN_SHIFT) & ORCA_RF_CFG_SD_RX_EN_MASK) + +#define ORCA_RF_CFG_SD_TX_EN_MASK (0x40U) +#define ORCA_RF_CFG_SD_TX_EN_SHIFT (6U) +#define ORCA_RF_CFG_SD_TX_EN(x) (((uint32_t)(x) << ORCA_RF_CFG_SD_TX_EN_SHIFT) & ORCA_RF_CFG_SD_TX_EN_MASK) + +#define ORCA_RF_CFG_DDR_RX_EN_MASK (0x80U) +#define ORCA_RF_CFG_DDR_RX_EN_SHIFT (7U) +#define ORCA_RF_CFG_DDR_RX_EN(x) (((uint32_t)(x) << ORCA_RF_CFG_DDR_RX_EN_SHIFT) & ORCA_RF_CFG_DDR_RX_EN_MASK) + +#define ORCA_RF_CFG_DDR_TX_EN_MASK (0x100U) +#define ORCA_RF_CFG_DDR_TX_EN_SHIFT (8U) +#define ORCA_RF_CFG_DDR_TX_EN(x) (((uint32_t)(x) << ORCA_RF_CFG_DDR_TX_EN_SHIFT) & ORCA_RF_CFG_DDR_TX_EN_MASK) + +#define ORCA_RF_CFG_CLKSEL_MASK (0x200U) +#define ORCA_RF_CFG_CLKSEL_SHIFT (9U) +#define ORCA_RF_CFG_CLKSEL(x) (((uint32_t)(x) << ORCA_RF_CFG_CLKSEL_SHIFT) & ORCA_RF_CFG_CLKSEL_MASK) + +#define ORCA_RF_CFG_MODE_MASK (0x400U) +#define ORCA_RF_CFG_MODE_SHIFT (10U) +#define ORCA_RF_CFG_MODE(x) (((uint32_t)(x) << ORCA_RF_CFG_MODE_SHIFT) & ORCA_RF_CFG_MODE_MASK) + +#define ORCA_RF_CFG_MODE_VAL_MASK (0x800U) +#define ORCA_RF_CFG_MODE_VAL_SHIFT (11U) +#define ORCA_RF_CFG_MODE_VAL(x) (((uint32_t)(x) << ORCA_RF_CFG_MODE_VAL_SHIFT) & ORCA_RF_CFG_MODE_VAL_MASK) + +#define ORCA_RF_CFG_MODE_RX_MASK (0x1000U) +#define ORCA_RF_CFG_MODE_RX_SHIFT (12U) +#define ORCA_RF_CFG_MODE_RX(x) (((uint32_t)(x) << ORCA_RF_CFG_MODE_RX_SHIFT) & ORCA_RF_CFG_MODE_RX_MASK) + +/* RF_STATUS - ORCA Status register */ + +#define ORCA_RF_STATUS_SYNC_FLAG_MASK (0x1U) +#define ORCA_RF_STATUS_SYNC_FLAG_SHIFT (0U) +#define ORCA_RF_STATUS_SYNC_FLAG(x) (((uint32_t)(x) /* << ORCA_RF_STATUS_SYNC_FLAG_SHIFT */) & ORCA_RF_STATUS_SYNC_FLAG_MASK) + +/* CLKDIV_EN - ORCA uDMA clock divider enable register */ + +#define ORCA_CLKDIV_EN_MASK (0x1U) +#define ORCA_CLKDIV_EN_SHIFT (0U) +#define ORCA_CLKDIV_EN(x) (((uint32_t)(x) /* << ORCA_CLKDIV_EN_SHIFT */) & ORCA_CLKDIV_EN_MASK) + +/* CLKDIV_CFG - ORCA uDMA clock divider configuration register */ + +#define ORCA_CLKDIV_CFG_MASK (0xFFU) +#define ORCA_CLKDIV_CFG_SHIFT (0U) +#define ORCA_CLKDIV_CFG(x) (((uint32_t)(x) /* << ORCA_CLKDIV_CFG_SHIFT */) & ORCA_CLKDIV_CFG_MASK) + +/* CLKDIV_UDP - ORCA uDMA clock divider enable register */ + +#define ORCA_CLKDIV_UDP_MASK (0x1U) +#define ORCA_CLKDIV_UDP_SHIFT (0U) +#define ORCA_CLKDIV_UDP(x) (((uint32_t)(x) /* << ORCA_CLKDIV_UDP_SHIFT */) & ORCA_CLKDIV_UDP_MASK) + +/* ORCA_CFG - ORCA configuration register */ + +#define ORCA_CFG_SIZE_MASK (0xFU) +#define ORCA_CFG_SIZE_SHIFT (0U) +#define ORCA_CFG_SIZE(x) (((uint32_t)(x) /* << ORCA_CFG_SIZE_SHIFT */) & ORCA_CFG_SIZE_MASK) + +#define ORCA_CFG_DELAY_MASK (0xF0U) +#define ORCA_CFG_DELAY_SHIFT (4U) +#define ORCA_CFG_DELAY(x) (((uint32_t)(x) << ORCA_CFG_DELAY_SHIFT) & ORCA_CFG_DELAY_MASK) + +#define ORCA_CFG_EN_MASK (0x100U) +#define ORCA_CFG_EN_SHIFT (8U) +#define ORCA_CFG_EN(x) (((uint32_t)(x) << ORCA_CFG_EN_SHIFT) & ORCA_CFG_EN_MASK) + +/* SPIM - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_SPIM; /* SPIM UDMA general register */ +} spim_reg_t; + +#define SPIM0_BASE (UDMA_BASE + 1 * 128U) +#define SPIM0 ((spim_reg_t *)SPIM0_BASE) +#define SPIM1_BASE (UDMA_BASE + 2 * 128U) +#define SPIM1 ((spim_reg_t *)SPIM1_BASE) + +/* uDMA - SPIM uDMA control CMD */ + +#define SPIM_CMD_CFG_ID 0 +#define SPIM_CMD_SOT_ID 1 +#define SPIM_CMD_SEND_CMD_ID 2 +#define SPIM_CMD_SEND_ADDR_ID 3 +#define SPIM_CMD_DUMMY_ID 4 +#define SPIM_CMD_WAIT_ID 5 +#define SPIM_CMD_TX_DATA_ID 6 +#define SPIM_CMD_RX_DATA_ID 7 +#define SPIM_CMD_RPT_ID 8 +#define SPIM_CMD_EOT_ID 9 +#define SPIM_CMD_RPT_END_ID 10 +#define SPIM_CMD_RX_CHECK_ID 11 +#define SPIM_CMD_FUL_ID 12 + +#define SPIM_CMD_MASK (0xF0000000U) +#define SPIM_CMD_SHIFT (28U) +#define SPIM_CMD(x) (((uint32_t)(x) << SPIM_CMD_SHIFT) & SPIM_CMD_MASK) + +/* SPIM_Register_Masks SPIM Register Masks */ + +/* CMD_CFG - SPIM configuration register */ + +#define SPIM_CMD_CFG_CLKDIV_MASK (0xFFU) +#define SPIM_CMD_CFG_CLKDIV_SHIFT (0U) +#define SPIM_CMD_CFG_CLKDIV(x) (((uint32_t)(x) /* << SPIM_CMD_CFG_CLKDIV_SHIFT */) & SPIM_CMD_CFG_CLKDIV_MASK) +#define SPIM_CMD_CFG_CPHA_MASK (0x100U) +#define SPIM_CMD_CFG_CPHA_SHIFT (8U) +#define SPIM_CMD_CFG_CPHA(x) (((uint32_t)(x) << SPIM_CMD_CFG_CPHA_SHIFT) & SPIM_CMD_CFG_CPHA_MASK) +#define SPIM_CMD_CFG_CPOL_MASK (0x200U) +#define SPIM_CMD_CFG_CPOL_SHIFT (9U) +#define SPIM_CMD_CFG_CPOL(x) (((uint32_t)(x) << SPIM_CMD_CFG_CPOL_SHIFT) & SPIM_CMD_CFG_CPOL_MASK) + +/* CMD_SOT - SPIM chip select (CS) */ + +#define SPIM_CMD_SOT_CS_MASK (0x3U) +#define SPIM_CMD_SOT_CS_SHIFT (0U) +#define SPIM_CMD_SOT_CS(x) (((uint32_t)(x) << SPIM_CMD_SOT_CS_SHIFT) & SPIM_CMD_SOT_CS_MASK) + +/* CMD_SEND_CMD - SPIM Transmit a command */ + +#define SPIM_CMD_SEND_VALUEL_MASK (0xFFU) +#define SPIM_CMD_SEND_VALUEL_SHIFT (0U) +#define SPIM_CMD_SEND_VALUEL(x) (((uint32_t)(x) /* << SPIM_CMD_SEND_VALUEL_SHIFT */) & SPIM_CMD_SEND_VALUEL_MASK) +#define SPIM_CMD_SEND_VALUEH_MASK (0xFF00U) +#define SPIM_CMD_SEND_VALUEH_SHIFT (8U) +#define SPIM_CMD_SEND_VALUEH(x) (((uint32_t)(x) << SPIM_CMD_SEND_VALUEH_SHIFT) & SPIM_CMD_SEND_VALUEH_MASK) +#define SPIM_CMD_SEND_CMD_SIZE_MASK (0x1F0000U) +#define SPIM_CMD_SEND_CMD_SIZE_SHIFT (16U) +#define SPIM_CMD_SEND_CMD_SIZE(x) (((uint32_t)(x) << SPIM_CMD_SEND_CMD_SIZE_SHIFT) & SPIM_CMD_SEND_CMD_SIZE_MASK) +#define SPIM_CMD_SEND_QPI_MASK (0x8000000U) +#define SPIM_CMD_SEND_QPI_SHIFT (27U) +#define SPIM_CMD_SEND_QPI(x) (((uint32_t)(x) << SPIM_CMD_SEND_QPI_SHIFT) & SPIM_CMD_SEND_QPI_MASK) + +/* CMD_SEND_ADDR - SPIM Transmit a address */ + +#define SPIM_CMD_SEND_ADDR_VALUE_MASK (0xFFFFU) +#define SPIM_CMD_SEND_ADDR_VALUE_SHIFT (0U) +#define SPIM_CMD_SEND_ADDR_VALUE(x) (((uint32_t)(x) /* << SPIM_CMD_SEND_ADDR_VALUE_SHIFT */) & SPIM_CMD_SEND_ADDR_VALUE_MASK) +#define SPIM_CMD_SEND_ADDR_CMD_SIZE_MASK (0x1F0000U) +#define SPIM_CMD_SEND_ADDR_CMD_SIZE_SHIFT (16U) +#define SPIM_CMD_SEND_ADDR_CMD_SIZE(x) (((uint32_t)(x) << SPIM_CMD_SEND_ADDR_CMD_SIZE_SHIFT) & SPIM_CMD_SEND_ADDR_CMD_SIZE_MASK) +#define SPIM_CMD_SEND_ADDR_QPI_MASK (0x8000000U) +#define SPIM_CMD_SEND_ADDR_QPI_SHIFT (27U) +#define SPIM_CMD_SEND_ADDR_QPI(x) (((uint32_t)(x) << SPIM_CMD_SEND_ADDR_QPI_SHIFT) & SPIM_CMD_SEND_ADDR_QPI_MASK) + +/* CMD_DUMMY - SPIM number of dummy cycle */ + +#define SPIM_CMD_DUMMY_CYCLE_MASK (0x1F0000U) +#define SPIM_CMD_DUMMY_CYCLE_SHIFT (16U) +#define SPIM_CMD_DUMMY_CYCLE(x) (((uint32_t)(x) << SPIM_CMD_DUMMY_CYCLE_SHIFT) & SPIM_CMD_DUMMY_CYCLE_MASK) + +/* CMD_WAIT - SPIM wait in which event - 2 bits */ + +#define SPIM_CMD_WAIT_EVENT_ID_MASK (0x3U) +#define SPIM_CMD_WAIT_EVENT_ID_SHIFT (0U) +#define SPIM_CMD_WAIT_EVENT_ID(x) (((uint32_t)(x) /* << SPIM_CMD_WAIT_EVENT_ID_SHIFT */) & SPIM_CMD_WAIT_EVENT_ID_MASK) + +/* CMD_TX_DATA - SPIM send data */ + +#define SPIM_CMD_TX_DATA_SIZE_MASK (0xFFFFU) +#define SPIM_CMD_TX_DATA_SIZE_SHIFT (0U) +#define SPIM_CMD_TX_DATA_SIZE(x) (((uint32_t)(x) /* << SPIM_CMD_TX_DATA_SIZE_SHIFT */) & SPIM_CMD_TX_DATA_SIZE_MASK) +#define SPIM_CMD_TX_DATA_BYTE_ALIGN_MASK (0x4000000U) +#define SPIM_CMD_TX_DATA_BYTE_ALIGN_SHIFT (26U) +#define SPIM_CMD_TX_DATA_BYTE_ALIGN(x) (((uint32_t)(x) << SPIM_CMD_TX_DATA_BYTE_ALIGN_SHIFT) & SPIM_CMD_TX_DATA_BYTE_ALIGN_MASK) +#define SPIM_CMD_TX_DATA_QPI_MASK (0x8000000U) +#define SPIM_CMD_TX_DATA_QPI_SHIFT (27U) +#define SPIM_CMD_TX_DATA_QPI(x) (((uint32_t)(x) << SPIM_CMD_TX_DATA_QPI_SHIFT) & SPIM_CMD_TX_DATA_QPI_MASK) + +/* CMD_RX_DATA - SPIM receive data */ + +#define SPIM_CMD_RX_DATA_SIZE_MASK (0xFFFFU) +#define SPIM_CMD_RX_DATA_SIZE_SHIFT (0U) +#define SPIM_CMD_RX_DATA_SIZE(x) (((uint32_t)(x) /* << SPIM_CMD_RX_DATA_SIZE_SHIFT */) & SPIM_CMD_RX_DATA_SIZE_MASK) +#define SPIM_CMD_RX_DATA_BYTE_ALIGN_MASK (0x4000000U) +#define SPIM_CMD_RX_DATA_BYTE_ALIGN_SHIFT (26U) +#define SPIM_CMD_RX_DATA_BYTE_ALIGN(x) (((uint32_t)(x) << SPIM_CMD_RX_DATA_BYTE_ALIGN_SHIFT) & SPIM_CMD_RX_DATA_BYTE_ALIGN_MASK) +#define SPIM_CMD_RX_DATA_QPI_MASK (0x8000000U) +#define SPIM_CMD_RX_DATA_QPI_SHIFT (27U) +#define SPIM_CMD_RX_DATA_QPI(x) (((uint32_t)(x) << SPIM_CMD_RX_DATA_QPI_SHIFT) & SPIM_CMD_RX_DATA_QPI_MASK) + +/* CMD_RPT - SPIM repeat the next transfer N times */ + +#define SPIM_CMD_RPT_CNT_MASK (0xFFFFU) +#define SPIM_CMD_RPT_CNT_SHIFT (0U) +#define SPIM_CMD_RPT_CNT(x) (((uint32_t)(x) /* << SPIM_CMD_RPT_CNT_SHIFT */) & SPIM_CMD_RPT_CNT_MASK) + +/* CMD_EOT - SPIM clears the chip select (CS), and send a end event or not */ + +#define SPIM_CMD_EOT_EVENT_GEN_MASK (0x1U) +#define SPIM_CMD_EOT_EVENT_GEN_SHIFT (0U) +#define SPIM_CMD_EOT_EVENT_GEN(x) (((uint32_t)(x) /* << SPIM_CMD_EOT_EVENT_GEN_SHIFT */) & SPIM_CMD_EOT_EVENT_GEN_MASK) + +/* CMD_RPT_END - SPIM End of the repeat loop */ + +#define SPIM_CMD_RPT_END_SPI_CMD_MASK (0xFU) +#define SPIM_CMD_RPT_END_SPI_CMD_SHIFT (0U) +#define SPIM_CMD_RPT_END_SPI_CMD(x) (((uint32_t)(x) /* << SPIM_CMD_RPT_END_SPI_CMD_SHIFT */) & SPIM_CMD_RPT_END_SPI_CMD_MASK) + +/* CMD_RX_CHECK - SPIM check up to 16 bits of data against an expected value */ + +#define SPIM_CMD_RX_CHECK_COMP_DATA_MASK (0xFFFFU) +#define SPIM_CMD_RX_CHECK_COMP_DATA_SHIFT (0U) +#define SPIM_CMD_RX_CHECK_COMP_DATA(x) (((uint32_t)(x) /* << SPIM_CMD_RX_CHECK_COMP_DATA_SHIFT */) & SPIM_CMD_RX_CHECK_COMP_DATA_MASK) + +/* The number of bits to check, maximum is 16bits */ + +#define SPIM_CMD_RX_CHECK_STATUS_SIZE_MASK (0xFF0000U) +#define SPIM_CMD_RX_CHECK_STATUS_SIZE_SHIFT (16U) +#define SPIM_CMD_RX_CHECK_STATUS_SIZE(x) (((uint32_t)(x) << SPIM_CMD_RX_CHECK_STATUS_SIZE_SHIFT) & SPIM_CMD_RX_CHECK_STATUS_SIZE_MASK) + +/* The type of checking, 0 - Equal; 1 - check the bits of one; + * 2 - check the bits of zero + */ + +#define SPIM_CMD_RX_CHECK_CHECK_TYPE_MASK (0x3000000U) +#define SPIM_CMD_RX_CHECK_CHECK_TYPE_SHIFT (24U) +#define SPIM_CMD_RX_CHECK_CHECK_TYPE(x) (((uint32_t)(x) << SPIM_CMD_RX_CHECK_CHECK_TYPE_SHIFT) & SPIM_CMD_RX_CHECK_CHECK_TYPE_MASK) +#define SPIM_CMD_RX_CHECK_BYTE_ALIGN_MASK (0x4000000U) +#define SPIM_CMD_RX_CHECK_BYTE_ALIGN_SHIFT (26U) +#define SPIM_CMD_RX_CHECK_BYTE_ALIGN(x) (((uint32_t)(x) << SPIM_CMD_RX_CHECK_BYTE_ALIGN_SHIFT) & SPIM_CMD_RX_CHECK_BYTE_ALIGN_MASK) + +/* The check bits transferred by QPI or not */ + +#define SPIM_CMD_RX_CHECK_QPI_MASK (0x8000000U) +#define SPIM_CMD_RX_CHECK_QPI_SHIFT (27U) +#define SPIM_CMD_RX_CHECK_QPI(x) (((uint32_t)(x) << SPIM_CMD_RX_CHECK_QPI_SHIFT) & SPIM_CMD_RX_CHECK_QPI_MASK) + +/* CMD_FULL_DULP - SPIM Activate full duplex mode */ + +#define SPIM_CMD_FULL_SIZE_CMD_MASK (0xFFFFU) +#define SPIM_CMD_FULL_SIZE_CMD_SHIFT (0U) +#define SPIM_CMD_FULL_SIZE_CMD(x) (((uint32_t)(x) /* << SPIM_CMD_FULL_SIZE_CMD_SHIFT */) & SPIM_CMD_FULL_SIZE_CMD_MASK) +#define SPIM_CMD_FULL_BYTE_ALIGN_CMD_MASK (0x4000000U) +#define SPIM_CMD_FULL_BYTE_ALIGN_CMD_SHIFT (26U) +#define SPIM_CMD_FULL_BYTE_ALIGN_CMD(x) (((uint32_t)(x) << SPIM_CMD_FULL_BYTE_ALIGN_CMD_SHIFT) & SPIM_CMD_FULL_BYTE_ALIGN_CMD_MASK) + +#define SPIM_CMD_CFG(clockDiv,cpol,cpha) (SPIM_CMD(SPIM_CMD_CFG_ID) \ + | SPIM_CMD_CFG_CLKDIV(clockDiv) \ + | SPIM_CMD_CFG_CPOL(cpol) \ + | SPIM_CMD_CFG_CPHA(cpha)) + +#define SPIM_CMD_SOT(cs) (SPIM_CMD(SPIM_CMD_SOT_ID) \ + | SPIM_CMD_SOT_CS(cs)) + +#define SPIM_CMD_SEND_CMD(cmd,bits,qpi) (SPIM_CMD(SPIM_CMD_SEND_CMD_ID) \ + | SPIM_CMD_SEND_VALUEL((cmd >> 8)) \ + | SPIM_CMD_SEND_VALUEH((cmd & 0xFF)) \ + | SPIM_CMD_SEND_CMD_SIZE(bits - 1) \ + | SPIM_CMD_SEND_QPI(qpi)) + +#define SPIM_CMD_SEND_ADDR(bits,qpi) (SPIM_CMD(SPIM_CMD_SEND_ADDR_ID) \ + | SPIM_CMD_SEND_ADDR_VALUE(0) \ + | SPIM_CMD_SEND_ADDR_CMD_SIZE((bits - 1)) \ + | SPIM_CMD_SEND_ADDR_QPI(qpi)) + +#ifndef __PLATFORM_GVSOC__ +#define SPIM_CMD_DUMMY(cycles) (cycles ? (SPIM_CMD(SPIM_CMD_DUMMY_ID) \ + | SPIM_CMD_DUMMY_CYCLE(cycles - 1)) : 0xFFFF0000u) +#else +#define SPIM_CMD_DUMMY(cycles) (cycles ? (SPIM_CMD(SPIM_CMD_DUMMY_ID) \ + | SPIM_CMD_DUMMY_CYCLE(cycles - 1)) : 0x0u) +#endif + +#define SPIM_CMD_TX_DATA(bits,qpi,byte_align) (SPIM_CMD(SPIM_CMD_TX_DATA_ID) \ + | SPIM_CMD_TX_DATA_SIZE((bits - 1)) \ + | SPIM_CMD_TX_DATA_BYTE_ALIGN(byte_align) \ + | SPIM_CMD_TX_DATA_QPI(qpi)) + +#define SPIM_CMD_RX_DATA(bits,qpi,byte_align) (SPIM_CMD(SPIM_CMD_RX_DATA_ID) \ + | SPIM_CMD_RX_DATA_SIZE((bits - 1)) \ + | SPIM_CMD_RX_DATA_BYTE_ALIGN(byte_align) \ + | SPIM_CMD_RX_DATA_QPI(qpi)) + +#define SPIM_CMD_RPT(iter) (SPIM_CMD(SPIM_CMD_RPT_ID) \ + | SPIM_CMD_RPT_CNT(iter)) + +#define SPIM_CMD_EOT(evt) (SPIM_CMD(SPIM_CMD_EOT_ID) \ + | SPIM_CMD_EOT_EVENT_GEN(evt)) + +#define SPIM_CMD_WAIT(event) (SPIM_CMD(SPIM_CMD_WAIT_ID) \ + | SPIM_CMD_WAIT_EVENT_ID(event)) + +#define SPIM_CMD_RPT_END() (SPIM_CMD(SPIM_CMD_RPT_END_ID)) + +#define SPIM_CMD_FUL(bits,byte_align) (SPIM_CMD(SPIM_CMD_RPT_END_ID) \ + | SPIM_CMD_FULL_SIZE_CMD((bits - 1)) \ + | SPIM_CMD_FULL_BYTE_ALIGN_CMD(byte_align)) + +#define SPIM_CMD_RX_CHECK(mode,bits,value,qpi,byte_align) \ + (SPIM_CMD(SPIM_CMD_RX_CHECK_ID) \ + | SPIM_CMD_RX_CHECK_COMP_DATA(value) \ + | SPIM_CMD_RX_CHECK_STATUS_SIZE((bits - 1)) \ + | SPIM_CMD_RX_CHECK_CHECK_TYPE(mode) \ + | SPIM_CMD_RX_CHECK_BYTE_ALIGN(byte_align) \ + | SPIM_CMD_RX_CHECK_QPI(qpi)) + +/* HYPERBUS - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_HYPERBUS; /* UDMA general register */ + volatile uint32_t EXT_ADDR; /* Memory access address register */ + volatile uint32_t EXT_CFG; /* Reserved */ + volatile uint32_t MEM_CFG0; /* Memory control Configuration register0 */ + volatile uint32_t MEM_CFG1; /* Memory control Configuration register1 */ + volatile uint32_t MEM_CFG2; /* Memory control Configuration register2 */ + volatile uint32_t MEM_CFG3; /* Memory control Configuration register3 */ + volatile uint32_t MEM_CFG4; /* Memory control Configuration register4 */ + volatile uint32_t MEM_CFG5; /* Memory control Configuration register5 */ + volatile uint32_t MEM_CFG6; /* Memory control Configuration register6 */ + volatile uint32_t MEM_CFG7; /* Memory control Configuration register7 */ +} hyperbus_reg_t; + +#define HYPERBUS_BASE0 (UDMA_BASE + 3 * 128U) +#define HYPERBUS0 ((hyperbus_reg_t *)HYPERBUS_BASE0) + +/* MEM_CFG0 - HYPERBUS Memory control Configuration register0 */ + +#define HYPERBUS_MEM_CFG0_MBR0_MASK (0xFFU) +#define HYPERBUS_MEM_CFG0_MBR0_SHIFT (0U) +#define HYPERBUS_MEM_CFG0_MBR0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG0_MBR0_SHIFT) & HYPERBUS_MEM_CFG0_MBR0_MASK) +#define HYPERBUS_MEM_CFG0_LATENCY0_MASK (0xF00U) +#define HYPERBUS_MEM_CFG0_LATENCY0_SHIFT (8U) +#define HYPERBUS_MEM_CFG0_LATENCY0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG0_LATENCY0_SHIFT) & HYPERBUS_MEM_CFG0_LATENCY0_MASK) +#define HYPERBUS_MEM_CFG0_WRAP_SIZE0_MASK (0x3000U) +#define HYPERBUS_MEM_CFG0_WRAP_SIZE0_SHIFT (12U) +#define HYPERBUS_MEM_CFG0_WRAP_SIZE0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG0_WRAP_SIZE0_SHIFT) & HYPERBUS_MEM_CFG0_WRAP_SIZE0_MASK) + +/* MEM_CFG1 - HYPERBUS Memory control Configuration register1 */ + +#define HYPERBUS_MEM_CFG1_RD_CSHI0_MASK (0xFU) +#define HYPERBUS_MEM_CFG1_RD_CSHI0_SHIFT (0U) +#define HYPERBUS_MEM_CFG1_RD_CSHI0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG1_RD_CSHI0_SHIFT) & HYPERBUS_MEM_CFG1_RD_CSHI0_MASK) +#define HYPERBUS_MEM_CFG1_RD_CSS0_MASK (0xF0U) +#define HYPERBUS_MEM_CFG1_RD_CSS0_SHIFT (4U) +#define HYPERBUS_MEM_CFG1_RD_CSS0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG1_RD_CSS0_SHIFT) & HYPERBUS_MEM_CFG1_RD_CSS0_MASK) +#define HYPERBUS_MEM_CFG1_RD_CSH0_MASK (0xF00U) +#define HYPERBUS_MEM_CFG1_RD_CSH0_SHIFT (8U) +#define HYPERBUS_MEM_CFG1_RD_CSH0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG1_RD_CSH0_SHIFT) & HYPERBUS_MEM_CFG1_RD_CSH0_MASK) +#define HYPERBUS_MEM_CFG1_WR_CSHI0_MASK (0xF000U) +#define HYPERBUS_MEM_CFG1_WR_CSHI0_SHIFT (12U) +#define HYPERBUS_MEM_CFG1_WR_CSHI0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG1_WR_CSHI0_SHIFT) & HYPERBUS_MEM_CFG1_WR_CSHI0_MASK) +#define HYPERBUS_MEM_CFG1_WR_CSS0_MASK (0xF0000U) +#define HYPERBUS_MEM_CFG1_WR_CSS0_SHIFT (16U) +#define HYPERBUS_MEM_CFG1_WR_CSS0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG1_WR_CSS0_SHIFT) & HYPERBUS_MEM_CFG1_WR_CSS0_MASK) +#define HYPERBUS_MEM_CFG1_WR_CSH0_MASK (0xF00000U) +#define HYPERBUS_MEM_CFG1_WR_CSH0_SHIFT (20U) +#define HYPERBUS_MEM_CFG1_WR_CSH0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG1_WR_CSH0_SHIFT) & HYPERBUS_MEM_CFG1_WR_CSH0_MASK) + +/* MEM_CFG2 - HYPERBUS Memory control Configuration register2 */ + +#define HYPERBUS_MEM_CFG2_RD_MAX_LENGTH0_MASK (0x1FFU) +#define HYPERBUS_MEM_CFG2_RD_MAX_LENGTH0_SHIFT (0U) +#define HYPERBUS_MEM_CFG2_RD_MAX_LENGTH0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG2_RD_MAX_LENGTH0_SHIFT) & HYPERBUS_MEM_CFG2_RD_MAX_LENGTH0_MASK) +#define HYPERBUS_MEM_CFG2_WR_MAX_LENGTH0_MASK (0x1FF0000U) +#define HYPERBUS_MEM_CFG2_WR_MAX_LENGTH0_SHIFT (16U) +#define HYPERBUS_MEM_CFG2_WR_MAX_LENGTH0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG2_WR_MAX_LENGTH0_SHIFT) & HYPERBUS_MEM_CFG2_WR_MAX_LENGTH0_MASK) + +/* MEM_CFG3 - HYPERBUS Memory control Configuration register3 */ + +#define HYPERBUS_MEM_CFG3_ACS0_MASK (0x1U) +#define HYPERBUS_MEM_CFG3_ACS0_SHIFT (0U) +#define HYPERBUS_MEM_CFG3_ACS0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG3_ACS0_SHIFT) & HYPERBUS_MEM_CFG3_ACS0_MASK) +#define HYPERBUS_MEM_CFG3_TCO0_MASK (0x2U) +#define HYPERBUS_MEM_CFG3_TCO0_SHIFT (1U) +#define HYPERBUS_MEM_CFG3_TCO0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG3_TCO0_SHIFT) & HYPERBUS_MEM_CFG3_TCO0_MASK) +#define HYPERBUS_MEM_CFG3_DT0_MASK (0x4U) +#define HYPERBUS_MEM_CFG3_DT0_SHIFT (2U) +#define HYPERBUS_MEM_CFG3_DT0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG3_DT0_SHIFT) & HYPERBUS_MEM_CFG3_DT0_MASK) +#define HYPERBUS_MEM_CFG3_CRT0_MASK (0x8U) +#define HYPERBUS_MEM_CFG3_CRT0_SHIFT (3U) +#define HYPERBUS_MEM_CFG3_CRT0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG3_CRT0_SHIFT) & HYPERBUS_MEM_CFG3_CRT0_MASK) +#define HYPERBUS_MEM_CFG3_RD_MAX_LEN_EN0_MASK (0x10U) +#define HYPERBUS_MEM_CFG3_RD_MAX_LEN_EN0_SHIFT (4U) +#define HYPERBUS_MEM_CFG3_RD_MAX_LEN_EN0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG3_RD_MAX_LEN_EN0_SHIFT) & HYPERBUS_MEM_CFG3_RD_MAX_LEN_EN0_MASK) +#define HYPERBUS_MEM_CFG3_WR_MAX_LEN_EN0_MASK (0x20U) +#define HYPERBUS_MEM_CFG3_WR_MAX_LEN_EN0_SHIFT (5U) +#define HYPERBUS_MEM_CFG3_WR_MAX_LEN_EN0(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG3_WR_MAX_LEN_EN0_SHIFT) & HYPERBUS_MEM_CFG3_WR_MAX_LEN_EN0_MASK) +#define HYPERBUS_MEM_CFG3_RDS_DELAY_ADJ_MASK (0x300U) +#define HYPERBUS_MEM_CFG3_RDS_DELAY_ADJ_SHIFT (8U) +#define HYPERBUS_MEM_CFG3_RDS_DELAY_ADJ(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG3_RDS_DELAY_ADJ_SHIFT) & HYPERBUS_MEM_CFG3_RDS_DELAY_ADJ_MASK) + +/* MEM_CFG4 - HYPERBUS Memory control Configuration register4 */ + +#define HYPERBUS_MEM_CFG4_MBR1_MASK (0xFFU) +#define HYPERBUS_MEM_CFG4_MBR1_SHIFT (0U) +#define HYPERBUS_MEM_CFG4_MBR1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG4_MBR1_SHIFT) & HYPERBUS_MEM_CFG4_MBR1_MASK) +#define HYPERBUS_MEM_CFG4_LATENCY1_MASK (0xF00U) +#define HYPERBUS_MEM_CFG4_LATENCY1_SHIFT (8U) +#define HYPERBUS_MEM_CFG4_LATENCY1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG4_LATENCY1_SHIFT) & HYPERBUS_MEM_CFG4_LATENCY1_MASK) +#define HYPERBUS_MEM_CFG4_WRAP_SIZE1_MASK (0x3000U) +#define HYPERBUS_MEM_CFG4_WRAP_SIZE1_SHIFT (12U) +#define HYPERBUS_MEM_CFG4_WRAP_SIZE1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG4_WRAP_SIZE1_SHIFT) & HYPERBUS_MEM_CFG4_WRAP_SIZE1_MASK) + +/* MEM_CFG5 - HYPERBUS Memory control Configuration register5 */ + +#define HYPERBUS_MEM_CFG5_RD_CSHI1_MASK (0xFU) +#define HYPERBUS_MEM_CFG5_RD_CSHI1_SHIFT (0U) +#define HYPERBUS_MEM_CFG5_RD_CSHI1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG5_RD_CSHI1_SHIFT) & HYPERBUS_MEM_CFG5_RD_CSHI1_MASK) +#define HYPERBUS_MEM_CFG5_RD_CSS1_MASK (0xF0U) +#define HYPERBUS_MEM_CFG5_RD_CSS1_SHIFT (4U) +#define HYPERBUS_MEM_CFG5_RD_CSS1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG5_RD_CSS1_SHIFT) & HYPERBUS_MEM_CFG5_RD_CSS1_MASK) +#define HYPERBUS_MEM_CFG5_RD_CSH1_MASK (0xF00U) +#define HYPERBUS_MEM_CFG5_RD_CSH1_SHIFT (8U) +#define HYPERBUS_MEM_CFG5_RD_CSH1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG5_RD_CSH1_SHIFT) & HYPERBUS_MEM_CFG5_RD_CSH1_MASK) +#define HYPERBUS_MEM_CFG5_WR_CSHI1_MASK (0xF000U) +#define HYPERBUS_MEM_CFG5_WR_CSHI1_SHIFT (12U) +#define HYPERBUS_MEM_CFG5_WR_CSHI1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG5_WR_CSHI1_SHIFT) & HYPERBUS_MEM_CFG5_WR_CSHI1_MASK) +#define HYPERBUS_MEM_CFG5_WR_CSS1_MASK (0xF0000U) +#define HYPERBUS_MEM_CFG5_WR_CSS1_SHIFT (16U) +#define HYPERBUS_MEM_CFG5_WR_CSS1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG5_WR_CSS1_SHIFT) & HYPERBUS_MEM_CFG5_WR_CSS1_MASK) +#define HYPERBUS_MEM_CFG5_WR_CSH1_MASK (0xF00000U) +#define HYPERBUS_MEM_CFG5_WR_CSH1_SHIFT (20U) +#define HYPERBUS_MEM_CFG5_WR_CSH1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG5_WR_CSH1_SHIFT) & HYPERBUS_MEM_CFG5_WR_CSH1_MASK) + +/* MEM_CFG6 - HYPERBUS Memory control Configuration register6 */ + +#define HYPERBUS_MEM_CFG6_RD_MAX_LENGTH1_MASK (0x1FFU) +#define HYPERBUS_MEM_CFG6_RD_MAX_LENGTH1_SHIFT (0U) +#define HYPERBUS_MEM_CFG6_RD_MAX_LENGTH1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG6_RD_MAX_LENGTH1_SHIFT) & HYPERBUS_MEM_CFG6_RD_MAX_LENGTH1_MASK) +#define HYPERBUS_MEM_CFG6_WR_MAX_LENGTH1_MASK (0x1FF0000U) +#define HYPERBUS_MEM_CFG6_WR_MAX_LENGTH1_SHIFT (16U) +#define HYPERBUS_MEM_CFG6_WR_MAX_LENGTH1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG6_WR_MAX_LENGTH1_SHIFT) & HYPERBUS_MEM_CFG6_WR_MAX_LENGTH1_MASK) + +/* MEM_CFG7 - HYPERBUS Memory control Configuration register7 */ + +#define HYPERBUS_MEM_CFG7_ACS1_MASK (0x1U) +#define HYPERBUS_MEM_CFG7_ACS1_SHIFT (0U) +#define HYPERBUS_MEM_CFG7_ACS1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG7_ACS1_SHIFT) & HYPERBUS_MEM_CFG7_ACS1_MASK) +#define HYPERBUS_MEM_CFG7_TCO1_MASK (0x2U) +#define HYPERBUS_MEM_CFG7_TCO1_SHIFT (1U) +#define HYPERBUS_MEM_CFG7_TCO1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG7_TCO1_SHIFT) & HYPERBUS_MEM_CFG7_TCO1_MASK) +#define HYPERBUS_MEM_CFG7_DT1_MASK (0x4U) +#define HYPERBUS_MEM_CFG7_DT1_SHIFT (2U) +#define HYPERBUS_MEM_CFG7_DT1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG7_DT1_SHIFT) & HYPERBUS_MEM_CFG7_DT1_MASK) +#define HYPERBUS_MEM_CFG7_CRT1_MASK (0x8U) +#define HYPERBUS_MEM_CFG7_CRT1_SHIFT (3U) +#define HYPERBUS_MEM_CFG7_CRT1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG7_CRT1_SHIFT) & HYPERBUS_MEM_CFG7_CRT1_MASK) +#define HYPERBUS_MEM_CFG7_RD_MAX_LEN_EN1_MASK (0x10U) +#define HYPERBUS_MEM_CFG7_RD_MAX_LEN_EN1_SHIFT (4U) +#define HYPERBUS_MEM_CFG7_RD_MAX_LEN_EN1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG7_RD_MAX_LEN_EN1_SHIFT) & HYPERBUS_MEM_CFG7_RD_MAX_LEN_EN1_MASK) +#define HYPERBUS_MEM_CFG7_WR_MAX_LEN_EN1_MASK (0x20U) +#define HYPERBUS_MEM_CFG7_WR_MAX_LEN_EN1_SHIFT (5U) +#define HYPERBUS_MEM_CFG7_WR_MAX_LEN_EN1(x) (((uint32_t)(x) << HYPERBUS_MEM_CFG7_WR_MAX_LEN_EN1_SHIFT) & HYPERBUS_MEM_CFG7_WR_MAX_LEN_EN1_MASK) + +/* UART - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_UART; /* UDMA general register */ + volatile uint32_t STATUS; /* Status register */ + volatile uint32_t SETUP; /* Configuration register */ +} uart_reg_t; + +#define UART_BASE (UDMA_BASE + 4 * 128U) +#define UART ((uart_reg_t *)UART_BASE) + +/* STATUS - UART Status register */ + +#define UART_STATUS_TX_BUSY_MASK (0x1U) +#define UART_STATUS_TX_BUSY_SHIFT (0U) +#define UART_STATUS_TX_BUSY(x) (((uint32_t)(x) << UART_STATUS_TX_BUSY_SHIFT) & UART_STATUS_TX_BUSY_MASK) +#define UART_STATUS_RX_BUSY_MASK (0x2U) +#define UART_STATUS_RX_BUSY_SHIFT (1U) +#define UART_STATUS_RX_BUSY(x) (((uint32_t)(x) << UART_STATUS_RX_BUSY_SHIFT) & UART_STATUS_RX_BUSY_MASK) +#define UART_STATUS_RX_PE_MASK (0x4U) +#define UART_STATUS_RX_PE_SHIFT (2U) +#define UART_STATUS_RX_PE(x) (((uint32_t)(x) << UART_STATUS_RX_PE_SHIFT) & UART_STATUS_RX_PE_MASK) + +/* SETUP - UART SETUP register */ + +#define UART_SETUP_PARITY_ENA_MASK (0x1U) +#define UART_SETUP_PARITY_ENA_SHIFT (0U) +#define UART_SETUP_PARITY_ENA(x) (((uint32_t)(x) << UART_SETUP_PARITY_ENA_SHIFT) & UART_SETUP_PARITY_ENA_MASK) + +#define UART_SETUP_BIT_LENGTH_MASK (0x6U) +#define UART_SETUP_BIT_LENGTH_SHIFT (1U) +#define UART_SETUP_BIT_LENGTH(x) (((uint32_t)(x) << UART_SETUP_BIT_LENGTH_SHIFT) & UART_SETUP_BIT_LENGTH_MASK) + +#define UART_SETUP_STOP_BITS_MASK (0x8U) +#define UART_SETUP_STOP_BITS_SHIFT (3U) +#define UART_SETUP_STOP_BITS(x) (((uint32_t)(x) << UART_SETUP_STOP_BITS_SHIFT) & UART_SETUP_STOP_BITS_MASK) + +#define UART_SETUP_TX_ENA_MASK (0x100U) +#define UART_SETUP_TX_ENA_SHIFT (8U) +#define UART_SETUP_TX_ENA(x) (((uint32_t)(x) << UART_SETUP_TX_ENA_SHIFT) & UART_SETUP_TX_ENA_MASK) + +#define UART_SETUP_RX_ENA_MASK (0x200U) +#define UART_SETUP_RX_ENA_SHIFT (9U) +#define UART_SETUP_RX_ENA(x) (((uint32_t)(x) << UART_SETUP_RX_ENA_SHIFT) & UART_SETUP_RX_ENA_MASK) + +#define UART_SETUP_CLKDIV_MASK (0xFFFF0000U) +#define UART_SETUP_CLKDIV_SHIFT (16U) +#define UART_SETUP_CLKDIV(x) (((uint32_t)(x) << UART_SETUP_CLKDIV_SHIFT) & UART_SETUP_CLKDIV_MASK) + +/* I2C - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_I2C; /* UDMA general register */ + volatile uint32_t STATUS; /* Status register */ + volatile uint32_t SETUP; /* Configuration register */ +} i2c_reg_t; + +#define I2C0_BASE (UDMA_BASE + 5 * 128U) +#define I2C0 ((i2c_reg_t *)I2C0_BASE) +#define I2C1_BASE (UDMA_BASE + 6 * 128U) +#define I2C1 ((i2c_reg_t *)I2C1_BASE) + +/* STATUS - I2C Status register */ + +#define I2C_STATUS_BUSY_MASK (0x1U) +#define I2C_STATUS_BUSY_SHIFT (0U) +#define I2C_STATUS_BUSY(x) (((uint32_t)(x) << I2C_STATUS_BUSY_SHIFT) & I2C_STATUS_BUSY_MASK) +#define I2C_STATUS_ARB_LOST_MASK (0x2U) +#define I2C_STATUS_ARB_LOST_SHIFT (1U) +#define I2C_STATUS_ARB_LOST(x) (((uint32_t)(x) << I2C_STATUS_ARB_LOST_SHIFT) & I2C_STATUS_ARB_LOST_MASK) + +/* SETUP - I2C SETUP register */ + +#define I2C_SETUP_DO_RST_MASK (0x1U) +#define I2C_SETUP_DO_RST_SHIFT (0U) +#define I2C_SETUP_DO_RST(x) (((uint32_t)(x) << I2C_SETUP_DO_RST_SHIFT) & I2C_SETUP_DO_RST_MASK) + +/* uDMA - I2C uDMA control CMD */ + +#define I2C_CMD_MASK (0xF0U) +#define I2C_CMD_SHIFT (4U) + +#define I2C_CMD_START ((((uint32_t)(0x0)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0x00 +#define I2C_CMD_WAIT_EV ((((uint32_t)(0x1)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0x10 +#define I2C_CMD_STOP ((((uint32_t)(0x2)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0x20 +#define I2C_CMD_RD_ACK ((((uint32_t)(0x4)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0x40 +#define I2C_CMD_RD_NACK ((((uint32_t)(0x6)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0x60 +#define I2C_CMD_WR ((((uint32_t)(0x8)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0x80 +#define I2C_CMD_WAIT ((((uint32_t)(0xA)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0xA0 +#define I2C_CMD_RPT ((((uint32_t)(0xC)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0xC0 +#define I2C_CMD_CFG ((((uint32_t)(0xE)) << I2C_CMD_SHIFT) & I2C_CMD_MASK) // 0xE0 + +/* TCDM - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_TCDM; /* UDMA general register */ + volatile uint32_t DST_ADDR; /* destination address register */ + volatile uint32_t SRC_ADDR; /* source address register */ +} tcdm_reg_t; + +#define TCDM_BASE (UDMA_BASE + 7 * 128U) +#define TCDM ((tcdm_reg_t *)TCDM_BASE) + +/* DST_ADDR - TCDM destination address register */ + +#define TCDM_DST_ADDR_MASK (0x1FFFFU) +#define TCDM_DST_ADDR_SHIFT (0U) +#define TCDM_DST_ADDR(x) (((uint32_t)(x) << TCDM_DST_ADDR_SHIFT) & TCDM_DST_ADDR_MASK) + +/* SRC_ADDR - TCDM source address register */ + +#define TCDM_SRC_ADDR_MASK (0x1FFFFU) +#define TCDM_SRC_ADDR_SHIFT (0U) +#define TCDM_SRC_ADDR(x) (((uint32_t)(x) << TCDM_SRC_ADDR_SHIFT) & TCDM_SRC_ADDR_MASK) + +/* I2S - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_I2S; /* UDMA general register */ + volatile uint32_t EXT; /* external clock configuration register */ + volatile uint32_t CFG_CLKGEN0; /* clock/WS generator 0 configuration register */ + volatile uint32_t CFG_CLKGEN1; /* clock/WS generator 1 configuration register */ + volatile uint32_t CHMODE; /* channels mode configuration register */ + volatile uint32_t FILT_CH0; /* channels 0 filtering configuration register */ + volatile uint32_t FILT_CH1; /* channels 0 filtering configuration register */ +} i2s_reg_t; + +#define I2S_BASE (UDMA_BASE + 8 * 128U) +#define I2S ((i2s_reg_t *)I2S_BASE) + +/* EXT - I2S external clock configuration Register */ + +#define I2S_EXT_BITS_WORD_MASK (0x1FU) +#define I2S_EXT_BITS_WORD_SHIFT (0U) +#define I2S_EXT_BITS_WORD(x) (((uint32_t)(x) << I2S_EXT_BITS_WORD_SHIFT) & I2S_EXT_BITS_WORD_MASK) + +/* CFG_CLKGEN0 - I2S clock/WS generator 0 configuration Register */ + +#define I2S_CFG_CLKGEN0_BITS_WORD_MASK (0x1FU) +#define I2S_CFG_CLKGEN0_BITS_WORD_SHIFT (0U) +#define I2S_CFG_CLKGEN0_BITS_WORD(x) (((uint32_t)(x) << I2S_CFG_CLKGEN0_BITS_WORD_SHIFT) & I2S_CFG_CLKGEN0_BITS_WORD_MASK) +#define I2S_CFG_CLKGEN0_CLK_EN_MASK (0x100U) +#define I2S_CFG_CLKGEN0_CLK_EN_SHIFT (8U) +#define I2S_CFG_CLKGEN0_CLK_EN(x) (((uint32_t)(x) << I2S_CFG_CLKGEN0_CLK_EN_SHIFT) & I2S_CFG_CLKGEN0_CLK_EN_MASK) +#define I2S_CFG_CLKGEN0_CLK_DIV_MASK (0xFFFF0000U) +#define I2S_CFG_CLKGEN0_CLK_DIV_SHIFT (16U) +#define I2S_CFG_CLKGEN0_CLK_DIV(x) (((uint32_t)(x) << I2S_CFG_CLKGEN0_CLK_DIV_SHIFT) & I2S_CFG_CLKGEN0_CLK_DIV_MASK) + +/* CFG_CLKGEN1 - I2S clock/WS generator 1 configuration Register */ + +#define I2S_CFG_CLKGEN1_BITS_WORD_MASK (0x1FU) +#define I2S_CFG_CLKGEN1_BITS_WORD_SHIFT (0U) +#define I2S_CFG_CLKGEN1_BITS_WORD(x) (((uint32_t)(x) << I2S_CFG_CLKGEN1_BITS_WORD_SHIFT) & I2S_CFG_CLKGEN1_BITS_WORD_MASK) +#define I2S_CFG_CLKGEN1_CLK_EN_MASK (0x100U) +#define I2S_CFG_CLKGEN1_CLK_EN_SHIFT (8U) +#define I2S_CFG_CLKGEN1_CLK_EN(x) (((uint32_t)(x) << I2S_CFG_CLKGEN1_CLK_EN_SHIFT) & I2S_CFG_CLKGEN1_CLK_EN_MASK) +#define I2S_CFG_CLKGEN1_CLK_DIV_MASK (0xFFFF0000U) +#define I2S_CFG_CLKGEN1_CLK_DIV_SHIFT (16U) +#define I2S_CFG_CLKGEN1_CLK_DIV(x) (((uint32_t)(x) << I2S_CFG_CLKGEN1_CLK_DIV_SHIFT) & I2S_CFG_CLKGEN1_CLK_DIV_MASK) + +/* CHMODE - I2S channels mode configuration Register */ + +#define I2S_CHMODE_CH0_SNAP_CAM_MASK (0x1U) +#define I2S_CHMODE_CH0_SNAP_CAM_SHIFT (0U) +#define I2S_CHMODE_CH0_SNAP_CAM(x) (((uint32_t)(x) << I2S_CHMODE_CH0_SNAP_CAM_SHIFT) & I2S_CHMODE_CH0_SNAP_CAM_MASK) +#define I2S_CHMODE_CH0_LSB_FIRST_MASK (0x10U) +#define I2S_CHMODE_CH0_LSB_FIRST_SHIFT (4U) +#define I2S_CHMODE_CH0_LSB_FIRST(x) (((uint32_t)(x) << I2S_CHMODE_CH0_LSB_FIRST_SHIFT) & I2S_CHMODE_CH0_LSB_FIRST_MASK) +#define I2S_CHMODE_CH0_PDM_USEFILTER_MASK (0x100U) +#define I2S_CHMODE_CH0_PDM_USEFILTER_SHIFT (8U) +#define I2S_CHMODE_CH0_PDM_USEFILTER(x) (((uint32_t)(x) << I2S_CHMODE_CH0_PDM_USEFILTER_SHIFT) & I2S_CHMODE_CH0_PDM_USEFILTER_MASK) +#define I2S_CHMODE_CH0_PDM_EN_MASK (0x1000U) +#define I2S_CHMODE_CH0_PDM_EN_SHIFT (12U) +#define I2S_CHMODE_CH0_PDM_EN(x) (((uint32_t)(x) << I2S_CHMODE_CH0_PDM_EN_SHIFT) & I2S_CHMODE_CH0_PDM_EN_MASK) +#define I2S_CHMODE_CH0_USEDDR_MASK (0x10000U) +#define I2S_CHMODE_CH0_USEDDR_SHIFT (16U) +#define I2S_CHMODE_CH0_USEDDR(x) (((uint32_t)(x) << I2S_CHMODE_CH0_USEDDR_SHIFT) & I2S_CHMODE_CH0_USEDDR_MASK) +#define I2S_CHMODE_CH0_MODE_MASK (0x3000000U) +#define I2S_CHMODE_CH0_MODE_SHIFT (24U) +#define I2S_CHMODE_CH0_MODE(x) (((uint32_t)(x) << I2S_CHMODE_CH0_MODE_SHIFT) & I2S_CHMODE_CH0_MODE_MASK) + +#define I2S_CHMODE_CH1_SNAP_CAM_MASK (0x2U) +#define I2S_CHMODE_CH1_SNAP_CAM_SHIFT (1U) +#define I2S_CHMODE_CH1_SNAP_CAM(x) (((uint32_t)(x) << I2S_CHMODE_CH1_SNAP_CAM_SHIFT) & I2S_CHMODE_CH1_SNAP_CAM_MASK) +#define I2S_CHMODE_CH1_LSB_FIRST_MASK (0x20U) +#define I2S_CHMODE_CH1_LSB_FIRST_SHIFT (5U) +#define I2S_CHMODE_CH1_LSB_FIRST(x) (((uint32_t)(x) << I2S_CHMODE_CH1_LSB_FIRST_SHIFT) & I2S_CHMODE_CH1_LSB_FIRST_MASK) +#define I2S_CHMODE_CH1_PDM_USEFILTER_MASK (0x200U) +#define I2S_CHMODE_CH1_PDM_USEFILTER_SHIFT (9U) +#define I2S_CHMODE_CH1_PDM_USEFILTER(x) (((uint32_t)(x) << I2S_CHMODE_CH1_PDM_USEFILTER_SHIFT) & I2S_CHMODE_CH1_PDM_USEFILTER_MASK) +#define I2S_CHMODE_CH1_PDM_EN_MASK (0x2000U) +#define I2S_CHMODE_CH1_PDM_EN_SHIFT (13U) +#define I2S_CHMODE_CH1_PDM_EN(x) (((uint32_t)(x) << I2S_CHMODE_CH1_PDM_EN_SHIFT) & I2S_CHMODE_CH1_PDM_EN_MASK) +#define I2S_CHMODE_CH1_USEDDR_MASK (0x20000U) +#define I2S_CHMODE_CH1_USEDDR_SHIFT (17U) +#define I2S_CHMODE_CH1_USEDDR(x) (((uint32_t)(x) << I2S_CHMODE_CH1_USEDDR_SHIFT) & I2S_CHMODE_CH1_USEDDR_MASK) +#define I2S_CHMODE_CH1_MODE_MASK (0xC000000U) +#define I2S_CHMODE_CH1_MODE_SHIFT (26U) +#define I2S_CHMODE_CH1_MODE(x) (((uint32_t)(x) << I2S_CHMODE_CH1_MODE_SHIFT) & I2S_CHMODE_CH1_MODE_MASK) + +/* FILT_CH0 - I2S channels 0 filtering configuration Register */ + +#define I2S_FILT_CH0_DECIMATION_MASK (0x3FFU) +#define I2S_FILT_CH0_DECIMATION_SHIFT (0U) +#define I2S_FILT_CH0_DECIMATION(x) (((uint32_t)(x) << I2S_FILT_CH0_DECIMATION_SHIFT) & I2S_FILT_CH0_DECIMATION_MASK) +#define I2S_FILT_CH0_SHIFT_MASK (0x70000U) +#define I2S_FILT_CH0_SHIFT_SHIFT (16U) +#define I2S_FILT_CH0_SHIFT(x) (((uint32_t)(x) << I2S_FILT_CH0_SHIFT_SHIFT) & I2S_FILT_CH0_SHIFT_MASK) + +/* FILT_CH1 - I2S channels 0 filtering configuration Register */ + +#define I2S_FILT_CH1_DECIMATION_MASK (0x3FFU) +#define I2S_FILT_CH1_DECIMATION_SHIFT (0U) +#define I2S_FILT_CH1_DECIMATION(x) (((uint32_t)(x) << I2S_FILT_CH1_DECIMATION_SHIFT) & I2S_FILT_CH1_DECIMATION_MASK) +#define I2S_FILT_CH1_SHIFT_MASK (0x70000U) +#define I2S_FILT_CH1_SHIFT_SHIFT (16U) +#define I2S_FILT_CH1_SHIFT(x) (((uint32_t)(x) << I2S_FILT_CH1_SHIFT_SHIFT) & I2S_FILT_CH1_SHIFT_MASK) + +/* CPI - Register Layout Typedef */ + +typedef struct +{ + udma_reg_t UDMA_CPI; /* UDMA general register */ + volatile uint32_t CFG_GLOB; /* global configuration register */ + volatile uint32_t CFG_LL; /* lower left comer configuration register */ + volatile uint32_t CFG_UR; /* upper right comer configuration register */ + volatile uint32_t CFG_SIZE; /* horizontal resolution configuration register */ + volatile uint32_t CFG_FILTER; /* RGB coefficients configuration register */ +} cpi_reg_t; + +#define CPI_BASE (UDMA_BASE + 9 * 128U) +#define CPI ((cpi_reg_t *)CPI_BASE) + +/* CFG_GLOB - CPI global configuration register */ + +#define CPI_CFG_GLOB_FRAMEDROP_EN_MASK (0x1U) +#define CPI_CFG_GLOB_FRAMEDROP_EN_SHIFT (0U) +#define CPI_CFG_GLOB_FRAMEDROP_EN(x) (((uint32_t)(x) << CPI_CFG_GLOB_FRAMEDROP_EN_SHIFT) & CPI_CFG_GLOB_FRAMEDROP_EN_MASK) +#define CPI_CFG_GLOB_FRAMEDROP_VAL_MASK (0x7EU) +#define CPI_CFG_GLOB_FRAMEDROP_VAL_SHIFT (1U) +#define CPI_CFG_GLOB_FRAMEDROP_VAL(x) (((uint32_t)(x) << CPI_CFG_GLOB_FRAMEDROP_VAL_SHIFT) & CPI_CFG_GLOB_FRAMEDROP_VAL_MASK) +#define CPI_CFG_GLOB_FRAMESLICE_EN_MASK (0x80U) +#define CPI_CFG_GLOB_FRAMESLICE_EN_SHIFT (7U) +#define CPI_CFG_GLOB_FRAMESLICE_EN(x) (((uint32_t)(x) << CPI_CFG_GLOB_FRAMESLICE_EN_SHIFT) & CPI_CFG_GLOB_FRAMESLICE_EN_MASK) +#define CPI_CFG_GLOB_FORMAT_MASK (0x700U) +#define CPI_CFG_GLOB_FORMAT_SHIFT (8U) +#define CPI_CFG_GLOB_FORMAT(x) (((uint32_t)(x) << CPI_CFG_GLOB_FORMAT_SHIFT) & CPI_CFG_GLOB_FORMAT_MASK) +#define CPI_CFG_GLOB_SHIFT_MASK (0x7800U) +#define CPI_CFG_GLOB_SHIFT_SHIFT (11U) +#define CPI_CFG_GLOB_SHIFT(x) (((uint32_t)(x) << CPI_CFG_GLOB_SHIFT_SHIFT) & CPI_CFG_GLOB_SHIFT_MASK) +#define CPI_CFG_GLOB_EN_MASK (0x80000000U) +#define CPI_CFG_GLOB_EN_SHIFT (31U) +#define CPI_CFG_GLOB_EN(x) (((uint32_t)(x) << CPI_CFG_GLOB_EN_SHIFT) & CPI_CFG_GLOB_EN_MASK) + +/* CFG_LL - CPI lower left comer configuration register */ + +#define CPI_CFG_LL_FRAMESLICE_LLX_MASK (0xFFFFU) +#define CPI_CFG_LL_FRAMESLICE_LLX_SHIFT (0U) +#define CPI_CFG_LL_FRAMESLICE_LLX(x) (((uint32_t)(x) << CPI_CFG_LL_FRAMESLICE_LLX_SHIFT) & CPI_CFG_LL_FRAMESLICE_LLX_MASK) +#define CPI_CFG_LL_FRAMESLICE_LLY_MASK (0xFFFF0000U) +#define CPI_CFG_LL_FRAMESLICE_LLY_SHIFT (16U) +#define CPI_CFG_LL_FRAMESLICE_LLY(x) (((uint32_t)(x) << CPI_CFG_LL_FRAMESLICE_LLY_SHIFT) & CPI_CFG_LL_FRAMESLICE_LLY_MASK) + +/* CFG_UR - CPI upper right comer configuration register */ + +#define CPI_CFG_UR_FRAMESLICE_URX_MASK (0xFFFFU) +#define CPI_CFG_UR_FRAMESLICE_URX_SHIFT (0U) +#define CPI_CFG_UR_FRAMESLICE_URX(x) (((uint32_t)(x) << CPI_CFG_UR_FRAMESLICE_URX_SHIFT) & CPI_CFG_UR_FRAMESLICE_URX_MASK) +#define CPI_CFG_UR_FRAMESLICE_URY_MASK (0xFFFF0000U) +#define CPI_CFG_UR_FRAMESLICE_URY_SHIFT (16U) +#define CPI_CFG_UR_FRAMESLICE_URY(x) (((uint32_t)(x) << CPI_CFG_UR_FRAMESLICE_URY_SHIFT) & CPI_CFG_UR_FRAMESLICE_URY_MASK) + +/* CFG_SIZE - CPI horizontal resolution configuration register */ + +#define CPI_CFG_SIZE_MASK (0xFFFF0000U) +#define CPI_CFG_SIZE_SHIFT (16U) +#define CPI_CFG_SIZE(x) (((uint32_t)(x) << CPI_CFG_SIZE_SHIFT) & CPI_CFG_SIZE_MASK) + +/* CFG_FILTER - CPI RGB coefficients configuration register */ + +#define CPI_CFG_FILTER_B_COEFF_MASK (0xFFU) +#define CPI_CFG_FILTER_B_COEFF_SHIFT (0U) +#define CPI_CFG_FILTER_B_COEFF(x) (((uint32_t)(x) << CPI_CFG_FILTER_B_COEFF_SHIFT) & CPI_CFG_FILTER_B_COEFF_MASK) +#define CPI_CFG_FILTER_G_COEFF_MASK (0xFF00U) +#define CPI_CFG_FILTER_G_COEFF_SHIFT (8U) +#define CPI_CFG_FILTER_G_COEFF(x) (((uint32_t)(x) << CPI_CFG_FILTER_G_COEFF_SHIFT) & CPI_CFG_FILTER_G_COEFF_MASK) +#define CPI_CFG_FILTER_R_COEFF_MASK (0xFF0000U) +#define CPI_CFG_FILTER_R_COEFF_SHIFT (16U) +#define CPI_CFG_FILTER_R_COEFF(x) (((uint32_t)(x) << CPI_CFG_FILTER_R_COEFF_SHIFT) & CPI_CFG_FILTER_R_COEFF_MASK) + +/* SOC_CTRL - Registers Layout Typedef */ + +typedef struct +{ + volatile uint32_t INFO; /* SOC_CTRL INFO register */ + volatile uint32_t _reserved0[2]; /* reserved */ + volatile uint32_t CLUSTER_ISO; /* SOC_CTRL Cluster Isolate register */ + volatile uint32_t _reserved1[23]; /* reserved */ + volatile uint32_t CLUSTER_BUSY; /* SOC_CTRL Busy register */ + volatile uint32_t CLUSTER_BYPASS; /* SOC_CTRL Cluster PMU bypass register */ + volatile uint32_t JTAG_REG; /* SOC_CTRL Jtag register */ + volatile uint32_t L2_SLEEP; /* SOC_CTRL L2 memory sleep register */ + volatile uint32_t SLEEP_CTRL; /* SOC_CTRL Slepp control register */ + volatile uint32_t CLKDIV0; /* SOC_CTRL Slepp control register */ + volatile uint32_t CLKDIV1; /* SOC_CTRL Slepp control register */ + volatile uint32_t CLKDIV2; /* SOC_CTRL Slepp control register */ + volatile uint32_t CLKDIV3; /* SOC_CTRL Slepp control register */ + volatile uint32_t CLKDIV4; /* SOC_CTRL Slepp control register */ + volatile uint32_t _reserved2[3]; /* reserved */ + volatile uint32_t CORE_STATUS; /* SOC_CTRL Slepp control register */ + volatile uint32_t CORE_STATUS_EOC; /* SOC_CTRL Slepp control register */ +} soc_strl_reg_t; + +#define SOC_CTRL_BASE (0x1A104000) +#define SOC_CTRL ((soc_strl_reg_t *)SOC_CTRL_BASE) + +/* CLUSTER_BYPASS - SOC_CTRL information register */ + +#define SOC_CTRL_CLUSTER_BYPASS_BYP_POW_MASK (0x1U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_POW_SHIFT (0U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_POW(x) (((uint32_t)(x) /* << SOC_CTRL_CLUSTER_BYPASS_BYP_POW_SHIFT*/) & SOC_CTRL_CLUSTER_BYPASS_BYP_POW_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_BYP_CFG_MASK (0x2U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_CFG_SHIFT (1U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_CFG(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_BYP_CFG_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_BYP_CFG_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_POW_MASK (0x8U) +#define SOC_CTRL_CLUSTER_BYPASS_POW_SHIFT (3U) +#define SOC_CTRL_CLUSTER_BYPASS_POW(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_POW_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_POW_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_CUURENT_SET_MASK (0x70U) +#define SOC_CTRL_CLUSTER_BYPASS_CUURENT_SET_SHIFT (4U) +#define SOC_CTRL_CLUSTER_BYPASS_CUURENT_SET(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_CUURENT_SET_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_CUURENT_SET_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_DELAY_MASK (0x180U) +#define SOC_CTRL_CLUSTER_BYPASS_DELAY_SHIFT (7U) +#define SOC_CTRL_CLUSTER_BYPASS_DELAY(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_DELAY_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_DELAY_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_BYP_CLK_MASK (0x200U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_CLK_SHIFT (9U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_CLK(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_BYP_CLK_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_BYP_CLK_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_CLK_GATE_MASK (0x400U) +#define SOC_CTRL_CLUSTER_BYPASS_CLK_GATE_SHIFT (10U) +#define SOC_CTRL_CLUSTER_BYPASS_CLK_GATE(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_CLK_GATE_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_CLK_GATE_MASK) +#define READ_SOC_CTRL_CLUSTER_BYPASS_CLK_GATE(x) (((uint32_t)(x) & SOC_CTRL_CLUSTER_BYPASS_CLK_GATE_MASK) >> SOC_CTRL_CLUSTER_BYPASS_CLK_GATE_SHIFT) + +#define SOC_CTRL_CLUSTER_BYPASS_FLL_PWD_MASK (0x800U) +#define SOC_CTRL_CLUSTER_BYPASS_FLL_PWD_SHIFT (11U) +#define SOC_CTRL_CLUSTER_BYPASS_FLL_PWD(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_FLL_PWD_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_FLL_PWD_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_FLL_RET_MASK (0x1000U) +#define SOC_CTRL_CLUSTER_BYPASS_FLL_RET_SHIFT (12U) +#define SOC_CTRL_CLUSTER_BYPASS_FLL_RET(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_FLL_RET_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_FLL_RET_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_RESET_MASK (0x2000U) +#define SOC_CTRL_CLUSTER_BYPASS_RESET_SHIFT (13U) +#define SOC_CTRL_CLUSTER_BYPASS_RESET(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_RESET_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_RESET_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_BYP_ISO_MASK (0x4000U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_ISO_SHIFT (14U) +#define SOC_CTRL_CLUSTER_BYPASS_BYP_ISO(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_BYP_ISO_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_BYP_ISO_MASK) + +#define SOC_CTRL_CLUSTER_BYPASS_PW_ISO_MASK (0x8000U) +#define SOC_CTRL_CLUSTER_BYPASS_PW_ISO_SHIFT (15U) +#define SOC_CTRL_CLUSTER_BYPASS_PW_ISO(x) (((uint32_t)(x) << SOC_CTRL_CLUSTER_BYPASS_PW_ISO_SHIFT) & SOC_CTRL_CLUSTER_BYPASS_PW_ISO_MASK) +#define READ_SOC_CTRL_CLUSTER_BYPASS_PW_ISO(x) (((uint32_t)(x) & SOC_CTRL_CLUSTER_BYPASS_PW_ISO_MASK) >> SOC_CTRL_CLUSTER_BYPASS_PW_ISO_SHIFT) + +/* STATUS - SOC_CTRL status register */ + +#define SOC_CTRL_CORE_STATUS_EOC_MASK (0x80000000U) +#define SOC_CTRL_CORE_STATUS_EOC_SHIFT (31U) +#define SOC_CTRL_CORE_STATUS_EOC(x) (((uint32_t)(x) << SOC_CTRL_CORE_STATUS_EOC_SHIFT) & SOC_CTRL_CORE_STATUS_EOC_MASK) + +/* PMU - General Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t RAR_DCDC; /* CTRL control register */ + volatile uint32_t SLEEP_CTRL; /* CTRL sleep control register */ + volatile uint32_t FORCE; /* CTRL register */ +} soc_ctrl_pmu_reg_t; + +#define PMU_CTRL_BASE (SOC_CTRL_BASE + 0x0100u) +#define PMU_CTRL ((soc_ctrl_pmu_reg_t *)PMU_CTRL_BASE) + +/* RAR_DCDC - PMU control register */ + +#define PMU_CTRL_RAR_DCDC_NV_MASK (0x1FU) +#define PMU_CTRL_RAR_DCDC_NV_SHIFT (0U) + +#define PMU_CTRL_RAR_DCDC_NV(x) (((uint32_t)(x) /* << PMU_CTRL_RAR_DCDC_NV_SHIFT */) & PMU_CTRL_RAR_DCDC_NV_MASK) + +#define READ_PMU_CTRL_RAR_DCDC_NV(x) (((uint32_t)(x) & PMU_CTRL_RAR_DCDC_NV_MASK) /* >> PMU_CTRL_RAR_DCDC_NV_SHIFT */) + +#define PMU_CTRL_RAR_DCDC_MV_MASK (0x1F00U) +#define PMU_CTRL_RAR_DCDC_MV_SHIFT (8U) +#define PMU_CTRL_RAR_DCDC_MV(x) (((uint32_t)(x) << PMU_CTRL_RAR_DCDC_MV_SHIFT) & PMU_CTRL_RAR_DCDC_MV_MASK) +#define READ_PMU_CTRL_RAR_DCDC_MV(x) (((uint32_t)(x) & PMU_CTRL_RAR_DCDC_MV_MASK) >> PMU_CTRL_RAR_DCDC_MV_SHIFT) +#define PMU_CTRL_RAR_DCDC_LV_MASK (0x1F0000U) +#define PMU_CTRL_RAR_DCDC_LV_SHIFT (16U) +#define PMU_CTRL_RAR_DCDC_LV(x) (((uint32_t)(x) << PMU_CTRL_RAR_DCDC_LV_SHIFT) & PMU_CTRL_RAR_DCDC_LV_MASK) +#define READ_PMU_CTRL_RAR_DCDC_LV(x) (((uint32_t)(x) & PMU_CTRL_RAR_DCDC_LV_MASK) >> PMU_CTRL_RAR_DCDC_LV_SHIFT) +#define PMU_CTRL_RAR_DCDC_RV_MASK (0x1F000000U) +#define PMU_CTRL_RAR_DCDC_RV_SHIFT (24U) +#define PMU_CTRL_RAR_DCDC_RV(x) (((uint32_t)(x) << PMU_CTRL_RAR_DCDC_RV_SHIFT) & PMU_CTRL_RAR_DCDC_RV_MASK) +#define READ_PMU_CTRL_RAR_DCDC_RV(x) (((uint32_t)(x) & PMU_CTRL_RAR_DCDC_RV_MASK) >> PMU_CTRL_RAR_DCDC_RV_SHIFT) + +/* SLEEP_CTRL - PMU control register */ + +#define PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET_MASK (0xFU) +#define PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET_SHIFT (0U) + +#define PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET(x) (((uint32_t)(x) /* << PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET_SHIFT */) & PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET_MASK) + +#define READ_PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET_MASK) /* >> PMU_CTRL_SLEEP_CTRL_CFG_MEM_RET_SHIFT */) + +#define PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET_MASK (0x10U) +#define PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET_SHIFT (4U) +#define PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET_SHIFT) & PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET_MASK) >> PMU_CTRL_SLEEP_CTRL_CFG_FLL_SOC_RET_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET_MASK (0x20U) +#define PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET_SHIFT (5U) +#define PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET_SHIFT) & PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET_MASK) >> PMU_CTRL_SLEEP_CTRL_CFG_FLL_CLUSTER_RET_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL_MASK (0x7C0U) +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL_SHIFT (6U) +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL_SHIFT) & PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL_MASK) >> PMU_CTRL_SLEEP_CTRL_EXT_WAKE_SEL_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE_MASK (0x1800U) +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE_SHIFT (11U) +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE_SHIFT) & PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE_MASK) >> PMU_CTRL_SLEEP_CTRL_EXT_WAKE_TYPE_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN_MASK (0x2000U) +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN_SHIFT (13U) +#define PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN_SHIFT) & PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN_MASK) >> PMU_CTRL_SLEEP_CTRL_EXT_WAKE_EN_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_WAKEUP_MASK (0xC000U) +#define PMU_CTRL_SLEEP_CTRL_WAKEUP_SHIFT (14U) +#define PMU_CTRL_SLEEP_CTRL_WAKEUP(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_WAKEUP_SHIFT) & PMU_CTRL_SLEEP_CTRL_WAKEUP_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_WAKEUP(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_WAKEUP_MASK) >> PMU_CTRL_SLEEP_CTRL_WAKEUP_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_BOOT_L2_MASK (0x10000U) +#define PMU_CTRL_SLEEP_CTRL_BOOT_L2_SHIFT (16U) +#define PMU_CTRL_SLEEP_CTRL_BOOT_L2(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_BOOT_L2_SHIFT) & PMU_CTRL_SLEEP_CTRL_BOOT_L2_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_BOOT_L2(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_BOOT_L2_MASK) >> PMU_CTRL_SLEEP_CTRL_BOOT_L2_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_REBOOT_MASK (0xC0000U) +#define PMU_CTRL_SLEEP_CTRL_REBOOT_SHIFT (18U) +#define PMU_CTRL_SLEEP_CTRL_REBOOT(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_REBOOT_SHIFT) & PMU_CTRL_SLEEP_CTRL_REBOOT_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_REBOOT(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_REBOOT_MASK) >> PMU_CTRL_SLEEP_CTRL_REBOOT_SHIFT) + +#define PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP_MASK (0x100000U) +#define PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP_SHIFT (20U) +#define PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP(x) (((uint32_t)(x) << PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP_SHIFT) & PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP_MASK) +#define READ_PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP(x) (((uint32_t)(x) & PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP_MASK) >> PMU_CTRL_SLEEP_CTRL_CLUSTER_WAKEUP_SHIFT) + +/* FORCE - PMU control register */ + +#define PMU_CTRL_FORCE_MEM_RET_MASK (0xFU) +#define PMU_CTRL_FORCE_MEM_RET_SHIFT (0U) +#define PMU_CTRL_FORCE_MEM_RET(x) (((uint32_t)(x) /* << PMU_CTRL_FORCE_MEM_RET_SHIFT*/) & PMU_CTRL_FORCE_MEM_RET_MASK) + +#define PMU_CTRL_FORCE_MEM_PWD_MASK (0xF0U) +#define PMU_CTRL_FORCE_MEM_PWD_SHIFT (4U) +#define PMU_CTRL_FORCE_MEM_PWD(x) (((uint32_t)(x) << PMU_CTRL_FORCE_MEM_PWD_SHIFT) & PMU_CTRL_FORCE_MEM_PWD_MASK) + +#define PMU_CTRL_FORCE_FLL_CLUSTER_RET_MASK (0x100U) +#define PMU_CTRL_FORCE_FLL_CLUSTER_RET_SHIFT (8U) +#define PMU_CTRL_FORCE_FLL_CLUSTER_RET(x) (((uint32_t)(x) << PMU_CTRL_FORCE_FLL_CLUSTER_RET_SHIFT) & PMU_CTRL_FORCE_FLL_CLUSTER_RET_MASK) + +#define PMU_CTRL_FORCE_FLL_CLUSTER_PWD_MASK (0x200U) +#define PMU_CTRL_FORCE_FLL_CLUSTER_PWD_SHIFT (9U) +#define PMU_CTRL_FORCE_FLL_CLUSTER_PWD(x) (((uint32_t)(x) << PMU_CTRL_FORCE_FLL_CLUSTER_PWD_SHIFT) & PMU_CTRL_FORCE_FLL_CLUSTER_PWD_MASK) + +/* PORT - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t PADFUN[4]; /* PORT pad function register 0 */ + volatile uint32_t SLEEP_PADCFG[4]; /* PORT sleep pad configuration register 0 */ + volatile uint32_t PAD_SLEEP; /* PORT pad sleep register */ + volatile uint32_t _reserved0[7]; /* reserved */ + volatile uint32_t PADCFG[16]; /* PORT pad configuration register 0 */ +} port_reg_t; + +#define PORTA_BASE (SOC_CTRL_BASE + 0x0140u) +#define PORTA ((port_reg_t *)PORTA_BASE) + +#define GPIO_NUM 32 + +#define PORT_PADCFG_PULL_EN_MASK (0x1U) +#define PORT_PADCFG_PULL_EN_SHIFT (0U) +#define PORT_PADCFG_PULL_EN(x) (((uint32_t)(x) << PORT_PADCFG_PULL_EN_SHIFT) & PORT_PADCFG_PULL_EN_MASK) + +#define PORT_PADCFG_DRIVE_STRENGTH_MASK (0x2U) +#define PORT_PADCFG_DRIVE_STRENGTH_SHIFT (1U) +#define PORT_PADCFG_DRIVE_STRENGTH(x) (((uint32_t)(x) << PORT_PADCFG_DRIVE_STRENGTH_SHIFT) & PORT_PADCFG_DRIVE_STRENGTH_MASK) + +#define PORT_PADFUN_MUX_MASK (0x3U) +#define PORT_PADFUN_MUX_SHIFT (0U) +#define PORT_PADFUN_MUX(x) (((uint32_t)(x) << PORT_PADFUN_MUX_SHIFT) & PORT_PADFUN_MUX_MASK) + +/* IO_ISO - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t GPIO_ISO; /* GPIO power domains isolation */ + volatile uint32_t CAM_ISO; /* Cemera power domains isolation */ + volatile uint32_t LVDS_ISO; /* LVDS power domains isolation */ +} io_iso_reg_t; + +#define IO_ISO_BASE (SOC_CTRL_BASE + 0x01C0u) +#define IO_ISO ((io_iso_reg_t *)IO_ISO_BASE) + +#define IO_ISO_GPIO_ISO_MASK (0x1U) +#define IO_ISO_GPIO_ISO_SHIFT (0U) +#define IO_ISO_GPIO_ISO(x) (((uint32_t)(x) /* << IO_ISO_GPIO_ISO_SHIFT */) & IO_ISO_GPIO_ISO_MASK) + +#define IO_ISO_CAM_ISO_MASK (0x1U) +#define IO_ISO_CAM_ISO_SHIFT (0U) +#define IO_ISO_CAM_ISO(x) (((uint32_t)(x) /* << IO_ISO_CAM_ISO_SHIFT */) & IO_ISO_CAM_ISO_MASK) + +#define IO_ISO_LVDS_ISO_MASK (0x1U) +#define IO_ISO_LVDS_ISO_SHIFT (0U) +#define IO_ISO_LVDS_ISO(x) (((uint32_t)(x) /* << IO_ISO_LVDS_ISO_SHIFT */) & IO_ISO_LVDS_ISO_MASK) + +/* PWM - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t EVENT_CFG; /* event configuration register */ + volatile uint32_t CH_EN; /* channel enable register */ +} pwm_ctrl_reg_t; + +#define PWM_CTRL_BASE (SOC_PERI_BASE + 0x05100u) +#define PWM_CTRL ((pwm_ctrl_reg_t *)PWM_CTRL_BASE) + +/* Set Event. */ + +#define PWM_CTRL_EVENT_TIMER_CHAN_SET_MASK (0xFFFFU) +#define PWM_CTRL_EVENT_TIMER_CHAN_SET_SHIFT(x) ((uint32_t)(x)) +#define PWM_CTRL_EVENT_TIMER_CHAN_SET(tim, chan, evt) (((uint32_t)((uint32_t)tim << 2 | (uint32_t)chan) << PWM_CTRL_EVENT_TIMER_CHAN_SET_SHIFT(evt << 2)) & PWM_CTRL_EVENT_TIMER_CHAN_SET_MASK) + +/* Enable Event. */ + +#define PWM_CTRL_EVENT_TIMER_ENA_MASK (0xF0000U) +#define PWM_CTRL_EVENT_TIMER_ENA_SHIFT (16) +#define PWM_CTRL_EVENT_TIMER_ENA(x) (((uint32_t)(x) << PWM_CTRL_EVENT_TIMER_ENA_SHIFT) & PWM_CTRL_EVENT_TIMER_ENA_MASK) + +/* Timer enable. */ + +#define PWM_CTRL_CG_ENA_MASK (0xFU) +#define PWM_CTRL_CG_ENA_SHIFT (0) +#define PWM_CTRL_CG_ENA(x) (((uint32_t)(x) << PWM_CTRL_CG_ENA_SHIFT) & PWM_CTRL_CG_ENA_MASK) + +/* ADV_TIMER - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t CMD; /* control register */ + volatile uint32_t CFG; /* configuration register */ + volatile uint32_t TH; /* threshold register */ + volatile uint32_t CH_TH[4]; /* Channles' threshold register */ + volatile uint32_t CH_LUT[4]; /* Channles' LUT register */ + volatile uint32_t COUNTER; /* Counter register */ +} pwm_reg_t; + +#define PWM0_BASE (SOC_PERI_BASE + 0x05000u) +#define PWM0 ((pwm_reg_t *)PWM0_BASE) +#define PWM1_BASE (PWM0_BASE + 0x40u) +#define PWM1 ((pwm_reg_t *)PWM1_BASE) +#define PWM2_BASE (PWM1_BASE + 0x40u) +#define PWM2 ((pwm_reg_t *)PWM2_BASE) +#define PWM3_BASE (PWM2_BASE + 0x40u) +#define PWM3 ((pwm_reg_t *)PWM3_BASE) + +/* Send command. */ + +#define PWM_CMD_MASK (0x1FU) +#define PWM_CMD_SHIFT (0) +#define PWM_CMD(x) (((uint32_t)(x) << PWM_CMD_SHIFT) & PWM_CMD_MASK) + +/* Timer config. */ + +#define PWM_CONFIG_INPUT_SRC_MASK (0xFFU) +#define PWM_CONFIG_INPUT_SRC_SHIFT (0) +#define PWM_CONFIG_INPUT_SRC(x) (((uint32_t)(x) << PWM_CONFIG_INPUT_SRC_SHIFT) & PWM_CONFIG_INPUT_SRC_MASK) + +#define PWM_CONFIG_INPUT_MODE_MASK (0x700U) +#define PWM_CONFIG_INPUT_MODE_SHIFT (8) +#define PWM_CONFIG_INPUT_MODE(x) (((uint32_t)(x) << PWM_CONFIG_INPUT_MODE_SHIFT) & PWM_CONFIG_INPUT_MODE_MASK) + +#define PWM_CONFIG_CLKSEL_MASK (0x800U) +#define PWM_CONFIG_CLKSEL_SHIFT (11) +#define PWM_CONFIG_CLKSEL(x) (((uint32_t)(x) << PWM_CONFIG_CLKSEL_SHIFT) & PWM_CONFIG_CLKSEL_MASK) + +#define PWM_CONFIG_UPDOWNSEL_MASK (0x1000U) +#define PWM_CONFIG_UPDOWNSEL_SHIFT (12) +#define PWM_CONFIG_UPDOWNSEL(x) (((uint32_t)(x) << PWM_CONFIG_UPDOWNSEL_SHIFT) & PWM_CONFIG_UPDOWNSEL_MASK) + +#define PWM_CONFIG_PRESCALE_MASK (0xFF0000U) +#define PWM_CONFIG_PRESCALE_SHIFT (16) +#define PWM_CONFIG_PRESCALE(x) (((uint32_t)(x) << PWM_CONFIG_PRESCALE_SHIFT) & PWM_CONFIG_PRESCALE_MASK) + +/* Channel config. */ + +#define PWM_THRESHOLD_LOW_MASK (0xFFFFU) +#define PWM_THRESHOLD_LOW_SHIFT (0) +#define PWM_THRESHOLD_LOW(x) (((uint32_t)(x) << PWM_THRESHOLD_LOW_SHIFT) & PWM_THRESHOLD_LOW_MASK) + +#define PWM_THRESHOLD_HIGH_MASK (0xFFFF0000U) +#define PWM_THRESHOLD_HIGH_SHIFT (16) +#define PWM_THRESHOLD_HIGH(x) (((uint32_t)(x) << PWM_THRESHOLD_HIGH_SHIFT) & PWM_THRESHOLD_HIGH_MASK) + +/* Channel config. */ + +#define PWM_CHANNEL_CONFIG_THRESHOLD_MASK (0xFFFFU) +#define PWM_CHANNEL_CONFIG_THRESHOLD_SHIFT (0) +#define PWM_CHANNEL_CONFIG_THRESHOLD(x) (((uint32_t)(x) << PWM_CHANNEL_CONFIG_THRESHOLD_SHIFT) & PWM_CHANNEL_CONFIG_THRESHOLD_MASK) + +#define PWM_CHANNEL_CONFIG_MODE_MASK (0x70000U) +#define PWM_CHANNEL_CONFIG_MODE_SHIFT (16) +#define PWM_CHANNEL_CONFIG_MODE(x) (((uint32_t)(x) << PWM_CHANNEL_CONFIG_MODE_SHIFT) & PWM_CHANNEL_CONFIG_MODE_MASK) + +/* SOCEU - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t EVENT; /* event register */ + volatile uint32_t FC_MASK_MSB; /* fc mask MSB register */ + volatile uint32_t FC_MASK_LSB; /* fc mask LSB register */ + volatile uint32_t CL_MASK_MSB; /* cluster mask MSB register */ + volatile uint32_t CL_MASK_LSB; /* cluster mask LSB register */ + volatile uint32_t PR_MASK_MSB; /* propagate mask MSB register */ + volatile uint32_t PR_MASK_LSB; /* propagate mask LSB register */ + volatile uint32_t ERR_MASK_MSB; /* error mask MSB register */ + volatile uint32_t ERR_MASK_LSB; /* error mask LSB register */ + volatile uint32_t TIMER_SEL_HI; /* timer high register */ + volatile uint32_t TIMER_SEL_LO; /* timer low register */ +} soceu_reg_t; + +#define SOCEU_BASE (SOC_PERI_BASE + 0x06000u) +#define SOCEU ((soceu_reg_t *)SOCEU_BASE) + +/* The SOC events number */ + +#define SOC_EVENTS_NUM 0x08 +#define EU_EVT_GETCLUSTERBASE(coreId) (0x00200800u + (coreId << 6)) + +/* PMU - General Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t PCTRL; /* PMU DLC control register */ + volatile uint32_t PRDATA; /* PMU DLC data register */ + volatile uint32_t DLC_SR; /* PMU DLC register */ + volatile uint32_t DLC_IMR; /* PMU DLC register */ + volatile uint32_t DLC_IFR; /* PMU DLC register */ + volatile uint32_t DLC_IOIFR; /* PMU DLC register */ + volatile uint32_t DLC_IDIFR; /* PMU DLC register */ + volatile uint32_t DLC_IMCIFR; /* PMU DLC register */ +} pmu_dlc_reg_t; + +#define PMU_DLC_BASE (SOC_PERI_BASE + 0x7000u) +#define PMU_DLC ((pmu_dlc_reg_t *)PMU_DLC_BASE) + +/* PCTRL - PMU DLC PICL control register */ + +#define PMU_DLC_PCTRL_START_MASK (0x1U) +#define PMU_DLC_PCTRL_START_SHIFT (0U) +#define PMU_DLC_PCTRL_START(x) (((uint32_t)(x) /* << PMU_DLC_PCTRL_START_SHIFT */) & PMU_DLC_PCTRL_START_MASK) +#define PMU_DLC_PCTRL_PADDR_MASK (0x7FFEU) +#define PMU_DLC_PCTRL_PADDR_SHIFT (1U) +#define PMU_DLC_PCTRL_PADDR(x) (((uint32_t)(x) << PMU_DLC_PCTRL_PADDR_SHIFT) & PMU_DLC_PCTRL_PADDR_MASK) +#define PMU_DLC_PCTRL_DIR_MASK (0x8000U) +#define PMU_DLC_PCTRL_DIR_SHIFT (15U) +#define PMU_DLC_PCTRL_DIR(x) (((uint32_t)(x) << PMU_DLC_PCTRL_DIR_SHIFT) & PMU_DLC_PCTRL_DIR_MASK) +#define PMU_DLC_PCTRL_PWDATA_MASK (0xFFFF0000U) +#define PMU_DLC_PCTRL_PWDATA_SHIFT (16U) +#define PMU_DLC_PCTRL_PWDATA(x) (((uint32_t)(x) << PMU_DLC_PCTRL_PWDATA_SHIFT) & PMU_DLC_PCTRL_PWDATA_MASK) + +/* PRDATA - PMU DLC PICL data read register */ + +#define PMU_DLC_PRDATA_PRDATA_MASK (0xFFU) +#define PMU_DLC_PRDATA_PRDATA_SHIFT (0U) +#define PMU_DLC_PRDATA_PRDATA(x) (((uint32_t)(x) /* << PMU_DLC_PRDATA_PRDATA_SHIFT */) & PMU_DLC_PRDATA_PRDATA_MASK) + +/* SR - PMU DLC DLC Status register */ + +#define PMU_DLC_SR_PICL_BUSY_MASK (0x1U) +#define PMU_DLC_SR_PICL_BUSY_SHIFT (0U) +#define PMU_DLC_SR_PICL_BUSY(x) (((uint32_t)(x) /* << PMU_DLC_SR_PICL_BUSY_SHIFT */) & PMU_DLC_SR_PICL_BUSY_MASK) +#define PMU_DLC_SR_SCU_BUSY_MASK (0x2U) +#define PMU_DLC_SR_SCU_BUSY_SHIFT (1U) +#define PMU_DLC_SR_SCU_BUSY(x) (((uint32_t)(x) << PMU_DLC_SR_SCU_BUSY_SHIFT) & PMU_DLC_SR_SCU_BUSY_MASK) + +/* IMR - PMU DLC Interrupt mask register */ + +#define PMU_DLC_IMR_ICU_OK_MASK_MASK (0x1U) +#define PMU_DLC_IMR_ICU_OK_MASK_SHIFT (0U) +#define PMU_DLC_IMR_ICU_OK_MASK(x) (((uint32_t)(x) /* << PMU_DLC_IMR_ICU_OK_MASK_SHIFT */) & PMU_DLC_IMR_ICU_OK_MASK_MASK) +#define PMU_DLC_IMR_ICU_DELAYED_MASK_MASK (0x2U) +#define PMU_DLC_IMR_ICU_DELAYED_MASK_SHIFT (1U) +#define PMU_DLC_IMR_ICU_DELAYED_MASK(x) (((uint32_t)(x) << PMU_DLC_IMR_ICU_DELAYED_MASK_SHIFT) & PMU_DLC_IMR_ICU_DELAYED_MASK_MASK) +#define PMU_DLC_IMR_ICU_MODE_CHANGED_MASK_MASK (0x4U) +#define PMU_DLC_IMR_ICU_MODE_CHANGED_MASK_SHIFT (2U) +#define PMU_DLC_IMR_ICU_MODE_CHANGED_MASK(x) (((uint32_t)(x) << PMU_DLC_IMR_ICU_MODE_CHANGED_MASK_SHIFT) & PMU_DLC_IMR_ICU_MODE_CHANGED_MASK_MASK) +#define PMU_DLC_IMR_PICL_OK_MASK_MASK (0x8U) +#define PMU_DLC_IMR_PICL_OK_MASK_SHIFT (3U) +#define PMU_DLC_IMR_PICL_OK_MASK(x) (((uint32_t)(x) << PMU_DLC_IMR_PICL_OK_MASK_SHIFT) & PMU_DLC_IMR_PICL_OK_MASK_MASK) +#define PMU_DLC_IMR_SCU_OK_MASK_MASK (0x10U) +#define PMU_DLC_IMR_SCU_OK_MASK_SHIFT (4U) +#define PMU_DLC_IMR_SCU_OK_MASK(x) (((uint32_t)(x) << PMU_DLC_IMR_SCU_OK_MASK_SHIFT) & PMU_DLC_IMR_SCU_OK_MASK_MASK) + +/* IFR - PMU DLC Interrupt flag register */ + +#define PMU_DLC_IFR_ICU_OK_FLAG_MASK (0x1U) +#define PMU_DLC_IFR_ICU_OK_FLAG_SHIFT (0U) +#define PMU_DLC_IFR_ICU_OK_FLAG(x) (((uint32_t)(x) /* << PMU_DLC_IFR_ICU_OK_FLAG_SHIFT */) & PMU_DLC_IFR_ICU_OK_FLAG_MASK) +#define PMU_DLC_IFR_ICU_DELAYED_FLAG_MASK (0x2U) +#define PMU_DLC_IFR_ICU_DELAYED_FLAG_SHIFT (1U) +#define PMU_DLC_IFR_ICU_DELAYED_FLAG(x) (((uint32_t)(x) << PMU_DLC_IFR_ICU_DELAYED_FLAG_SHIFT) & PMU_DLC_IFR_ICU_DELAYED_FLAG_MASK) +#define PMU_DLC_IFR_ICU_MODE_CHANGED_FLAG_MASK (0x4U) +#define PMU_DLC_IFR_ICU_MODE_CHANGED_FLAG_SHIFT (2U) +#define PMU_DLC_IFR_ICU_MODE_CHANGED_FLAG(x) (((uint32_t)(x) << PMU_DLC_IFR_ICU_MODE_CHANGED_FLAG_SHIFT) & PMU_DLC_IFR_ICU_MODE_CHANGED_FLAG_MASK) +#define PMU_DLC_IFR_PICL_OK_FLAG_MASK (0x8U) +#define PMU_DLC_IFR_PICL_OK_FLAG_SHIFT (3U) +#define PMU_DLC_IFR_PICL_OK_FLAG(x) (((uint32_t)(x) << PMU_DLC_IFR_PICL_OK_FLAG_SHIFT) & PMU_DLC_IFR_PICL_OK_FLAG_MASK) +#define PMU_DLC_IFR_SCU_OK_FLAG_MASK (0x10U) +#define PMU_DLC_IFR_SCU_OK_FLAG_SHIFT (4U) +#define PMU_DLC_IFR_SCU_OK_FLAG(x) (((uint32_t)(x) << PMU_DLC_IFR_SCU_OK_FLAG_SHIFT) & PMU_DLC_IFR_SCU_OK_FLAG_MASK) + +/* IOIFR - PMU DLC icu_ok interrupt flag register */ + +#define PMU_DLC_IOIFR_ICU_OK_FLAG_MASK (0xFFFFFFFEU) +#define PMU_DLC_IOIFR_ICU_OK_FLAG_SHIFT (1U) +#define PMU_DLC_IOIFR_ICU_OK_FLAG(x) (((uint32_t)(x) << PMU_DLC_IOIFR_ICU_OK_FLAG_SHIFT) & PMU_DLC_IOIFR_ICU_OK_FLAG_MASK) + +/* IDIFR - PMU DLC icu_delayed interrupt flag register */ + +#define PMU_DLC_IDIFR_ICU_DELAYED_FLAG_MASK (0xFFFFFFFEU) +#define PMU_DLC_IDIFR_ICU_DELAYED_FLAG_SHIFT (1U) +#define PMU_DLC_IDIFR_ICU_DELAYED_FLAG(x) (((uint32_t)(x) << PMU_DLC_IDIFR_ICU_DELAYED_FLAG_SHIFT) & PMU_DLC_IDIFR_ICU_DELAYED_FLAG_MASK) + +/* IMCIFR - PMU DLC icu_mode changed interrupt flag register */ + +#define PMU_DLC_IMCIFR_ICU_MODE_CHANGED_FLAG_MASK (0xFFFFFFFEU) +#define PMU_DLC_IMCIFR_ICU_MODE_CHANGED_FLAG_SHIFT (1U) +#define PMU_DLC_IMCIFR_ICU_MODE_CHANGED_FLAG(x) (((uint32_t)(x) << PMU_DLC_IMCIFR_ICU_MODE_CHANGED_FLAG_SHIFT) & PMU_DLC_IMCIFR_ICU_MODE_CHANGED_FLAG_MASK) + +/* PCTRL_PADDR The address to write in the DLC_PADDR register is + * CHIP_SEL_ADDR[4:0] concatenated with REG_ADDR[4:0]. + */ + +#define PMU_DLC_PICL_REG_ADDR_MASK (0x1FU) +#define PMU_DLC_PICL_REG_ADDR_SHIFT (0U) +#define PMU_DLC_PICL_REG_ADDR(x) (((uint32_t)(x) /* << PMU_DLC_PICL_REG_ADDR_SHIFT */) & PMU_DLC_PICL_REG_ADDR_MASK) +#define PMU_DLC_PICL_CHIP_SEL_ADDR_MASK (0x3E0U) +#define PMU_DLC_PICL_CHIP_SEL_ADDR_SHIFT (5U) +#define PMU_DLC_PICL_CHIP_SEL_ADDR(x) (((uint32_t)(x) << PMU_DLC_PICL_CHIP_SEL_ADDR_SHIFT) & PMU_DLC_PICL_CHIP_SEL_ADDR_MASK) + +/* CHIP_SEL_ADDR[4:0] */ + +#define PICL_WIU_ADDR 0x00 +#define PICL_ICU_ADDR 0x01 + +/* REG_ADDR[4:0] */ + +#define WIU_ISPMR_0 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x00)) +#define WIU_ISPMR_1 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x01)) +#define WIU_IFR_0 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x02)) +#define WIU_IFR_1 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x03)) +#define WIU_ICR_0 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x04)) +#define WIU_ICR_1 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x05)) +#define WIU_ICR_2 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x06)) +#define WIU_ICR_3 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x07)) +#define WIU_ICR_4 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x08)) +#define WIU_ICR_5 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x09)) +#define WIU_ICR_6 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x0A)) +#define WIU_ICR_7 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x0B)) +#define WIU_ICR_8 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x0C)) +#define WIU_ICR_9 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x0D)) +#define WIU_ICR_10 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x0E)) +#define WIU_ICR_11 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x0F)) +#define WIU_ICR_12 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x10)) +#define WIU_ICR_13 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x11)) +#define WIU_ICR_14 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x12)) +#define WIU_ICR_15 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_WIU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x13)) + +/* REG_ADDR[4:0] */ + +#define ICU_CR (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_ICU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x00)) +#define ICU_MR (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_ICU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x01)) +#define ICU_ISMR (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_ICU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x02)) +#define ICU_DMR_0 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_ICU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x03)) +#define ICU_DMA_1 (PMU_DLC_PICL_CHIP_SEL_ADDR(PICL_ICU_ADDR) | PMU_DLC_PICL_REG_ADDR(0x04)) + +/* RTC_APB - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t STATUS; /* RTC_APB_Status register */ + volatile uint32_t REQUEST; /* RTC_APB_Request register */ + volatile uint32_t DATA; /* RTC_APB_Data register */ + volatile uint32_t _reserved; /* reserved */ + volatile uint32_t IRQ_CTRL; /* RTC_APB_IRQ_Control register */ + volatile uint32_t IRQ_MASK; /* RTC_APB_IRQ_Mask register */ + volatile uint32_t IRQ_FLAG; /* RTC_APB_IRQ_Flag register */ +} rtc_apb_reg_t; + +#define RTC_APB_BASE (SOC_PERI_BASE + 0x08000u) +#define RTC_APB ((rtc_apb_reg_t *)RTC_APB_BASE) + +/* STATUS - RTC_APB STATUS register */ + +#define RTC_APB_STATUS_IRQ_EN_MASK (0x3FU) +#define RTC_APB_STATUS_IRQ_EN_SHIFT (0U) +#define RTC_APB_STATUS_IRQ_EN(x) (((uint32_t)(x)/* << RTC_APB_STATUS_IRQ_EN_SHIFT*/) & RTC_APB_STATUS_IRQ_EN_MASK) + +/* REQUEST - RTC_APB REQUEST Access register */ + +#define RTC_APB_REQUEST_ACCESS_ADDR_MASK (0x3FU) +#define RTC_APB_REQUEST_ACCESS_ADDR_SHIFT (0U) +#define RTC_APB_REQUEST_ACCESS_ADDR(x) (((uint32_t)(x)/* << RTC_APB_REQUEST_ACCESS_ADDR_SHIFT*/) & RTC_APB_REQUEST_ACCESS_ADDR_MASK) +#define RTC_APB_REQUEST_ACCESS_RW_MASK (0x10000U) +#define RTC_APB_REQUEST_ACCESS_RW_SHIFT (16U) +#define RTC_APB_REQUEST_ACCESS_RW(x) (((uint32_t)(x) << RTC_APB_REQUEST_ACCESS_RW_SHIFT) & RTC_APB_REQUEST_ACCESS_RW_MASK) + +/* IRQ_FLAG - RTC_APB IRQ_FLAG Access register */ + +#define RTC_APB_IRQ_FLAG_READ_MASK (0x1U) +#define RTC_APB_IRQ_FLAG_READ_SHIFT (0U) +#define RTC_APB_IRQ_FLAG_READ(x) (((uint32_t)(x)/* << RTC_APB_IRQ_FLAG_READ_SHIFT*/) & RTC_APB_IRQ_FLAG_READ_MASK) +#define RTC_APB_IRQ_FLAG_WRITE_MASK (0x2U) +#define RTC_APB_IRQ_FLAG_WRITE_SHIFT (1U) +#define RTC_APB_IRQ_FLAG_WRITE(x) (((uint32_t)(x) << RTC_APB_IRQ_FLAG_WRITE_SHIFT) & RTC_APB_IRQ_FLAG_WRITE_MASK) + +/* Bit field of RTC indirect Access Register */ + +#define RTC_STATUS_ADDR 0x00 +#define RTC_CTRL_ADDR 0x01 +#define RTC_CLK_CTRL_ADDR 0x02 +#define RTC_IRQ_CTRL_ADDR 0x08 +#define RTC_IRQ_MASK_ADDR 0x09 +#define RTC_IRQ_FLAG_ADDR 0x0A +#define RTC_CALENDAR_CTRL_ADDR 0x10 +#define RTC_CALENDAR_TIME_ADDR 0x12 +#define RTC_CALENDAR_DATE_ADDR 0x13 +#define RTC_ALARM_CTRL_ADDR 0x18 +#define RTC_ALARM_TIME_ADDR 0x1A +#define RTC_ALARM_DATE_ADDR 0x1B +#define RTC_TIMER_CTRL_ADDR 0x20 +#define RTC_TIMER_INIT_ADDR 0x21 +#define RTC_TIMER_VALUE_ADDR 0x22 +#define RTC_CLKIN_DIV_ADDR 0x28 +#define RTC_REF_CLK_CONF_ADDR 0x2A +#define RTC_TEST_ADDR 0x30 + +/* SR - RTC Status register */ + +#define RTC_SR_INT_RTC_MASK (0x1U) +#define RTC_SR_INT_RTC_SHIFT (0U) +#define RTC_SR_INT_RTC(x) (((uint32_t)(x)/* << RTC_SR_INT_RTC_SHIFT*/) & RTC_SR_INT_RTC_MASK) + +/* CR - RTC Control register */ + +#define RTC_CR_STANDBY_MASK (0x1U) +#define RTC_CR_STANDBY_SHIFT (0U) +#define RTC_CR_STANDBY(x) (((uint32_t)(x)/* << RTC_CR_STANDBY_SHIFT*/) & RTC_CR_STANDBY_MASK) +#define RTC_CR_CALIBRATION_EN_MASK (0x10U) +#define RTC_CR_CALIBRATION_EN_SHIFT (4U) +#define RTC_CR_CALIBRATION_EN(x) (((uint32_t)(x) << RTC_CR_CALIBRATION_EN_SHIFT) & RTC_CR_CALIBRATION_EN_MASK) +#define RTC_CR_SOFT_RST_MASK (0x100U) +#define RTC_CR_SOFT_RST_SHIFT (8U) +#define RTC_CR_SOFT_RST(x) (((uint32_t)(x) << RTC_CR_SOFT_RST_SHIFT) & RTC_CR_SOFT_RST_MASK) + +/* CCR - RTC Clock Control register */ + +#define RTC_CCR_CKOUT_STANDBY_MASK (0x1U) +#define RTC_CCR_CKOUT_STANDBY_SHIFT (0U) +#define RTC_CCR_CKOUT_STANDBY(x) (((uint32_t)(x)/* << RTC_CCR_CKOUT_STANDBY_SHIFT*/) & RTC_CCR_CKOUT_STANDBY_MASK) +#define RTC_CCR_DIV_AUTOCAL_MASK (0x1000U) +#define RTC_CCR_DIV_AUTOCAL_SHIFT (12U) +#define RTC_CCR_DIV_AUTOCAL(x) (((uint32_t)(x) << RTC_CCR_DIV_AUTOCAL_SHIFT) & RTC_CCR_DIV_AUTOCAL_MASK) +#define RTC_CCR_DIV_COMP_MASK (0x1F0000U) +#define RTC_CCR_DIV_COMP_SHIFT (16U) +#define RTC_CCR_DIV_COMP(x) (((uint32_t)(x) << RTC_CCR_DIV_COMP_SHIFT) & RTC_CCR_DIV_COMP_MASK) + +/* ICR - RTC IRQ Control register + * + * 00 INT_RTC high; + * 01 INT_RTC low; + * 10; INT_RTC high pulse with duration of 1 CKIN cycle + * 11; INT_RTC low pulse with duration of 1 CKIN cycle + */ + +#define RTC_ICR_FORM_MASK (0x3U) +#define RTC_ICR_FORM_SHIFT (0U) +#define RTC_ICR_FORM(x) (((uint32_t)(x)/* << RTC_ICR_FORM_SHIFT*/) & RTC_ICR_FORM_MASK) + +/* IMR - RTC IRQ MASK register */ + +#define RTC_IMR_ALARM_MASK (0x1U) +#define RTC_IMR_ALARM_SHIFT (0U) +#define RTC_IMR_ALARM(x) (((uint32_t)(x)/* << RTC_IMR_ALARM_SHIFT*/) & RTC_IMR_ALARM_MASK) +#define RTC_IMR_TIMER_MASK (0x10U) +#define RTC_IMR_TIMER_SHIFT (4U) +#define RTC_IMR_TIMER(x) (((uint32_t)(x) << RTC_IMR_TIMER_SHIFT) & RTC_IMR_TIMER_MASK) +#define RTC_IMR_CALIBRATION_MASK (0x1000U) +#define RTC_IMR_CALIBRATION_SHIFT (12U) +#define RTC_IMR_CALIBRATION(x) (((uint32_t)(x) << RTC_IMR_CALIBRATION_SHIFT) & RTC_IMR_CALIBRATION_MASK) + +/* IFR - RTC IRQ Flag register */ + +#define RTC_IFR_ALARM_MASK (0x1U) +#define RTC_IFR_ALARM_SHIFT (0U) +#define RTC_IFR_ALARM(x) (((uint32_t)(x)/* << RTC_IFR_ALARM_SHIFT*/) & RTC_IFR_ALARM_MASK) +#define RTC_IFR_TIMER_MASK (0x10U) +#define RTC_IFR_TIMER_SHIFT (4U) +#define RTC_IFR_TIMER(x) (((uint32_t)(x) << RTC_IFR_TIMER_SHIFT) & RTC_IFR_TIMER_MASK) +#define RTC_IFR_CALIBRATION_MASK (0x1000U) +#define RTC_IFR_CALIBRATION_SHIFT (12U) +#define RTC_IFR_CALIBRATION(x) (((uint32_t)(x) << RTC_IFR_CALIBRATION_SHIFT) & RTC_IFR_CALIBRATION_MASK) + +/* CALENDAR CTRL - RTC CALENDAR Control register */ + +#define RTC_CALENDAR_CTRL_STANDBY_MASK (0x1U) +#define RTC_CALENDAR_CTRL_STANDBY_SHIFT (0U) +#define RTC_CALENDAR_CTRL_STANDBY(x) (((uint32_t)(x)/* << RTC_CALENDAR_CTRL_STANDBY_SHIFT*/) & RTC_CALENDAR_CTRL_STANDBY_MASK) + +/* ALARM_CTRL - RTC Alarm control register */ + +#define RTC_ALARM_CTRL_STANDBY_MASK (0x1U) +#define RTC_ALARM_CTRL_STANDBY_SHIFT (0U) +#define RTC_ALARM_CTRL_STANDBY(x) (((uint32_t)(x)/* << RTC_ALARM_CTRL_STANDBY_SHIFT*/) & RTC_ALARM_CTRL_STANDBY_MASK) +#define RTC_ALARM_CTRL_MODE_MASK (0x10U) +#define RTC_ALARM_CTRL_MODE_SHIFT (4U) +#define RTC_ALARM_CTRL_MODE(x) (((uint32_t)(x) << RTC_ALARM_CTRL_MODE_SHIFT) & RTC_ALARM_CTRL_MODE_MASK) +#define RTC_ALARM_CTRL_CONFIG_MASK (0xF0000U) +#define RTC_ALARM_CTRL_CONFIG_SHIFT (16U) +#define RTC_ALARM_CTRL_CONFIG(x) (((uint32_t)(x) << RTC_ALARM_CTRL_CONFIG_SHIFT) & RTC_ALARM_CTRL_CONFIG_MASK) + +/* TIMER - RTC Count down register */ + +#define RTC_TIMER_STANDBY_MASK (0x1U) +#define RTC_TIMER_STANDBY_SHIFT (0U) +#define RTC_TIMER_STANDBY(x) (((uint32_t)(x)/* << RTC_TIMER_STANDBY_SHIFT*/) & RTC_TIMER_STANDBY_MASK) +#define RTC_TIMER_MODE_MASK (0x10U) +#define RTC_TIMER_MODE_SHIFT (4U) +#define RTC_TIMER_MODE(x) (((uint32_t)(x) << RTC_TIMER_MODE_SHIFT) & RTC_TIMER_MODE_MASK) + +/* CLKIN_DIV - RTC Clock in divider register */ + +#define RTC_CLKIN_DIV_VAL_MASK (0xFFFFU) +#define RTC_CLKIN_DIV_VAL_SHIFT (0U) +#define RTC_CLKIN_DIV_VAL(x) (((uint32_t)(x)/* << RTC_CLKIN_DIV_VAL_SHIFT*/) & RTC_CLKIN_DIV_VAL_MASK) + +/* CKREF_CONF - RTC Reference Clock configuration */ + +#define RTC_CKREF_CONF_VAL_MASK (0x3FFFFFU) +#define RTC_CKREF_CONF_VAL_SHIFT (0U) +#define RTC_CKREF_CONF_VAL(x) (((uint32_t)(x)/* << RTC_CKREF_CONF_VAL_SHIFT*/) & RTC_CKREF_CONF_VAL_MASK) + +/* EFUSE_CTRL - Register Layout Typedef */ + +typedef struct +{ + volatile uint32_t CMD; /* EFUSE_Control register */ + volatile uint32_t CFG; /* EFUSE_Control register */ +} efuse_ctrl_reg_t; + +#define EFUSE_CTRL_BASE (SOC_PERI_BASE + 0x09000u) +#define EFUSE_CTRL ((efuse_ctrl_reg_t *)EFUSE_CTRL_BASE) + +#define EFUSE_CTRL_CMD_READ 0x1 +#define EFUSE_CTRL_CMD_WRITE 0x2 +#define EFUSE_CTRL_CMD_SLEEP 0x4 + +/* EFUSE_REGS - Registers Layout Typedef */ + +typedef struct +{ + volatile uint32_t INFO; /**< EFUSE INFO register, offset: 0x000 */ + volatile uint32_t INFO2; /**< EFUSE_INFO2 register, offset: 0x004 */ + volatile uint32_t AES_KEY[16]; /**< EFUSE_AES_KEY registers, offset: 0x008 */ + volatile uint32_t AES_IV[8]; /**< EFUSE_AES_IV registers, offset: 0x048 */ + volatile uint32_t WAIT_XTAL_DELTA_LSB; /**< EFUSE_WAIT_XTAL_DELTA_LSB register, offset: 0x068 */ + volatile uint32_t WAIT_XTAL_DELTA_MSB; /**< EFUSE_WAIT_XTAL_DELTA_MSB register, offset: 0x06C */ + volatile uint32_t WAIT_XTAL_MIN; /**< EFUSE_WAIT_XTAL_MIN registers, offset: 0x070 */ + volatile uint32_t WAIT_XTAL_MAX; /**< EFUSE_WAIT_XTAL_MAX registers, offset: 0x074 */ +} efuse_regs_reg_t; + +#define EFUSE_REGS_BASE (SOC_PERI_BASE + 0x09200u) +#define EFUSE_REGS ((efuse_regs_reg_t *)EFUSE_REGS_BASE) + +/* INFO - EFUSE information register */ + +#define EFUSE_INFO_PLT_MASK (0x07U) +#define EFUSE_INFO_PLT_SHIFT (0U) +#define EFUSE_INFO_PLT(x) (((uint32_t)(x) << EFUSE_INFO_PLT_SHIFT) & EFUSE_INFO_PLT_MASK) + +#define EFUSE_INFO_BOOT_MASK (0x38U) +#define EFUSE_INFO_BOOT_SHIFT (3U) +#define EFUSE_INFO_BOOT(x) (((uint32_t)(x) << EFUSE_INFO_BOOT_SHIFT) & EFUSE_INFO_BOOT_MASK) + +#define EFUSE_INFO_ENCRYPTED_MASK (0x40U) +#define EFUSE_INFO_ENCRYPTED_SHIFT (6U) +#define EFUSE_INFO_ENCRYPTED(x) (((uint32_t)(x) << EFUSE_INFO_ENCRYPTED_SHIFT) & EFUSE_INFO_ENCRYPTED_MASK) + +#define EFUSE_INFO_WAIT_XTAL_MASK (0x80U) +#define EFUSE_INFO_WAIT_XTAL_SHIFT (7U) +#define EFUSE_INFO_WAIT_XTAL(x) (((uint32_t)(x) << EFUSE_INFO_WAIT_XTAL_SHIFT) & EFUSE_INFO_WAIT_XTAL_MASK) + +/* FC_STDOUT - Registers Layout Typedef */ + +typedef struct +{ + volatile uint32_t PUTC[16]; /* FC_STDOUT INFO register, offset: 0x000 */ +} fc_stdout_reg_t; + +#define FC_STDOUT_BASE (SOC_PERI_BASE + 0x10000u + (32 << 7)) +#define FC_STDOUT ((fc_stdout_reg_t *)FC_STDOUT_BASE) + +#ifdef FEATURE_CLUSTER +/* CLUSTER_STDOUT - Registers Layout Typedef */ + +typedef struct +{ + volatile uint32_t PUTC[16]; /* CLUSTER_STDOUT INFO register, offset: 0x000 */ +} cluster_stdout_reg_t; + +#define CLUSTER_STDOUT_BASE (SOC_PERI_BASE + 0x10000u) +#define CLUSTER_STDOUT ((cluster_stdout_reg_t *)CLUSTER_STDOUT_BASE) + +/* HWCE - Registers Layout Typedef */ + +typedef struct +{ + volatile uint32_t HWCE_TRIGGER_REG; /* Trigger register */ + volatile uint32_t HWCE_ACQUIRE_REG; /* Acquire register */ + volatile uint32_t HWCE_FINISHED_REG; /* Finished register */ + volatile uint32_t HWCE_STATUS_REG; /* Status register */ + volatile uint32_t HWCE_RUNNING_JOB_REG; /* Running Job register */ + volatile uint32_t HWCE_SOFT_CLEAR_REG; /* Soft_Clear register */ + volatile uint32_t _reserved0[2]; /* Non used registers */ + volatile uint32_t HWCE_GEN_CONFIG0_REG; /* Gen_Config0 register */ + volatile uint32_t HWCE_GEN_CONFIG1_REG; /* Gen_Config1 register */ + volatile uint32_t _reserved1[6]; /* unused registers */ + volatile uint32_t HWCE_Y_TRANS_SIZE_REG; /* Y_Trans_Size register */ + volatile uint32_t HWCE_Y_LINE_STRIDE_LENGTH_REG; /* Y_Line_Stride_Length register */ + volatile uint32_t HWCE_Y_FEAT_STRIDE_LENGTH_REG; /* Y_Feat_Stride_Length register */ + volatile uint32_t HWCE_Y_OUT_3_REG; /* Y_Out_3 register */ + volatile uint32_t HWCE_Y_OUT_2_REG; /* Y_Out_2 register */ + volatile uint32_t HWCE_Y_OUT_1_REG; /* Y_Out_1 register */ + volatile uint32_t HWCE_Y_OUT_0_REG; /* Y_Out_0 register */ + volatile uint32_t HWCE_Y_IN_3_REG; /* Y_In_3 register */ + volatile uint32_t HWCE_Y_IN_2_REG; /* Y_In_2 register */ + volatile uint32_t HWCE_Y_IN_1_REG; /* Y_In_1 register */ + volatile uint32_t HWCE_Y_IN_0_REG; /* Y_In_0 register */ + volatile uint32_t HWCE_X_TRANS_SIZE_REG; /* X_Trans_Size register */ + volatile uint32_t HWCE_X_LINE_STRIDE_LENGTH_REG; /* X_Line_Stride_Length register */ + volatile uint32_t HWCE_X_FEAT_STRIDE_LENGTH_REG; /* X_Feat_Stride_Length register */ + volatile uint32_t HWCE_X_IN_REG; /* X_In register */ + volatile uint32_t HWCE_W_REG; /* W register */ + volatile uint32_t HWCE_JOB_CONFIG0_REG; /* Job_Config0 register */ + volatile uint32_t HWCE_JOB_CONFIG1_REG; /* Job_Config1 register */ +} hwce_reg_t; + +#define HWCE_BASE (CORE_PERI_BASE + 0x00001000) +#define HWCE ((hwce_reg_t *) HWCE_BASE) + +/* Internal registers */ + +#define HWCE_TRIGGER (0x00) +#define HWCE_ACQUIRE (0x04) +#define HWCE_FINISHED (0x08) +#define HWCE_STATUS (0x0C) +#define HWCE_RUNNING_JOB (0x10) +#define HWCE_SOFT_CLEAR (0x14) +#define HWCE_GEN_CONFIG0 (0x20) +#define HWCE_GEN_CONFIG1 (0x24) + +/* Configuration registers */ + +#define HWCE_Y_TRANS_SIZE (0x40) +#define HWCE_Y_LINE_STRIDE_LENGTH (0x44) +#define HWCE_Y_FEAT_STRIDE_LENGTH (0x48) +#define HWCE_Y_OUT_3_BASE_ADDR (0x4C) +#define HWCE_Y_OUT_2_BASE_ADDR (0x50) +#define HWCE_Y_OUT_1_BASE_ADDR (0x54) +#define HWCE_Y_OUT_0_BASE_ADDR (0x58) +#define HWCE_Y_IN_3_BASE_ADDR (0x5C) +#define HWCE_Y_IN_2_BASE_ADDR (0x60) +#define HWCE_Y_IN_1_BASE_ADDR (0x64) +#define HWCE_Y_IN_0_BASE_ADDR (0x68) +#define HWCE_X_TRANS_SIZE (0x6C) +#define HWCE_X_LINE_STRIDE_LENGTH (0x70) +#define HWCE_X_FEAT_STRIDE_LENGTH (0x74) +#define HWCE_X_IN_BASE_ADDR (0x78) +#define HWCE_W_BASE_ADDR (0x7C) +#define HWCE_JOB_CONFIG0 (0x80) +#define HWCE_JOB_CONFIG1 (0x84) + +#define HWCE_NB_IO_REGS (18) + +#define HWCE_ACQUIRE_CONTEXT_COPY (-3) +#define HWCE_ACQUIRE_LOCKED (-2) +#define HWCE_ACQUIRE_QUEUE_FULL (-1) +#define HWCE_ACQUIRE_READY (0) + +#define HWCE_GEN_CONFIG0_WSTRIDE(x) ((x) >> 16) +#define HWCE_GEN_CONFIG0_NCP(x) (((x) >> 13) & 0x1) +#define HWCE_GEN_CONFIG0_CONV(x) (((x) >> 11) & 0x3) +#define HWCE_GEN_CONFIG0_VECT(x) (((x) >> 9) & 0x3) +#define HWCE_GEN_CONFIG0_UNS(x) (((x) >> 8) & 1) +#define HWCE_GEN_CONFIG0_NY(x) (((x) >> 7) & 1) +#define HWCE_GEN_CONFIG0_NF(x) (((x) >> 6) & 1) +#define HWCE_GEN_CONFIG0_QF(x) ((x) & 0x3f) + +#define HWCE_GEN_CONFIG0_CONV_5x5 (0) +#define HWCE_GEN_CONFIG0_CONV_3x3 (1) +#define HWCE_GEN_CONFIG0_CONV_4x7 (2) + +#define HWCE_GEN_CONFIG0_VECT_1 (0) +#define HWCE_GEN_CONFIG0_VECT_2 (1) +#define HWCE_GEN_CONFIG0_VECT_4 (2) + +#define HWCE_GEN_CONFIG1_PIXSHIFTR(x) (((x) >> 16) & 0x1F) +#define HWCE_GEN_CONFIG1_PIXMODE(x) (((x) >> 8) & 0x3) +#define HWCE_GEN_CONFIG1_PIXSHIFTL(x) (((x) >> 0) & 0x1F) + +#define HWCE_JOB_CONFIG0_NOYCONST(x) ((x) >> 16) +#define HWCE_JOB_CONFIG0_LBUFLEN(x) ((x) & 0x3ff) + +#define HWCE_JOB_CONFIG1_LO(x) (((x) >> 24) & 0x1) +#define HWCE_JOB_CONFIG1_WIF(x) (((x) >> 16) & 0x3F) +#define HWCE_JOB_CONFIG1_WOF(x) (((x) >> 8) & 0x1F) +#define HWCE_JOB_CONFIG1_VECT_DISABLE_MASK(x) (((x) >> 0) & 0xF) + +#define HWCE_JOB_STRIDE(x) ((x) >> 16) +#define HWCE_JOB_LENGTH(x) ((x) & 0xffff) + +#endif + +#endif /* __ARCH_RISC_V_SRC_GAP8_GAP8_H */ diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_allocateheap.c b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_allocateheap.c new file mode 100755 index 00000000..302c092a --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_allocateheap.c @@ -0,0 +1,98 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_allocateheap.c + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include + +#include +#include +#include + +#include "riscv_arch.h" +#include "riscv_internal.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_allocate_heap + * + * Description: + * This function will be called to dynamically set aside the heap region. + * + * For the kernel build (CONFIG_BUILD_KERNEL=y) with both kernel- and + * user-space heaps (CONFIG_MM_KERNEL_HEAP=y), this function provides the + * size of the unprotected, user-space heap. + * + * If a protected kernel-space heap is provided, the kernel heap must be + * allocated (and protected) by an analogous up_allocate_kheap(). + * + ****************************************************************************/ + +void up_allocate_heap(FAR void **heap_start, size_t *heap_size) +{ + /* These values come from GAP8.ld */ + + extern uint8_t *_heap_start; + extern uint8_t *_heap_end; + uint32_t hstart = (uint32_t)&_heap_start; + uint32_t hend = (uint32_t)&_heap_end; + + *heap_start = &_heap_start; + *heap_size = hend - hstart; +} + +/**************************************************************************** + * Name: riscv_addregion + * + * Description: + * RAM may be added in non-contiguous chunks. This routine adds all chunks + * that may be used for heap. + * + ****************************************************************************/ + +#if CONFIG_MM_REGIONS > 1 +void riscv_addregion(void) +{ + /* TODO: add L1 memorie */ +} +#endif diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_idle.c b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_idle.c new file mode 100755 index 00000000..c11a630c --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_idle.c @@ -0,0 +1,84 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_idle.c + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#include "riscv_internal.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_idle + * + * Description: + * up_idle() is the logic that will be executed when there is no other + * ready-to-run task. This is processor idle time and will continue until + * some interrupt occurs to cause a context switch from the idle task. + * + * Processing in this state may be processor-specific. e.g., this is where + * power management operations might be performed. + * + ****************************************************************************/ + +void up_idle(void) +{ +#if defined(CONFIG_SUPPRESS_INTERRUPTS) || defined(CONFIG_SUPPRESS_TIMER_INTS) + /* If the system is idle and there are no timer interrupts, then process + * "fake" timer interrupts. Hopefully, something will wake up. + */ + + nxsched_process_timer(); +#else + + /* GAP8 would sleep on software event #3, which would be triggered at + * gap8_dispatch_irq(). + */ + + gap8_sleep_wait_sw_evnt(1 << 3); + +#ifdef CONFIG_SCHED_WORKQUEUE + irqstate_t flags = enter_critical_section(); + leave_critical_section(flags); +#endif +#endif +} diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_schedulesigaction.c b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_schedulesigaction.c new file mode 100755 index 00000000..138105c1 --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/gap8_schedulesigaction.c @@ -0,0 +1,199 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_schedulesigaction.c + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * Modified for RISC-V: + * + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include +#include +#include + +#include "sched/sched.h" +#include "riscv_internal.h" +#include "riscv_arch.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_schedule_sigaction + * + * Description: + * This function is called by the OS when one or more + * signal handling actions have been queued for execution. + * The architecture specific code must configure things so + * that the 'sigdeliver' callback is executed on the thread + * specified by 'tcb' as soon as possible. + * + * This function may be called from interrupt handling logic. + * + * This operation should not cause the task to be unblocked + * nor should it cause any immediate execution of sigdeliver. + * Typically, a few cases need to be considered: + * + * (1) This function may be called from an interrupt handler + * During interrupt processing, all xcptcontext structures + * should be valid for all tasks. That structure should + * be modified to invoke sigdeliver() either on return + * from (this) interrupt or on some subsequent context + * switch to the recipient task. + * (2) If not in an interrupt handler and the tcb is NOT + * the currently executing task, then again just modify + * the saved xcptcontext structure for the recipient + * task so it will invoke sigdeliver when that task is + * later resumed. + * (3) If not in an interrupt handler and the tcb IS the + * currently executing task -- just call the signal + * handler now. + * + * Assumptions: + * Called from critical section + * + ****************************************************************************/ +irqstate_t flags; +void up_schedule_sigaction(struct tcb_s *tcb, sig_deliver_t sigdeliver) +{ + // uint32_t int_ctx; + + sinfo("tcb=0x%p sigdeliver=0x%p\n", tcb, sigdeliver); + + /* Make sure that interrupts are disabled */ + + flags = enter_critical_section(); + + /* Refuse to handle nested signal actions */ + + if (!tcb->xcp.sigdeliver) + { + /* First, handle some special cases when the signal is + * being delivered to the currently executing task. + */ + + sinfo("rtcb=0x%p g_current_regs=0x%p\n", + this_task(), g_current_regs); + + if (tcb == this_task()) + { + /* CASE 1: We are not in an interrupt handler and + * a task is signaling itself for some reason. + */ + + if (!g_current_regs) + { + /* In this case just deliver the signal now. */ + + sigdeliver(tcb); + } + + /* CASE 2: We are in an interrupt handler AND the + * interrupted task is the same as the one that + * must receive the signal, then we will have to modify + * the return state as well as the state in the TCB. + * + * Hmmm... there looks like a latent bug here: The following + * logic would fail in the strange case where we are in an + * interrupt handler, the thread is signaling itself, but + * a context switch to another task has occurred so that + * g_current_regs does not refer to the thread of this_task()! + */ + + else + { + /* Save the return EPC and STATUS registers. These will be + * restored by the signal trampoline after the signals have + * been delivered. + */ + + tcb->xcp.sigdeliver = sigdeliver; + tcb->xcp.saved_epc = g_current_regs[REG_EPC]; + + /* Then set up to vector to the trampoline with interrupts + * disabled + */ + + g_current_regs[REG_EPC] = (uint32_t)up_sigdeliver; + + /* And make sure that the saved context in the TCB + * is the same as the interrupt return context. + */ + + up_savestate(tcb->xcp.regs); + + // sinfo("PC/STATUS Saved: %08x/%08x New: %08x/%08x\n", + // tcb->xcp.saved_epc, tcb->xcp.saved_int_ctx, + // g_current_regs[REG_EPC], g_current_regs[REG_STATUS]); + } + } + + /* Otherwise, we are (1) signaling a task is not running + * from an interrupt handler or (2) we are not in an + * interrupt handler and the running task is signaling + * some non-running task. + */ + + else + { + /* Save the return EPC and STATUS registers. These will be + * restored by the signal trampoline after the signals have + * been delivered. + */ + + tcb->xcp.sigdeliver = sigdeliver; + tcb->xcp.saved_epc = tcb->xcp.regs[REG_EPC]; + + /* Then set up to vector to the trampoline with interrupts + * disabled + */ + + tcb->xcp.regs[REG_EPC] = (uint32_t)up_sigdeliver; + + // sinfo("PC/STATUS Saved: %08x/%08x New: %08x/%08x\n", + // tcb->xcp.saved_epc, tcb->xcp.saved_int_ctx, + // tcb->xcp.regs[REG_EPC], tcb->xcp.regs[REG_STATUS]); + } + } +} diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/interrupt.c b/Ubiquitous/XiUOS/arch/risc-v/gap8/interrupt.c new file mode 100755 index 00000000..74543e78 --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/interrupt.c @@ -0,0 +1,361 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_interrupt.c + * GAP8 event system + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * GAP8 features a FC controller and a 8-core cluster. IRQ from peripherals + * have unique ID, which are dispatched to the FC or cluster by the SOC + * event unit, and then by the FC event unit or cluster event unit, and + * finally to FC or cluster. Peripherals share the same IRQ entry. + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +volatile uint32_t *g_current_regs; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/* Function exported to the NuttX kernel */ + +void up_mdelay(unsigned int time) +{ + while (time--) + { + volatile int dummy = 200000; + while (dummy--) + { + } + } +} + +/**************************************************************************** + * Name: up_disable_irq + * + * Description: + * Disable the IRQ specified by 'irq'. Mind the Machine privilege. + * + ****************************************************************************/ + +int ArchDisableHwIrq(uint32_t irq_num) +{ + FCEU->MASK_IRQ_AND = (1UL << irq_num); +} +/**************************************************************************** + * Name: up_enable_irq + * + * Description: + * Enable the IRQ specified by 'irq'. Mind the Machine privilege. + * + ****************************************************************************/ + +int ArchEnableHwIrq(uint32_t irq_num) +{ + FCEU->MASK_IRQ_OR = (1 << irq_num); +} + + + + +/**************************************************************************** + * Name: up_ack_irq + * + * Description: + * Acknowledge the IRQ + * + ****************************************************************************/ + +static inline void up_ack_irq(int irq) +{ +} + +/**************************************************************************** + * Name: _current_privilege + * + * Description: + * Get the current privilege mode. 0x0 for user mode, and 0x3 for machine + * mode. + * + ****************************************************************************/ + +static inline uint32_t _current_privilege(void) +{ + uint32_t result; + + asm volatile ("csrr %0, 0xC10" : "=r" (result)); + + return result; +} +/**************************************************************************** + * Name: up_irq_restore + * + * Description: + * Restore previous IRQ mask state + * + ****************************************************************************/ + +static inline void up_irq_restore(unsigned int pri) +{ + if (_current_privilege()) + { + /* Machine mode - mstatus */ + + asm volatile("csrw 0x300, %0" : /* no output */ : "r" (pri)); + } + else + { + /* User mode - ustatus */ + + asm volatile("csrw 0x000, %0" : /* no output */ : "r" (pri)); + } +} +/**************************************************************************** + * Name: up_irq_save + * + * Description: + * Disable interrupt and return the current interrupt state. + * + ****************************************************************************/ + + x_base up_irq_save(void) +{ + x_base oldstat; + x_base newstat; + + if (_current_privilege()) + { + /* Machine mode: Unset MIE and UIE */ + + asm volatile ("csrr %0, 0x300": "=r" (oldstat)); + newstat = oldstat & ~(0x9); + asm volatile("csrw 0x300, %0" : /* no output */ : "r" (newstat)); + } + else + { + /* User mode: Unset UIE */ + + asm volatile ("csrr %0, 0x000": "=r" (oldstat)); + newstat = oldstat & ~(1L << 0); + asm volatile("csrw 0x000, %0" : /* no output */ : "r" (newstat)); + } + + return oldstat; +} +/**************************************************************************** + * Name: up_irq_save + * + * Description: + * Disable interrupt and return the current interrupt state. + * + ****************************************************************************/ + +x_base DisableLocalInterrupt(void) +{ + // x_base oldstat; + // x_base newstat; + + // if (_current_privilege()) + // { + // /* Machine mode: Unset MIE and UIE */ + // asm volatile("nop"); + // asm volatile ("csrr %0, 0x300": "=r" (oldstat)); + // newstat = oldstat & ~(0x9); + // asm volatile("csrw 0x300, %0" : /* no output */ : "r" (newstat)); + // } + // else + // { + // /* User mode: Unset UIE */ + + // asm volatile ("csrr %0, 0x000": "=r" (oldstat)); + // newstat = oldstat & ~(1L << 0); + // asm volatile("csrw 0x000, %0" : /* no output */ : "r" (newstat)); + // } + + // return oldstat; + + x_base level; + asm volatile("nop"); + asm volatile ("csrrci %0, mstatus, 8" : "=r"(level)); + + return level; +} + + + +/**************************************************************************** + * Name: up_irq_enable + * + * Description: + * Return the current interrupt state and enable interrupts + * + ****************************************************************************/ + +void EnableLocalInterrupt(x_base oldstat) +{ + x_base newstat; + + // if (_current_privilege()) + // { + // /* Machine mode: Set MIE and UIE */ + // asm volatile("nop"); + // asm volatile ("csrr %0, 0x300": "=r" (oldstat)); + // newstat = oldstat | (0x8); + // // asm volatile("csrw 0x300, %0" : /* no output */ : "r" (newstat)); + // asm volatile("csrw mstatus, %0" : /* no output */ : "r" (newstat)); + // } + // else + // { + // /* User mode: Set UIE */ + + // asm volatile ("csrr %0, 0x000": "=r" (oldstat)); + // newstat = oldstat | (1L << 0); + // asm volatile("csrw 0x000, %0" : /* no output */ : "r" (newstat)); + // } + asm volatile ("csrw mstatus, %0" :: "r"(oldstat)); +} + +/**************************************************************************** + * Name: gap8_sleep_wait_sw_evnt + * + * Description: + * Sleep on specific event. + * + ****************************************************************************/ + +// static inline void gap8_sleep_wait_sw_evnt(uint32_t event_mask) +// { +// FCEU->MASK_OR = event_mask; +// __builtin_pulp_event_unit_read((void *)&FCEU->EVENT_WAIT_CLEAR, 0); +// FCEU->MASK_AND = event_mask; +// } + +/**************************************************************************** + * Public Function Prototypes + * + + +/**************************************************************************** + * Name: up_get_newintctx + * + * Description: + * Return a value for EPIC. But GAP8 doesn't use EPIC for event control. + * + ****************************************************************************/ + +uint32_t up_get_newintctx(void) +{ + return 0; +} + +/**************************************************************************** + * Name: up_irqinitialize + * + * Description: + * Initialize the IRQ on FC. + * + ****************************************************************************/ +extern void gap8_udma_doirq(int irq, void *arg); +void irqinitialize(void) +{ + x_base level; + /* Deactivate all the soc events */ + + SOC_EU->FC_MASK_MSB = 0xffffffff; + SOC_EU->FC_MASK_LSB = 0xffffffff; + + /* enable soc peripheral interrupt */ + + isrManager.done->registerIrq(GAP8_IRQ_FC_UDMA, gap8_udma_doirq, NONE); + isrManager.done->enableIrq(GAP8_IRQ_FC_UDMA); + + /* Attach system call handler */ + + // extern int up_swint(int irq, FAR void *context, FAR void *arg); + // RegisterHwIrq(GAP8_IRQ_SYSCALL, up_swint, NULL); + + // EnableLocalInterrupt(0); +} + +/**************************************************************************** + * Name: gap8_dispatch_irq + * + * Description: + * Called from IRQ vectors. Input vector id. Return SP pointer, modified + * or not. + * + ****************************************************************************/ +extern void KTaskOsAssignAfterIrq(void *context); + +void *gap8_dispatch_irq(uint32_t vector, void *current_regs) +{ + /* Clear pending bit and trigger a software event. + * GAP8 would sleep on sw event 3 on up_idle(). + */ + + FCEU->BUFFER_CLEAR = (1 << vector); + EU_SW_EVNT_TRIG->TRIGGER_SET[3] = 0; + + /* Call nuttx kernel, which may change curr_regs, to perform + * a context switch + */ + + g_current_regs = current_regs; + // irq_dispatch(vector, current_regs); + + isrManager.done->incCounter(); + isrManager.done->handleIrq(vector); + + isrManager.done->decCounter(); + + KTaskOsAssignAfterIrq(current_regs); + + current_regs = (void *)g_current_regs; + g_current_regs = NONE; + + return current_regs; +} + + diff --git a/Ubiquitous/XiUOS/arch/risc-v/gap8/tick.c b/Ubiquitous/XiUOS/arch/risc-v/gap8/tick.c new file mode 100755 index 00000000..8aa23fdc --- /dev/null +++ b/Ubiquitous/XiUOS/arch/risc-v/gap8/tick.c @@ -0,0 +1,19 @@ +/* +* Copyright (c) 2020 AIIT XUOS Lab +* XiUOS is licensed under Mulan PSL v2. +* You can use this software according to the terms and conditions of the Mulan PSL v2. +* You may obtain a copy of Mulan PSL v2 at: +* http://license.coscl.org.cn/MulanPSL2 +* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND, +* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT, +* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE. +* See the Mulan PSL v2 for more details. +*/ +#include +static volatile unsigned long tick_cycles = 0; +int TickIsr(void) +{ + TickAndTaskTimesliceUpdate(); + + return 0; +} \ No newline at end of file diff --git a/Ubiquitous/XiUOS/board/gapuino/Kconfig b/Ubiquitous/XiUOS/board/gapuino/Kconfig new file mode 100755 index 00000000..9043127c --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/Kconfig @@ -0,0 +1,69 @@ +mainmenu "XiUOS Project Configuration" + +config BSP_DIR + string + option env="BSP_ROOT" + default "." + +config KERNEL_DIR + string + option env="KERNEL_ROOT" + default "../.." + +config BOARD_GAPUINO + bool + select ARCH_RISCV + default y + + +source "$KERNEL_DIR/arch/Kconfig" + +menu "gapuino feature" + source "$BSP_DIR/third_party_driver/Kconfig" + + menu "config default board resources" + menu "config board app name" + config BOARD_APP_NAME + string "config board app name" + default "/XiUOS_gapuino_app.bin" + endmenu + + menu "config board service table" + config SERVICE_TABLE_ADDRESS + hex "board service table address" + default 0x80100000 + endmenu + + menu "config hardware resources for connection" + if CONNECTION_COMMUNICATION_ETHERNET + config ETHERNET_UART_NAME + string "ethernet uart name" + default "/dev/uart3_dev3" + endif + if CONNECTION_COMMUNICATION_WIFI + config WIFI_UART_NAME + string "wifi uart name" + default "/dev/uart3_dev3" + endif + + endmenu + + endmenu + + config __STACKSIZE__ + int "stack size for interrupt" + default 4096 + +endmenu + + + + + +menu "Hardware feature" +source "$KERNEL_DIR/resources/Kconfig" +endmenu + +source "$KERNEL_DIR/Kconfig" + + diff --git a/Ubiquitous/XiUOS/board/gapuino/Makefile b/Ubiquitous/XiUOS/board/gapuino/Makefile new file mode 100755 index 00000000..12f41481 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/Makefile @@ -0,0 +1,6 @@ +SRC_FILES := board.c + +SRC_DIR := third_party_driver + + +include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/board/gapuino/README.txt b/Ubiquitous/XiUOS/board/gapuino/README.txt new file mode 100755 index 00000000..ee27958e --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/README.txt @@ -0,0 +1,89 @@ +README +====== + +gapuino is an evaluation board for GAP8, a 1+8-core DSP-like RISC-V +MCU. GAP8 features a RI5CY core called Fabric Controller(FC), and a +cluster of 8 RI5CY cores that runs at a bit slower speed. GAP8 is an +implementation of the opensource PULP platform, a Parallel-Ultra-Low- +Power design. + +The port is currently very minimal, though additional support may be +added in the future to address more of the board peripherals. + + Supported: + - USB UART (console port) + - uDMA on SOC domain + - FLL clock scaling + + Not supported: + - SPI, I2C, I2S, CPI, LVDS, Hyper-bus on the uDMA subsystem + - the sensor board + - the 8-core cluster + - the Hardware convolution engine + +See also: +gapuino board and the sensor board: +https://gwt-website-files.s3.amazonaws.com/gapuino_um.pdf +https://gwt-website-files.s3.amazonaws.com/gapuino_multisensor_um.pdf +GAP8 datasheet: +https://gwt-website-files.s3.amazonaws.com/gap8_datasheet.pdf + +Contents +======== + + - Environment Setup + - Configurations + - Execute + +Environment Setup +================= + First, setup the gap_sdk from GreenwavesTechnologies' github repo. + Follow the README to setup the toolchain and environment. + https://github.com/GreenWaves-Technologies/gap_sdk/ + +Configurations +============== + Each gapuino configuration is maintained in a sub-directory and can + be selected as follow: + + tools/configure.sh gapuino: + + Where is one of the following: + + nsh + --- + This is an NSH example that uses the UART connected to FT2232 as + the console. Default UART settings are 115200, 8N1. + +Execute +======= + You may download the ELF to the board by `plpbridge` in gap_sdk. + Remember to first `cd` to the gap_sdk/ and `source sourceme.sh`, so + that you have the $GAP_SDK_HOME environment variable. + + Use the following command to download and run the ELF through JTAG: + + $GAP_SDK_HOME/install/workstation/bin/plpbridge \ + --cable=ftdi@digilent --boot-mode=jtag --chip=gap \ + --binary=nuttx \ + load ioloop reqloop start wait + + As for debugging, the following command download the ELF and opens + a gdbserver on port 1234: + + $GAP_SDK_HOME/install/workstation/bin/plpbridge \ + --cable=ftdi@digilent --boot-mode=jtag --chip=gap \ + --binary=nuttx \ + load ioloop gdb wait + + And then launch the gdb on another terminal: + + riscv32-unknown-elf-gdb nuttx + ... + (gdb) target remote :1234 + Remote debugging using :1234 + IRQ_U_Vector_Base () at chip/startup_gap8.S:293 + 293 j reset_handler /* 32 */ + (gdb) + + And then enjoy yourself debugging with the CLI gdb :-) diff --git a/Ubiquitous/XiUOS/board/gapuino/board.c b/Ubiquitous/XiUOS/board/gapuino/board.c new file mode 100755 index 00000000..9cd99506 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/board.c @@ -0,0 +1,69 @@ +/* +* Copyright (c) 2020 AIIT XUOS Lab +* XiUOS is licensed under Mulan PSL v2. +* You can use this software according to the terms and conditions of the Mulan PSL v2. +* You may obtain a copy of Mulan PSL v2 at: +* http://license.coscl.org.cn/MulanPSL2 +* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND, +* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT, +* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE. +* See the Mulan PSL v2 for more details. +*/ + +/** +* @file board.c +* @brief support hifive1-rev-B-board init configure and start-up +* @version 1.0 +* @author AIIT XUOS Lab +* @date 2021-04-25 +*/ + +#include +#include +#include +#include + +extern void entry(void); +extern int InitHwUart(void); +extern void irqinitialize(void); +extern void timer_initialize(void); +extern void up_serialinit(void); + +extern unsigned int __bss_end__; + +extern void test_dma_txstart(char c, uint32_t size); +extern void test_gap8_uartinit(); +extern void gapuino_sysinit(void); + +void GapuinoStart(uint32_t mhartid) +{ + gapuino_sysinit(); + entry(); +} +void InitBoardHardware(void) +{ + x_base newstat; + x_base oldstat; + irqinitialize(); + + InitBoardMemory(MEMORY_START_ADDRESS, MEMORY_END_ADDRESS); + + InitHwUart(); + InstallConsole("uart0", "uart0_drv", "uart0_dev0"); + + // asm volatile("nop"); + // asm volatile ("csrr %0, 0x300": "=r" (oldstat)); + // newstat = oldstat | (0x8); + // asm volatile("csrw mstatus, %0" : /* no output */ : "r" (newstat)); + KPrintf("console init completed.\n"); + KPrintf("board initialization......\n"); + + timer_initialize(); + KPrintf("memory address range: [0x%08x - 0x%08x], size: %d\n", (x_ubase) MEMORY_START_ADDRESS, (x_ubase) MEMORY_END_ADDRESS, GAP8_SRAM_SIZE); + /* initialize memory system */ + + KPrintf("board init done.\n"); + KPrintf("start kernel...\n"); + return; +} + diff --git a/Ubiquitous/XiUOS/board/gapuino/board.h b/Ubiquitous/XiUOS/board/gapuino/board.h new file mode 100755 index 00000000..713e7bb3 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/board.h @@ -0,0 +1,85 @@ +/**************************************************************************** + * boards/risc-v/gap8/gapuino/include/board.h + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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 BOARD_H__ +#define BOARD_H__ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include + + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Public Data + ****************************************************************************/ + +#ifndef __ASSEMBLY__ + +#undef EXTERN +#if defined(__cplusplus) +#define EXTERN extern "C" +extern "C" +{ +#else +#define EXTERN extern +#endif + +extern unsigned int __bss_start__; +extern unsigned int __bss_end__; +extern unsigned int _end; +extern unsigned int __stack_end__; +extern unsigned int g_service_table_start; +extern unsigned int g_service_table_end; + +// #define MEMORY_START_ADDRESS (void*)(&__bss_end__) +#define MEMORY_START_ADDRESS (void*)(&_end) +#define GAP8_SRAM_SIZE 512 +#define MEMORY_END_ADDRESS (void*)(0x1C000000 + GAP8_SRAM_SIZE * 1024) + + +#undef EXTERN +#if defined(__cplusplus) +} +#endif +#endif + +#endif diff --git a/Ubiquitous/XiUOS/board/gapuino/config.mk b/Ubiquitous/XiUOS/board/gapuino/config.mk new file mode 100755 index 00000000..2e0fcc08 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/config.mk @@ -0,0 +1,38 @@ +# ARCHCFLAGS = -fno-builtin +# ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti +# ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 + +# ARCHOPTIMIZATION = -g +# ASARCHCPUFLAGS += -Wa,-g + +# ARCHCPUFLAGS = -march=rv32imcxgap8 -mPE=8 -mFC=1 -D__riscv__ -D__pulp__ -D__GAP8__ -fno-common -ffunction-sections -fdata-sections -fstrict-volatile-bitfields + +# export CFLAGS := $(ARCHCFLAGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) -O0 -g3 -gdwarf-2 + +# export AFLAGS := $(CFLAGS) -D__ASSEMBLY__ $(ASARCHCPUFLAGS) + +# export LFLAGS := -march=rv32imcxgap8 -mPE=8 -mFC=1 -nostartfiles -Wl,--gc-sections,-Map=XiUOS_gap8.map,-cref,-u,reset_handler -T $(BSP_ROOT)/link.lds + +# export APPLFLAGS := -march=rv32imcxgap8 -mPE=8 -mFC=1 -nostartfiles -Wl,--gc-sections,-Map=XiUOS_app.map,-cref,-u, -T $(BSP_ROOT)/link_userspace.lds + +# export CXXFLAGS := $(ARCHCXXFLAGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) + +# export CROSS_COMPILE ?=/opt/gap_riscv_toolchain/bin/riscv32-unknown-elf- + + +export CFLAGS := -mcmodel=medany -march=rv32imac -mabi=ilp32 -fno-common -ffunction-sections -fdata-sections -fstrict-volatile-bitfields -O0 -ggdb -fgnu89-inline -Werror +export AFLAGS := -c -mcmodel=medany -march=rv32imac -mabi=ilp32 -x assembler-with-cpp -ggdb +export LFLAGS := -mcmodel=medany -march=rv32imac -mabi=ilp32 -nostartfiles -Wl,--gc-sections,-Map=XiUOS_gap8.map,-cref,-u,_start -T $(BSP_ROOT)/link.lds + +export APPLFLAGS := -mcmodel=medany -march=rv32imac -mabi=ilp32 -nostartfiles -Wl,--gc-sections,-Map=XiUOS_app.map,-cref,-u, -T $(BSP_ROOT)/link_userspace.lds + +export CXXFLAGS := -mcmodel=medany -march=rv32imac -mabi=ilp32 -fno-common -ffunction-sections -fdata-sections -fstrict-volatile-bitfields -O0 -ggdb -Werror + +export CROSS_COMPILE ?=/opt/gnu-mcu-eclipse/riscv-none-gcc/8.2.0-2.1-20190425-1021/bin/riscv-none-embed- + +export DEFINES := -DHAVE_CCONFIG_H -DHAVE_SIGINFO + +export ARCH = risc-v +export MCU = GAP8 + + diff --git a/Ubiquitous/XiUOS/board/gapuino/link.lds b/Ubiquitous/XiUOS/board/gapuino/link.lds new file mode 100755 index 00000000..4414883a --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/link.lds @@ -0,0 +1,175 @@ +/**************************************************************************** + * boards/risc-v/gap8/gapuino/scripts/ld.script + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/* Not needed, but we need separate linker scripts anyway */ + +OUTPUT_ARCH( riscv ) +SEARCH_DIR(.) +__DYNAMIC = 0; + +MEMORY +{ + L2 (wxa!ri) : ORIGIN = 0x1C000000, LENGTH = 0x80000 + FC_tcdm : ORIGIN = 0x1B000004, LENGTH = 0x3ffc + FC_tcdm_aliased : ORIGIN = 0x00000004, LENGTH = 0x3ffc +} + +__L1_STACK_SIZE = 0x400; +__FC_STACK_SIZE = 4096; + +/* We have to align each sector to word boundaries as our current s19->slm + * conversion scripts are not able to handle non-word aligned sections. + */ +ENTRY( reset_handler ) +SECTIONS +{ + .vectors_M : + { + . = ALIGN(4); + IRQ_U_Vector_Base = .; + KEEP(*(.vectors_M)) + } > L2 + + .dbg_struct : + { + . = ALIGN(4); + IRQ_M_Vector_Base = .; + KEEP(*(.dbg_struct)) + } > L2 + + . = ALIGN(4); + + .text : { + PROVIDE( _text = ABSOLUTE(.) ); + /* _stext = .; */ + *(.text .text.*) + /* *(.rodata .rodata*) */ + /* _etext = .; */ + + /* section information for shell */ + . = ALIGN(4); + _shell_command_start = .; + KEEP (*(shellCommand)) + _shell_command_end = .; + . = ALIGN(4); + + PROVIDE(__ctors_start__ = .); + KEEP (*(SORT(.init_array.*))) + KEEP (*(.init_array)) + PROVIDE(__ctors_end__ = .); + + . = ALIGN(4); + __isrtbl_idx_start = .; + KEEP(*(.isrtbl.idx)) + __isrtbl_start = .; + KEEP(*(.isrtbl)) + __isrtbl_end = .; + . = ALIGN(4); + + PROVIDE(g_service_table_start = ABSOLUTE(.)); + KEEP(*(.g_service_table)) + PROVIDE(g_service_table_end = ABSOLUTE(.)); + + /* _endtext = .; */ + PROVIDE( _etext = ABSOLUTE(.) ); + } > L2 + + .rodata : { + /* Due to limitations on FPGA loader, loadable sections must have + * base and size aligned on 4 bytes + */ + + . = ALIGN(4); + *(.rodata); + *(.rodata.*) + . = ALIGN(4); + } > L2 + . = ALIGN(4); + .data : { + + __data_start__ = .; /* create a global symbol at data start */ + *(.data .data.*) + + . = ALIGN(4); + PROVIDE( __global_pointer$ = ABSOLUTE(.) + 0x800 ); + *(.sdata .sdata.*) + + __data_end__ = .; /* define a global symbol at data end */ + } > L2 + + . = ALIGN(4); + + .bss : + { + /* . = ALIGN(4); + _sbss = .; + __bss_start__ = .; + _fbss = .; + *(.bss) + *(.bss.*) + *(.sbss) + *(.sbss.*) + *(COMMON) + . = ALIGN(4); + __bss_end__ = .; + _ebss = .; */ + __bss_start = ABSOLUTE(.); + _fbss = .; + + /* Writable uninitialized small data segment (.sbss segment)*/ + *(.sbss .sbss.*) + *(.scommon) + + /* Uninitialized writeable data section (.bss segment)*/ + *(.bss .bss.*) + *(COMMON) + + . = ALIGN(4); + __bss_end = ABSOLUTE(.); + + } > L2 + + .stack : + { + . = ALIGN(4); + PROVIDE(_idle_stack_start = ABSOLUTE(.)); + + . = . + __FC_STACK_SIZE; + + PROVIDE( _idle_stack_end = ABSOLUTE(.) ); + } > L2 + _end = ABSOLUTE(.); + +} diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/Kconfig b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/Kconfig new file mode 100755 index 00000000..1e9a497d --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/Kconfig @@ -0,0 +1,33 @@ +menuconfig BSP_USING_GPIO + bool "Using GPIO device" + default y + select RESOURCES_PIN + if BSP_USING_GPIO + source "$BSP_DIR/third_party_driver/gpio/Kconfig" + endif + +menuconfig BSP_USING_SYSCLOCK + bool "Using SYSCLOCK device" + default y + if BSP_USING_SYSCLOCK + source "$BSP_DIR/third_party_driver/sys_clock/Kconfig" + endif + +menuconfig BSP_USING_HWTIMER + bool "Using HWTIMER device" + default n + select RESOURCES_HWTIMER + if BSP_USING_HWTIMER + source "$BSP_DIR/third_party_driver/timer/Kconfig" + endif + +menuconfig BSP_USING_UART + bool "Using UART device" + default y + select RESOURCES_SERIAL + if BSP_USING_UART + source "$BSP_DIR/third_party_driver/uart/Kconfig" + endif + + + \ No newline at end of file diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/Makefile b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/Makefile new file mode 100755 index 00000000..03af9c3f --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/Makefile @@ -0,0 +1,28 @@ +SRC_FILES := + +ifeq ($(CONFIG_BSP_USING_DMA),y) + SRC_DIR += udma +endif + +ifeq ($(CONFIG_BSP_USING_GPIO),y) + SRC_DIR += gpio +endif + +ifeq ($(CONFIG_BSP_USING_PLIC),y) + SRC_DIR += plic +endif + +ifeq ($(CONFIG_BSP_USING_SYSCLOCK),y) + SRC_DIR += sys_clock +endif + +ifeq ($(CONFIG_BSP_USING_HWTIMER),y) + SRC_DIR += timer +endif + +ifeq ($(CONFIG_BSP_USING_UART),y) + SRC_DIR += uart +endif + + +include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Kconfig b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Kconfig new file mode 100755 index 00000000..35dce739 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Kconfig @@ -0,0 +1,11 @@ +config PIN_BUS_NAME + string "pin bus name" + default "pin" + +config PIN_DRIVER_NAME + string "pin driver name" + default "pin_drv" + +config PIN_DEVICE_NAME + string "pin device name" + default "pin_dev" diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Makefile b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Makefile new file mode 100755 index 00000000..0eb74832 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/Makefile @@ -0,0 +1,3 @@ +SRC_FILES := hardware_gpio.c + +include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/hardware_gpio.c b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/hardware_gpio.c new file mode 100755 index 00000000..477283f6 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/gpio/hardware_gpio.c @@ -0,0 +1,218 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_gpio.c + * GAP8 FLL clock generator + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * GAP8 has only 1 port. Each pin could be configured to GPIO or alternative + * functions. + ****************************************************************************/ + +/** +* @file hardware_gpio.c +* @brief add from Gap8 riscv SDK +* https://greenwavesdev2.wpengine.com/sdk-manuals/ +* @version 1.1 +* @author AIIT XUOS Lab +* @date 2021-07-27 +*/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "hardware_gpio.h" + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gap8_configpin + * + * Description: + * Configure a pin based on bit-encoded description of the pin. + * + * GPIO software abstraction: bitmap configuration of pins + * + * |31 18| 17 | 16 | 15 |14 10|9 8|7 0| + * | --- | drive | pull-up/OD | I/O | GPIOn | alt | pinnum | + * | --- | 1-bit | 1-bit | 1-b | 5-bit | 2-bit | 8-bit | + * + * Returned Value: + * OK on success + * ERROR on invalid pin. + * + ****************************************************************************/ + +int gap8_configpin(uint32_t cfgset) +{ + uint32_t pinnum = cfgset & 0xff; + uint32_t altfunc = (cfgset >> 8) & 0x3; + uint32_t pin_dr_pu = (cfgset >> 16) & 0x3; + uint32_t port_cfg_reg; + uint32_t pin_alt_reg; + int shiftcnt; + + if (pinnum > MAX_PIN_NUM) + { + return -1; + } + + /* Set pin drive strength (or pin speed in other words) and pulling + * If it's a GPIO, set input or output. + * + * Note that GPIO and non-GPIO uses different register sets... + * And all the GPIO functions are mapped to ALT-1, and ALT-1 contains + * only GPIO functions... + */ + + port_cfg_reg = PORTA->PADCFG[pinnum >> 2]; + shiftcnt = (pinnum & 0x3) << 3; + port_cfg_reg &= ~(0x3 << shiftcnt); + port_cfg_reg |= pin_dr_pu << shiftcnt; + PORTA->PADCFG[pinnum >> 2] = port_cfg_reg; + + if (altfunc == 1) + { + uint32_t gpio_n = (cfgset >> 10) & 0x1f; + uint32_t gpio_dir = (cfgset >> 15) & 0x1; + uint32_t tmp; + + /* It must be a GPIO */ + + GPIOA->EN |= (1L << gpio_n); + + tmp = GPIOA->PADCFG[gpio_n >> 2]; + shiftcnt = (gpio_n & 0x3) << 3; + tmp &= ~(0x3 << shiftcnt); + tmp |= pin_dr_pu << shiftcnt; + GPIOA->PADCFG[gpio_n >> 2] = tmp; + + tmp = GPIOA->DIR; + tmp &= ~(1L << gpio_n); + tmp |= gpio_dir << gpio_n; + GPIOA->DIR = tmp; + } + + /* Set pin alternative function */ + + pin_alt_reg = PORTA->PADFUN[pinnum >> 4]; + shiftcnt = (pinnum & 0xf) << 1; + pin_alt_reg &= ~(0x3 << shiftcnt); + pin_alt_reg |= altfunc << shiftcnt; + PORTA->PADFUN[pinnum >> 4] = pin_alt_reg; + + return 0; +} + +/**************************************************************************** + * Name: gap8_gpiowrite + * + * Description: + * Write one or zero to the selected GPIO pin + * + * Bit encoded pinset: + * + * |31 15|14 10|9 0| + * | --- | GPIOn | --- | + * | --- | 5-bit | --- | + * + ****************************************************************************/ + +void gap8_gpiowrite(uint32_t pinset, bool value) +{ + uint32_t gpio_n = (pinset >> 10) & 0x1f; + if (value) + { + GPIOA->OUT |= (1L << gpio_n); + } + else + { + GPIOA->OUT &= ~(1L << gpio_n); + } +} + +/**************************************************************************** + * Name: gap8_gpioread + * + * Description: + * Read one or zero from the selected GPIO pin + * + * Bit encoded pinset: + * + * |31 15|14 10|9 0| + * | --- | GPIOn | --- | + * | --- | 5-bit | --- | + * + ****************************************************************************/ + +bool gap8_gpioread(uint32_t pinset) +{ + uint32_t gpio_n = (pinset >> 10) & 0x1f; + return (GPIOA->IN >> gpio_n) & 0x1; +} + +/**************************************************************************** + * Name: gap8_gpioirqset + * + * Description: + * Enable or disable interrupt on GPIO + * + * Bit encoded pinset: + * + * |31 20|19 18|17 15|14 10|9 0| + * | --- | int-typ | --- | GPIOn | --- | + * | --- | 2-bit | --- | 5-bit | --- | + * + ****************************************************************************/ + +void gap8_gpioirqset(uint32_t pinset, bool enable) +{ + uint32_t gpio_n = (pinset >> 10) & 0x1f; + uint32_t int_type = (pinset >> 18) * 0x3; + uint32_t tmp; + uint32_t shitfcnt; + + if (enable) + { + shitfcnt = (gpio_n & 0xf) << 1; + tmp = GPIOA->INTCFG[gpio_n >> 4]; + tmp &= ~(0x3 << shitfcnt); + tmp |= int_type << shitfcnt; + GPIOA->INTCFG[gpio_n >> 4] = tmp; + + GPIOA->INTEN |= (1L << gpio_n); + } +} diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/connect_uart.h b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/connect_uart.h new file mode 100755 index 00000000..1bfa4568 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/connect_uart.h @@ -0,0 +1,38 @@ +/* +* Copyright (c) 2020 AIIT XUOS Lab +* XiUOS is licensed under Mulan PSL v2. +* You can use this software according to the terms and conditions of the Mulan PSL v2. +* You may obtain a copy of Mulan PSL v2 at: +* http://license.coscl.org.cn/MulanPSL2 +* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND, +* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT, +* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE. +* See the Mulan PSL v2 for more details. +*/ + +/** +* @file connect_uart.h +* @brief define gap8-board uart function and struct +* @version 1.1 +* @author AIIT XUOS Lab +* @date 2021-07-27 +*/ + +#ifndef CONNECT_UART_H +#define CONNECT_UART_H + +#include + +#ifdef __cplusplus +extern "C" { +#endif + + + +int InitHwUart(void); + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_fll.h b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_fll.h new file mode 100755 index 00000000..26e8a4f5 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_fll.h @@ -0,0 +1,75 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_fll.h + * GAP8 FLL clock generator + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * FC can run up to 250MHz@1.2V, and 150MHz@1.0V. While the default voltage + * of PMU is 1.2V, it's okay to boost up without considering PMU. + ****************************************************************************/ + +#ifndef __ARCH_RISC_V_SRC_GAP8_FLL_H +#define __ARCH_RISC_V_SRC_GAP8_FLL_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "gap8.h" + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: gap8_setfreq + * + * Description: + * Set frequency up to 250MHz. Input frequency in Hz. + * + ****************************************************************************/ + +void gap8_setfreq(uint32_t frequency); + +/**************************************************************************** + * Name: gap8_getfreq + * + * Description: + * Get current system clock frequency in Hz. + * + ****************************************************************************/ + +uint32_t gap8_getfreq(void); + +#endif /* __ARCH_RISC_V_SRC_GAP8_FLL_H */ diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_tim.h b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_tim.h new file mode 100755 index 00000000..581c6272 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_tim.h @@ -0,0 +1,87 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_tim.h + * PIN driver for GAP8 + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * GAP8 features a 64-bit basic timer, able to split into 2 32-bit timers, + * with identicle memory map and 2 IRQ channels, for both FC core and + * cluster. We would use it as system timer. + ****************************************************************************/ + +#ifndef __ARCH_RISC_V_SRC_GAP8_TIM_H +#define __ARCH_RISC_V_SRC_GAP8_TIM_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "gap8.h" + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Name: gap8_timer_initialize + * + * Description: + * Initialize the timer based on the frequency of source clock and ticks + * per second. + * + ****************************************************************************/ + +void gap8_timer_initialize(uint32_t source_clock, uint32_t tick_per_second); + +/**************************************************************************** + * Name: gap8_register_timercallback + * + * Description: + * Register a callback function called on timer IRQ + * + ****************************************************************************/ + +void gap8_register_timercallback(void (*on_timer)(void*arg), void *arg); + +/**************************************************************************** + * Name: gap8_timer_isr + * + * Description: + * ISR for timer + * + ****************************************************************************/ + +void gap8_timer_isr(void); + +#endif /* __ARCH_RISC_V_SRC_GAP8_TIM_H */ diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_uart.h b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_uart.h new file mode 100755 index 00000000..108c6997 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/gap8_uart.h @@ -0,0 +1,70 @@ +/************************************************************************************ + * arch/risc-v/src/gap8/gap8_uart.h + * UART driver on uDMA subsystem for GAP8 + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * This UART IP has no flow control. So ioctl is limited. + ************************************************************************************/ + +#ifndef _ARCH_RISCV_SRC_GAP8_UART_H +#define _ARCH_RISCV_SRC_GAP8_UART_H + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include "gap8.h" +#include "gap8_udma.h" +#include "gap8_gpio.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +#define GAP8_NR_UART 1 + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +void up_earlyserialinit(void); +void up_serialinit(void); +int up_putc(int ch); + +#endif /* _ARCH_RISCV_SRC_GAP8_UART_H */ diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_gpio.h b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_gpio.h new file mode 100755 index 00000000..b43274f5 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_gpio.h @@ -0,0 +1,305 @@ +/************************************************************************************ + * arch/risc-v/src/gap8/gap8_gpio.h + * PIN driver for GAP8 + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * GAP8 has only 1 port. Each pin could be configured to GPIO or alternative + * functions. + ************************************************************************************/ + +#ifndef __HARDWARE_GPIO_H__ +#define __HARDWARE_GPIO_H__ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include +#include +#include + +#include "gap8.h" + +/************************************************************************************ + * Pre-Processor Definitions + ************************************************************************************/ + +#define MAX_PIN_NUM 47 + +/* GPIO software abstraction: bitmap configuration of pins + * + * |31 20|19 18| 17 | 16 | 15 |14 10|9 8|7 0| + * | --- | int-typ | drive | pull-up/OD | I/O | GPIOn | alt | pinnum | + * | --- | 2-bit | 1-bit | 1-bit | 1-b | 5-bit | 2-bit | 8-bit | + */ + +#define GAP8_GPIO_INT_FALLING (0L << 18) +#define GAP8_GPIO_INT_RISING (1L << 18) +#define GAP8_GPIO_INT_RISING_AND_FALLING (2L << 18) + +#define GAP8_PIN_SPEED_HIGH (1L << 17) +#define GAP8_PIN_SPEED_LOW (0L << 17) + +#define GAP8_PIN_PULL_UP (1L << 16) +#define GAP8_PIN_PULL_NONE (0L << 16) + +#define GAP8_GPIO_INPUT (0L << 15) +#define GAP8_GPIO_OUTPUT (1L << 15) + +#define GAP8_PIN_A4_SPIM1_MISO ((0L << 8) | 0) +#define GAP8_PIN_A4_GPIOA0 ((1L << 8) | (0L << 10) | 0) + +#define GAP8_PIN_B3_SPIM1_MOSI ((0L << 8) | 1) +#define GAP8_PIN_B3_GPIOA1 ((1L << 8) | (1L << 10) | 1) + +#define GAP8_PIN_A5_SPIM1_CS0 ((0L << 8) | 2) +#define GAP8_PIN_A5_GPIOA2 ((1L << 8) | (2L << 10) | 2) +#define GAP8_PIN_A5_I2C1_SDA ((2L << 8) | 2) + +#define GAP8_PIN_B4_SPIM1_SCK ((0L << 8) | 3) +#define GAP8_PIN_B4_GPIOA3 ((1L << 8) | (3L << 10) | 3) +#define GAP8_PIN_B4_I2C1_SCL ((2L << 8) | 3) + +#define GAP8_PIN_A3_ORCA_TXSYNC ((0L << 8) | 4) +#define GAP8_PIN_A3_GPIOA0 ((1L << 8) | (0L << 10) | 4) +#define GAP8_PIN_A3_SPIM1_CS0 ((2L << 8) | 4) + +#define GAP8_PIN_B2_ORCA_RXSYNC ((0L << 8) | 5) +#define GAP8_PIN_B2_GPIOA1 ((1L << 8) | (1L << 10) | 5) +#define GAP8_PIN_B2_SPIM1_CS1 ((2L << 8) | 5) + +#define GAP8_PIN_A2_ORCA_TX1 ((0L << 8) | 6) +#define GAP8_PIN_A2_GPIOA2 ((1L << 8) | (2L << 10) | 6) + +#define GAP8_PIN_B1_ORCA_TXQ ((0L << 8) | 7) +#define GAP8_PIN_B1_GPIOA3 ((1L << 8) | (3L << 10) | 7) + +#define GAP8_PIN_A44_ORCA_RXI ((0L << 8) | 8) +#define GAP8_PIN_A44_GPIOA4 ((1L << 8) | (4L << 10) | 8) +#define GAP8_PIN_A44_SPIS0_D0 ((2L << 8) | 8) +#define GAP8_PIN_A44_SPIS0_D2 ((3L << 8) | 8) + +#define GAP8_PIN_B40_ORCA_RXQ ((0L << 8) | 9) +#define GAP8_PIN_B40_GPIOA5 ((1L << 8) | (5L << 10) | 9) +#define GAP8_PIN_B40_SPIS0_D1 ((2L << 8) | 9) +#define GAP8_PIN_B40_SPIS0_D3 ((3L << 8) | 9) + +#define GAP8_PIN_A43_CAM_PCLK ((0L << 8) | 10) +#define GAP8_PIN_A43_GPIOA4 ((1L << 8) | (4L << 10) | 10) +#define GAP8_PIN_A43_TIM1_CH0 ((2L << 8) | 10) + +#define GAP8_PIN_A37_CAM_HSYNC ((0L << 8) | 11) +#define GAP8_PIN_A37_GPIOA5 ((1L << 8) | (5L << 10) | 11) +#define GAP8_PIN_A37_TIM1_CH1 ((2L << 8) | 11) + +#define GAP8_PIN_B39_CAM_D0 ((0L << 8) | 12) +#define GAP8_PIN_B39_GPIOA6 ((1L << 8) | (6L << 10) | 12) +#define GAP8_PIN_B39_TIM1_CH2 ((2L << 8) | 12) + +#define GAP8_PIN_A42_CAM_D1 ((0L << 8) | 13) +#define GAP8_PIN_A42_GPIOA7 ((1L << 8) | (7L << 10) | 13) +#define GAP8_PIN_A42_TIM1_CH3 ((2L << 8) | 13) + +#define GAP8_PIN_B38_CAM_D2 ((0L << 8) | 14) +#define GAP8_PIN_B38_GPIOA8 ((1L << 8) | (8L << 10) | 14) +#define GAP8_PIN_B38_TIM2_CH0 ((2L << 8) | 14) + +#define GAP8_PIN_A41_CAM_D3 ((0L << 8) | 15) +#define GAP8_PIN_A41_GPIOA9 ((1L << 8) | (9L << 10) | 15) +#define GAP8_PIN_A41_TIM2_CH1 ((2L << 8) | 15) + +#define GAP8_PIN_B37_CAM_D4 ((0L << 8) | 16) +#define GAP8_PIN_B37_GPIOA10 ((1L << 8) | (10L << 10) | 16) +#define GAP8_PIN_B37_TIM2_CH2 ((2L << 8) | 16) + +#define GAP8_PIN_A40_CAM_D5 ((0L << 8) | 17) +#define GAP8_PIN_A40_GPIOA11 ((1L << 8) | (11L << 10) | 17) +#define GAP8_PIN_A40_TIM2_CH3 ((2L << 8) | 17) + +#define GAP8_PIN_B36_CAM_D6 ((0L << 8) | 18) +#define GAP8_PIN_B36_GPIOA12 ((1L << 8) | (12L << 10) | 18) +#define GAP8_PIN_B36_TIM3_CH0 ((2L << 8) | 18) + +#define GAP8_PIN_A38_CAM_D7 ((0L << 8) | 19) +#define GAP8_PIN_A38_GPIOA13 ((1L << 8) | (13L << 10) | 19) +#define GAP8_PIN_A38_TIM3_CH1 ((2L << 8) | 19) + +#define GAP8_PIN_A36_CAM_VSYNC ((0L << 8) | 20) +#define GAP8_PIN_A36_GPIOA14 ((1L << 8) | (14L << 10) | 20) +#define GAP8_PIN_A36_TIM3_CH2 ((2L << 8) | 20) + +#define GAP8_PIN_B34_I2C1_SDA ((0L << 8) | 21) +#define GAP8_PIN_B34_GPIOA15 ((1L << 8) | (15L << 10) | 21) +#define GAP8_PIN_B34_TIM3_CH3 ((2L << 8) | 21) + +#define GAP8_PIN_D1_I2C1_SCL ((0L << 8) | 22) +#define GAP8_PIN_D1_GPIOA16 ((1L << 8) | (16L << 10) | 22) +#define GAP8_PIN_D1_ORCA_CLK ((2L << 8) | 22) + +#define GAP8_PIN_B11_TIM0_CH0 ((0L << 8) | 23) +#define GAP8_PIN_B11_GPIOA17 ((1L << 8) | (17L << 10) | 23) + +#define GAP8_PIN_A13_TIM0_CH1 ((0L << 8) | 24) +#define GAP8_PIN_A13_GPIOA18 ((1L << 8) | (18L << 10) | 24) +#define GAP8_PIN_A13_TIM1_CH0 ((2L << 8) | 24) + +#define GAP8_PIN_B12_TIM0_CH2 ((0L << 8) | 25) +#define GAP8_PIN_B12_GPIOA19 ((1L << 8) | (19L << 10) | 25) +#define GAP8_PIN_B12_TIM2_CH0 ((2L << 8) | 25) + +#define GAP8_PIN_A14_TIM0_CH3 ((0L << 8) | 26) +#define GAP8_PIN_A14_GPIOA20 ((1L << 8) | (20L << 10) | 26) +#define GAP8_PIN_A14_TIM3_CH0 ((2L << 8) | 26) + +#define GAP8_PIN_B13_I2S1_SCK ((0L << 8) | 27) +#define GAP8_PIN_B13_GPIOA21 ((1L << 8) | (21L << 10) | 27) +#define GAP8_PIN_B13_SPIS0_SCK ((2L << 8) | 27) +#define GAP8_PIN_B13_I2S1_SDI ((3L << 8) | 27) + +#define GAP8_PIN_A15_I2S1_WS ((0L << 8) | 28) +#define GAP8_PIN_A15_GPIOA22 ((1L << 8) | (22L << 10) | 28) +#define GAP8_PIN_A15_SPIS0_CS ((2L << 8) | 28) +#define GAP8_PIN_A15_HYPER_CKN ((3L << 8) | 28) + +#define GAP8_PIN_B14_I2S1_SDI ((0L << 8) | 29) +#define GAP8_PIN_B14_GPIOA23 ((1L << 8) | (23L << 10) | 29) +#define GAP8_PIN_B14_SPIS0_D2 ((2L << 8) | 29) +#define GAP8_PIN_B14_HYPER_CK ((3L << 8) | 29) + +#define GAP8_PIN_B6_UART_RX ((0L << 8) | 30) +#define GAP8_PIN_B6_GPIOA24 ((1L << 8) | (24L << 10) | 30) + +#define GAP8_PIN_A7_UART_TX ((0L << 8) | 31) +#define GAP8_PIN_A7_GPIOA25 ((1L << 8) | (25L << 10) | 31) + +#define GAP8_PIN_D2_SPIM0_D0 ((0L << 8) | 32) +#define GAP8_PIN_D2_HYPER_D0 ((3L << 8) | 32) + +#define GAP8_PIN_A11_SPIM0_D1 ((0L << 8) | 33) +#define GAP8_PIN_A11_HYPER_D1 ((3L << 8) | 33) + +#define GAP8_PIN_B10_SPIM0_D2 ((0L << 8) | 34) +#define GAP8_PIN_B10_GPIOA26 ((1L << 8) | (26L << 10) | 34) +#define GAP8_PIN_B10_I2C1_SDA ((2L << 8) | 34) +#define GAP8_PIN_B10_HYPER_D2 ((3L << 8) | 34) + +#define GAP8_PIN_A10_SPIM0_D3 ((0L << 8) | 35) +#define GAP8_PIN_A10_GPIOA27 ((1L << 8) | (27L << 10) | 35) +#define GAP8_PIN_A10_I2C1_SCL ((2L << 8) | 35) +#define GAP8_PIN_A10_HYPER_D3 ((3L << 8) | 35) + +#define GAP8_PIN_B8_SPIM0_CS0 ((0L << 8) | 36) +#define GAP8_PIN_B8_HYPER_D4 ((3L << 8) | 36) + +#define GAP8_PIN_A8_SPIM0_CS1 ((0L << 8) | 37) +#define GAP8_PIN_A8_GPIOA28 ((1L << 8) | (28L << 10) | 37) +#define GAP8_PIN_A8_SPIS0_D3 ((2L << 8) | 37) +#define GAP8_PIN_A8_HYPER_D5 ((3L << 8) | 37) + +#define GAP8_PIN_B7_SPIM0_SCK ((0L << 8) | 38) +#define GAP8_PIN_B7_HYPER_D6 ((3L << 8) | 38) + +#define GAP8_PIN_A9_SPIS0_CS ((0L << 8) | 39) +#define GAP8_PIN_A9_GPIOA29 ((1L << 8) | (29L << 10) | 39) +#define GAP8_PIN_A9_SPIM1_CS0 ((2L << 8) | 39) +#define GAP8_PIN_A9_HYPER_D7 ((3L << 8) | 39) + +#define GAP8_PIN_B15_SPIS0_D0 ((0L << 8) | 40) +#define GAP8_PIN_B15_GPIOA30 ((1L << 8) | (30L << 10) | 40) +#define GAP8_PIN_B15_SPIM1_CS1 ((2L << 8) | 40) +#define GAP8_PIN_B15_HYPER_CS0 ((3L << 8) | 40) + +#define GAP8_PIN_A16_SPIS0_D1 ((0L << 8) | 41) +#define GAP8_PIN_A16_GPIOA31 ((1L << 8) | (31L << 10) | 41) +#define GAP8_PIN_A16_HYPER_CS1 ((3L << 8) | 41) + +#define GAP8_PIN_B9_SPIS0_SCK ((0L << 8) | 42) +#define GAP8_PIN_B9_HYPER_RWDS ((3L << 8) | 42) + +#define GAP8_PIN_B22_I2C0_SDA ((0L << 8) | 43) +#define GAP8_PIN_A25_I2C0_SCL ((0L << 8) | 44) +#define GAP8_PIN_A24_I2S0_SCK ((0L << 8) | 45) +#define GAP8_PIN_A26_I2S0_WS ((0L << 8) | 46) +#define GAP8_PIN_B23_I2S0_SDI ((0L << 8) | 47) + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: gap8_configpin + * + * Description: + * Configure a pin based on bit-encoded description of the pin. + * + * Returned Value: + * OK on success + * ERROR on invalid port, or when pin is locked as ALT function. + * + ************************************************************************************/ + +int gap8_configpin(uint32_t cfgset); + +/************************************************************************************ + * Name: gap8_gpiowrite + * + * Description: + * Write one or zero to the selected GPIO pin + * + ************************************************************************************/ + +void gap8_gpiowrite(uint32_t pinset, bool value); + +/************************************************************************************ + * Name: gap8_gpioread + * + * Description: + * Read one or zero from the selected GPIO pin + * + ************************************************************************************/ + +bool gap8_gpioread(uint32_t pinset); + +/************************************************************************************ + * Name: gap8_gpioirqset + * + * Description: + * Enable or disable interrupt on GPIO + * + ************************************************************************************/ + +void gap8_gpioirqset(uint32_t pinset, bool enable); + +#endif /* _ARCH_RISCV_SRC_GAP8_GPIO_H */ diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_udma.h b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_udma.h new file mode 100755 index 00000000..859f8948 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/include/hardware_udma.h @@ -0,0 +1,234 @@ +/************************************************************************************ + * arch/risc-v/src/gap8/gap8_udma.h + * uDMA driver for GAP8 + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ************************************************************************************/ + +/************************************************************************************ + * GAP8 features a simple uDMA subsystem. Peripherals including UART, SPI, I2C, I2S, + * CPI, LVDS, Hyperbus, have config registers memory-mapped, but not data registers. + * The only way to send or receive data is using the uDMA. These peripherals share + * the same uDMA ISR. + * + * uDMA subsystem drivers are object oriented to some extend. Peripherals inherit + * the udma class, which handles all the data exchange stuff. + ************************************************************************************/ + +/** +* @file hardware_udma.h +* @brief add from Gap8 riscv SDK +* https://greenwavesdev2.wpengine.com/sdk-manuals/ +* @version 1.1 +* @author AIIT XUOS Lab +* @date 2021-07-27 +*/ + +#ifndef __HARDWARE_UDMA_H__ +#define __HARDWARE_UDMA_H__ + +/************************************************************************************ + * Included Files + ************************************************************************************/ + +#include + +#include "gap8.h" + +/************************************************************************************ + * Pre-processor Definitions + ************************************************************************************/ + +/* uDMA channel ID */ + +#define GAP8_UDMA_ID_LVDS 0 +#define GAP8_UDMA_ID_SPIM0 1 +#define GAP8_UDMA_ID_SPIM1 2 +#define GAP8_UDMA_ID_HYPER 3 +#define GAP8_UDMA_ID_UART 4 +#define GAP8_UDMA_ID_I2C0 5 +#define GAP8_UDMA_ID_I2C1 6 +#define GAP8_UDMA_ID_TCDM 7 /* l2 to fc-l1 */ +#define GAP8_UDMA_ID_I2S 8 +#define GAP8_UDMA_ID_CPI 9 + +/* Total udma channels */ + +#define GAP8_UDMA_NR_CHANNELS 10 + +/************************************************************************************ + * Public Types + ************************************************************************************/ + +/* Software abstraction for uDMA */ + +/* One round of data exchange on one channel gathered into linked list because + * threads would request for data exchange simultaneously. + * Private for udma driver. + */ + +struct __udma_queue +{ + uint8_t *buff; /* Memory address. either TX or RX */ + uint32_t block_size; /* Size of a data block in bytes */ + int block_count; /* Number of blocks to send or recv */ +}; + +/* This is the base class of uDMA subsystem. Peripherals connected to uDMA + * should inherited this class. + */ + +struct gap8_udma_peripheral +{ + /* Public */ + + udma_reg_t *regs; /* Hardware config regs */ + uint32_t id; /* GAP8_UDMA_ID_x */ + void (*on_tx)(void *arg); /* tx callback */ + void (*on_rx)(void *arg); /* rx callback */ + void *tx_arg; /* tx argument */ + void *rx_arg; /* rx argument */ + uint16_t is_tx_continous; + uint16_t is_rx_continous; + + /* Private */ + + struct __udma_queue tx; /* TX queue */ + struct __udma_queue rx; /* RX queue */ +}; + +/************************************************************************************ + * Public Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Name: gap8_udma_init + * + * Description: + * Initialize (and enable) a udma peripheral. + * + * Input: + * instance: pointer to a peripheral instance connected to uDMA + * + ************************************************************************************/ + +int gap8_udma_init(struct gap8_udma_peripheral *instance); + +/************************************************************************************ + * Name: gap8_udma_deinit + * + * Description: + * Deinit a udma peripheral + * + ************************************************************************************/ + +int gap8_udma_deinit(struct gap8_udma_peripheral *instance); + +/************************************************************************************ + * Name: gap8_udma_tx_setirq + * + * Description: + * Enable or disable the tx interrupt. + * + ************************************************************************************/ + +int gap8_udma_tx_setirq(struct gap8_udma_peripheral *instance, bool enable); + +/************************************************************************************ + * Name: gap8_udma_rx_setirq + * + * Description: + * Enable or disable the rx interrupt. + * + ************************************************************************************/ + +int gap8_udma_rx_setirq(struct gap8_udma_peripheral *instance, bool enable); + +/************************************************************************************ + * Name: gap8_udma_tx_start + * + * Description: + * Send size * count bytes non-blocking. + * + * Return ERROR if unable to send. The caller should poll on execution, or register + * a on_tx to get the signal. + * + ************************************************************************************/ + +int gap8_udma_tx_start(struct gap8_udma_peripheral *instance, + uint8_t *buff, uint32_t size, int count); + +/************************************************************************************ + * Name: gap8_udma_rx_start + * + * Description: + * Receive size * count bytes + * + * Return ERROR if unable to send. The caller should poll on execution, or register + * a on_rx to get the signal. + * + ************************************************************************************/ + +int gap8_udma_rx_start(struct gap8_udma_peripheral *instance, + uint8_t *buff, uint32_t size, int count); + +/************************************************************************************ + * Name: gap8_udma_tx_poll + * + * Description: + * Return OK if tx finished. + * + ************************************************************************************/ + +int gap8_udma_tx_poll(struct gap8_udma_peripheral *instance); + +/************************************************************************************ + * Name: gap8_udma_rx_poll + * + * Description: + * Return OK if rx finished. + * + ************************************************************************************/ + +int gap8_udma_rx_poll(struct gap8_udma_peripheral *instance); + +/************************************************************************************ + * Name: gap8_udma_doirq + * + * Description: + * uDMA ISR + * + ************************************************************************************/ + +int gap8_udma_doirq(int irq, void *context, void *arg); + +#endif /* _ARCH_RISCV_SRC_GAP8_UDMA_H */ diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Kconfig b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Kconfig new file mode 100755 index 00000000..8b137891 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Kconfig @@ -0,0 +1 @@ + diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Makefile b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Makefile new file mode 100755 index 00000000..ed938c8c --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/Makefile @@ -0,0 +1,3 @@ +SRC_FILES := gapuino_sysinit.c gap8_fll.c + +include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gap8_fll.c b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gap8_fll.c new file mode 100755 index 00000000..6c90993e --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gap8_fll.c @@ -0,0 +1,128 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_fll.c + * GAP8 FLL clock generator + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * FC can run up to 250MHz@1.2V, and 150MHz@1.0V. While the default voltage + * of PMU is 1.2V, it's okay to boost up without considering PMU. + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "gap8_fll.h" + +/**************************************************************************** + * Pre-Processor Declarations + ****************************************************************************/ + +/* Log2(FLL_REF_CLK=32768) */ + +#define LOG2_REFCLK 15 + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gap8_setfreq + * + * Description: + * Set frequency up to 250MHz. Input frequency counted by Hz. + * + ****************************************************************************/ + +void gap8_setfreq(uint32_t frequency) +{ + uint32_t mult; + uint32_t mult_factor_diff; + + /* FreqOut = Fref * mult/2^(div-1) + * With 16-bit mult and 4-bit div + * div = 1 + */ + + mult = frequency >> LOG2_REFCLK; + + /* Gain : 2-1 - 2-10 (0x2-0xB) + * Return to close loop mode and give gain to feedback loop + */ + + FLL_CTRL->SOC_CONF2 = FLL_CTRL_CONF2_LOOPGAIN(0x7) | + FLL_CTRL_CONF2_DEASSERT_CYCLES(0x10) | + FLL_CTRL_CONF2_ASSERT_CYCLES(0x10) | + FLL_CTRL_CONF2_LOCK_TOLERANCE(0x100) | + FLL_CTRL_CONF2_CONF_CLK_SEL(0x0) | + FLL_CTRL_CONF2_OPEN_LOOP(0x0) | + FLL_CTRL_CONF2_DITHERING(0x1); + + /* Configure mult and div */ + + FLL_CTRL->SOC_CONF1 = FLL_CTRL_CONF1_MODE(1) | + FLL_CTRL_CONF1_MULTI_FACTOR(mult) | + FLL_CTRL_CONF1_CLK_OUT_DIV(1); + + /* Check FLL converge by compare status register with multiply factor */ + + do + { + mult_factor_diff = (FLL_CTRL->SOC_FLL_STATUS - mult); + } + while (mult_factor_diff > 0x10); + + FLL_CTRL->SOC_CONF2 = FLL_CTRL_CONF2_LOOPGAIN(0xb) | + FLL_CTRL_CONF2_DEASSERT_CYCLES(0x10) | + FLL_CTRL_CONF2_ASSERT_CYCLES(0x10) | + FLL_CTRL_CONF2_LOCK_TOLERANCE(0x100) | + FLL_CTRL_CONF2_CONF_CLK_SEL(0x0) | + FLL_CTRL_CONF2_OPEN_LOOP(0x0) | + FLL_CTRL_CONF2_DITHERING(0x1); +} + +/**************************************************************************** + * Name: gap8_getfreq + * + * Description: + * Get current system clock frequency in Hz. + * + ****************************************************************************/ + +uint32_t gap8_getfreq(void) +{ + /* FreqOut = Fref * mult/2^(div-1), where div = 1 */ + + return FLL_REF_CLK * (FLL_CTRL->SOC_FLL_STATUS & 0xffff); +} diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gapuino_sysinit.c b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gapuino_sysinit.c new file mode 100755 index 00000000..c1f0b56f --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/sys_clock/gapuino_sysinit.c @@ -0,0 +1,119 @@ +/**************************************************************************** + * boards/risc-v/gap8/gapuino/src/gapuino_sysinit.c + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ +#include +#include +#include + +#include "gap8.h" +#include "gap8_fll.h" + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Used to communicate with plpbridge */ + +struct _debug_struct +{ + /* Used by external debug bridge to get exit status when using the board */ + + uint32_t exitStatus; + + /* Printf */ + + uint32_t useInternalPrintf; + uint32_t putcharPending; + uint32_t putcharCurrent; + uint8_t putcharBuffer[128]; + + /* Debug step, used for showing progress to host loader */ + + uint32_t debugStep; + uint32_t debugStepPending; + + /* Requests */ + + uint32_t firstReq; + uint32_t lastReq; + uint32_t firstBridgeReq; + + uint32_t notifReqAddr; + uint32_t notifReqValue; + + uint32_t bridgeConnected; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* Place a dummy debug struct */ + +struct _debug_struct Debug_Struct = +{ + .useInternalPrintf = 1, +}; + +uint32_t g_current_freq = 0; + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gapuino_sysinit + * + * Description: + * Initialize cache, clock, etc. + * + ****************************************************************************/ + +void gapuino_sysinit(void) +{ + SCBC->ICACHE_ENABLE = 0xffffffff; + gap8_setfreq(CONFIG_CORE_CLOCK_FREQ); + + /* For debug usage */ + + g_current_freq = gap8_getfreq(); +} diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Kconfig b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Kconfig new file mode 100755 index 00000000..fdc67b1a --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Kconfig @@ -0,0 +1,19 @@ +if BSP_USING_HWTIMER + config HWTIMER_BUS_NAME_1 + string "hwtimer bus name" + default "hwtim1" + + menuconfig ENABLE_TIM1 + bool "enable TIM1" + default y + + if ENABLE_TIM1 + config HWTIMER_1_DEVICE_NAME_1 + string "TIM1 dev name" + default "hwtim1_dev1" + + config HWTIMER_DRIVER_NAME_1 + string "TIM1 drv name" + default "hwtim1_drv" + endif +endif diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Makefile b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Makefile new file mode 100755 index 00000000..2d3d7a42 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/Makefile @@ -0,0 +1,3 @@ +SRC_FILES := hardware_hwtimer.c + +include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/hardware_hwtimer.c b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/hardware_hwtimer.c new file mode 100755 index 00000000..27d650df --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/timer/hardware_hwtimer.c @@ -0,0 +1,116 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_tim.c + * GAP8 basic timer + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * FC core has a 64-bit basic timer, able to split into 2 32-bit timers, + * with identicle memory map and 2 IRQ channels, for both FC core and + * cluster. We would use it as system timer. + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ +#include +#include + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +struct gap8_tim_instance +{ + basic_tim_reg_t *reg; + uint32_t core_clock; +}; + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct gap8_tim_instance fc_basic_timer = +{ + .reg = BASIC_TIM, + .core_clock = 200000000, +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gap8_timisr + * + * Description: + * Timer ISR to perform RR context switch + * + ****************************************************************************/ +extern int TickIsr(void); +void gap8_timisr(int irq, void *arg) +{ + TickIsr(); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: up_timer_initialize + * + * Description: + * Initialize the timer based on the frequency of source clock and ticks + * per second. + * + ****************************************************************************/ + +void timer_initialize(void) +{ + /* Set input clock to 1MHz. FC won't exceed 250MHz */ + + uint32_t prescaler = (fc_basic_timer.core_clock / 1000000) & 0xff; + uint32_t cmpval = TICK_PER_SECOND; + + /* Initialize timer registers */ + + fc_basic_timer.reg->CMP_LO = cmpval; + fc_basic_timer.reg->CFG_REG_LO = (prescaler << 8) | + BASIC_TIM_CLKSRC_FLL | BASIC_TIM_PRESC_ENABLE | BASIC_TIM_MODE_CYCL | + BASIC_TIM_IRQ_ENABLE | BASIC_TIM_RESET | BASIC_TIM_ENABLE; + fc_basic_timer.reg->VALUE_LO = 0; + + isrManager.done->registerIrq(GAP8_IRQ_FC_TIMER_LO, gap8_timisr, NONE); + isrManager.done->enableIrq(GAP8_IRQ_FC_TIMER_LO); +} diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Kconfig b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Kconfig new file mode 100755 index 00000000..3da44cdb --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Kconfig @@ -0,0 +1,14 @@ +menuconfig BSP_USING_UART0 + bool "Enable UART0" + default y + if BSP_USING_UART0 + config SERIAL_BUS_NAME_0 + string "serial bus name" + default "uart0" + config SERIAL_DRV_NAME_0 + string "serial bus driver name" + default "uart0_drv" + config SERIAL_0_DEVICE_NAME_0 + string "serial bus device name" + default "uart0_dev0" + endif diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Makefile b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Makefile new file mode 100755 index 00000000..e2f8c71a --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/Makefile @@ -0,0 +1,4 @@ +SRC_FILES := connect_uart.c hardware_udma.c + + +include $(KERNEL_ROOT)/compiler.mk diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/connect_uart.c b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/connect_uart.c new file mode 100755 index 00000000..d48c168d --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/connect_uart.c @@ -0,0 +1,326 @@ +/* +* Copyright (c) 2020 AIIT XUOS Lab +* XiUOS is licensed under Mulan PSL v2. +* You can use this software according to the terms and conditions of the Mulan PSL v2. +* You may obtain a copy of Mulan PSL v2 at: +* http://license.coscl.org.cn/MulanPSL2 +* THIS SOFTWARE IS PROVIDED ON AN "AS IS" BASIS, WITHOUT WARRANTIES OF ANY KIND, +* EITHER EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO NON-INFRINGEMENT, +* MERCHANTABILITY OR FIT FOR A PARTICULAR PURPOSE. +* See the Mulan PSL v2 for more details. +*/ + +/** +* @file connect_usart.c +* @brief support gap8-board uart function and register to bus framework +* @version 1.1 +* @author AIIT XUOS Lab +* @date 2021-07-23 +*/ + +#include +#include + +#include "connect_uart.h" +#include "hardware_udma.h" +#include "hardware_gpio.h" +#include + +static void SerialCfgParamCheck(struct SerialCfgParam *serial_cfg_default, struct SerialCfgParam *serial_cfg_new) +{ + struct SerialDataCfg *data_cfg_default = &serial_cfg_default->data_cfg; + struct SerialDataCfg *data_cfg_new = &serial_cfg_new->data_cfg; + + if ((data_cfg_default->serial_baud_rate != data_cfg_new->serial_baud_rate) && (data_cfg_new->serial_baud_rate)) { + data_cfg_default->serial_baud_rate = data_cfg_new->serial_baud_rate; + } + + if ((data_cfg_default->serial_bit_order != data_cfg_new->serial_bit_order) && (data_cfg_new->serial_bit_order)) { + data_cfg_default->serial_bit_order = data_cfg_new->serial_bit_order; + } + + if ((data_cfg_default->serial_buffer_size != data_cfg_new->serial_buffer_size) && (data_cfg_new->serial_buffer_size)) { + data_cfg_default->serial_buffer_size = data_cfg_new->serial_buffer_size; + } + + if ((data_cfg_default->serial_data_bits != data_cfg_new->serial_data_bits) && (data_cfg_new->serial_data_bits)) { + data_cfg_default->serial_data_bits = data_cfg_new->serial_data_bits; + } + + if ((data_cfg_default->serial_invert_mode != data_cfg_new->serial_invert_mode) && (data_cfg_new->serial_invert_mode)) { + data_cfg_default->serial_invert_mode = data_cfg_new->serial_invert_mode; + } + + if ((data_cfg_default->serial_parity_mode != data_cfg_new->serial_parity_mode) && (data_cfg_new->serial_parity_mode)) { + data_cfg_default->serial_parity_mode = data_cfg_new->serial_parity_mode; + } + + if ((data_cfg_default->serial_stop_bits != data_cfg_new->serial_stop_bits) && (data_cfg_new->serial_stop_bits)) { + data_cfg_default->serial_stop_bits = data_cfg_new->serial_stop_bits; + } +} + +static void UartRxIsr(void *arg) +{ + struct SerialBus *serial_bus = (struct SerialBus *)arg; + struct SerialHardwareDevice *serial_dev = (struct SerialHardwareDevice *)serial_bus->bus.owner_haldev; + + SerialSetIsr(serial_dev, SERIAL_EVENT_RX_IND); +} + +static uint32 SerialInit(struct SerialDriver *serial_drv, struct BusConfigureInfo *configure_info) +{ + asm volatile("nop"); + NULL_PARAM_CHECK(serial_drv); + struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_drv->private_data; + + if (configure_info->private_data) { + struct SerialCfgParam *serial_cfg_new = (struct SerialCfgParam *)configure_info->private_data; + SerialCfgParamCheck(serial_cfg, serial_cfg_new); + } + + struct gap8_udma_peripheral *uart_udma = (struct gap8_udma_peripheral *)serial_cfg->hw_cfg.private_data; + uart_reg_t *uart_reg = (uart_reg_t *)uart_udma->regs; + uint32_t cfg_reg = 0; + + uint16_t div = CONFIG_CORE_CLOCK_FREQ / serial_cfg->data_cfg.serial_baud_rate; + + gap8_udma_init(uart_udma); + + /* Setup baudrate etc. */ + cfg_reg = UART_SETUP_BIT_LENGTH(serial_cfg->data_cfg.serial_data_bits - 5) | + UART_SETUP_PARITY_ENA(serial_cfg->data_cfg.serial_parity_mode - 1) | + UART_SETUP_STOP_BITS(serial_cfg->data_cfg.serial_stop_bits - 1) | + UART_SETUP_TX_ENA(1) | + UART_SETUP_RX_ENA(1) | + UART_SETUP_CLKDIV(div); + uart_reg->SETUP = cfg_reg; + + gap8_configpin(GAP8_PIN_A7_UART_TX | GAP8_PIN_PULL_UP | GAP8_PIN_SPEED_HIGH); + gap8_configpin(GAP8_PIN_B6_UART_RX | GAP8_PIN_PULL_UP | GAP8_PIN_SPEED_HIGH); + + return EOK; +} + +static uint32 SerialConfigure(struct SerialDriver *serial_drv, int serial_operation_cmd) +{ + NULL_PARAM_CHECK(serial_drv); + + struct SerialHardwareDevice *serial_dev = (struct SerialHardwareDevice *)serial_drv->driver.owner_bus->owner_haldev; + + struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_drv->private_data; + struct gap8_udma_peripheral *uart_udma = (struct gap8_udma_peripheral *)serial_cfg->hw_cfg.private_data; + + if (OPER_SET_INT == serial_operation_cmd) { + x_base lock = 0; + lock = DISABLE_INTERRUPT(); + + gap8_udma_rx_setirq(uart_udma, 1); + + gap8_udma_rx_start(uart_udma, serial_dev->serial_fifo.serial_rx->serial_rx_buffer, 1, 1); + + ENABLE_INTERRUPT(lock); + } else if (OPER_CLR_INT == serial_operation_cmd) { + gap8_udma_rx_setirq(uart_udma, 0); + + gap8_udma_deinit(uart_udma); + } + + return EOK; +} + +static uint32 SerialDrvConfigure(void *drv, struct BusConfigureInfo *configure_info) +{ + NULL_PARAM_CHECK(drv); + NULL_PARAM_CHECK(configure_info); + + x_err_t ret = EOK; + int serial_operation_cmd; + struct SerialDriver *serial_drv = (struct SerialDriver *)drv; + + switch (configure_info->configure_cmd) + { + case OPE_INT: + ret = SerialInit(serial_drv, configure_info); + break; + case OPE_CFG: + serial_operation_cmd = *(int *)configure_info->private_data; + ret = SerialConfigure(serial_drv, serial_operation_cmd); + break; + default: + break; + } + + return ret; +} + +static int SerialPutChar(struct SerialHardwareDevice *serial_dev, char c) +{ + struct Driver *drv = serial_dev->haldev.owner_bus->owner_driver; + struct SerialDriver *serial_drv = (struct SerialDriver *)drv; + struct SerialDevParam *serial_dev_param = (struct SerialDevParam *)serial_dev->haldev.private_data; + struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_dev->private_data; + struct gap8_udma_peripheral *uart_udma = (struct gap8_udma_peripheral *)serial_cfg->hw_cfg.private_data; + + gap8_udma_tx_setirq(uart_udma,1); + gap8_udma_tx_start(uart_udma, &c, 1, 1); + + for(int i = 999 ; i> 0 ; i--); + + return 0; +} + +static int SerialGetChar(struct SerialHardwareDevice *serial_dev) +{ + struct Driver *drv = serial_dev->haldev.owner_bus->owner_driver; + struct SerialDriver *serial_drv = (struct SerialDriver *)drv; + struct SerialDevParam *serial_dev_param = (struct SerialDevParam *)serial_dev->haldev.private_data; + struct SerialCfgParam *serial_cfg = (struct SerialCfgParam *)serial_dev->private_data; + struct gap8_udma_peripheral *uart_udma = (struct gap8_udma_peripheral *)serial_cfg->hw_cfg.private_data; + + uint8_t rx_buf[4] = {0}; + uint8_t ch = rx_buf[0]; + + /* Then trigger another reception */ + + gap8_udma_rx_start(uart_udma, rx_buf, 1, 1); + if (ch == 0) + return -ERROR; + + return ch; +} + +static const struct SerialDataCfg data_cfg_init = +{ + .serial_baud_rate = BAUD_RATE_115200, + .serial_data_bits = DATA_BITS_8, + .serial_stop_bits = STOP_BITS_1, + .serial_parity_mode = PARITY_NONE, + .serial_bit_order = BIT_ORDER_LSB, + .serial_invert_mode = NRZ_NORMAL, + .serial_buffer_size = SERIAL_RB_BUFSZ, +}; + +static struct gap8_udma_peripheral gap8_udma = +{ + .regs = (udma_reg_t *)UART, + .id = GAP8_UDMA_ID_UART, + .on_tx = NONE,//UartRxIsr?? + // .on_tx = UartTxIsr,//UartRxIsr?? + .tx_arg = NONE, + .on_rx = UartRxIsr, + .rx_arg = NONE, + .is_tx_continous = 0, + .is_rx_continous = 1, +}; + +/*manage the serial device operations*/ +static const struct SerialDrvDone drv_done = +{ + .init = SerialInit, + .configure = SerialConfigure, +}; + +/*manage the serial device hal operations*/ +static struct SerialHwDevDone hwdev_done = +{ + .put_char = SerialPutChar, + .get_char = SerialGetChar, +}; + +static int BoardSerialBusInit(struct SerialBus *serial_bus, struct SerialDriver *serial_driver, const char *bus_name, const char *drv_name) +{ + x_err_t ret = EOK; + + /*Init the serial bus */ + ret = SerialBusInit(serial_bus, bus_name); + if (EOK != ret) { + KPrintf("InitHwUart SerialBusInit error %d\n", ret); + return ERROR; + } + + /*Init the serial driver*/ + ret = SerialDriverInit(serial_driver, drv_name); + if (EOK != ret) { + KPrintf("InitHwUart SerialDriverInit error %d\n", ret); + return ERROR; + } + + /*Attach the serial driver to the serial bus*/ + ret = SerialDriverAttachToBus(drv_name, bus_name); + if (EOK != ret) { + KPrintf("InitHwUart SerialDriverAttachToBus error %d\n", ret); + return ERROR; + } + + return ret; +} + +/*Attach the serial device to the serial bus*/ +static int BoardSerialDevBend(struct SerialHardwareDevice *serial_device, void *serial_param, const char *bus_name, const char *dev_name) +{ + x_err_t ret = EOK; + + ret = SerialDeviceRegister(serial_device, serial_param, dev_name); + if (EOK != ret) { + KPrintf("InitHwUart SerialDeviceInit device %s error %d\n", dev_name, ret); + return ERROR; + } + + ret = SerialDeviceAttachToBus(dev_name, bus_name); + if (EOK != ret) { + KPrintf("InitHwUart SerialDeviceAttachToBus device %s error %d\n", dev_name, ret); + return ERROR; + } + + return ret; +} + +int InitHwUart(void) +{ + x_err_t ret = EOK; + + static struct SerialBus serial_bus; + memset(&serial_bus, 0, sizeof(struct SerialBus)); + + + static struct SerialDriver serial_driver; + memset(&serial_driver, 0, sizeof(struct SerialDriver)); + + static struct SerialHardwareDevice serial_device; + memset(&serial_device, 0, sizeof(struct SerialHardwareDevice)); + + static struct SerialCfgParam serial_cfg; + memset(&serial_cfg, 0, sizeof(struct SerialCfgParam)); + + static struct SerialDevParam serial_dev_param; + memset(&serial_dev_param, 0, sizeof(struct SerialDevParam)); + + serial_driver.drv_done = &drv_done; + serial_driver.configure = &SerialDrvConfigure; + serial_device.hwdev_done = &hwdev_done; + + serial_cfg.data_cfg = data_cfg_init; + + serial_cfg.hw_cfg.private_data = (void *)&gap8_udma; + serial_driver.private_data = (void *)&serial_cfg; + + serial_dev_param.serial_work_mode = SIGN_OPER_INT_RX; + serial_device.haldev.private_data = (void *)&serial_dev_param; + + ret = BoardSerialBusInit(&serial_bus, &serial_driver, SERIAL_BUS_NAME_0, SERIAL_DRV_NAME_0); + if (EOK != ret) { + KPrintf("InitHwUart uarths error ret %u\n", ret); + return ERROR; + } + + ret = BoardSerialDevBend(&serial_device, (void *)&serial_cfg, SERIAL_BUS_NAME_0, SERIAL_0_DEVICE_NAME_0); + if (EOK != ret) { + KPrintf("InitHwUart uarths error ret %u\n", ret); + return ERROR; + } + + gap8_udma.rx_arg = (void *)&serial_bus; + + return ret; +} diff --git a/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/hardware_udma.c b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/hardware_udma.c new file mode 100755 index 00000000..f8a616e5 --- /dev/null +++ b/Ubiquitous/XiUOS/board/gapuino/third_party_driver/uart/hardware_udma.c @@ -0,0 +1,387 @@ +/**************************************************************************** + * arch/risc-v/src/gap8/gap8_udma.c + * uDMA driver for GAP8 + * + * Copyright (C) 2018 Gregory Nutt. All rights reserved. + * Author: hhuysqt <1020988872@qq.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. + * 3. Neither the name NuttX nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * 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. + * + ****************************************************************************/ + +/**************************************************************************** + * GAP8 features a simple uDMA subsystem. Peripherals including UART, SPI, + * I2C, I2S, CPI, LVDS, Hyperbus, have config registers memory-mapped, but + * not data registers. The only way to send or receive data is using the + * uDMA. Those peripherals share the same uDMA ISR. + * + * Note that uDMA can only recognize L2 RAM. So data must not be stored at + * L1, which means that if you link the stack at L1, you cannot use local + * buffers as data src or destination. + * + * As for the UART driver, the SOC_EU may fire a redundant IRQ even if the + * uDMA hasn't finished its job. So I spin on TX channel and bypass on RX + * channel, if the IRQ is redundant. + ****************************************************************************/ + +/** +* @file hardware_udma.c +* @brief add from Gap8 riscv SDK +* https://greenwavesdev2.wpengine.com/sdk-manuals/ +* @version 1.1 +* @author AIIT XUOS Lab +* @date 2021-07-27 +*/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include "hardware_udma.h" +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +#define CHECK_CHANNEL_ID(INSTANCE) \ + if ((INSTANCE) == NULL || \ + (INSTANCE)->id >= GAP8_UDMA_NR_CHANNELS) \ + { \ + return -1; \ + } + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/* uDMA peripheral instances + * The peripheral driver instantiate it and register through _init() + */ + +static struct gap8_udma_peripheral *_peripherals[GAP8_UDMA_NR_CHANNELS] = + { + 0 + }; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +static void _dma_txstart(struct gap8_udma_peripheral *the_peri) +{ + the_peri->regs->TX_SADDR = (uint32_t)the_peri->tx.buff; + the_peri->regs->TX_SIZE = (uint32_t)the_peri->tx.block_size; + the_peri->regs->TX_CFG = UDMA_CFG_EN(1); +} + +static void _dma_rxstart(struct gap8_udma_peripheral *the_peri) +{ + the_peri->regs->RX_SADDR = (uint32_t)the_peri->rx.buff; + the_peri->regs->RX_SIZE = (uint32_t)the_peri->rx.block_size; + the_peri->regs->RX_CFG = UDMA_CFG_EN(1); +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: gap8_udma_init + * + * Description: + * Initialize (and enable) a udma peripheral. + * + * Input: + * instance: pointer to a peripheral instance connected to uDMA + * + ****************************************************************************/ + +int gap8_udma_init(struct gap8_udma_peripheral *instance) +{ + uint32_t id; + asm volatile("nop"); + CHECK_CHANNEL_ID(instance) + + id = instance->id; + _peripherals[id] = instance; + + /* Enable clock gating */ + + UDMA_GC->CG |= (1L << id); + + return 0; +} + +/**************************************************************************** + * Name: gap8_udma_deinit + * + * Description: + * Deinit a udma peripheral + * + ****************************************************************************/ + +int gap8_udma_deinit(struct gap8_udma_peripheral *instance) +{ + uint32_t id; + + CHECK_CHANNEL_ID(instance) + + id = instance->id; + _peripherals[id] = NULL; + + /* Disable clock gating */ + + UDMA_GC->CG &= ~(1L << id); + + return 0; +} + +/**************************************************************************** + * Name: gap8_udma_tx_setirq + * + * Description: + * Enable or disable the tx interrupt. + * + ****************************************************************************/ + +int gap8_udma_tx_setirq(struct gap8_udma_peripheral *instance, bool enable) +{ + CHECK_CHANNEL_ID(instance) + + /* The irq enable bit happened to be 2*id + 1 */ + + if (enable) + { + up_enable_event(1 + (instance->id << 1)); + } + else + { + up_disable_event(1 + (instance->id << 1)); +#if 0 + instance->regs->TX_CFG = UDMA_CFG_CLR(1); +#endif + } + + return 0; +} + +/**************************************************************************** + * Name: gap8_udma_rx_setirq + * + * Description: + * Enable or disable the rx interrupt. + * + ****************************************************************************/ + +int gap8_udma_rx_setirq(struct gap8_udma_peripheral *instance, bool enable) +{ + CHECK_CHANNEL_ID(instance) + + /* The irq enable bit happened to be 2*id */ + + if (enable) + { + up_enable_event(instance->id << 1); + } + else + { + up_disable_event(instance->id << 1); +#if 0 + instance->regs->RX_CFG = UDMA_CFG_CLR(1); +#endif + } + + return 0; +} + +/**************************************************************************** + * Name: gap8_udma_tx_start + * + * Description: + * Send size * count bytes non-blocking. + * + * This function may be called from ISR, so it cannot be blocked. The + * caller should manage the muxing. + * + ****************************************************************************/ + +int gap8_udma_tx_start(struct gap8_udma_peripheral *instance, + uint8_t *buff, uint32_t size, int count) +{ + CHECK_CHANNEL_ID(instance) + + instance->tx.buff = buff; + instance->tx.block_size = size; + instance->tx.block_count = count; + + _dma_txstart(instance); + + return 0; +} + +/**************************************************************************** + * Name: gap8_udma_rx_start + * + * Description: + * Receive size * count bytes + * + * This function may be called from ISR, so it cannot be blocked. The + * caller should manage the muxing. + * + ****************************************************************************/ + +int gap8_udma_rx_start(struct gap8_udma_peripheral *instance, + uint8_t *buff, uint32_t size, int count) +{ + CHECK_CHANNEL_ID(instance) + + instance->rx.buff = buff; + instance->rx.block_size = size; + instance->rx.block_count = count; + + _dma_rxstart(instance); + + return 0; +} + +/**************************************************************************** + * Name: gap8_udma_tx_poll + * + * Description: + * Return 0 if the buffer is not in the tx pending list. + * + ****************************************************************************/ + +int gap8_udma_tx_poll(struct gap8_udma_peripheral *instance) +{ + CHECK_CHANNEL_ID(instance) + + return instance->tx.block_count <= 0 ? 0 : -1; +} + +/**************************************************************************** + * Name: gap8_udma_rx_poll + * + * Description: + * Return 0 if the buffer is not in the rx pending list. + * + ****************************************************************************/ + +int gap8_udma_rx_poll(struct gap8_udma_peripheral *instance) +{ + CHECK_CHANNEL_ID(instance) + + return instance->rx.block_count <= 0 ? 0 : -1; +} + +/**************************************************************************** + * Name: gap8_udma_doirq + * + * Description: + * uDMA ISR + * + ****************************************************************************/ +int gap8_udma_doirq(int irq, void *context, void *arg) +{ + struct gap8_udma_peripheral *the_peripheral; + uint32_t event = SOC_EVENTS->CURRENT_EVENT & 0xff; + + if (event > GAP8_UDMA_MAX_EVENT) + { + /* Bypass */ + + return 0; + } + + + /* Peripheral id happened to be half of event... */ + + the_peripheral = _peripherals[event >> 1]; + if (the_peripheral == NULL) + { + return 0; + } + + if (event & 0x1) + { + /* Tx channel */ + + if (the_peripheral->tx.block_count > 1) + { + the_peripheral->tx.block_count--; + the_peripheral->tx.buff += the_peripheral->tx.block_size; + _dma_txstart(the_peripheral); + } + else + { + /* The buffer is exhausted. Forward to peripheral's driver */ + + while (the_peripheral->regs->TX_SIZE != 0) + { + /* I don't know why but I have to spin here. SOC_EU would + * fire the IRQ even if uDMA hasn't finished the job. + * If I bypassed it, I would lose the finish event... + */ + } + + the_peripheral->tx.block_count = 0; + if (the_peripheral->on_tx) + { + the_peripheral->on_tx(the_peripheral->tx_arg); + } + } + } + else + { + /* Rx channel */ + asm volatile("nop"); + if (the_peripheral->rx.block_count > 1) + { + the_peripheral->rx.block_count--; + the_peripheral->rx.buff += the_peripheral->rx.block_size; + _dma_rxstart(the_peripheral); + } + else if (!(the_peripheral->regs->RX_CFG & UDMA_CFG_CLR(1))) + { + /* The buffer is exhausted. Forward to peripheral's driver + * + * Again I don't know why but I have to test the PENDING bit of + * the uDMA, so as to avoid the redundant IRQ... + */ + + the_peripheral->rx.block_count = 0; + if (the_peripheral->on_rx) + { + the_peripheral->on_rx(the_peripheral->rx_arg); + } + } + } + + return 0; +} diff --git a/Ubiquitous/XiUOS/path_kernel.mk b/Ubiquitous/XiUOS/path_kernel.mk old mode 100644 new mode 100755 index 6a4a6aa5..9ca5c106 --- a/Ubiquitous/XiUOS/path_kernel.mk +++ b/Ubiquitous/XiUOS/path_kernel.mk @@ -73,6 +73,13 @@ KERNELPATHS :=-I$(BSP_ROOT) \ -I$(BSP_ROOT)/include # endif +ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/gapuino) +KERNELPATHS :=-I$(BSP_ROOT) \ + -I$(BSP_ROOT)/third_party_driver \ + -I$(BSP_ROOT)/third_party_driver/include \ + -I$(KERNEL_ROOT)/include # +endif + ifeq ($(BSP_ROOT),$(KERNEL_ROOT)/board/hifive1-rev-B) KERNELPATHS :=-I$(BSP_ROOT) \ -I$(BSP_ROOT)/third_party_driver \ @@ -204,6 +211,9 @@ endif ifeq ($(MCU), FE310) KERNELPATHS +=-I$(KERNEL_ROOT)/arch/risc-v/fe310 endif +ifeq ($(MCU), GAP8) + KERNELPATHS +=-I$(KERNEL_ROOT)/arch/risc-v/gap8 +endif endif