soc: Microchip: MEC172x initial submission

This is a work in progress initial submission for the
Microchip MEC172x family SoC. This submission does
not contain all header files or power management.

Signed-off-by: Scott Worley <scott.worley@microchip.com>
This commit is contained in:
Scott Worley 2021-06-25 08:38:11 -04:00 committed by Anas Nashif
commit 174707b7e7
10 changed files with 2121 additions and 0 deletions

View file

@ -0,0 +1,19 @@
#
# Copyright (c) 2021, Microchip Technology Inc.
#
# SPDX-License-Identifier: Apache-2.0
#
zephyr_include_directories(${ZEPHYR_BASE}/drivers)
zephyr_sources(
soc.c
)
if(CONFIG_SOC_HAS_TIMING_FUNCTIONS AND NOT CONFIG_BOARD_HAS_TIMING_FUNCTIONS)
if(CONFIG_TIMING_FUNCTIONS)
# Use MEC172x timing calculations only if DWT is not present
if(NOT CONFIG_CORTEX_M_DWT)
zephyr_library_sources(timing.c)
endif()
endif()
endif()

View file

@ -0,0 +1,81 @@
# Microchip MEC172XNSZ MCU
# Copyright (c) 2021 Microchip Technology Inc.
# SPDX-License-Identifier: Apache-2.0
if SOC_MEC172X_NSZ
config SOC
default "mec172xnsz"
config UART_NS16550
default y
depends on SERIAL
config PINMUX_XEC
default y
depends on PINMUX
config GPIO
default y
config ADC_XEC
default y
depends on ADC
config GPIO_XEC
default y
depends on GPIO
config I2C_XEC
default y
depends on I2C
config ESPI_XEC
default y
depends on ESPI
config COUNTER_XEC
default y
depends on COUNTER
config PS2_XEC
default y
depends on PS2
config PWM_XEC
default y
depends on PWM
config KSCAN_XEC
default y
depends on KSCAN
config PECI_XEC
default y
depends on PECI
config SPI_XEC_QMSPI
default y
depends on SPI
config WDT_XEC
default n
depends on WATCHDOG
if SOC_POWER_MANAGEMENT
config PM
default y if SYS_CLOCK_EXISTS
help
Enable the kernel handles extra power management policies whenever
system enters idle state.
config PM_DEVICE
default n
help
Enable device power management support.
endif # SOC_POWER_MANAGEMENT
endif # SOC_MEC172X_NSZ

View file

@ -0,0 +1,36 @@
# Microchip MEC MCU series configuration options
# Copyright (c) 2021 Microchip Technology Inc.
# SPDX-License-Identifier: Apache-2.0
if SOC_SERIES_MEC172X
config SOC_SERIES
default "mec172x"
config NUM_IRQS
# must be >= the highest interrupt number used
# - include the UART interrupts
# All NVIC external sources.
default 181
source "soc/arm/microchip_mec/mec172x/Kconfig.defconfig.mec172x*"
if RTOS_TIMER
config MCHP_XEC_RTOS_TIMER
default y
config SOC_HAS_TIMING_FUNCTIONS
default y if !CORTEX_M_DWT
config ARCH_HAS_CUSTOM_BUSY_WAIT
default y
endif # RTOS_TIMER
config CORTEX_M_SYSTICK
default y
depends on !RTOS_TIMER
endif # SOC_SERIES_MEC172X

View file

@ -0,0 +1,16 @@
# Microchip MEC172X MCU core series
# Copyright (c) 2021 Microchip Technology Inc.
# SPDX-License-Identifier: Apache-2.0
config SOC_SERIES_MEC172X
bool "Microchip MEC172X Series"
select ARM
select CPU_CORTEX_M4
select CPU_CORTEX_M_HAS_DWT
select CPU_HAS_FPU
select CPU_HAS_ARM_MPU
select SOC_FAMILY_MEC
select HAS_SWO
help
Enable support for Microchip MEC Cortex-M4F MCU series

View file

