summaryrefslogtreecommitdiff
path: root/chip
diff options
context:
space:
mode:
authorDino Li <Dino.Li@ite.com.tw>2019-06-10 16:26:36 +0800
committerCommit Bot <commit-bot@chromium.org>2019-06-11 17:26:38 +0000
commit59d060ebfe68082f4ea87214ffcda976c55176af (patch)
treee237e25e9979220a716b72b65d43fb559504bc60 /chip
parent3a668749460466ff002b5dd2cbf00529f97e5974 (diff)
downloadchrome-ec-59d060ebfe68082f4ea87214ffcda976c55176af.tar.gz
core:RISC-V / chip:IT83202
The IT83202 is an embedded controller with RISC-V core. It supports maximum ram size to 256KB and internal flash to 1MB. BUG=none BRANCH=none TEST=EC boots and test console commands (eg: taskinfo, version, sysjump...) on it83202 EVB. Change-Id: I424c0d2878beb941c816363b5c7a3f57fda9fd13 Signed-off-by: Dino Li <Dino.Li@ite.com.tw> Reviewed-on: https://chromium-review.googlesource.com/c/chromiumos/platform/ec/+/1588300 Reviewed-by: Jett Rink <jettrink@chromium.org> Commit-Queue: Jett Rink <jettrink@chromium.org>
Diffstat (limited to 'chip')
-rw-r--r--chip/it83xx/build.mk10
-rw-r--r--chip/it83xx/clock.c56
-rw-r--r--chip/it83xx/config_chip.h91
-rw-r--r--chip/it83xx/config_chip_it8320.h90
-rw-r--r--chip/it83xx/config_chip_it8xxx2.h53
-rw-r--r--chip/it83xx/flash.c31
-rw-r--r--chip/it83xx/intc.h12
-rw-r--r--chip/it83xx/irq.c18
-rw-r--r--chip/it83xx/registers.h11
-rw-r--r--chip/it83xx/system.c40
-rw-r--r--chip/it83xx/watchdog.c9
11 files changed, 299 insertions, 122 deletions
diff --git a/chip/it83xx/build.mk b/chip/it83xx/build.mk
index 5ce2bc8397..23ae81b674 100644
--- a/chip/it83xx/build.mk
+++ b/chip/it83xx/build.mk
@@ -6,8 +6,13 @@
# IT83xx chip specific files build
#
-# IT83xx SoC family has an Andes N801 core.
+# IT8xxx1 and IT83xx are Andes N8 core.
+# IT8xxx2 is RISC-V core.
+ifeq ($(CHIP_FAMILY), it8xxx2)
+CORE:=riscv-rv32i
+else
CORE:=nds32
+endif
# Required chip modules
chip-y=hwtimer.o uart.o gpio.o system.o clock.o irq.o intc.o
@@ -16,7 +21,10 @@ chip-y=hwtimer.o uart.o gpio.o system.o clock.o irq.o intc.o
chip-$(CONFIG_WATCHDOG)+=watchdog.o
chip-$(CONFIG_FANS)+=fan.o pwm.o
chip-$(CONFIG_FLASH_PHYSICAL)+=flash.o
+# IT8xxx2 series use the FPU instruction set of RISC-V (single-precision only).
+ifneq ($(CHIP_FAMILY), it8xxx2)
chip-$(CONFIG_FPU)+=it83xx_fpu.o
+endif
chip-$(CONFIG_PWM)+=pwm.o
chip-$(CONFIG_ADC)+=adc.o
chip-$(CONFIG_HOSTCMD_X86)+=lpc.o ec2i.o
diff --git a/chip/it83xx/clock.c b/chip/it83xx/clock.c
index fde5045389..ee0d20f8a8 100644
--- a/chip/it83xx/clock.c
+++ b/chip/it83xx/clock.c
@@ -141,7 +141,11 @@ void __ram_code clock_ec_pll_ctrl(enum ec_pll_ctrl mode)
IT83XX_ECPM_PLLCTRL = mode;
/* for deep doze / sleep mode */
IT83XX_ECPM_PLLCTRL = mode;
- asm volatile ("dsb");
+ /*
+ * barrier: ensure low power mode setting is taken into control
+ * register before standby instruction.
+ */
+ data_serialization_barrier();
}
void __ram_code clock_pll_changed(void)
@@ -163,12 +167,21 @@ void __ram_code clock_pll_changed(void)
IT83XX_ECPM_SCDCR3 = (pll_div_jtag << 4) | pll_div_ec;
/* EC sleep after standby instruction */
clock_ec_pll_ctrl(EC_PLL_SLEEP);
- /* Global interrupt enable */
- asm volatile ("setgie.e");
- /* EC sleep */
- asm("standby wake_grant");
- /* Global interrupt disable */
- asm volatile ("setgie.d");
+ if (IS_ENABLED(CHIP_CORE_NDS32)) {
+ /* Global interrupt enable */
+ asm volatile ("setgie.e");
+ /* EC sleep */
+ asm("standby wake_grant");
+ /* Global interrupt disable */
+ asm volatile ("setgie.d");
+ } else if (IS_ENABLED(CHIP_CORE_RISCV)) {
+ /* Global interrupt enable */
+ asm volatile ("csrsi mstatus, 0x8");
+ /* EC sleep */
+ asm("wfi");
+ /* Global interrupt disable */
+ asm volatile ("csrci mstatus, 0x8");
+ }
/* New FND clock frequency */
IT83XX_ECPM_SCDCR0 = (pll_div_fnd << 4);
/* EC doze after standby instruction */
@@ -180,6 +193,10 @@ static void clock_set_pll(enum pll_freq_idx idx)
{
int pll;
+ /* TODO(b/134542199): fix me... Changing PLL failed on it83202/ax */
+ if (IS_ENABLED(CHIP_VARIANT_IT83202AX))
+ return;
+
pll_div_fnd = clock_pll_ctrl[idx].div_fnd;
pll_div_ec = clock_pll_ctrl[idx].div_ec;
pll_div_jtag = clock_pll_ctrl[idx].div_jtag;
@@ -401,6 +418,23 @@ int clock_ec_wake_from_sleep(void)
return ec_sleep;
}
+void clock_cpu_standby(void)
+{
+ /* standby instruction */
+ if (IS_ENABLED(CHIP_CORE_NDS32)) {
+ asm("standby wake_grant");
+ } else if (IS_ENABLED(CHIP_CORE_RISCV)) {
+ /*
+ * An interrupt is not able to wake EC up from low power mode.
+ * (AX bug)
+ */
+ if (IS_ENABLED(CHIP_VARIANT_IT83202AX))
+ asm("nop");
+ else
+ asm("wfi");
+ }
+}
+
void __enter_hibernate(uint32_t seconds, uint32_t microseconds)
{
int i;
@@ -455,11 +489,10 @@ defined(CONFIG_HOSTCMD_ESPI)
clock_ec_pll_ctrl(EC_PLL_SLEEP);
interrupt_enable();
/* standby instruction */
- asm("standby wake_grant");
+ clock_cpu_standby();
/* we should never reach that point */
- while (1)
- ;
+ __builtin_unreachable();
}
void clock_sleep_mode_wakeup_isr(void)
@@ -552,8 +585,7 @@ void __idle(void)
clock_ec_pll_ctrl(EC_PLL_DOZE);
idle_doze_cnt++;
}
- /* standby instruction */
- asm("standby wake_grant");
+ clock_cpu_standby();
interrupt_enable();
}
}
diff --git a/chip/it83xx/config_chip.h b/chip/it83xx/config_chip.h
index 7522e89ade..cc5ecb1b57 100644
--- a/chip/it83xx/config_chip.h
+++ b/chip/it83xx/config_chip.h
@@ -6,8 +6,13 @@
#ifndef __CROS_EC_CONFIG_CHIP_H
#define __CROS_EC_CONFIG_CHIP_H
-/* CPU core BFD configuration */
-#include "core/nds32/config_core.h"
+#if defined(CHIP_FAMILY_IT8320) /* N8 core */
+#include "config_chip_it8320.h"
+#elif defined(CHIP_FAMILY_IT8XXX2) /* RISCV core */
+#include "config_chip_it8xxx2.h"
+#else
+#error "Unsupported chip family!"
+#endif
/* Number of IRQ vectors on the IVIC */
#define CONFIG_IRQ_COUNT IT83XX_IRQ_COUNT
@@ -29,25 +34,18 @@
#define I2C_STANDARD_PORT_COUNT 3
#define I2C_ENHANCED_PORT_COUNT 3
-/****************************************************************************/
-/* Memory mapping */
-
-#define CONFIG_RAM_BASE 0x00080000
-#define CONFIG_RAM_SIZE 0x0000C000
-
/* System stack size */
#define CONFIG_STACK_SIZE 1024
/* non-standard task stack sizes */
-#define SMALLER_TASK_STACK_SIZE 384
-#define IDLE_TASK_STACK_SIZE 512
-#define LARGER_TASK_STACK_SIZE 768
-#define VENTI_TASK_STACK_SIZE 896
+#define SMALLER_TASK_STACK_SIZE (384 + CHIP_EXTRA_STACK_SPACE)
+#define IDLE_TASK_STACK_SIZE (512 + CHIP_EXTRA_STACK_SPACE)
+#define LARGER_TASK_STACK_SIZE (768 + CHIP_EXTRA_STACK_SPACE)
+#define VENTI_TASK_STACK_SIZE (896 + CHIP_EXTRA_STACK_SPACE)
/* Default task stack size */
-#define TASK_STACK_SIZE 512
+#define TASK_STACK_SIZE (512 + CHIP_EXTRA_STACK_SPACE)
-#define CONFIG_PROGRAM_MEMORY_BASE 0x00000000
#define CONFIG_FLASH_BANK_SIZE 0x00000800 /* protect bank size */
#define CONFIG_FLASH_ERASE_SIZE 0x00000400 /* erase bank size */
#define CONFIG_FLASH_WRITE_SIZE 0x00000004 /* minimum write size */
@@ -65,66 +63,6 @@
*/
#define CONFIG_FLASH_WRITE_IDEAL_SIZE CONFIG_FLASH_ERASE_SIZE
-#if defined(CHIP_VARIANT_IT8320BX)
-/* This is the physical size of the flash on the chip. We'll reserve one bank
- * in order to emulate per-bank write-protection UNTIL REBOOT. The hardware
- * doesn't support a write-protect pin, and if we make the write-protection
- * permanent, it can't be undone easily enough to support RMA. */
-#define CONFIG_FLASH_SIZE 0x00040000
-/* For IT8320BX, we have to reload cc parameters after ec softreset. */
-#define IT83XX_USBPD_CC_PARAMETER_RELOAD
-/*
- * The voltage detector of CC1 and CC2 is enabled/disabled by different bit
- * of the control register (bit1 and bit5 at register IT83XX_USBPD_CCCSR).
- */
-#define IT83XX_USBPD_CC_VOLTAGE_DETECTOR_INDEPENDENT
-/* For IT8320BX, we have to write 0xff to clear pending bit.*/
-#define IT83XX_ESPI_VWCTRL1_WRITE_FF_CLEAR
-/* For IT8320BX, we have to read observation register of external timer two
- * times to get correct time.
- */
-#define IT83XX_EXT_OBSERVATION_REG_READ_TWO_TIMES
-#elif defined(CHIP_VARIANT_IT8320DX)
-#define CONFIG_FLASH_SIZE 0x00080000
-/*
- * Disable eSPI pad, then PLL change
- * (include EC clock frequency) is succeed even CS# is low.
- */
-#define IT83XX_ESPI_INHIBIT_CS_BY_PAD_DISABLED
-/* The slave frequency is adjustable (bit[2-0] at register IT83XX_ESPI_GCAC1) */
-#define IT83XX_ESPI_SLAVE_MAX_FREQ_CONFIGURABLE
-/*
- * TODO(b/111480168): eSPI HW reset can't be used because the DMA address
- * gets set incorrectly resulting in a memory access exception.
- */
-#define IT83XX_ESPI_RESET_MODULE_BY_FW
-/* Watchdog reset supports hardware reset. */
-/* TODO(b/111264984): watchdog hardware reset function failed. */
-#undef IT83XX_ETWD_HW_RESET_SUPPORT
-/*
- * (b/112452221):
- * Floating-point multiplication single-precision is failed on DX version,
- * so we use the formula "A/(1/B)" to replace a multiplication operation
- * (A*B = A/(1/B)).
- */
-#define IT83XX_FPU_MUL_BY_DIV
-/*
- * More GPIOs can be set as 1.8v input.
- * Please refer to gpio_1p8v_sel[] for 1.8v GPIOs.
- */
-#define IT83XX_GPIO_1P8V_PIN_EXTENDED
-/* All GPIOs support interrupt on rising, falling, and either edge. */
-#define IT83XX_GPIO_INT_FLEXIBLE
-/* Enable interrupts of group 21 and 22. */
-#define IT83XX_INTC_GROUP_21_22_SUPPORT
-/* Enable detect type-c plug in interrupt. */
-#define IT83XX_INTC_PLUG_IN_SUPPORT
-/* Chip Dx transmit status bit of PD register is different from Bx. */
-#define IT83XX_PD_TX_ERROR_STATUS_BIT5
-#else
-#error "Unsupported chip variant!"
-#endif
-
/****************************************************************************/
/* Define our flash layout. */
@@ -144,8 +82,11 @@
/*
* Only it839x series and IT838x DX support mapping LPC I/O cycle 800h ~ 9FFh
* to 0x8D800h ~ 0x8D9FFh of DLM13.
+ *
+ * IT8xxx2 series support mapping LPC/eSPI I/O cycle 800h ~ 9FFh
+ * to 0x80081800 ~ 0x800819FF of DLM1.
*/
-#define CONFIG_H2RAM_BASE 0x0008D000
+#define CONFIG_H2RAM_BASE (CHIP_H2RAM_BASE)
#define CONFIG_H2RAM_SIZE 0x00001000
#define CONFIG_H2RAM_HOST_LPC_IO_BASE 0x800
diff --git a/chip/it83xx/config_chip_it8320.h b/chip/it83xx/config_chip_it8320.h
new file mode 100644
index 0000000000..3bbb2060ea
--- /dev/null
+++ b/chip/it83xx/config_chip_it8320.h
@@ -0,0 +1,90 @@
+/* Copyright 2019 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef __CROS_EC_CONFIG_CHIP_IT8320_H
+#define __CROS_EC_CONFIG_CHIP_IT8320_H
+
+/* CPU core BFD configuration */
+#include "core/nds32/config_core.h"
+
+/* N8 core */
+#define CHIP_CORE_NDS32
+/* The base address of EC interrupt controller registers. */
+#define CHIP_EC_INTC_BASE 0x00F01100
+
+/****************************************************************************/
+/* Memory mapping */
+
+#define CHIP_H2RAM_BASE 0x0008D000 /* 0x0008D000~0x0008DFFF */
+#define CHIP_RAMCODE_BASE 0x0008E000 /* 0x0008E000~0x0008EFFF */
+#define CHIP_EXTRA_STACK_SPACE 0
+
+#define CONFIG_RAM_BASE 0x00080000
+#define CONFIG_RAM_SIZE 0x0000C000
+
+#define CONFIG_PROGRAM_MEMORY_BASE 0x00000000
+
+#if defined(CHIP_VARIANT_IT8320BX)
+/* This is the physical size of the flash on the chip. We'll reserve one bank
+ * in order to emulate per-bank write-protection UNTIL REBOOT. The hardware
+ * doesn't support a write-protect pin, and if we make the write-protection
+ * permanent, it can't be undone easily enough to support RMA.
+ */
+#define CONFIG_FLASH_SIZE 0x00040000
+/* For IT8320BX, we have to reload cc parameters after ec softreset. */
+#define IT83XX_USBPD_CC_PARAMETER_RELOAD
+/*
+ * The voltage detector of CC1 and CC2 is enabled/disabled by different bit
+ * of the control register (bit1 and bit5 at register IT83XX_USBPD_CCCSR).
+ */
+#define IT83XX_USBPD_CC_VOLTAGE_DETECTOR_INDEPENDENT
+/* For IT8320BX, we have to write 0xff to clear pending bit.*/
+#define IT83XX_ESPI_VWCTRL1_WRITE_FF_CLEAR
+/* For IT8320BX, we have to read observation register of external timer two
+ * times to get correct time.
+ */
+#define IT83XX_EXT_OBSERVATION_REG_READ_TWO_TIMES
+#elif defined(CHIP_VARIANT_IT8320DX)
+#define CONFIG_FLASH_SIZE 0x00080000
+/*
+ * Disable eSPI pad, then PLL change
+ * (include EC clock frequency) is succeed even CS# is low.
+ */
+#define IT83XX_ESPI_INHIBIT_CS_BY_PAD_DISABLED
+/* The slave frequency is adjustable (bit[2-0] at register IT83XX_ESPI_GCAC1) */
+#define IT83XX_ESPI_SLAVE_MAX_FREQ_CONFIGURABLE
+/*
+ * TODO(b/111480168): eSPI HW reset can't be used because the DMA address
+ * gets set incorrectly resulting in a memory access exception.
+ */
+#define IT83XX_ESPI_RESET_MODULE_BY_FW
+/* Watchdog reset supports hardware reset. */
+/* TODO(b/111264984): watchdog hardware reset function failed. */
+#undef IT83XX_ETWD_HW_RESET_SUPPORT
+/*
+ * (b/112452221):
+ * Floating-point multiplication single-precision is failed on DX version,
+ * so we use the formula "A/(1/B)" to replace a multiplication operation
+ * (A*B = A/(1/B)).
+ */
+#define IT83XX_FPU_MUL_BY_DIV
+/*
+ * More GPIOs can be set as 1.8v input.
+ * Please refer to gpio_1p8v_sel[] for 1.8v GPIOs.
+ */
+#define IT83XX_GPIO_1P8V_PIN_EXTENDED
+/* All GPIOs support interrupt on rising, falling, and either edge. */
+#define IT83XX_GPIO_INT_FLEXIBLE
+/* Enable interrupts of group 21 and 22. */
+#define IT83XX_INTC_GROUP_21_22_SUPPORT
+/* Enable detect type-c plug in interrupt. */
+#define IT83XX_INTC_PLUG_IN_SUPPORT
+/* Chip Dx transmit status bit of PD register is different from Bx. */
+#define IT83XX_PD_TX_ERROR_STATUS_BIT5
+#else
+#error "Unsupported chip variant!"
+#endif
+
+#endif /* __CROS_EC_CONFIG_CHIP_IT8320_H */
diff --git a/chip/it83xx/config_chip_it8xxx2.h b/chip/it83xx/config_chip_it8xxx2.h
new file mode 100644
index 0000000000..0c2dbced13
--- /dev/null
+++ b/chip/it83xx/config_chip_it8xxx2.h
@@ -0,0 +1,53 @@
+/* Copyright 2019 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef __CROS_EC_CONFIG_CHIP_IT8XXX2_H
+#define __CROS_EC_CONFIG_CHIP_IT8XXX2_H
+
+/* CPU core BFD configuration */
+#include "core/riscv-rv32i/config_core.h"
+
+ /* RISCV core */
+#define CHIP_CORE_RISCV
+#define CHIP_ILM_DLM_ORDER
+/* The base address of EC interrupt controller registers. */
+#define CHIP_EC_INTC_BASE 0x00F03F00
+
+/****************************************************************************/
+/* Memory mapping */
+
+#define CHIP_ILM_BASE 0x80000000
+#define CHIP_H2RAM_BASE 0x80081000 /* 0x80081000~0x80081FFF */
+#define CHIP_RAMCODE_BASE 0x80082000 /* 0x80082000~0x80082FFF */
+#define CHIP_EXTRA_STACK_SPACE 128
+/* We reserve 12KB space for ramcode, h2ram, and immu sections. */
+#define CHIP_RAM_SPACE_RESERVED 0x3000
+
+#define CONFIG_RAM_BASE 0x80080000
+#define CONFIG_RAM_SIZE 0x00040000
+
+#define CONFIG_PROGRAM_MEMORY_BASE (CHIP_ILM_BASE)
+
+#if defined(CHIP_VARIANT_IT83202AX)
+/* TODO(b/133460224): enable properly chip config option. */
+#define CONFIG_FLASH_SIZE 0x00040000
+/* chip id is 3 bytes */
+#define IT83XX_CHIP_ID_3BYTES
+/*
+ * More GPIOs can be set as 1.8v input.
+ * Please refer to gpio_1p8v_sel[] for 1.8v GPIOs.
+ */
+#define IT83XX_GPIO_1P8V_PIN_EXTENDED
+/* All GPIOs support interrupt on rising, falling, and either edge. */
+#define IT83XX_GPIO_INT_FLEXIBLE
+/* Enable interrupts of group 21 and 22. */
+#define IT83XX_INTC_GROUP_21_22_SUPPORT
+/* Enable detect type-c plug in interrupt. */
+#define IT83XX_INTC_PLUG_IN_SUPPORT
+#else
+#error "Unsupported chip variant!"
+#endif
+
+#endif /* __CROS_EC_CONFIG_CHIP_IT8XXX2_H */
diff --git a/chip/it83xx/flash.c b/chip/it83xx/flash.c
index dd50dc3803..658819a193 100644
--- a/chip/it83xx/flash.c
+++ b/chip/it83xx/flash.c
@@ -8,6 +8,7 @@
#include "flash.h"
#include "flash_chip.h"
#include "host_command.h"
+#include "intc.h"
#include "system.h"
#include "util.h"
#include "watchdog.h"
@@ -95,9 +96,10 @@ void FLASH_DMA_CODE dma_reset_immu(int fill_immu)
/* Immu tag sram reset */
IT83XX_GCTRL_MCCR |= 0x10;
/* Make sure the immu(dynamic cache) is reset */
- asm volatile ("dsb");
+ data_serialization_barrier();
+
IT83XX_GCTRL_MCCR &= ~0x10;
- asm volatile ("dsb");
+ data_serialization_barrier();
#ifdef IMMU_CACHE_TAG_INVALID
/*
@@ -122,18 +124,25 @@ void FLASH_DMA_CODE dma_reset_immu(int fill_immu)
void FLASH_DMA_CODE dma_flash_follow_mode(void)
{
- /* Enter follow mode and FSCE# high level */
- IT83XX_SMFI_ECINDAR3 = 0x4F;
+ /*
+ * ECINDAR3-0 are EC-indirect memory address registers.
+ *
+ * Enter follow mode by writing 0xf to low nibble of ECINDAR3 register,
+ * and set high nibble as 0x4 to select internal flash.
+ */
+ IT83XX_SMFI_ECINDAR3 = (EC_INDIRECT_READ_INTERNAL_FLASH | 0xf);
+ /* Set FSCE# as high level by writing 0 to address xfff_fe00h */
IT83XX_SMFI_ECINDAR2 = 0xFF;
IT83XX_SMFI_ECINDAR1 = 0xFE;
IT83XX_SMFI_ECINDAR0 = 0x00;
+ /* EC-indirect memory data register */
IT83XX_SMFI_ECINDDR = 0x00;
}
void FLASH_DMA_CODE dma_flash_follow_mode_exit(void)
{
- /* Exit follow mode */
- IT83XX_SMFI_ECINDAR3 = 0x00;
+ /* Exit follow mode, and keep the setting of selecting internal flash */
+ IT83XX_SMFI_ECINDAR3 = EC_INDIRECT_READ_INTERNAL_FLASH;
IT83XX_SMFI_ECINDAR2 = 0x00;
}
@@ -266,7 +275,7 @@ void FLASH_DMA_CODE dma_flash_cmd_aai_write(int addr, int wlen, uint8_t *wbuf)
uint8_t FLASH_DMA_CODE dma_flash_indirect_fast_read(int addr)
{
- IT83XX_SMFI_ECINDAR3 = 0x40;
+ IT83XX_SMFI_ECINDAR3 = EC_INDIRECT_READ_INTERNAL_FLASH;
IT83XX_SMFI_ECINDAR2 = (addr >> 16) & 0xFF;
IT83XX_SMFI_ECINDAR1 = (addr >> 8) & 0xFF;
IT83XX_SMFI_ECINDAR0 = (addr & 0xFF);
@@ -559,12 +568,16 @@ static void flash_code_static_dma(void)
interrupt_disable();
/* invalid static DMA first */
+ if (IS_ENABLED(CHIP_ILM_DLM_ORDER))
+ IT83XX_GCTRL_MCCR3 &= ~ILMCR_ILM2_ENABLE;
IT83XX_SMFI_SCAR2H = 0x08;
/* Copy to DLM */
IT83XX_GCTRL_MCCR2 |= 0x20;
- memcpy((void *)SCAR2_ILM2_DLM14, (const void *)FLASH_DMA_START,
+ memcpy((void *)CHIP_RAMCODE_BASE, (const void *)FLASH_DMA_START,
IT83XX_ILM_BLOCK_SIZE);
+ if (IS_ENABLED(CHIP_ILM_DLM_ORDER))
+ IT83XX_GCTRL_MCCR3 |= ILMCR_ILM2_ENABLE;
IT83XX_GCTRL_MCCR2 &= ~0x20;
/*
@@ -595,6 +608,8 @@ int flash_pre_init(void)
{
int32_t reset_flags, prot_flags, unwanted_prot_flags;
+ /* By default, select internal flash for indirect fast read. */
+ IT83XX_SMFI_ECINDAR3 = EC_INDIRECT_READ_INTERNAL_FLASH;
flash_code_static_dma();
reset_flags = system_get_reset_flags();
diff --git a/chip/it83xx/intc.h b/chip/it83xx/intc.h
index 3a05e3d5a3..add8e4b9d7 100644
--- a/chip/it83xx/intc.h
+++ b/chip/it83xx/intc.h
@@ -8,6 +8,16 @@
#ifndef __CROS_EC_INTC_H
#define __CROS_EC_INTC_H
+/*
+ * The DSB instruction guarantees a modified architecture or hardware state
+ * can be seen by any following dependent data operations.
+ */
+static inline void data_serialization_barrier(void)
+{
+ if (IS_ENABLED(CHIP_CORE_NDS32))
+ asm volatile ("dsb");
+}
+
int intc_get_ec_int(void);
void pm1_ibf_interrupt(void);
void pm2_ibf_interrupt(void);
@@ -30,6 +40,8 @@ void espi_interrupt(void);
void espi_vw_interrupt(void);
void espi_enable_pad(int enable);
void espi_init(void);
+int chip_get_intc_group(int irq);
+void clock_cpu_standby(void);
#if defined(CONFIG_HOSTCMD_X86) && defined(HAS_TASK_KEYPROTO)
void lpc_kbc_ibf_interrupt(void);
diff --git a/chip/it83xx/irq.c b/chip/it83xx/irq.c
index ee18050627..931cb60710 100644
--- a/chip/it83xx/irq.c
+++ b/chip/it83xx/irq.c
@@ -50,13 +50,19 @@ static const struct {
#endif
};
+int chip_get_intc_group(int irq)
+{
+ return irq_groups[irq / 8].cpu_int[irq % 8];
+}
+
int chip_enable_irq(int irq)
{
int group = irq / 8;
int bit = irq % 8;
- IT83XX_INTC_REG(irq_groups[group].ier_off) |= 1 << bit;
- IT83XX_INTC_REG(IT83XX_INTC_EXT_IER_OFF(group)) |= 1 << bit;
+ IT83XX_INTC_REG(irq_groups[group].ier_off) |= BIT(bit);
+ if (IS_ENABLED(CHIP_CORE_NDS32))
+ IT83XX_INTC_REG(IT83XX_INTC_EXT_IER_OFF(group)) |= BIT(bit);
return irq_groups[group].cpu_int[bit];
}
@@ -67,7 +73,8 @@ int chip_disable_irq(int irq)
int bit = irq % 8;
IT83XX_INTC_REG(irq_groups[group].ier_off) &= ~BIT(bit);
- IT83XX_INTC_REG(IT83XX_INTC_EXT_IER_OFF(group)) &= ~BIT(bit);
+ if (IS_ENABLED(CHIP_CORE_NDS32))
+ IT83XX_INTC_REG(IT83XX_INTC_EXT_IER_OFF(group)) &= ~BIT(bit);
return -1; /* we don't want to mask other IRQs */
}
@@ -78,7 +85,7 @@ int chip_clear_pending_irq(int irq)
int bit = irq % 8;
/* always write 1 clear, no | */
- IT83XX_INTC_REG(irq_groups[group].isr_off) = 1 << bit;
+ IT83XX_INTC_REG(irq_groups[group].isr_off) = BIT(bit);
return -1; /* everything has been done */
}
@@ -98,6 +105,7 @@ void chip_init_irqs(void)
/* Clear all IERx and EXT_IERx */
for (i = 0; i < ARRAY_SIZE(irq_groups); i++) {
IT83XX_INTC_REG(irq_groups[i].ier_off) = 0;
- IT83XX_INTC_REG(IT83XX_INTC_EXT_IER_OFF(i)) = 0;
+ if (IS_ENABLED(CHIP_CORE_NDS32))
+ IT83XX_INTC_REG(IT83XX_INTC_EXT_IER_OFF(i)) = 0;
}
}
diff --git a/chip/it83xx/registers.h b/chip/it83xx/registers.h
index 13f6609662..184b7985fb 100644
--- a/chip/it83xx/registers.h
+++ b/chip/it83xx/registers.h
@@ -414,7 +414,7 @@
#define CPU_INT(irq) CONCAT2(IT83XX_CPU_INT_IRQ_, irq)
/* --- INTC --- */
-#define IT83XX_INTC_BASE 0x00F01100
+#define IT83XX_INTC_BASE CHIP_EC_INTC_BASE
#define IT83XX_INTC_REG(n) REG8(IT83XX_INTC_BASE+(n))
@@ -766,8 +766,14 @@ enum clock_gate_offsets {
/* --- General Control (GCTRL) --- */
#define IT83XX_GCTRL_BASE 0x00F02000
+#ifdef IT83XX_CHIP_ID_3BYTES
+#define IT83XX_GCTRL_CHIPID1 REG8(IT83XX_GCTRL_BASE+0x85)
+#define IT83XX_GCTRL_CHIPID2 REG8(IT83XX_GCTRL_BASE+0x86)
+#define IT83XX_GCTRL_CHIPID3 REG8(IT83XX_GCTRL_BASE+0x87)
+#else
#define IT83XX_GCTRL_CHIPID1 REG8(IT83XX_GCTRL_BASE+0x00)
#define IT83XX_GCTRL_CHIPID2 REG8(IT83XX_GCTRL_BASE+0x01)
+#endif
#define IT83XX_GCTRL_CHIPVER REG8(IT83XX_GCTRL_BASE+0x02)
#define IT83XX_GCTRL_WNCKR REG8(IT83XX_GCTRL_BASE+0x0B)
#define IT83XX_GCTRL_RSTS REG8(IT83XX_GCTRL_BASE+0x06)
@@ -784,6 +790,8 @@ enum clock_gate_offsets {
#define IT83XX_GCTRL_MCCR2 REG8(IT83XX_GCTRL_BASE+0x44)
#define IT83XX_GCTRL_SSCR REG8(IT83XX_GCTRL_BASE+0x4A)
#define IT83XX_GCTRL_ETWDUARTCR REG8(IT83XX_GCTRL_BASE+0x4B)
+#define IT83XX_GCTRL_MCCR3 REG8(IT83XX_GCTRL_BASE+0x5D)
+#define ILMCR_ILM2_ENABLE BIT(2)
#define IT83XX_GCTRL_EWPR0PFH(i) REG8(IT83XX_GCTRL_BASE+0x60+i)
#define IT83XX_GCTRL_EWPR0PFD(i) REG8(IT83XX_GCTRL_BASE+0xA0+i)
#define IT83XX_GCTRL_EWPR0PFEC(i) REG8(IT83XX_GCTRL_BASE+0xC0+i)
@@ -1030,6 +1038,7 @@ REG8(IT83XX_PMC_BASE + (ch > LPC_PM2 ? 5 : 8) + (ch << 4))
#define IT83XX_SMFI_ECINDAR1 REG8(IT83XX_SMFI_BASE+0x3C)
#define IT83XX_SMFI_ECINDAR2 REG8(IT83XX_SMFI_BASE+0x3D)
#define IT83XX_SMFI_ECINDAR3 REG8(IT83XX_SMFI_BASE+0x3E)
+#define EC_INDIRECT_READ_INTERNAL_FLASH BIT(6)
#define IT83XX_SMFI_ECINDDR REG8(IT83XX_SMFI_BASE+0x3F)
#define IT83XX_SMFI_SCAR2L REG8(IT83XX_SMFI_BASE+0x46)
#define IT83XX_SMFI_SCAR2M REG8(IT83XX_SMFI_BASE+0x47)
diff --git a/chip/it83xx/system.c b/chip/it83xx/system.c
index d4f1987d4d..80bd30fc78 100644
--- a/chip/it83xx/system.c
+++ b/chip/it83xx/system.c
@@ -87,7 +87,7 @@ static void system_reset_cause_is_unknown(void)
/*
* We decrease 4 or 2 for "ec_reset_lp" here, that depend on
* which jump and link instruction has executed.
- * (jral5: LP=PC+2, jal: LP=PC+4)
+ * eg: Andes core (jral5: LP=PC+2, jal: LP=PC+4)
*/
ccprintf("===Unknown reset! jump from %x or %x===\n",
ec_reset_lp - 4, ec_reset_lp - 2);
@@ -230,9 +230,14 @@ uint32_t system_get_scratchpad(void)
return value;
}
-static uint16_t system_get_chip_id(void)
+static uint32_t system_get_chip_id(void)
{
+#ifdef IT83XX_CHIP_ID_3BYTES
+ return (IT83XX_GCTRL_CHIPID1 << 16) | (IT83XX_GCTRL_CHIPID2 << 8) |
+ IT83XX_GCTRL_CHIPID3;
+#else
return (IT83XX_GCTRL_CHIPID1 << 8) | IT83XX_GCTRL_CHIPID2;
+#endif
}
static uint8_t system_get_chip_version(void)
@@ -255,16 +260,13 @@ const char *system_get_chip_vendor(void)
const char *system_get_chip_name(void)
{
- static char buf[7];
- uint16_t chip_id = system_get_chip_id();
-
- buf[0] = 'i';
- buf[1] = 't';
- buf[2] = to_hex((chip_id >> 12) & 0xf);
- buf[3] = to_hex((chip_id >> 8) & 0xf);
- buf[4] = to_hex((chip_id >> 4) & 0xf);
- buf[5] = to_hex(chip_id & 0xf);
- buf[6] = '\0';
+ static char buf[8] = {'i', 't'};
+ int num = (IS_ENABLED(IT83XX_CHIP_ID_3BYTES) ? 4 : 3);
+ uint32_t chip_id = system_get_chip_id();
+
+ for (int n = 2; num >= 0; n++, num--)
+ buf[n] = to_hex(chip_id >> (num * 4) & 0xF);
+
return buf;
}
@@ -323,12 +325,10 @@ BUILD_ASSERT(EC_VBNV_BLOCK_SIZE <= BRAM_NVCONTEXT_SIZE);
uintptr_t system_get_fw_reset_vector(uintptr_t base)
{
- uintptr_t reset_vector, num;
-
- num = *(uintptr_t *)base;
- reset_vector = ((num>>24)&0xff) | ((num<<8)&0xff0000) |
- ((num>>8)&0xff00) | ((num<<24)&0xff000000);
- reset_vector = ((reset_vector & 0xffffff) << 1) + base;
-
- return reset_vector;
+ /*
+ * Because our reset vector is at the beginning of image copy
+ * (see init.S). So I just need to return 'base' here and EC will jump
+ * to the reset vector.
+ */
+ return base;
}
diff --git a/chip/it83xx/watchdog.c b/chip/it83xx/watchdog.c
index c9641114ab..54b916a61b 100644
--- a/chip/it83xx/watchdog.c
+++ b/chip/it83xx/watchdog.c
@@ -41,7 +41,11 @@ static void watchdog_set_warning_timer(int32_t ms, int init)
void watchdog_warning_irq(void)
{
#ifdef CONFIG_SOFTWARE_PANIC
+#if defined(CHIP_CORE_NDS32)
pdata_ptr->nds_n8.ipc = get_ipc();
+#elif defined(CHIP_CORE_RISCV)
+ pdata_ptr->riscv.mepc = get_mepc();
+#endif
#endif
/* clear interrupt status */
task_clear_pending_irq(et_ctrl_regs[WDT_EXT_TIMER].irq);
@@ -49,6 +53,7 @@ void watchdog_warning_irq(void)
/* Reset warning timer. */
IT83XX_ETWD_ETXCTRL(WDT_EXT_TIMER) = 0x03;
+#if defined(CHIP_CORE_NDS32)
/*
* The IPC (Interruption Program Counter) is the shadow stack register
* of the PC (Program Counter). It stores the return address of program
@@ -60,6 +65,10 @@ void watchdog_warning_irq(void)
*/
panic_printf("Pre-WDT warning! IPC:%08x LP:%08x TASK_ID:%d\n",
get_ipc(), ilp, task_get_current());
+#elif defined(CHIP_CORE_RISCV)
+ panic_printf("Pre-WDT warning! MEPC:%08x RA:%08x TASK_ID:%d\n",
+ get_mepc(), ira, task_get_current());
+#endif
if (!wdt_warning_fired++)
/*