From c047c1412f13406a1dba4abe86c01ae28fcd5ca4 Mon Sep 17 00:00:00 2001 From: Xiang Xiao Date: Thu, 11 Mar 2021 11:43:42 +0800 Subject: [PATCH] Remove all gap8(risc-v) arch and board source code Signed-off-by: Xiang Xiao --- .../introduction/detailed_support.rst | 12 - .../introduction/supported_platforms.rst | 5 - README.md | 3 - arch/README.txt | 1 - arch/risc-v/Kconfig | 11 - arch/risc-v/include/gap8/chip.h | 57 - arch/risc-v/include/gap8/irq.h | 450 ---- arch/risc-v/include/rv32im/irq.h | 9 +- arch/risc-v/src/gap8/Kconfig | 13 - arch/risc-v/src/gap8/Make.defs | 71 - arch/risc-v/src/gap8/gap8.h | 2045 ----------------- arch/risc-v/src/gap8/gap8_allocateheap.c | 98 - arch/risc-v/src/gap8/gap8_fll.c | 128 -- arch/risc-v/src/gap8/gap8_fll.h | 75 - arch/risc-v/src/gap8/gap8_gpio.c | 209 -- arch/risc-v/src/gap8/gap8_gpio.h | 305 --- arch/risc-v/src/gap8/gap8_head.S | 373 --- arch/risc-v/src/gap8/gap8_idle.c | 84 - arch/risc-v/src/gap8/gap8_interrupt.c | 147 -- arch/risc-v/src/gap8/gap8_schedulesigaction.c | 199 -- arch/risc-v/src/gap8/gap8_tim.c | 121 - arch/risc-v/src/gap8/gap8_tim.h | 87 - arch/risc-v/src/gap8/gap8_uart.c | 660 ------ arch/risc-v/src/gap8/gap8_uart.h | 70 - arch/risc-v/src/gap8/gap8_udma.c | 378 --- arch/risc-v/src/gap8/gap8_udma.h | 225 -- arch/risc-v/src/rv32im/Kconfig | 9 - arch/risc-v/src/rv32im/Toolchain.defs | 9 - boards/Kconfig | 11 - boards/risc-v/gap8/gapuino/Kconfig | 9 - boards/risc-v/gap8/gapuino/README.txt | 89 - .../risc-v/gap8/gapuino/configs/nsh/defconfig | 50 - boards/risc-v/gap8/gapuino/include/board.h | 77 - boards/risc-v/gap8/gapuino/scripts/Make.defs | 64 - boards/risc-v/gap8/gapuino/scripts/ld.script | 221 -- boards/risc-v/gap8/gapuino/src/Makefile | 6 - .../risc-v/gap8/gapuino/src/gapuino_appinit.c | 94 - .../risc-v/gap8/gapuino/src/gapuino_sysinit.c | 123 - 38 files changed, 1 insertion(+), 6597 deletions(-) delete mode 100644 arch/risc-v/include/gap8/chip.h delete mode 100644 arch/risc-v/include/gap8/irq.h delete mode 100644 arch/risc-v/src/gap8/Kconfig delete mode 100644 arch/risc-v/src/gap8/Make.defs delete mode 100644 arch/risc-v/src/gap8/gap8.h delete mode 100644 arch/risc-v/src/gap8/gap8_allocateheap.c delete mode 100644 arch/risc-v/src/gap8/gap8_fll.c delete mode 100644 arch/risc-v/src/gap8/gap8_fll.h delete mode 100644 arch/risc-v/src/gap8/gap8_gpio.c delete mode 100644 arch/risc-v/src/gap8/gap8_gpio.h delete mode 100644 arch/risc-v/src/gap8/gap8_head.S delete mode 100644 arch/risc-v/src/gap8/gap8_idle.c delete mode 100644 arch/risc-v/src/gap8/gap8_interrupt.c delete mode 100644 arch/risc-v/src/gap8/gap8_schedulesigaction.c delete mode 100644 arch/risc-v/src/gap8/gap8_tim.c delete mode 100644 arch/risc-v/src/gap8/gap8_tim.h delete mode 100644 arch/risc-v/src/gap8/gap8_uart.c delete mode 100644 arch/risc-v/src/gap8/gap8_uart.h delete mode 100644 arch/risc-v/src/gap8/gap8_udma.c delete mode 100644 arch/risc-v/src/gap8/gap8_udma.h delete mode 100644 boards/risc-v/gap8/gapuino/Kconfig delete mode 100644 boards/risc-v/gap8/gapuino/README.txt delete mode 100644 boards/risc-v/gap8/gapuino/configs/nsh/defconfig delete mode 100644 boards/risc-v/gap8/gapuino/include/board.h delete mode 100644 boards/risc-v/gap8/gapuino/scripts/Make.defs delete mode 100644 boards/risc-v/gap8/gapuino/scripts/ld.script delete mode 100644 boards/risc-v/gap8/gapuino/src/Makefile delete mode 100644 boards/risc-v/gap8/gapuino/src/gapuino_appinit.c delete mode 100644 boards/risc-v/gap8/gapuino/src/gapuino_sysinit.c diff --git a/Documentation/introduction/detailed_support.rst b/Documentation/introduction/detailed_support.rst index bb687035a791d..71894ee4d7f90 100644 --- a/Documentation/introduction/detailed_support.rst +++ b/Documentation/introduction/detailed_support.rst @@ -3020,18 +3020,6 @@ RISC-V RISC-V Architectural Support. Basic support for the RISC-V architecture was contributed by Ken Pettit in NuttX-7.19. -GreenWaves GAP8 ---------------- - -(RV32IM architecture) - -Basic support GreenWaves GAP8 *gapuino* board -was added by hhuysqt in NuttX-7.27. The GAP8 is a 1+8-core DSP-like -RISC-V MCU. The GAP8 features a RI5CY core called Fabric Controller(FC), -and a cluster of 8 RI5CY cores that runs at a bit slower speed. The GAP8 -is an implementation of the opensource PULP platform, a -Parallel-Ultra-Low-Power design. - `Sipeed Maix bit <#k210>`__ Initial support for the Sipeed Maix bit board was added in NuttX-9.0. diff --git a/Documentation/introduction/supported_platforms.rst b/Documentation/introduction/supported_platforms.rst index bc9defc413502..04ef20208fe15 100644 --- a/Documentation/introduction/supported_platforms.rst +++ b/Documentation/introduction/supported_platforms.rst @@ -68,7 +68,6 @@ from board-to-board. Follow the links for the details: - - :ref:`introduction/detailed_support:RISC-V` (2) - - :ref:`introduction/detailed_support:GreenWaves GAP8` (1) - :ref:`introduction/detailed_support:LiteX on Arty A7` (1) - Xtensa LX6: @@ -106,10 +105,6 @@ MCU. Follow the links for the details: - :ref:`introduction/detailed_support:Xtensa LX6 ESP32` (Dual Xtensa LX6) - - GreenWaves - - - :ref:`introduction/detailed_support:Greenwaves GAP8` (RISC-V RV32IM) - - Host PC based simulations - :ref:`introduction/detailed_support:Linux User Mode Simulation` diff --git a/README.md b/README.md index fcff738eb0a0c..fd09d45422c30 100644 --- a/README.md +++ b/README.md @@ -2302,9 +2302,6 @@ Below is a guide to the available README files in the NuttX source tree: | | `- us7032evb1/ | | `- README.txt | |- risc-v/ - | | `- gap8/ - | | `- gapuino/ - | | `- README.txt | |- sim/ | | `- sim/ | | `- sim/ diff --git a/arch/README.txt b/arch/README.txt index 3efdcb426639c..c3944eacf9dcf 100644 --- a/arch/README.txt +++ b/arch/README.txt @@ -255,7 +255,6 @@ arch/risc-v MCU support arch/risc-v/include/fe310 and arch/risc-v/src/fe310 - arch/risc-v/include/gap8 and arch/risc-v/src/gap8 arch/risc-v/include/k210 and arch/risc-v/src/k210 arch/risc-v/include/litex and arch/risc-v/src/litex arch/risc-v/include/rv32im and arch/risc-v/src/rv32im diff --git a/arch/risc-v/Kconfig b/arch/risc-v/Kconfig index 3924ef6b76faf..ce24e1c2e64cf 100644 --- a/arch/risc-v/Kconfig +++ b/arch/risc-v/Kconfig @@ -31,13 +31,6 @@ config ARCH_CHIP_LITEX ---help--- Enjoy Digital LITEX VEXRISCV softcore processor (RV32IMA). -config ARCH_CHIP_GAP8 - bool "GreenwavesTechnologies GAP8" - select ARCH_RV32IM - ---help--- - GreenwavesTechnologies GAP8 features a 1+8-core RI5CY DSP-like - processor, which originally comes from the ETH PULP platform. - config ARCH_CHIP_BL602 bool "BouffaloLab BL602" select ARCH_RV32IM @@ -95,7 +88,6 @@ config ARCH_CHIP default "fe310" if ARCH_CHIP_FE310 default "k210" if ARCH_CHIP_K210 default "litex" if ARCH_CHIP_LITEX - default "gap8" if ARCH_CHIP_GAP8 default "bl602" if ARCH_CHIP_BL602 default "esp32c3" if ARCH_CHIP_ESP32C3 default "c906" if ARCH_CHIP_C906 @@ -115,9 +107,6 @@ endif if ARCH_CHIP_LITEX source arch/risc-v/src/litex/Kconfig endif -if ARCH_CHIP_GAP8 -source arch/risc-v/src/gap8/Kconfig -endif if ARCH_CHIP_BL602 source arch/risc-v/src/bl602/Kconfig endif diff --git a/arch/risc-v/include/gap8/chip.h b/arch/risc-v/include/gap8/chip.h deleted file mode 100644 index eff9f00b2700b..0000000000000 --- a/arch/risc-v/include/gap8/chip.h +++ /dev/null @@ -1,57 +0,0 @@ -/**************************************************************************** - * 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/arch/risc-v/include/gap8/irq.h b/arch/risc-v/include/gap8/irq.h deleted file mode 100644 index c366765d39d68..0000000000000 --- a/arch/risc-v/include/gap8/irq.h +++ /dev/null @@ -1,450 +0,0 @@ -/**************************************************************************** - * 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_RISC_V_INCLUDE_GAP8_IRQ_H -#define __ARCH_RISC_V_INCLUDE_GAP8_IRQ_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#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) - -/**************************************************************************** - * Inline Functions - ****************************************************************************/ - -/**************************************************************************** - * 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); - } -} - -/**************************************************************************** - * Name: up_disable_irq - * - * Description: - * Disable the IRQ specified by 'irq'. Mind the Machine privilege. - * - ****************************************************************************/ - -static inline void up_disable_irq(int irq) -{ - FCEU->MASK_IRQ_AND = (1UL << irq); -} - -/**************************************************************************** - * Name: up_enable_irq - * - * Description: - * Enable the IRQ specified by 'irq'. Mind the Machine privilege. - * - ****************************************************************************/ - -static inline void up_enable_irq(int irq) -{ - FCEU->MASK_IRQ_OR = (1 << irq); -} - -/**************************************************************************** - * 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_save - * - * Description: - * Disable interrupt and return the current interrupt state. - * - ****************************************************************************/ - -static inline irqstate_t up_irq_save(void) -{ - irqstate_t oldstat; - irqstate_t 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_restore - * - * Description: - * Restore previous IRQ mask state - * - ****************************************************************************/ - -static inline void up_irq_restore(uint32_t 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_enable - * - * Description: - * Return the current interrupt state and enable interrupts - * - ****************************************************************************/ - -static inline irqstate_t up_irq_enable(void) -{ - irqstate_t oldstat; - irqstate_t newstat; - - if (_current_privilege()) - { - /* Machine mode: Set 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: Set UIE */ - - asm volatile ("csrr %0, 0x000": "=r" (oldstat)); - newstat = oldstat | (1L << 0); - asm volatile("csrw 0x000, %0" : /* no output */ : "r" (newstat)); - } - return 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 - ****************************************************************************/ - -#endif /* __ARCH_RISC_V_INCLUDE_GAP8_IRQ_H */ diff --git a/arch/risc-v/include/rv32im/irq.h b/arch/risc-v/include/rv32im/irq.h index db54ce3c08276..b1ed3afdc0dab 100644 --- a/arch/risc-v/include/rv32im/irq.h +++ b/arch/risc-v/include/rv32im/irq.h @@ -114,14 +114,7 @@ #define REG_INT_CTX_NDX 32 -#ifdef CONFIG_ARCH_CHIP_GAP8 -/* 31 registers, ePC, plus 6 loop registers */ - -# define INT_XCPT_REGS (32 + 6) -#else -# define INT_XCPT_REGS 33 -#endif - +#define INT_XCPT_REGS 33 #define INT_XCPT_SIZE (4 * INT_XCPT_REGS) #ifdef CONFIG_ARCH_FPU diff --git a/arch/risc-v/src/gap8/Kconfig b/arch/risc-v/src/gap8/Kconfig deleted file mode 100644 index 83238360dfb7e..0000000000000 --- a/arch/risc-v/src/gap8/Kconfig +++ /dev/null @@ -1,13 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see the file kconfig-language.txt in the NuttX tools repository. -# - -comment "GAP8 configuration" - -config CORE_CLOCK_FREQ - int "Core clock frequency" - range 150000000 250000000 - default 200000000 - ---help--- - The core clock in Hz. GAP8 is able to run up to 250MHz. diff --git a/arch/risc-v/src/gap8/Make.defs b/arch/risc-v/src/gap8/Make.defs deleted file mode 100644 index 1005f2d8de0d9..0000000000000 --- a/arch/risc-v/src/gap8/Make.defs +++ /dev/null @@ -1,71 +0,0 @@ -############################################################################ -# arch/risc-v/src/gap8/Make.defs -# -# 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. -# -############################################################################ - -# Specify our HEAD assembly file. This will be linked as the first object -# file, so it will appear at address 0 - -HEAD_ASRC = gap8_head.S - -# Specify our general Assembly files - -CHIP_ASRCS = riscv_syscall.S - -ifeq ($(CONFIG_ARCH_SETJMP_H),y) -CMN_ASRCS += riscv_setjmp.S -endif - -# Override the arch to enable hardware MUL during assembly. -# This is to support our hardware mul test. For that test, -# we have to disable hardware mul for C code so the soft -# math libs will be used to compare software mul vs hw mul. -# But hw mul must be enabled to compile the .S file, or we -# will get an illegal instruction error. - -ASARCHCPUFLAGS += -march=rv32imcxgap8 -mPE=8 -mFC=1 -D__riscv__ -D__pulp__ -D__GAP8__ - -# Specify C code within the common directory to be included - -CMN_CSRCS += riscv_initialize.c riscv_swint.c -CMN_CSRCS += riscv_createstack.c riscv_exit.c -CMN_CSRCS += riscv_assert.c riscv_blocktask.c riscv_copystate.c riscv_initialstate.c -CMN_CSRCS += riscv_interruptcontext.c riscv_releasepending.c riscv_reprioritizertr.c -CMN_CSRCS += riscv_releasestack.c riscv_stackframe.c riscv_sigdeliver.c -CMN_CSRCS += riscv_unblocktask.c riscv_usestack.c riscv_copyfullstate.c - -ifeq ($(CONFIG_ARCH_HAVE_VFORK),y) -CMN_CSRCS += riscv_vfork.c -endif - -# Specify our C code within this directory to be included - -CHIP_CSRCS = gap8_allocateheap.c gap8_fll.c gap8_gpio.c gap8_interrupt.c -CHIP_CSRCS += gap8_tim.c gap8_uart.c gap8_udma.c gap8_idle.c gap8_schedulesigaction.c diff --git a/arch/risc-v/src/gap8/gap8.h b/arch/risc-v/src/gap8/gap8.h deleted file mode 100644 index 32cd5523811f4..0000000000000 --- a/arch/risc-v/src/gap8/gap8.h +++ /dev/null @@ -1,2045 +0,0 @@ -/************************************************************************************ - * 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 */ - -/* 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/arch/risc-v/src/gap8/gap8_allocateheap.c b/arch/risc-v/src/gap8/gap8_allocateheap.c deleted file mode 100644 index 302c092a24366..0000000000000 --- a/arch/risc-v/src/gap8/gap8_allocateheap.c +++ /dev/null @@ -1,98 +0,0 @@ -/**************************************************************************** - * 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/arch/risc-v/src/gap8/gap8_fll.c b/arch/risc-v/src/gap8/gap8_fll.c deleted file mode 100644 index 7e6d63d33d739..0000000000000 --- a/arch/risc-v/src/gap8/gap8_fll.c +++ /dev/null @@ -1,128 +0,0 @@ -/**************************************************************************** - * 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 = __builtin_pulp_abs(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/arch/risc-v/src/gap8/gap8_fll.h b/arch/risc-v/src/gap8/gap8_fll.h deleted file mode 100644 index 26e8a4f5612d8..0000000000000 --- a/arch/risc-v/src/gap8/gap8_fll.h +++ /dev/null @@ -1,75 +0,0 @@ -/**************************************************************************** - * 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/arch/risc-v/src/gap8/gap8_gpio.c b/arch/risc-v/src/gap8/gap8_gpio.c deleted file mode 100644 index 7bdbcdd96a217..0000000000000 --- a/arch/risc-v/src/gap8/gap8_gpio.c +++ /dev/null @@ -1,209 +0,0 @@ -/**************************************************************************** - * 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. - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include "gap8_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 ERROR; - } - - /* 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 OK; -} - -/**************************************************************************** - * 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/arch/risc-v/src/gap8/gap8_gpio.h b/arch/risc-v/src/gap8/gap8_gpio.h deleted file mode 100644 index bca8d3022c92a..0000000000000 --- a/arch/risc-v/src/gap8/gap8_gpio.h +++ /dev/null @@ -1,305 +0,0 @@ -/************************************************************************************ - * 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 _ARCH_RISCV_SRC_GAP8_GPIO_H -#define _ARCH_RISCV_SRC_GAP8_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/arch/risc-v/src/gap8/gap8_head.S b/arch/risc-v/src/gap8/gap8_head.S deleted file mode 100644 index cd5d9228efad2..0000000000000 --- a/arch/risc-v/src/gap8/gap8_head.S +++ /dev/null @@ -1,373 +0,0 @@ -/**************************************************************************** - * 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 _idle_stack_end - - .extern gap8_dispatch_irq - .extern nx_start - .extern gapuino_sysinit - -/******************************************************************************* - * Reset handler - *******************************************************************************/ - -reset_handler: -#if 0 - csrr a0, 0xf14 /* Cluster ID */ - srli a0, a0, 5 -#endif - - 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, _sbss - la x27, _ebss - - 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() */ - - jal x1, nx_start - - /* 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/arch/risc-v/src/gap8/gap8_idle.c b/arch/risc-v/src/gap8/gap8_idle.c deleted file mode 100644 index c11a630c902b3..0000000000000 --- a/arch/risc-v/src/gap8/gap8_idle.c +++ /dev/null @@ -1,84 +0,0 @@ -/**************************************************************************** - * 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/arch/risc-v/src/gap8/gap8_interrupt.c b/arch/risc-v/src/gap8/gap8_interrupt.c deleted file mode 100644 index a4e8eaccbfd15..0000000000000 --- a/arch/risc-v/src/gap8/gap8_interrupt.c +++ /dev/null @@ -1,147 +0,0 @@ -/**************************************************************************** - * 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 - -#include "gap8_udma.h" -#include "gap8_tim.h" - -/**************************************************************************** - * 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_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. - * - ****************************************************************************/ - -void up_irqinitialize(void) -{ - /* Deactivate all the soc events */ - - SOC_EU->FC_MASK_MSB = 0xffffffff; - SOC_EU->FC_MASK_LSB = 0xffffffff; - - /* enable soc peripheral interrupt */ - - irq_attach(GAP8_IRQ_FC_UDMA, gap8_udma_doirq, NULL); - up_enable_irq(GAP8_IRQ_FC_UDMA); - - /* Attach system call handler */ - - extern int up_swint(int irq, FAR void *context, FAR void *arg); - irq_attach(GAP8_IRQ_SYSCALL, up_swint, NULL); - - up_irq_enable(); -} - -/**************************************************************************** - * Name: gap8_dispatch_irq - * - * Description: - * Called from IRQ vectors. Input vector id. Return SP pointer, modified - * or not. - * - ****************************************************************************/ - -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); - current_regs = (void *)g_current_regs; - g_current_regs = NULL; - - return current_regs; -} diff --git a/arch/risc-v/src/gap8/gap8_schedulesigaction.c b/arch/risc-v/src/gap8/gap8_schedulesigaction.c deleted file mode 100644 index f66367baef7f8..0000000000000 --- a/arch/risc-v/src/gap8/gap8_schedulesigaction.c +++ /dev/null @@ -1,199 +0,0 @@ -/**************************************************************************** - * 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 - * - ****************************************************************************/ - -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/arch/risc-v/src/gap8/gap8_tim.c b/arch/risc-v/src/gap8/gap8_tim.c deleted file mode 100644 index 16bcd6174b059..0000000000000 --- a/arch/risc-v/src/gap8/gap8_tim.c +++ /dev/null @@ -1,121 +0,0 @@ -/**************************************************************************** - * 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 -#include - -#include "gap8_tim.h" - -/**************************************************************************** - * 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 - * - ****************************************************************************/ - -static int gap8_timisr(int irq, void *context, FAR void *arg) -{ - nxsched_process_timer(); - return 0; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: up_timer_initialize - * - * Description: - * Initialize the timer based on the frequency of source clock and ticks - * per second. - * - ****************************************************************************/ - -void up_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 = CONFIG_USEC_PER_TICK; - - /* 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; - - irq_attach(GAP8_IRQ_FC_TIMER_LO, gap8_timisr, NULL); - up_enable_irq(GAP8_IRQ_FC_TIMER_LO); -} diff --git a/arch/risc-v/src/gap8/gap8_tim.h b/arch/risc-v/src/gap8/gap8_tim.h deleted file mode 100644 index 581c62720d594..0000000000000 --- a/arch/risc-v/src/gap8/gap8_tim.h +++ /dev/null @@ -1,87 +0,0 @@ -/**************************************************************************** - * 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/arch/risc-v/src/gap8/gap8_uart.c b/arch/risc-v/src/gap8/gap8_uart.c deleted file mode 100644 index 1302bb4e61083..0000000000000 --- a/arch/risc-v/src/gap8/gap8_uart.c +++ /dev/null @@ -1,660 +0,0 @@ -/**************************************************************************** - * arch/risc-v/src/gap8/gap8_uart.c - * 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. - * Note that here we don't use the uDMA to send multiple bytes, because - * NuttX serial drivers don't have abstraction for puts(). - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include - -#ifdef CONFIG_SERIAL_TERMIOS -# include -#endif - -#include -#include -#include - -#include "gap8_uart.h" - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/* Software abstraction - * inherit class _udma_peripheral - */ - -struct gap8_uart_t -{ - struct gap8_udma_peripheral udma; - - /* Private */ - - uint32_t tx_gpio; - uint32_t rx_gpio; - uint32_t coreclock; - uint32_t baud; - uint8_t nr_bits; - uint8_t parity_enable; - uint8_t stop_bits; - uint8_t is_initialized; - - /* IO buffer for uDMA */ - - uint8_t tx_buf[4]; - uint8_t rx_buf[4]; - int tx_cnt; - int rx_cnt; -}; - -/**************************************************************************** - * Private Function prototype - ****************************************************************************/ - -/* uart ISR routine */ - -static void uart_tx_isr(void *arg); -static void uart_rx_isr(void *arg); - -/* Serial driver methods */ - -static int up_setup(struct uart_dev_s *dev); -static void up_shutdown(struct uart_dev_s *dev); -static int up_attach(struct uart_dev_s *dev); -static void up_detach(struct uart_dev_s *dev); -static int up_ioctl(struct file *filep, int cmd, unsigned long arg); -static int up_receive(struct uart_dev_s *dev, unsigned int *status); -static void up_rxint(struct uart_dev_s *dev, bool enable); -static bool up_rxavailable(struct uart_dev_s *dev); -static void up_send(struct uart_dev_s *dev, int ch); -static void up_txint(struct uart_dev_s *dev, bool enable); -static bool up_txready(struct uart_dev_s *dev); -static bool up_txempty(struct uart_dev_s *dev); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static uart_dev_t g_uart0port; - -/* nuttx serial console operations */ - -static const struct uart_ops_s g_uart_ops = -{ - .setup = up_setup, - .shutdown = up_shutdown, - .attach = up_attach, - .detach = up_detach, - .ioctl = up_ioctl, - .receive = up_receive, - .rxint = up_rxint, - .rxavailable = up_rxavailable, -#ifdef CONFIG_SERIAL_IFLOWCONTROL - .rxflowcontrol = NULL, -#endif - .send = up_send, - .txint = up_txint, - .txready = up_txready, - .txempty = up_txempty, -}; - -/* instantiate the UART */ - -static struct gap8_uart_t gap8_uarts[GAP8_NR_UART] = -{ - { - .udma = - { - .regs = (udma_reg_t *)UART, - .id = GAP8_UDMA_ID_UART, - .on_tx = uart_tx_isr, - .tx_arg = &g_uart0port, - .on_rx = uart_rx_isr, - .rx_arg = &g_uart0port, - .is_tx_continous = 0, - .is_rx_continous = 1, - }, - - .tx_gpio = GAP8_PIN_A7_UART_TX | GAP8_PIN_PULL_UP | GAP8_PIN_SPEED_HIGH, - .rx_gpio = GAP8_PIN_B6_UART_RX | GAP8_PIN_PULL_UP | GAP8_PIN_SPEED_HIGH, - .coreclock = CONFIG_CORE_CLOCK_FREQ, /* to be modified */ - .baud = CONFIG_UART_BAUD, - .nr_bits = CONFIG_UART_BITS, - .parity_enable = CONFIG_UART_PARITY, - .stop_bits = CONFIG_UART_2STOP, - .is_initialized = 0, - } -}; - -/* IO buffers */ - -static char g_uart1rxbuffer[CONFIG_UART_RXBUFSIZE]; -static char g_uart1txbuffer[CONFIG_UART_TXBUFSIZE]; - -/* Instantiate serial device */ - -static uart_dev_t g_uart0port = -{ - .isconsole = 1, - .recv = - { - .size = CONFIG_UART_RXBUFSIZE, - .buffer = g_uart1rxbuffer, - }, - .xmit = - { - .size = CONFIG_UART_TXBUFSIZE, - .buffer = g_uart1txbuffer, - }, - .ops = &g_uart_ops, - .priv = &gap8_uarts[0], -}; - -/**************************************************************************** - * Private Function prototype - ****************************************************************************/ - -/**************************************************************************** - * Name: uart_tx_isr & uart_rx_isr - * - * Description: - * These are the UART interrupt handler. It is called on uDMA ISR. It - * should call uart_transmitchars or uart_receivechar to invoke the NuttX - * kernel. - * - ****************************************************************************/ - -static void uart_tx_isr(void *arg) -{ - uart_dev_t *dev = (uart_dev_t *)arg; - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - the_uart->tx_cnt = 0; - uart_xmitchars(dev); -} - -static void uart_rx_isr(void *arg) -{ - uart_dev_t *dev = (uart_dev_t *)arg; - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - the_uart->rx_cnt = 1; - uart_recvchars(dev); -} - -/**************************************************************************** - * Name: up_setup - * - * Description: - * Configure the UART baud, bits, parity, etc. This method is called the - * first time that the serial port is opened. - * - ****************************************************************************/ - -static int up_setup(struct uart_dev_s *dev) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - uart_reg_t *uartreg = (uart_reg_t *)the_uart->udma.regs; - uint32_t cfgreg = 0; - - if (the_uart->is_initialized == 0) - { - uint16_t div = the_uart->coreclock / the_uart->baud; - - gap8_udma_init(&the_uart->udma); - - /* Setup baudrate etc. */ - - cfgreg = UART_SETUP_BIT_LENGTH(the_uart->nr_bits - 5) | - UART_SETUP_PARITY_ENA(the_uart->parity_enable) | - UART_SETUP_STOP_BITS(the_uart->stop_bits) | - UART_SETUP_TX_ENA(1) | - UART_SETUP_RX_ENA(1) | - UART_SETUP_CLKDIV(div); - uartreg->SETUP = cfgreg; - - gap8_configpin(the_uart->tx_gpio); - gap8_configpin(the_uart->rx_gpio); - - the_uart->tx_cnt = 0; - the_uart->rx_cnt = 0; - -#if 0 - /* Start continuous rx */ - - gap8_udma_rx_start(&the_uart->udma, the_uart->rx_buf, 1, 1); -#endif - } - - the_uart->is_initialized = 1; - return OK; -} - -/**************************************************************************** - * Name: up_shutdown - * - * Description: - * Disable the UART. This method is called when the serial - * port is closed - * - ****************************************************************************/ - -static void up_shutdown(struct uart_dev_s *dev) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - gap8_udma_deinit(&the_uart->udma); - the_uart->is_initialized = 0; -} - -/**************************************************************************** - * Name: up_attach - * - * Description: - * Configure the UART to operation in interrupt driven mode. This method is - * called when the serial port is opened. Normally, this is just after the - * the setup() method is called, however, the serial console may operate in - * a non-interrupt driven mode during the boot phase. - * - * RX and TX interrupts are not enabled by the attach method (unless the - * hardware supports multiple levels of interrupt enabling). The RX and TX - * interrupts are not enabled until the txint() and rxint() methods are - * called. - * - ****************************************************************************/ - -static int up_attach(struct uart_dev_s *dev) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - if (the_uart->is_initialized == 0) - { - up_setup(dev); - } - - return OK; -} - -/**************************************************************************** - * Name: up_detach - * - * Description: - * Detach UART interrupts. This method is called when the serial port is - * closed normally just before the shutdown method is called. The exception - * is the serial console which is never shutdown. - * - ****************************************************************************/ - -static void up_detach(struct uart_dev_s *dev) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - gap8_udma_tx_setirq(&the_uart->udma, 0); - gap8_udma_rx_setirq(&the_uart->udma, 0); -} - -/**************************************************************************** - * Name: up_ioctl - * - * Description: - * All ioctl calls will be routed through this method - * - ****************************************************************************/ - -static int up_ioctl(struct file *filep, int cmd, unsigned long arg) -{ -#ifdef CONFIG_SERIAL_TERMIOS - struct inode *inode; - struct uart_dev_s *dev; - struct gap8_uart_t *priv; - int ret = OK; - - DEBUGASSERT(filep, filep->f_inode); - inode = filep->f_inode; - dev = inode->i_private; - - DEBUGASSERT(dev, dev->priv); - priv = (struct gap8_uart_t *)dev->priv; - - switch (cmd) - { - case TCGETS: - { - struct termios *termiosp = (struct termios *)arg; - - if (!termiosp) - { - ret = -EINVAL; - break; - } - - /* TODO: Other termios fields are not yet returned. - * Note that only cfsetospeed is not necessary because we have - * knowledge that only one speed is supported. - */ - - cfsetispeed(termiosp, priv->baud); - } - break; - - case TCSETS: - { - struct termios *termiosp = (struct termios *)arg; - - if (!termiosp) - { - ret = -EINVAL; - break; - } - - /* TODO: Handle other termios settings. - * Note that only cfgetispeed is used besued we have knowledge - * that only one speed is supported. - */ - - priv->baud = cfgetispeed(termiosp); - -#if 0 - gap8_uartconfigure(priv->uartbase, priv->baud, priv->parity, - priv->bits, priv->stopbits2); -#endif - } - break; - - default: - ret = -ENOTTY; - break; - } - - return ret; -#else - return -ENOTTY; -#endif -} - -/**************************************************************************** - * Name: up_receive - * - * Description: - * Called (usually) from the interrupt level to receive one - * character from the UART. Error bits associated with the - * receipt are provided in the return 'status'. - * - ****************************************************************************/ - -static int up_receive(struct uart_dev_s *dev, unsigned int *status) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - uint8_t ch = the_uart->rx_buf[0]; - - the_uart->rx_cnt = 0; - - if (status) - { - *status = 0; /* We are not yet tracking serial errors */ - } - - /* Then trigger another reception */ - - gap8_udma_rx_start(&the_uart->udma, the_uart->rx_buf, 1, 1); - - return (int)ch; -} - -/**************************************************************************** - * Name: up_rxint - * - * Description: - * Call to enable or disable RX interrupts - * - ****************************************************************************/ - -static void up_rxint(struct uart_dev_s *dev, bool enable) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - irqstate_t flags; - - flags = enter_critical_section(); - - if (enable) - { - gap8_udma_rx_setirq(&the_uart->udma, 1); - -#if 0 - if (the_uart->rx_cnt == 0) -#endif - { - gap8_udma_rx_start(&the_uart->udma, the_uart->rx_buf, 1, 1); - } - } -#if 0 - else - { - gap8_udma_rx_setirq(&the_uart->udma, 0); - } -#endif - - leave_critical_section(flags); -} - -/**************************************************************************** - * Name: up_rxavailable - * - * Description: - * Return true if the receive register is not empty - * - ****************************************************************************/ - -static bool up_rxavailable(struct uart_dev_s *dev) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - return the_uart->rx_cnt > 0; -} - -/**************************************************************************** - * Name: up_send - * - * Description: - * This method will send one byte on the UART. - * - ****************************************************************************/ - -static void up_send(struct uart_dev_s *dev, int ch) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - the_uart->tx_buf[0] = (uint8_t)ch; - the_uart->tx_buf[1] = 0; - the_uart->tx_cnt = 1; - gap8_udma_tx_start(&the_uart->udma, the_uart->tx_buf, 1, 1); -} - -/**************************************************************************** - * Name: up_txint - * - * Description: - * Call to enable or disable TX interrupts - * - ****************************************************************************/ - -static void up_txint(struct uart_dev_s *dev, bool enable) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - irqstate_t flags; - - flags = enter_critical_section(); - - if (enable) - { - gap8_udma_tx_setirq(&the_uart->udma, 1); - - /* Fake a TX interrupt here by just calling uart_xmitchars() with - * interrupts disabled (note this may recurse). - */ - - uart_xmitchars(dev); - } - else - { - gap8_udma_tx_setirq(&the_uart->udma, 0); - } - - leave_critical_section(flags); -} - -/**************************************************************************** - * Name: up_txready - * - * Description: - * Return true if the tranmsit data register is empty - * - ****************************************************************************/ - -static bool up_txready(struct uart_dev_s *dev) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - return (the_uart->tx_cnt == 0) ? true : false; -} - -/**************************************************************************** - * Name: up_txempty - * - * Description: - * Return true if the transmit data register is empty - * - ****************************************************************************/ - -static bool up_txempty(struct uart_dev_s *dev) -{ - struct gap8_uart_t *the_uart = (struct gap8_uart_t *)dev->priv; - - return (the_uart->tx_cnt == 0) ? true : false; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -#ifdef USE_EARLYSERIALINIT - -/**************************************************************************** - * Name: up_earlyserialinit - * - * Description: - * Performs the low level UART initialization early in debug so that the - * serial console will be available during bootup. This must be called - * before up_serialinit. NOTE: This function depends on GPIO pin - * configuration performed in up_consoleinit() and main clock - * initialization performed in up_clkinitialize(). - * - ****************************************************************************/ - -void up_earlyserialinit(void) -{ - /* Configuration whichever one is the console */ - -#ifdef CONFIG_UART_SERIAL_CONSOLE - g_uart0port.isconsole = true; - up_setup(&g_uart0port); -#endif -} -#endif - -/**************************************************************************** - * Name: up_serialinit - * - * Description: - * Register serial console and serial ports. This assumes - * that up_earlyserialinit was called previously. - * - ****************************************************************************/ - -void up_serialinit(void) -{ -#ifdef CONFIG_UART_SERIAL_CONSOLE - uart_register("/dev/console", &g_uart0port); -#endif - - uart_register("/dev/ttyS0", &g_uart0port); -} - -/**************************************************************************** - * Name: up_putc - * - * Description: - * Provide priority, low-level access to support OS debug writes - * - ****************************************************************************/ - -int up_putc(int ch) -{ -#ifdef CONFIG_UART_SERIAL_CONSOLE - struct uart_dev_s *dev = (struct uart_dev_s *)&g_uart0port; - - /* Check for LF */ - - if (ch == '\n') - { - /* Add CR */ - - up_putc('\r'); - } - - up_send(dev, ch); -#endif - return ch; -} diff --git a/arch/risc-v/src/gap8/gap8_uart.h b/arch/risc-v/src/gap8/gap8_uart.h deleted file mode 100644 index 108c6997cfa82..0000000000000 --- a/arch/risc-v/src/gap8/gap8_uart.h +++ /dev/null @@ -1,70 +0,0 @@ -/************************************************************************************ - * 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/arch/risc-v/src/gap8/gap8_udma.c b/arch/risc-v/src/gap8/gap8_udma.c deleted file mode 100644 index 86628cdc185de..0000000000000 --- a/arch/risc-v/src/gap8/gap8_udma.c +++ /dev/null @@ -1,378 +0,0 @@ -/**************************************************************************** - * 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. - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include "gap8_udma.h" -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -#define CHECK_CHANNEL_ID(INSTANCE) \ - if ((INSTANCE) == NULL || \ - (INSTANCE)->id >= GAP8_UDMA_NR_CHANNELS) \ - { \ - return ERROR; \ - } - -/**************************************************************************** - * 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; - - CHECK_CHANNEL_ID(instance) - - id = instance->id; - _peripherals[id] = instance; - - /* Enable clock gating */ - - UDMA_GC->CG |= (1L << id); - - return OK; -} - -/**************************************************************************** - * 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 OK; -} - -/**************************************************************************** - * 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 OK; -} - -/**************************************************************************** - * 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 OK; -} - -/**************************************************************************** - * 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 OK; -} - -/**************************************************************************** - * 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 OK; -} - -/**************************************************************************** - * Name: gap8_udma_tx_poll - * - * Description: - * Return OK 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 ? OK : ERROR; -} - -/**************************************************************************** - * Name: gap8_udma_rx_poll - * - * Description: - * Return OK 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 ? OK : ERROR; -} - -/**************************************************************************** - * Name: gap8_udma_doirq - * - * Description: - * uDMA ISR - * - ****************************************************************************/ - -int gap8_udma_doirq(int irq, void *context, FAR void *arg) -{ - struct gap8_udma_peripheral *the_peripheral; - uint32_t event = SOC_EVENTS->CURRENT_EVENT & 0xff; - - if (event > GAP8_UDMA_MAX_EVENT) - { - /* Bypass */ - - return OK; - } - - /* Peripheral id happened to be half of event... */ - - the_peripheral = _peripherals[event >> 1]; - if (the_peripheral == NULL) - { - return OK; - } - - 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 */ - - 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 OK; -} diff --git a/arch/risc-v/src/gap8/gap8_udma.h b/arch/risc-v/src/gap8/gap8_udma.h deleted file mode 100644 index d7f3f34b677ed..0000000000000 --- a/arch/risc-v/src/gap8/gap8_udma.h +++ /dev/null @@ -1,225 +0,0 @@ -/************************************************************************************ - * 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. - ************************************************************************************/ - -#ifndef _ARCH_RISCV_SRC_GAP8_UDMA_H -#define _ARCH_RISCV_SRC_GAP8_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, FAR void *arg); - -#endif /* _ARCH_RISCV_SRC_GAP8_UDMA_H */ diff --git a/arch/risc-v/src/rv32im/Kconfig b/arch/risc-v/src/rv32im/Kconfig index fd5939b82e0a2..0233852a41787 100644 --- a/arch/risc-v/src/rv32im/Kconfig +++ b/arch/risc-v/src/rv32im/Kconfig @@ -26,15 +26,6 @@ config RV32IM_TOOLCHAIN_GNU_RVGW This option should work for any modern GNU toolchain (GCC 5.2 or newer) configured for riscv32-unknown-elf. -config RI5CY_GAP8_TOOLCHAIN - bool "toolchain from gap_riscv_toolchain" - select ARCH_TOOLCHAIN_GNU - ---help--- - Choose the toolchain of riscv32-unknown-elf with full support - for PULP extensions. gap_sdk also uses it. - https://github.com/GreenWaves-Technologies/gap_riscv_toolchain/ - - endchoice config RV32IM_HW_MULDIV diff --git a/arch/risc-v/src/rv32im/Toolchain.defs b/arch/risc-v/src/rv32im/Toolchain.defs index 13825557c657d..17ac2ea649310 100644 --- a/arch/risc-v/src/rv32im/Toolchain.defs +++ b/arch/risc-v/src/rv32im/Toolchain.defs @@ -52,10 +52,6 @@ ifeq ($(filter y, $(CONFIG_RV32IM_TOOLCHAIN_GNU_RVGW)),y) CONFIG_RISCV_TOOLCHAIN ?= GNU_RVG endif -ifeq ($(filter y, $(CONFIG_RI5CY_GAP8_TOOLCHAIN)),y) - CONFIG_RISCV_TOOLCHAIN ?= GNU_RISCY -endif - # # Supported toolchains # @@ -88,11 +84,6 @@ ifeq ($(CONFIG_RISCV_TOOLCHAIN),GNU_RVG) endif endif -ifeq ($(CONFIG_RISCV_TOOLCHAIN),GNU_RISCY) - CROSSDEV ?= riscv32-unknown-elf- - ARCHCPUFLAGS = -march=rv32imcxgap8 -mPE=8 -mFC=1 -D__riscv__ -D__pulp__ -D__GAP8__ -endif - # Individual tools may limit the optimization level but, by default, the # optimization level will be set to -Os diff --git a/boards/Kconfig b/boards/Kconfig index c4ddc79a24e2c..fbdbce64ee560 100644 --- a/boards/Kconfig +++ b/boards/Kconfig @@ -345,13 +345,6 @@ config ARCH_BOARD_FREEDOM_KL26Z This is the configuration for the NXP/FreeScale Freedom KL26Z board. This board has the K26Z128VLH4 chip with a built-in SDA debugger. -config ARCH_BOARD_GAPUINO - bool "GWT gapuino board" - depends on ARCH_CHIP_GAP8 - select UART_SERIALDRIVER - ---help--- - NuttX port for gapuino, a GAP8 evaluation board. - config ARCH_BOARD_HIFIVE1_REVB bool "HiFive1 Rev B board" depends on ARCH_CHIP_FE310 @@ -2242,7 +2235,6 @@ config ARCH_BOARD default "freedom-k66f" if ARCH_BOARD_FREEDOM_K66F default "freedom-kl25z" if ARCH_BOARD_FREEDOM_KL25Z default "freedom-kl26z" if ARCH_BOARD_FREEDOM_KL26Z - default "gapuino" if ARCH_BOARD_GAPUINO default "hifive1-revb" if ARCH_BOARD_HIFIVE1_REVB default "hymini-stm32v" if ARCH_BOARD_HYMINI_STM32V default "imxrt1020-evk" if ARCH_BOARD_IMXRT1020_EVK @@ -3034,9 +3026,6 @@ endif if ARCH_BOARD_ARTY_A7 source "boards/risc-v/litex/arty_a7/Kconfig" endif -if ARCH_BOARD_GAPUINO -source "boards/risc-v/gap8/gapuino/Kconfig" -endif if ARCH_BOARD_HIFIVE_REVB source "boards/risc-v/fe310/hifive1-revb/Kconfig" endif diff --git a/boards/risc-v/gap8/gapuino/Kconfig b/boards/risc-v/gap8/gapuino/Kconfig deleted file mode 100644 index 90a103939101c..0000000000000 --- a/boards/risc-v/gap8/gapuino/Kconfig +++ /dev/null @@ -1,9 +0,0 @@ -# -# For a description of the syntax of this configuration file, -# see misc/tools/kconfig-language.txt. -# - -if ARCH_BOARD_GAPUINO - - -endif diff --git a/boards/risc-v/gap8/gapuino/README.txt b/boards/risc-v/gap8/gapuino/README.txt deleted file mode 100644 index ee27958eae2d1..0000000000000 --- a/boards/risc-v/gap8/gapuino/README.txt +++ /dev/null @@ -1,89 +0,0 @@ -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/boards/risc-v/gap8/gapuino/configs/nsh/defconfig b/boards/risc-v/gap8/gapuino/configs/nsh/defconfig deleted file mode 100644 index 4294bf62a0bee..0000000000000 --- a/boards/risc-v/gap8/gapuino/configs/nsh/defconfig +++ /dev/null @@ -1,50 +0,0 @@ -# -# This file is autogenerated: PLEASE DO NOT EDIT IT. -# -# You can use "make menuconfig" to make any modifications to the installed .config file. -# You can then do "make savedefconfig" to generate a new defconfig file that includes your -# modifications. -# -# CONFIG_NSH_DISABLE_LOSMART is not set -# CONFIG_STANDARD_SERIAL is not set -CONFIG_ARCH="risc-v" -CONFIG_ARCH_BOARD="gapuino" -CONFIG_ARCH_BOARD_GAPUINO=y -CONFIG_ARCH_CHIP="gap8" -CONFIG_ARCH_CHIP_GAP8=y -CONFIG_ARCH_RISCV=y -CONFIG_ARCH_STACKDUMP=y -CONFIG_BOARD_LOOPSPERMSEC=15000 -CONFIG_BUILTIN=y -CONFIG_DEBUG_FULLOPT=y -CONFIG_DEBUG_SYMBOLS=y -CONFIG_DEV_ZERO=y -CONFIG_FS_PROCFS=y -CONFIG_IDLETHREAD_STACKSIZE=2048 -CONFIG_INTELHEX_BINARY=y -CONFIG_LIBC_PERROR_STDOUT=y -CONFIG_LIBC_STRERROR=y -CONFIG_MAX_TASKS=16 -CONFIG_NFILE_DESCRIPTORS=8 -CONFIG_NSH_ARCHINIT=y -CONFIG_NSH_BUILTIN_APPS=y -CONFIG_NSH_DISABLE_IFUPDOWN=y -CONFIG_NSH_DISABLE_MKRD=y -CONFIG_NSH_FILEIOSIZE=512 -CONFIG_NSH_LINELEN=64 -CONFIG_NSH_READLINE=y -CONFIG_NSH_STRERROR=y -CONFIG_PREALLOC_TIMERS=4 -CONFIG_RAM_SIZE=524288 -CONFIG_RAM_START=0x1C000000 -CONFIG_RAW_BINARY=y -CONFIG_RI5CY_GAP8_TOOLCHAIN=y -CONFIG_RR_INTERVAL=200 -CONFIG_RV32IM_HW_MULDIV=y -CONFIG_RV32IM_SYSTEM_CSRRS_SUPPORT=y -CONFIG_START_DAY=27 -CONFIG_START_YEAR=2013 -CONFIG_SYSTEM_NSH=y -CONFIG_TASK_NAME_SIZE=0 -CONFIG_UART_SERIAL_CONSOLE=y -CONFIG_USER_ENTRYPOINT="nsh_main" diff --git a/boards/risc-v/gap8/gapuino/include/board.h b/boards/risc-v/gap8/gapuino/include/board.h deleted file mode 100644 index 64637acaa6bf9..0000000000000 --- a/boards/risc-v/gap8/gapuino/include/board.h +++ /dev/null @@ -1,77 +0,0 @@ -/**************************************************************************** - * 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 __BOARDS_RISC-V_GAP8_GAPUINO_INCLUDE_BOARD_H -#define __BOARDS_RISC-V_GAP8_GAPUINO_INCLUDE_BOARD_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#ifndef __ASSEMBLY__ -# include -#endif - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Public Data - ****************************************************************************/ - -#ifndef __ASSEMBLY__ - -#undef EXTERN -#if defined(__cplusplus) -#define EXTERN extern "C" -extern "C" -{ -#else -#define EXTERN extern -#endif - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#undef EXTERN -#if defined(__cplusplus) -} -#endif -#endif /* __ASSEMBLY__ */ -#endif /* __BOARDS_RISC-V_GAP8_GAPUINO_INCLUDE_BOARD_H */ diff --git a/boards/risc-v/gap8/gapuino/scripts/Make.defs b/boards/risc-v/gap8/gapuino/scripts/Make.defs deleted file mode 100644 index 5b1a70ebbcfe8..0000000000000 --- a/boards/risc-v/gap8/gapuino/scripts/Make.defs +++ /dev/null @@ -1,64 +0,0 @@ -############################################################################ -# boards/risc-v/gap8/gapuino/scripts/Make.defs -# -# Licensed to the Apache Software Foundation (ASF) under one or more -# contributor license agreements. See the NOTICE file distributed with -# this work for additional information regarding copyright ownership. The -# ASF licenses this file to you under the Apache License, Version 2.0 (the -# "License"); you may not use this file except in compliance with the -# License. You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, WITHOUT -# WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the -# License for the specific language governing permissions and limitations -# under the License. -# -############################################################################ - -include $(TOPDIR)/.config -include $(TOPDIR)/tools/Config.mk -include $(TOPDIR)/arch/risc-v/src/rv32im/Toolchain.defs - -LDSCRIPT = ld.script - -ifeq ($(CONFIG_CYGWIN_WINTOOL),y) - ARCHSCRIPT = -T "${shell cygpath -w $(BOARD_DIR)$(DELIM)scripts$(DELIM)$(LDSCRIPT)}" -else - ARCHSCRIPT = -T$(BOARD_DIR)$(DELIM)scripts$(DELIM)$(LDSCRIPT) -endif - -ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - ARCHOPTIMIZATION = -g - ASARCHCPUFLAGS += -Wa,-g -endif - -ifneq ($(CONFIG_DEBUG_NOOPT),y) - ARCHOPTIMIZATION += $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer -endif - -ARCHCFLAGS = -fno-builtin -ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fcheck-new -fno-rtti -ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow -Wundef -ARCHWARNINGSXX = -Wall -Wshadow -Wundef -ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10 - -CFLAGS := $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS) -pipe -CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS) -CXXFLAGS := $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS) -pipe -CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS) -CPPFLAGS := $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRAFLAGS) -AFLAGS += $(CFLAGS) -D__ASSEMBLY__ $(ASARCHCPUFLAGS) - -NXFLATLDFLAGS1 = -r -d -warn-common -NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections -LDNXFLATFLAGS = -e main -s 2048 - -ifneq ($(CROSSDEV),arm-nuttx-elf-) - LDFLAGS += -nostartfiles -nodefaultlibs -melf32lriscv -endif -ifeq ($(CONFIG_DEBUG_SYMBOLS),y) - LDFLAGS += -g -melf32lriscv -endif diff --git a/boards/risc-v/gap8/gapuino/scripts/ld.script b/boards/risc-v/gap8/gapuino/scripts/ld.script deleted file mode 100644 index 52bd44e026cf7..0000000000000 --- a/boards/risc-v/gap8/gapuino/scripts/ld.script +++ /dev/null @@ -1,221 +0,0 @@ -/**************************************************************************** - * 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 : ORIGIN = 0x1C000000, LENGTH = 0x80000 - FC_tcdm : ORIGIN = 0x1B000004, LENGTH = 0x3ffc - FC_tcdm_aliased : ORIGIN = 0x00000004, LENGTH = 0x3ffc -} - -__L1_STACK_SIZE = 0x400; -__FC_STACK_SIZE = 0x1000; - -/* 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. - */ - -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 - - .text : { - . = ALIGN(4); - _stext = .; - *(.text.reset) - *(.text) - *(.text.*) - _etext = .; - *(.lit) - *(.shdata) - _endtext = .; - } > L2 - - .ctors : - { - . = ALIGN(4); - __CTOR_LIST__ = .; - - /* gcc uses crtbegin.o to find the start of - * the constructors, so we make sure it is - * first. Because this is a wildcard, it - * doesn't matter if the user does not - * actually link against crtbegin.o; the - * linker won't look for a file to match a - * wildcard. The wildcard also means that it - * doesn't matter which directory crtbegin.o - * is in. - */ - - KEEP (*crtbegin.o(.ctors)) - KEEP (*crtbegin?.o(.ctors)) - - /* We don't want to include the .ctor section from - * from the crtend.o file until after the sorted ctors. - * The .ctor section from the crtend file contains the - * end of ctors marker and it must be last - */ - - KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors)) - KEEP (*(SORT(.ctors.*))) - KEEP (*(.ctors)) - __CTOR_END__ = .; - } > L2 - - .dtors : { - . = ALIGN(4); - __DTOR_LIST__ = .; - KEEP (*crtbegin.o(.dtors)) - KEEP (*crtbegin?.o(.dtors)) - KEEP (*(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors)) - KEEP (*(SORT(.dtors.*))) - KEEP (*(.dtors)) - __DTOR_END__ = .; - } > L2 - - /*--------------------------------------------------------------------*/ - /* Global constructor/destructor segment */ - /*--------------------------------------------------------------------*/ - - .preinit_array : - { - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP (*(.preinit_array*)) - PROVIDE_HIDDEN (__preinit_array_end = .); - } > L2 - - .init_array : - { - PROVIDE_HIDDEN (__init_array_start = .); - KEEP (*(SORT(.init_array.*))) - KEEP (*(.init_array*)) - PROVIDE_HIDDEN (__init_array_end = .); - } > L2 - - .fini_array : - { - PROVIDE_HIDDEN (__fini_array_start = .); - KEEP (*(SORT(.fini_array.*))) - KEEP (*(.fini_array*)) - PROVIDE_HIDDEN (__fini_array_end = .); - } > 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 - - .gnu.offload_funcs : - /* GCC Offload table of offloaded functions and variables */ - { - . = ALIGN(4); - KEEP(*(.gnu.offload_funcs)) - } > L2 - - .gnu.offload_vars : - { - . = ALIGN(4); - KEEP(*(.gnu.offload_vars)) - } > L2 - - .data : { - . = ALIGN(4); - __DATA_RAM = .; - __data_start__ = .; /* create a global symbol at data start */ - *(.data); - *(.data.*) - KEEP(*(.jcr*)) - . = ALIGN(4); - __data_end__ = .; /* define a global symbol at data end */ - } > L2 - - .bss : - { - . = ALIGN(4); - _sbss = .; - __bss_start__ = .; - *(.bss) - *(.bss.*) - *(.sbss) - *(.sbss.*) - *(COMMON) - . = ALIGN(4); - __bss_end__ = .; - _ebss = .; - } > L2 - - /* Heap would exhaust the L2 RAM */ - - _heap_start = .; - _heap_end = ORIGIN(L2) + LENGTH(L2); - - /* Idle stack is on FC tdcm */ - _idle_stack_start = ORIGIN(FC_tcdm); - _idle_stack_end = ORIGIN(FC_tcdm) + LENGTH(FC_tcdm); - - .stab 0 (NOLOAD) : - { - [ .stab ] - } - - .stabstr 0 (NOLOAD) : - { - [ .stabstr ] - } -} diff --git a/boards/risc-v/gap8/gapuino/src/Makefile b/boards/risc-v/gap8/gapuino/src/Makefile deleted file mode 100644 index 0beac0cfccadb..0000000000000 --- a/boards/risc-v/gap8/gapuino/src/Makefile +++ /dev/null @@ -1,6 +0,0 @@ - -include $(TOPDIR)/Make.defs - -CSRCS = gapuino_appinit.c gapuino_sysinit.c - -include $(TOPDIR)/boards/Board.mk diff --git a/boards/risc-v/gap8/gapuino/src/gapuino_appinit.c b/boards/risc-v/gap8/gapuino/src/gapuino_appinit.c deleted file mode 100644 index b8bc2aef0c379..0000000000000 --- a/boards/risc-v/gap8/gapuino/src/gapuino_appinit.c +++ /dev/null @@ -1,94 +0,0 @@ -/**************************************************************************** - * boards/risc-v/gap8/gapuino/src/gapuino_appinit.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 -#include - -#include -#include - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: board_app_initialize - * - * Description: - * Perform architecture specific initialization - * - * Input Parameters: - * arg - The boardctl() argument is passed to the board_app_initialize() - * implementation without modification. The argument has no - * meaning to NuttX; the meaning of the argument is a contract - * between the board-specific initialization logic and the - * matching application logic. The value could be such things as a - * mode enumeration value, a set of DIP switch switch settings, a - * pointer to configuration data read from a file or serial FLASH, - * or whatever you would like to do with it. Every implementation - * should accept zero/NULL as a default configuration. - * - * Returned Value: - * Zero (OK) is returned on success; a negated errno value is returned on - * any failure to indicate the nature of the failure. - * - ****************************************************************************/ - -int board_app_initialize(uintptr_t arg) -{ - int ret = OK; - -#ifdef CONFIG_FS_PROCFS - /* Mount the proc filesystem */ - - ret = nx_mount(NULL, CONFIG_NSH_PROC_MOUNTPOINT, "procfs", 0, NULL); - if (ret < 0) - { - syslog(LOG_ERR, - "ERROR: Failed to mount the PROC filesystem: %d\n", ret); - return ret; - } -#endif - - return ret; -} diff --git a/boards/risc-v/gap8/gapuino/src/gapuino_sysinit.c b/boards/risc-v/gap8/gapuino/src/gapuino_sysinit.c deleted file mode 100644 index 4fc4e943293e8..0000000000000 --- a/boards/risc-v/gap8/gapuino/src/gapuino_sysinit.c +++ /dev/null @@ -1,123 +0,0 @@ -/**************************************************************************** - * 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 -#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(); -}