@ -0,0 +1,84 @@
# Microchip MEC172x MCU core series
# Copyright (c) 2021 Microchip Technology Inc.
# SPDX-License-Identifier: Apache-2.0
choice
prompt "MEC172x Selection"
depends on SOC_SERIES_MEC172X
config SOC_MEC172X_NSZ
bool "MEC172X_NSZ"
endchoice
config RTOS_TIMER
bool "MEC172X RTOS timer(32KHz) as kernel timer"
config SOC_POWER_MANAGEMENT
bool "MEC172X Power Management"
config SOC_MEC172X_PROC_CLK_DIV
int "PROC_CLK_DIV"
default 1
range 1 48
help
This divisor defines a ratio between processor clock (HCLK)
and main 96 MHz clock (MCK):
HCLK = MCK / PROC_CLK_DIV
Allowed divider values: 1, 3, 4, 16, and 48.
config SOC_MEC172X_VCI_PINS_AS_GPIOS
bool "Use VCI block pins as GPIOS"
default y
help
By default these pins are not GPIOs, but HW controlled.
Set this if VCI pin block HW logic is not required in the board
design.
choice
prompt "MEC172X debug interface general configuration"
default SOC_MEC172X_DEBUG_WITHOUT_TRACING
depends on SOC_SERIES_MEC172X
help
Select Debug SoC interface support for MEC172x SoC family
config SOC_MEC172X_DEBUG_DISABLED
bool "Disable debug support"
help
Debug port is disabled, JTAG/SWD cannot be enabled. JTAG_RST#
pin is ignored. All other JTAG pins can be used as GPIOs
or other non-JTAG alternate functions.
config SOC_MEC172X_DEBUG_WITHOUT_TRACING
bool "Debug support via Serial wire debug"
help
JTAG port in SWD mode. UART2 and ADC00-03 can be used.
config SOC_MEC172X_DEBUG_AND_TRACING
bool "Debug support via Serial wire debug with tracing enabled"
help
JTAG port is enabled in SWD mode. Refer to tracing options
to see if ADC00-03 can be used or not.
endchoice
choice
prompt "MEC172X debug interface trace configuration"
default SOC_MEC172X_DEBUG_AND_ETM_TRACING
depends on SOC_MEC172X_DEBUG_AND_TRACING
help
Select tracing mode for debug interface
config SOC_MEC172X_DEBUG_AND_ETM_TRACING
bool "Debug support via Serial wire debug"
help
JTAG port in SWD mode and SWV as tracing method.
UART1 can be used, but ADC00-03 and I2C ports 9 and 15 cannot.
config SOC_MEC172X_DEBUG_AND_SWV_TRACING
bool "debug support via Serial Wire Debug and Viewer"
help
JTAG port in SWD mode and SWV as tracing method.
I2C ports 9 and 15 cannot be used.
endchoice

View file

@ -0,0 +1,9 @@
/* linker.ld - Linker command/script file */
/*
* Copyright (c) 2014 Wind River Systems, Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <arch/arm/aarch32/cortex_m/scripts/linker.ld>

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,451 @@
/*
* Copyright (c) 2019 Intel Corporation
* Copyright (c) 2021 Microchip Technology Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <sys/__assert.h>
#include <device.h>
#include <init.h>
#include <soc.h>
#include <kernel.h>
#include <arch/cpu.h>
#include <arch/arm/aarch32/cortex_m/cmsis.h>
#define ECIA_XEC_REG_BASE \
((struct ecia_regs *)(DT_REG_ADDR(DT_NODELABEL(ecia))))
#define ECS_XEC_REG_BASE \
((struct ecs_regs *)(DT_REG_ADDR(DT_NODELABEL(ecs))))
#define GPIO_CTRL_XEC_REG_BASE \
((struct gpio_ctrl_regs *)(DT_REG_ADDR(DT_INST(0, microchip_xec_gpio))))
#define PCR_XEC_REG_BASE \
((struct pcr_regs *)(DT_REG_ADDR(DT_NODELABEL(pcr))))
#define VBATR_XEC_REG_BASE \
((struct vbatr_regs *)(DT_REG_ADDR(DT_NODELABEL(vbr))))
#define CLK32K_SIL_OSC_DELAY 256U
#define CLK32K_PLL_LOCK_WAIT (16U * 1024U)
#define CLK32K_PIN_WAIT 4096U
#define CLK32K_XTAL_WAIT 4096U
#define CLK32K_XTAL_MON_WAIT (64U * 1024U)
#define DEST_PLL 0
#define DEST_PERIPH 1
#define CLK32K_FLAG_CRYSTAL_SE BIT(0)
#define CLK32K_FLAG_PIN_FB_CRYSTAL BIT(1)
#define PIN_32KHZ_IN_MODE (MCHP_GPIO_CTRL_PUD_NONE |\
MCHP_GPIO_CTRL_PWRG_VTR_IO | MCHP_GPIO_CTRL_IDET_DISABLE |\
MCHP_GPIO_CTRL_MUX_F1)
enum clk32k_src {
CLK32K_SRC_SIL_OSC = 0,
CLK32K_SRC_CRYSTAL,
CLK32K_SRC_PIN,
CLK32K_SRC_MAX
};
enum clk32k_dest { CLK32K_DEST_PLL = 0, CLK32K_DEST_PERIPH, CLK32K_DEST_MAX };
/*
* In early Zephyr initialization we don't have timer services. Also, the SoC
* may be running on its ring oscillator (+/- 50% accuracy). Configuring the
* SoC's clock subsystem requires wait/delays. We implement a simple delay
* by writing to a read-only hardware register in the PCR block.
*/
static uint32_t spin_delay(uint32_t cnt)
{
struct pcr_regs *pcr = PCR_XEC_REG_BASE;
uint32_t n;
for (n = 0U; n < cnt; n++) {
pcr->OSC_ID = n;
}
return n;
}
/*
* Make sure PCR sleep enables are clear except for crypto
* which do not have internal clock gating.
*/
static int soc_pcr_init(void)
{
struct pcr_regs *pcr = PCR_XEC_REG_BASE;
pcr->SYS_SLP_CTRL = 0U;
for (int i = 0; i < MCHP_MAX_PCR_SCR_REGS; i++) {
pcr->SLP_EN[i] = 0U;
}
pcr->SLP_EN[3] = MCHP_PCR3_CRYPTO_MASK;
return 0;
}
/*
* Initialize MEC172x EC Interrupt Aggregator (ECIA) and external NVIC
* inputs.
*/
static int soc_ecia_init(void)
{
struct ecia_regs *eciar = ECIA_XEC_REG_BASE;
struct ecs_regs *ecsr = ECS_XEC_REG_BASE;
uint32_t n;
mchp_pcr_periph_slp_ctrl(PCR_ECIA, MCHP_PCR_SLEEP_DIS);
ecsr->INTR_CTRL |= MCHP_ECS_ICTRL_DIRECT_EN;
/* gate off all aggregated outputs */
eciar->BLK_EN_CLR = UINT32_MAX;
/* gate on GIRQ's that are aggregated only */
eciar->BLK_EN_SET = MCHP_ECIA_AGGR_BITMAP;
/* Clear all GIRQn source enables */
for (n = 0; n < MCHP_GIRQ_IDX_MAX; n++) {
eciar->GIRQ[n].EN_CLR = UINT32_MAX;
}
/* Clear all external NVIC enables and pending status */
for (n = 0u; n < MCHP_NUM_NVIC_REGS; n++) {
NVIC->ICER[n] = UINT32_MAX;
NVIC->ICPR[n] = UINT32_MAX;
}
return 0;
}
static bool is_sil_osc_enabled(void)
{
struct vbatr_regs *vbr = VBATR_XEC_REG_BASE;
if (vbr->CLK32_SRC & MCHP_VBATR_CS_SO_EN) {
return true;
}
return false;
}
static void enable_sil_osc(uint32_t delay_cnt)
{
struct vbatr_regs *vbr = VBATR_XEC_REG_BASE;
vbr->CLK32_SRC |= MCHP_VBATR_CS_SO_EN;
spin_delay(delay_cnt);
}
/*
* MEC172x PLL requires a stable 32 KHz input. There are three possible sources
* for 32 KHz input:
* Internal silicon oscillator +/- 2% accuracy
* External crystal: parallel/single ended connection
* External 32 KHz 50% duty cycle waveform on the 32KHZ_IN pin.
* This routine configures the GPIO alternate function used as 32KHZ_IN and
* then spins of the PCR power reset status register until the SoC detects
* edges on the 32KHZ_IN signal or timeout error. If 0 (success) returned the
* caller can switch the PLL input to 32KHZ_IN.
*/
static int enable_32k_pin(uint32_t wait_cnt)
{
struct pcr_regs *pcr = PCR_XEC_REG_BASE;
struct gpio_ctrl_regs *gpcr = GPIO_CTRL_XEC_REG_BASE;
gpcr->CTRL_0165 = PIN_32KHZ_IN_MODE;
do {
if (pcr->PWR_RST_STS & MCHP_PCR_PRS_32K_ACTIVE_RO) {
return 0;
}
} while (wait_cnt--);
return -ETIMEDOUT;
}
/* Do nothing if crystal configuration matches request. */
static int enable_32k_crystal(uint32_t flags)
{
struct vbatr_regs *vbr = VBATR_XEC_REG_BASE;
uint32_t vbcs = vbr->CLK32_SRC;
uint32_t cfg = MCHP_VBATR_CS_SO_EN;
if (flags & CLK32K_FLAG_CRYSTAL_SE) {
cfg |= MCHP_VBATR_CS_XTAL_SE;
}
if ((vbcs & cfg) == cfg) {
return 0;
}
/* parallel and clear high startup current disable */
vbcs &= ~(MCHP_VBATR_CS_SO_EN | MCHP_VBATR_CS_XTAL_SE |
MCHP_VBATR_CS_XTAL_DHC | MCHP_VBATR_CS_XTAL_CNTR_MSK);
if (flags & CLK32K_FLAG_CRYSTAL_SE) { /* single ended connection? */
vbcs |= MCHP_VBATR_CS_XTAL_SE;
}
/* XTAL mode and enable must be separate writes */
vbr->CLK32_SRC = vbcs | MCHP_VBATR_CS_XTAL_CNTR_DG;
vbr->CLK32_SRC |= MCHP_VBATR_CS_SO_EN;
spin_delay(CLK32K_XTAL_WAIT);
vbr->CLK32_SRC |= MCHP_VBATR_CS_XTAL_DHC;
return 0;
}
/*
* Counter checks:
* 32KHz period counter minimum for pass/fail: 16-bit
* 32KHz period counter maximum for pass/fail: 16-bit
* 32KHz duty cycle variation max for pass/fail: 16-bit
* 32KHz valid count minimum: 8-bit
*
* 32768 Hz period is 30.518 us
* HW count resolution is 48 MHz.
* One 32KHz clock pulse = 1464.84 48 MHz counts.
*/
#define CNT32K_TMIN 1435
#define CNT32K_TMAX 1495
#define CNT32K_DUTY_MAX 74
#define CNT32K_VAL_MIN 4
static int check_32k_crystal(void)
{
struct pcr_regs *pcr = PCR_XEC_REG_BASE;
pcr->CNT32K_CTRL = 0U;
pcr->CLK32K_MON_IEN = 0U;
pcr->CLK32K_MON_ISTS = MCHP_PCR_CLK32M_ISTS_MASK;
pcr->CNT32K_PER_MIN = CNT32K_TMIN;
pcr->CNT32K_PER_MAX = CNT32K_TMAX;
pcr->CNT32K_DV_MAX = CNT32K_DUTY_MAX;
pcr->CNT32K_VALID_MIN = CNT32K_VAL_MIN;
pcr->CNT32K_CTRL =
MCHP_PCR_CLK32M_CTRL_PER_EN | MCHP_PCR_CLK32M_CTRL_DC_EN |
MCHP_PCR_CLK32M_CTRL_VAL_EN | MCHP_PCR_CLK32M_CTRL_CLR_CNT;
uint32_t timeout = CLK32K_XTAL_MON_WAIT;
uint32_t status = pcr->CLK32K_MON_ISTS;
while (status == 0) {
if (timeout == 0U) {
return -ETIMEDOUT;
}
timeout--;
status = pcr->CLK32K_MON_ISTS;
}
pcr->CNT32K_CTRL = 0U;
if (status ==
(MCHP_PCR_CLK32M_ISTS_PULSE_RDY | MCHP_PCR_CLK32M_ISTS_PASS_PER |
MCHP_PCR_CLK32M_ISTS_PASS_DC | MCHP_PCR_CLK32M_ISTS_VALID)) {
return 0;
}
return -EBUSY;
}
static void connect_32k_source(enum clk32k_src src, enum clk32k_dest dest,
uint32_t flags)
{
struct pcr_regs *pcr = PCR_XEC_REG_BASE;
struct vbatr_regs *vbr = VBATR_XEC_REG_BASE;
if (dest == CLK32K_DEST_PLL) {
switch (src) {
case CLK32K_SRC_SIL_OSC:
pcr->CLK32K_SRC_VTR = MCHP_PCR_VTR_32K_SRC_SILOSC;
break;
case CLK32K_SRC_CRYSTAL:
pcr->CLK32K_SRC_VTR = MCHP_PCR_VTR_32K_SRC_XTAL;
break;
case CLK32K_SRC_PIN:
pcr->CLK32K_SRC_VTR = MCHP_PCR_VTR_32K_SRC_PIN;
break;
default: /* do not touch HW */
break;
}
} else if (dest == CLK32K_DEST_PERIPH) {
uint32_t vbcs = vbr->CLK32_SRC & ~(MCHP_VBATR_CS_PCS_MSK);
switch (src) {
case CLK32K_SRC_SIL_OSC:
vbr->CLK32_SRC = vbcs | MCHP_VBATR_CS_PCS_VTR_VBAT_SO;
break;
case CLK32K_SRC_CRYSTAL:
vbr->CLK32_SRC = vbcs | MCHP_VBATR_CS_PCS_VTR_VBAT_XTAL;
break;
case CLK32K_SRC_PIN:
if (flags & CLK32K_FLAG_PIN_FB_CRYSTAL) {
vbr->CLK32_SRC =
vbcs | MCHP_VBATR_CS_PCS_VTR_PIN_SO;
} else {
vbr->CLK32_SRC =
vbcs | MCHP_VBATR_CS_PCS_VTR_PIN_XTAL;
}
break;
default: /* do not touch HW */
break;
}
}
}
/*
* This routine checks if the PLL is locked to its input source. Minimum lock
* time is 3.3 ms. Lock time can be larger when the source is an external
* crystal. Crystal cold start times may vary greatly based on many factors.
* Crystals do not like being power cycled.
*/
static int pll_wait_lock(uint32_t wait_cnt)
{
struct pcr_regs *regs = PCR_XEC_REG_BASE;
while (!(regs->OSC_ID & MCHP_PCR_OSC_ID_PLL_LOCK)) {
if (wait_cnt == 0) {
return -ETIMEDOUT;
}
--wait_cnt;
}
return 0;
}
/*
* MEC172x has two 32 KHz clock domains
* PLL domain: 32 KHz clock input for PLL to produce 96 MHz and 48 MHz clocks
* Peripheral domain: 32 KHz clock for subset of peripherals.
* Each domain 32 KHz clock input can be from one of the following sources:
* Internal Silicon oscillator: +/- 2%
* External Crystal connected as parallel or single ended
* External 32KHZ_PIN 50% duty cycle waveform with fall back to either
* Silicon OSC or crystal when 32KHZ_PIN signal goes away or VTR power rail
* goes off.
* At chip reset the PLL is held in reset and the +/- 50% ring oscillator is
* the main clock.
* If no VBAT reset occurs the VBAT 32 KHz soure register maintains its state.
*/
static int soc_clk32_init(enum clk32k_src pll_clk_src,
enum clk32k_src periph_clk_src,
uint32_t flags)
{
if (!is_sil_osc_enabled()) {
enable_sil_osc(CLK32K_SIL_OSC_DELAY);
}
/* Default to 32KHz Silicon OSC for PLL and peripherals */
connect_32k_source(CLK32K_SRC_SIL_OSC, CLK32K_DEST_PLL, 0);
connect_32k_source(CLK32K_SRC_SIL_OSC, CLK32K_DEST_PERIPH, 0);
int rc = pll_wait_lock(CLK32K_PLL_LOCK_WAIT);
if (rc) {
return rc;
}
/*
* We only allow Silicon OSC or Crystal as PLL source.
* Any of the three source is allowed for Peripheral clock
*/
if ((pll_clk_src == CLK32K_SRC_CRYSTAL) ||
(periph_clk_src == CLK32K_SRC_CRYSTAL)) {
enable_32k_crystal(flags);
rc = check_32k_crystal();
if (rc) {
return rc;
}
if (pll_clk_src == CLK32K_SRC_CRYSTAL) {
connect_32k_source(CLK32K_SRC_CRYSTAL, CLK32K_DEST_PLL,
flags);
}
if (periph_clk_src == CLK32K_SRC_CRYSTAL) {
connect_32k_source(CLK32K_SRC_CRYSTAL,
CLK32K_DEST_PERIPH,
flags);
}
rc = pll_wait_lock(CLK32K_PLL_LOCK_WAIT);
} else if (periph_clk_src == CLK32K_SRC_PIN) {
rc = enable_32k_pin(CLK32K_PIN_WAIT);
if (rc) {
return rc;
}
connect_32k_source(CLK32K_SRC_PIN, CLK32K_DEST_PERIPH, flags);
}
return rc;
}
uint32_t soc_get_core_clock(void)
{
struct pcr_regs *regs = PCR_XEC_REG_BASE;
return (uint32_t)(MCHP_EC_CLOCK_INPUT_HZ) / regs->PROC_CLK_CTRL;
}
/*
* MEC172x Errata document DS80000913C
* Programming the PCR clock divider that divides the clock input to the ARM
* Cortex-M4 may cause a clock glitch. The recommended work-around is to
* issue four NOP instruction before and after the write to the PCR processor
* clock control register. The final four NOP instructions are followed by
* data and instruction barriers to flush the Cortex-M4's pipeline.
* NOTE: Zephyr provides inline functions for Cortex-Mx NOP but not for
* data and instruction barrier instructions. Caller's should only invoke this
* function with interrupts locked.
*/
void soc_set_core_clock_div(uint8_t clkdiv)
{
struct pcr_regs *regs = PCR_XEC_REG_BASE;
arch_nop();
arch_nop();
arch_nop();
arch_nop();
regs->PROC_CLK_CTRL = (uint32_t)clkdiv;
arch_nop();
arch_nop();
arch_nop();
arch_nop();
__DSB();
__ISB();
}
static int soc_init(const struct device *dev)
{
uint32_t key, clk32_flags;
int rc = 0;
enum clk32k_src clk_src_pll, clk_src_periph;
ARG_UNUSED(dev);
key = irq_lock();
soc_pcr_init();
soc_ecia_init();
clk32_flags = 0U;
clk_src_pll = DT_PROP_OR(DT_NODELABEL(pcr), pll_32k_src,
CLK32K_SRC_SIL_OSC);
clk_src_periph = DT_PROP_OR(DT_NODELABEL(vbr), periph_32k_src,
CLK32K_SRC_SIL_OSC);
rc = soc_clk32_init(clk_src_pll, clk_src_periph, clk32_flags);
__ASSERT(rc == 0, "SoC: PLL and 32 KHz clock initialization failed");
soc_set_core_clock_div(DT_PROP_OR(DT_NODELABEL(pcr),
cpu_clk_div, CONFIG_SOC_MEC172X_PROC_CLK_DIV));
irq_unlock(key);
return rc;
}
SYS_INIT(soc_init, PRE_KERNEL_1, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT);

View file

@ -0,0 +1,40 @@
/*
* Copyright (c) 2019 Intel Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef __MEC_SOC_H
#define __MEC_SOC_H
#ifndef _ASMLANGUAGE
/*
* MEC172x includes the ARM single precision FPU and the ARM MPU with
* eight regions. Zephyr has an in-tree CMSIS header located in the arch
* include hierarchy that includes the correct ARM CMSIS core_xxx header
* from hal_cmsis based on the k-config CPU selection.
* The Zephyr in-tree header does not provide all the symbols ARM CMSIS
* requires. Zephyr does not define CMSIS FPU present and defaults CMSIS
* MPU present to 0. We define these two symbols here based on our k-config
* selections. NOTE: Zephyr in-tree CMSIS defines the Cortex-M4 hardware
* revision to 0. At this time ARM CMSIS does not appear to use the hardware
* revision in any macros.
*/
#define __FPU_PRESENT CONFIG_CPU_HAS_FPU
#define __MPU_PRESENT CONFIG_CPU_HAS_ARM_MPU
#include "reg/mec172x_regs.h"
#include <sys/util.h>
#include "../common/soc_gpio.h"
#include "../common/soc_pins.h"
#include "../common/soc_espi_channels.h"
#include "../common/soc_espi_saf.h"
uint32_t soc_get_core_clock(void);
#endif
#endif

View file

@ -0,0 +1,76 @@
/*
* Copyright (c) 2020 Intel Corporation.
* Copyright (c) 2021 Microchip Technology Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <arch/arm/aarch32/arch.h>
#include <kernel.h>
#include <sys_clock.h>
#include <timing/timing.h>
#include <soc.h>
/*
* This code is conditionally built please refer to the SoC cmake file and
* is not built normally. If this is is not built then timer5 is available
* for other uses.
*/
#define BTMR_XEC_REG_BASE \
((struct btmr_regs *)(DT_REG_ADDR(DT_NODELABEL(timer5))))
void soc_timing_init(void)
{
struct btmr_regs *regs = BTMR_XEC_REG_BASE;
/* Setup counter */
regs->CTRL = MCHP_BTMR_CTRL_ENABLE | MCHP_BTMR_CTRL_AUTO_RESTART |
MCHP_BTMR_CTRL_COUNT_UP;
regs->PRLD = 0; /* Preload */
regs->CNT = 0; /* Counter value */
regs->IEN = 0; /* Disable interrupt */
regs->STS = 1; /* Clear interrupt */
}
void soc_timing_start(void)
{
regs->CTRL |= MCHP_BTMR_CTRL_START;
}
void soc_timing_stop(void)
{
regs->CTRL &= ~MCHP_BTMR_CTRL_START;
}
timing_t soc_timing_counter_get(void)
{
return regs->CNT;
}
uint64_t soc_timing_cycles_get(volatile timing_t *const start,
volatile timing_t *const end)
{
return *end - *start;
}
uint64_t soc_timing_freq_get(void)
{
return CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC;
}
uint64_t soc_timing_cycles_to_ns(uint64_t cycles)
{
return cycles * NSEC_PER_SEC / CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC;
}
uint64_t soc_timing_cycles_to_ns_avg(uint64_t cycles, uint32_t count)
{
return (uint32_t)soc_timing_cycles_to_ns(cycles) / count;
}
uint32_t soc_timing_freq_get_mhz(void)
{
return (uint32_t)(soc_timing_freq_get() / 1000000);
}