summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--board/tglrvp_ish/board.h2
-rwxr-xr-xchip/ish/aontaskfw/ipapg.S130
-rw-r--r--chip/ish/aontaskfw/ish_aon_defs.h37
-rw-r--r--chip/ish/aontaskfw/ish_aon_share.h4
-rw-r--r--chip/ish/aontaskfw/ish_aontask.c167
-rw-r--r--chip/ish/build.mk5
-rw-r--r--chip/ish/i2c.c12
-rw-r--r--chip/ish/power_mgt.c45
-rw-r--r--chip/ish/power_mgt.h5
-rw-r--r--chip/ish/registers.h28
-rw-r--r--core/minute-ia/interrupts.c7
-rw-r--r--include/config.h5
12 files changed, 435 insertions, 12 deletions
diff --git a/board/tglrvp_ish/board.h b/board/tglrvp_ish/board.h
index 07de274bdd..a9a3d4d544 100644
--- a/board/tglrvp_ish/board.h
+++ b/board/tglrvp_ish/board.h
@@ -79,6 +79,8 @@
#define CONFIG_ISH_PM_D3
#define CONFIG_ISH_PM_RESET_PREP
+#define CONFIG_ISH_IPAPG
+
#define CONFIG_ISH_D0I2_MIN_USEC (15*MSEC)
#define CONFIG_ISH_D0I3_MIN_USEC (50*MSEC)
diff --git a/chip/ish/aontaskfw/ipapg.S b/chip/ish/aontaskfw/ipapg.S
new file mode 100755
index 0000000000..f0d3f8c554
--- /dev/null
+++ b/chip/ish/aontaskfw/ipapg.S
@@ -0,0 +1,130 @@
+/* Copyright 2020 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.
+ */
+
+#include "registers.h"
+
+ .equ PMU_STATUS_PG, (1 << 4)
+ .equ PMU_STATUS_PG_AON, (1 << 5)
+
+ .equ PMU_PG_EN, (1 << 0)
+ .equ PMU_PG_EXIT_COMPLETE, (1 << 8)
+
+ .equ FWST_AON_STATE_MASK, (0x7 << 24)
+ .equ FWST_AON_STATE_HALT, (0x2 << 24)
+
+ .equ EFLAGS_NT, (1 << 14)
+
+ .equ TSS_ESP0_OFFSET, 0x4
+ .equ TSS_LDT_SEG_SEL_OFFSET, 0x60
+
+ .equ AON_CS, 0x4
+ .equ AON_DS, 0xc
+
+
+ .global ipapg
+ipapg:
+ push %ebp
+ push %edi
+ push %esi
+ push %ebx
+ mov %cr0, %eax
+ push %eax
+ mov %cr4, %eax
+ push %eax
+
+ clts
+
+ #write down return address for ROM
+ movl $(PMU_STATUS_PG|PMU_STATUS_PG_AON), PMU_STATUS_REG_ADDR
+ movl $out_of_pg, %eax
+ movl %eax, PMU_SCRATCHPAD0_REG_ADDR
+ movl (%eax), %eax
+ movl %eax, PMU_SCRATCHPAD1_REG_ADDR
+
+ #enable IPAPG, we will actually enter PG on the next halt
+ movl $(PMU_PG_EN|PMU_PG_EXIT_COMPLETE), PMU_PG_EN_REG_ADDR
+
+ #save esp so we can restore stack after returning from ROM
+ lea aon_tss, %eax
+ movl %esp, TSS_ESP0_OFFSET(%eax)
+
+ sti
+ hlt
+
+ #unreachable
+
+
+ #got out of IPAPG, jumped here from ROM if there was no abort condition
+out_of_pg:
+ cli
+
+ #restore stack
+ lea aon_tss, %eax
+ movl TSS_ESP0_OFFSET(%eax), %esp
+
+ #set the nested task bit in eflags
+ pushfl
+ orl $EFLAGS_NT, (%esp)
+ popfl
+
+ clts
+ fninit
+
+ #restore non-volatile registers and CR0 & CR4
+ pop %eax
+ mov %eax, %cr4
+ pop %eax
+ mov %eax, %cr0
+ pop %ebx
+ pop %esi
+ pop %edi
+ pop %ebp
+
+ #check if we're indeed after IPAPG exit
+ testl $PMU_STATUS_PG, PMU_STATUS_REG_ADDR
+ jz after_pg
+
+ #we didn't go through ROM, clear PG_EN bit and return an abort condition to AON
+ movl $0, PMU_PG_EN_REG_ADDR
+ movl $0, %eax
+ jmp return_to_aon
+
+after_pg:
+ #return to caller that we got ouf of PG
+ movl $1, %eax
+
+return_to_aon:
+ movl $0, PMU_STATUS_REG_ADDR
+
+ #return to AON task (still with ROM GDT and segments in case of PG exit)
+ ret
+
+ .global pg_exit_save_ctx
+pg_exit_save_ctx:
+ sgdtl mainfw_gdt
+ str tr
+ ret
+
+ .global pg_exit_restore_ctx
+pg_exit_restore_ctx:
+
+ #load RTOS GDT and AON task
+ lgdtl mainfw_gdt
+ ltr tr
+
+ #load AON LDT and segments
+ lea aon_tss, %eax
+ lldt TSS_LDT_SEG_SEL_OFFSET(%eax)
+ mov $AON_DS, %ax
+ mov %ax, %ds
+ mov %ax, %es
+ mov %ax, %fs
+ mov %ax, %gs
+ mov %ax, %ss
+ ljmpl $AON_CS, $cont
+
+cont:
+ nop
+ ret
diff --git a/chip/ish/aontaskfw/ish_aon_defs.h b/chip/ish/aontaskfw/ish_aon_defs.h
new file mode 100644
index 0000000000..3cc3a491c0
--- /dev/null
+++ b/chip/ish/aontaskfw/ish_aon_defs.h
@@ -0,0 +1,37 @@
+/* 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_ISH_AON_DEFS_H
+#define __CROS_EC_ISH_AON_DEFS_H
+
+#include "ia_structs.h"
+
+/* aontask entry point function */
+void ish_aon_main(void);
+
+#ifdef CONFIG_ISH_IPAPG
+extern int ipapg(void);
+extern void pg_exit_restore_ctx(void);
+extern void pg_exit_save_ctx(void);
+#else
+static int ipapg(void)
+{
+ return 0;
+}
+static void pg_exit_restore_ctx(void)
+{
+}
+static void pg_exit_save_ctx(void)
+{
+}
+#endif
+
+struct gdt_header mainfw_gdt;
+uint16_t tr;
+
+#define FPU_REG_SET_SIZE 108
+uint8_t fpu_reg_set[FPU_REG_SET_SIZE];
+
+#endif /* __CROS_EC_ISH_AON_DEFS_H */
diff --git a/chip/ish/aontaskfw/ish_aon_share.h b/chip/ish/aontaskfw/ish_aon_share.h
index e804bd72e8..ff60a004c9 100644
--- a/chip/ish/aontaskfw/ish_aon_share.h
+++ b/chip/ish/aontaskfw/ish_aon_share.h
@@ -27,6 +27,10 @@ struct ish_aon_share {
uint32_t error_count;
/* last error */
int last_error;
+ /* successfully exit from IPAPG or not */
+ uint32_t pg_exit;
+ /* high 32bits of 64 bits dram address for dma */
+ uint32_t uma_msb;
/* aontask's TSS segment entry */
struct tss_entry *aon_tss;
/* aontask's LDT start address */
diff --git a/chip/ish/aontaskfw/ish_aontask.c b/chip/ish/aontaskfw/ish_aontask.c
index c6e5552127..ab9d02abbf 100644
--- a/chip/ish/aontaskfw/ish_aontask.c
+++ b/chip/ish/aontaskfw/ish_aontask.c
@@ -46,6 +46,7 @@
#include "common.h"
#include "ia_structs.h"
#include "ish_aon_share.h"
+#include "ish_aon_defs.h"
#include "ish_dma.h"
#include "power_mgt.h"
@@ -166,17 +167,14 @@ static struct idt_header aon_idt_hdr = {
(sizeof(struct idt_entry) * AON_IDT_ENTRY_VEC_FIRST))
};
-/* aontask entry point function */
-void ish_aon_main(void);
-
/**
* 8 bytes reserved on stack, just for GDB to show the correct stack
- * information when doing source code level debuging
+ * information when doing source code level debugging
*/
#define AON_SP_RESERVED (8)
/* TSS segment for aon task */
-static struct tss_entry aon_tss = {
+struct tss_entry aon_tss = {
.prev_task_link = 0,
.reserved1 = 0,
.esp0 = (uint8_t *)(CONFIG_AON_PERSISTENT_BASE - AON_SP_RESERVED),
@@ -190,7 +188,7 @@ static struct tss_entry aon_tss = {
.ss2 = 0,
.reserved4 = 0,
.cr3 = 0,
- /* task excute entry point */
+ /* task execute entry point */
.eip = (uint32_t)&ish_aon_main,
.eflags = 0,
.eax = 0,
@@ -525,6 +523,104 @@ static void sram_power(int on)
}
}
+#define RTC_TICKS_IN_SECOND 32768
+
+static __maybe_unused uint64_t get_rtc(void)
+{
+ uint32_t lower;
+ uint32_t upper;
+ do {
+ upper = MISC_ISH_RTC_COUNTER1;
+ lower = MISC_ISH_RTC_COUNTER0;
+ } while (upper != MISC_ISH_RTC_COUNTER1);
+
+ return ((uint64_t)upper << 32) | lower;
+}
+
+#ifdef CONFIG_ISH_IPAPG
+static int is_ipapg_allowed(void)
+{
+ uint32_t power_ctrl_enabled, sw_power_req, power_ctrl_wake;
+ int system_power_state;
+
+ if (!IS_ENABLED(CONFIG_ISH_IPAPG))
+ return 0;
+
+ system_power_state = ((PMU_PMC_HOST_RST_CTL & PMU_HOST_RST_B) == 0);
+
+ PMU_PMC_HOST_RST_CTL = PMU_PMC_HOST_RST_CTL;
+
+ power_ctrl_enabled = PMU_D3_STATUS;
+ sw_power_req = PMU_SW_PG_REQ;
+ power_ctrl_wake = PMU_PMC_PG_WAKE;
+
+ if (system_power_state)
+ power_ctrl_enabled |= PMU_PCE_PG_ALLOWED;
+
+ PMU_INTERNAL_PCE = (power_ctrl_enabled & PMU_PCE_SHADOW_MASK) |
+ (PMU_PCE_CHANGE_DETECTED) | (PMU_PCE_CHANGE_MASK);
+
+ PMU_SW_PG_REQ = sw_power_req | PMU_SW_PG_REQ_B_RISE |
+ PMU_SW_PG_REQ_B_FALL;
+ PMU_PMC_PG_WAKE = power_ctrl_wake | PMU_PMC_PG_WAKE_RISE |
+ PMU_PMC_PG_WAKE_FALL;
+ PMU_D3_STATUS = (PMU_D3_STATUS) & (PMU_D0I3_ENABLE_MASK |
+ PMU_D3_BIT_SET | PMU_BME_BIT_SET);
+
+ power_ctrl_enabled = PMU_D3_STATUS;
+ sw_power_req = PMU_SW_PG_REQ;
+ power_ctrl_wake = PMU_PMC_PG_WAKE;
+
+ if (system_power_state) {
+ uint64_t rtc_start = get_rtc();
+ uint64_t rtc_end;
+ while (power_ctrl_wake & PMU_PMC_PG_WAKE_VAL) {
+ power_ctrl_wake = PMU_PMC_PG_WAKE;
+ rtc_end = get_rtc();
+ if (rtc_end - rtc_start > RTC_TICKS_IN_SECOND)
+ break;
+ }
+ }
+
+ if (((power_ctrl_enabled & PMU_PCE_PG_ALLOWED) || system_power_state) &&
+ (((sw_power_req & PMU_SW_PG_REQ_B_VAL) == 0) ||
+ ((power_ctrl_enabled & PMU_PCE_PMCRE) == 0)) &&
+ ((power_ctrl_wake & PMU_PMC_PG_WAKE_VAL) == 0))
+ return 1;
+ else
+ return 0;
+}
+#else
+static int is_ipapg_allowed(void)
+{
+ return 0;
+}
+#endif
+
+#define NUMBER_IRQ_PINS 30
+static uint32_t ioapic_rte[NUMBER_IRQ_PINS];
+
+static int do_ipapg(void)
+{
+ int ret;
+ uint32_t rte_offset = IOAPIC_IOREDTBL;
+
+ for (int pin = 0; pin < ARRAY_SIZE(ioapic_rte); pin++) {
+ IOAPIC_IDX = rte_offset + pin * 2;
+ ioapic_rte[pin] = IOAPIC_WDW;
+ }
+
+ ret = ipapg();
+
+ rte_offset = IOAPIC_IOREDTBL;
+ for (int pin = 0; pin < ARRAY_SIZE(ioapic_rte); pin++) {
+ IOAPIC_IDX = rte_offset + pin * 2;
+ IOAPIC_WDW = ioapic_rte[pin];
+ }
+
+ return ret;
+}
+
static inline void set_vnnred_aoncg(void)
{
if (IS_ENABLED(CONFIG_ISH_NEW_PM)) {
@@ -543,6 +639,11 @@ static inline void clear_vnnred_aoncg(void)
static void handle_d0i2(void)
{
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ pg_exit_save_ctx();
+ aon_share.pg_exit = 0;
+ }
+
/* set main SRAM into retention mode*/
PMU_LDO_CTRL = PMU_LDO_ENABLE_BIT
| PMU_LDO_RETENTION_BIT;
@@ -552,7 +653,19 @@ static void handle_d0i2(void)
set_vnnred_aoncg();
- ish_mia_halt();
+ if (IS_ENABLED(CONFIG_ISH_IPAPG) && is_ipapg_allowed()) {
+ uint32_t sram_cfg_reg;
+
+ sram_cfg_reg = ISH_SRAM_CTRL_CSFGR;
+
+ aon_share.pg_exit = do_ipapg();
+
+ if (aon_share.pg_exit)
+ ISH_SRAM_CTRL_CSFGR = sram_cfg_reg;
+ } else {
+ ish_mia_halt();
+ }
+
/* wakeup from PMU interrupt */
clear_vnnred_aoncg();
@@ -566,12 +679,23 @@ static void handle_d0i2(void)
*/
while (!(PMU_LDO_CTRL & PMU_LDO_READY_BIT))
continue;
+
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ if (aon_share.pg_exit)
+ ish_dma_set_msb(PAGING_CHAN, aon_share.uma_msb,
+ aon_share.uma_msb);
+ }
}
static void handle_d0i3(void)
{
int ret;
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ pg_exit_save_ctx();
+ aon_share.pg_exit = 0;
+ }
+
/* store main FW 's context to IMR DDR from main SRAM */
ret = store_main_fw();
@@ -584,7 +708,19 @@ static void handle_d0i3(void)
set_vnnred_aoncg();
- ish_mia_halt();
+ if (IS_ENABLED(CONFIG_ISH_IPAPG) && is_ipapg_allowed()) {
+ uint32_t sram_cfg_reg;
+
+ sram_cfg_reg = ISH_SRAM_CTRL_CSFGR;
+
+ aon_share.pg_exit = do_ipapg();
+
+ if (aon_share.pg_exit)
+ ISH_SRAM_CTRL_CSFGR = sram_cfg_reg;
+ } else {
+ ish_mia_halt();
+ }
+
/* wakeup from PMU interrupt */
clear_vnnred_aoncg();
@@ -592,6 +728,12 @@ static void handle_d0i3(void)
/* power on main SRAM */
sram_power(1);
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ if (aon_share.pg_exit)
+ ish_dma_set_msb(PAGING_CHAN, aon_share.uma_msb,
+ aon_share.uma_msb);
+ }
+
/* restore main FW 's context to main SRAM from IMR DDR */
ret = restore_main_fw();
@@ -787,9 +929,16 @@ void ish_aon_main(void)
/* restore main FW's IDT and switch back to main FW */
__asm__ volatile(
"lidtl %0;\n"
- "iret;"
:
: "m" (aon_share.main_fw_idt_hdr)
);
+
+ if (IS_ENABLED(CONFIG_ISH_IPAPG) && aon_share.pg_exit) {
+ mainfw_gdt.entries[tr / sizeof(struct gdt_entry)]
+ .flags &= 0xfd;
+ pg_exit_restore_ctx();
+ }
+
+ __asm__ volatile ("iret;");
}
}
diff --git a/chip/ish/build.mk b/chip/ish/build.mk
index 34eace379e..9f220abd21 100644
--- a/chip/ish/build.mk
+++ b/chip/ish/build.mk
@@ -33,6 +33,7 @@ test-list-y=
# Build ish aon task fw
ish-aon-name=ish_aontask
ish-aon-$(CONFIG_ISH_PM_AONTASK)=aontaskfw/ish_aontask.o dma.o
+ish-aon-$(CONFIG_ISH_IPAPG)+=aontaskfw/ipapg.o
# Rules for building ish aon task fw
ish-aon-out=$(out)/aontaskfw
@@ -65,6 +66,10 @@ $(ish-aon-out)/%.o: %.c
-@ mkdir -p $(@D)
$(call quiet,c_to_o,CC )
+$(ish-aon-out)/%.o: %.S
+ -@ mkdir -p $(@D)
+ $(call quiet,c_to_o,AS )
+
# Location of the scripts used to pack image
SCRIPTDIR:=./chip/${CHIP}/util
diff --git a/chip/ish/i2c.c b/chip/ish/i2c.c
index 7e297a20eb..3978011033 100644
--- a/chip/ish/i2c.c
+++ b/chip/ish/i2c.c
@@ -528,11 +528,17 @@ static void i2c_initial_board_config(struct i2c_context *ctx)
bus_info->high_speed.lcnt = default_lcnt_scl_hs[freq];
}
-void i2c_init(void)
+void i2c_port_restore(void)
{
- int i;
+ for (int i = 0; i < i2c_ports_used; i++) {
+ int port = i2c_ports[i].port;
+ i2c_init_hardware(&i2c_ctxs[port]);
+ }
+}
- for (i = 0; i < i2c_ports_used; i++) {
+void i2c_init(void)
+{
+ for (int i = 0; i < i2c_ports_used; i++) {
int port = i2c_ports[i].port;
i2c_initial_board_config(&i2c_ctxs[port]);
/* Config speed from i2c_ports[] defined in board.c */
diff --git a/chip/ish/power_mgt.c b/chip/ish/power_mgt.c
index 66c19aa1f2..ca03d6c29a 100644
--- a/chip/ish/power_mgt.c
+++ b/chip/ish/power_mgt.c
@@ -25,6 +25,23 @@ extern uint32_t __aon_ro_end;
extern uint32_t __aon_rw_start;
extern uint32_t __aon_rw_end;
+static void pg_exit_restore_hw(void)
+{
+ lapic_restore();
+ i2c_port_restore();
+
+ CCU_RST_HST = CCU_RST_HST;
+ CCU_TCG_ENABLE = 0;
+ CCU_BCG_ENABLE = 0;
+
+ CCU_BCG_MIA = 0;
+ CCU_BCG_DMA = 0;
+ CCU_BCG_I2C = 0;
+ CCU_BCG_SPI = 0;
+ CCU_BCG_UART = 0;
+ CCU_BCG_GPIO = 0;
+}
+
/**
* on ISH, uart interrupt can only wakeup ISH from low power state via
* CTS pin, but most ISH platforms only have Rx and Tx pins, no CTS pin
@@ -67,6 +84,7 @@ struct pm_statistics {
struct pm_stat d0i1;
struct pm_stat d0i2;
struct pm_stat d0i3;
+ struct pm_stat pg;
};
static struct pm_statistics pm_stats;
@@ -192,6 +210,8 @@ static void init_aon_task(void)
aon_share->main_fw_rw_size = (uint32_t)&__aon_rw_end -
(uint32_t)&__aon_rw_start;
+ aon_share->uma_msb = IPC_UMA_RANGE_LOWER_1;
+
ish_dma_init();
}
@@ -394,6 +414,11 @@ static void enter_d0i2(void)
/* returned from aontask */
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ if (pm_ctx.aon_share->pg_exit)
+ pg_exit_restore_hw();
+ }
+
if (IS_ENABLED(CONFIG_ISH_NEW_PM))
clear_fabric_error();
@@ -408,6 +433,10 @@ static void enter_d0i2(void)
t1 = __hw_clock_source_read();
pm_ctx.aon_share->pm_state = ISH_PM_STATE_D0;
log_pm_stat(&pm_stats.d0i2, t0, t1);
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ if (pm_ctx.aon_share->pg_exit)
+ log_pm_stat(&pm_stats.pg, t0, t1);
+ }
/* Reload watchdog before enabling interrupts again */
watchdog_reload();
@@ -445,6 +474,11 @@ static void enter_d0i3(void)
/* returned from aontask */
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ if (pm_ctx.aon_share->pg_exit)
+ pg_exit_restore_hw();
+ }
+
if (IS_ENABLED(CONFIG_ISH_NEW_PM))
clear_fabric_error();
@@ -459,6 +493,10 @@ static void enter_d0i3(void)
t1 = __hw_clock_source_read();
pm_ctx.aon_share->pm_state = ISH_PM_STATE_D0;
log_pm_stat(&pm_stats.d0i3, t0, t1);
+ if (IS_ENABLED(CONFIG_ISH_IPAPG)) {
+ if (pm_ctx.aon_share->pg_exit)
+ log_pm_stat(&pm_stats.pg, t0, t1);
+ }
/* Reload watchdog before enabling interrupts again */
watchdog_reload();
@@ -587,6 +625,11 @@ void ish_pm_init(void)
/* unmask all wake up events */
PMU_MASK_EVENT = ~PMU_MASK_EVENT_BIT_ALL;
+ if (IS_ENABLED(CONFIG_ISH_NEW_PM)) {
+ PMU_ISH_FABRIC_CNT = (PMU_ISH_FABRIC_CNT & 0xffff0000) | FABRIC_IDLE_COUNT;
+ PMU_PGCB_CLKGATE_CTRL = TRUNK_CLKGATE_COUNT;
+ }
+
if (IS_ENABLED(CONFIG_ISH_PM_RESET_PREP)) {
/* unmask reset prep avail interrupt */
PMU_RST_PREP = 0;
@@ -677,6 +720,8 @@ static int command_idle_stats(int argc, char **argv)
print_stats("D0i1", &pm_stats.d0i1);
print_stats("D0i2", &pm_stats.d0i2);
print_stats("D0i3", &pm_stats.d0i3);
+ if (IS_ENABLED(CONFIG_ISH_IPAPG))
+ print_stats("IPAPG", &pm_stats.pg);
if (pm_ctx.aon_valid) {
ccprintf(" Aontask status:\n");
diff --git a/chip/ish/power_mgt.h b/chip/ish/power_mgt.h
index bb56191508..6144502286 100644
--- a/chip/ish/power_mgt.h
+++ b/chip/ish/power_mgt.h
@@ -12,6 +12,11 @@
extern void uart_port_restore(void);
extern void uart_to_idle(void);
extern void clear_fabric_error(void);
+extern void i2c_port_restore(void);
+extern void lapic_restore(void);
+
+#define FABRIC_IDLE_COUNT 50
+#define TRUNK_CLKGATE_COUNT 0xf
/* power states for ISH */
enum ish_pm_state {
diff --git a/chip/ish/registers.h b/chip/ish/registers.h
index b8bca3e975..5942a89083 100644
--- a/chip/ish/registers.h
+++ b/chip/ish/registers.h
@@ -199,7 +199,29 @@ enum ish_i2c_port {
#define PMU_BME_BIT_RISING_EDGE_MASK BIT(8)
#define PMU_BME_BIT_FALLING_EDGE_MASK BIT(9)
#else
+#define PMU_STATUS_REG_ADDR (ISH_PMU_BASE + 0xF00)
+#define PMU_SCRATCHPAD0_REG_ADDR (ISH_PMU_BASE + 0xF04)
+#define PMU_SCRATCHPAD1_REG_ADDR (ISH_PMU_BASE + 0xF08)
+#define PMU_PG_EN_REG_ADDR (ISH_PMU_BASE + 0xF10)
+#define PMU_PMC_HOST_RST_CTL REG32(ISH_PMU_BASE + 0xF20)
+#define PMU_SW_PG_REQ REG32(ISH_PMU_BASE + 0xF14)
+#define PMU_PMC_PG_WAKE REG32(ISH_PMU_BASE + 0xF18)
+#define PMU_INTERNAL_PCE REG32(ISH_PMU_BASE + 0xF30)
#define PMU_D3_STATUS REG32(ISH_PMU_BASE + 0x100)
+#define PMU_HOST_RST_B BIT(0)
+#define PMU_PCE_SHADOW_MASK 0x1F
+#define PMU_PCE_PG_ALLOWED BIT(4)
+#define PMU_PCE_CHANGE_MASK BIT(9)
+#define PMU_PCE_CHANGE_DETECTED BIT(8)
+#define PMU_PCE_PMCRE BIT(0)
+#define PMU_SW_PG_REQ_B_VAL BIT(0)
+#define PMU_SW_PG_REQ_B_RISE BIT(1)
+#define PMU_SW_PG_REQ_B_FALL BIT(2)
+#define PMU_PMC_PG_WAKE_VAL BIT(0)
+#define PMU_PMC_PG_WAKE_RISE BIT(1)
+#define PMU_PMC_PG_WAKE_FALL BIT(2)
+#define PMU_PCE_PG_ALLOWED BIT(4)
+#define PMU_D0I3_ENABLE_MASK BIT(23)
#define PMU_D3_BIT_SET BIT(16)
#define PMU_D3_BIT_RISING_EDGE_STATUS BIT(17)
#define PMU_D3_BIT_FALLING_EDGE_STATUS BIT(18)
@@ -212,6 +234,10 @@ enum ish_i2c_port {
#define PMU_BME_BIT_FALLING_EDGE_MASK BIT(28)
#endif
+#define PMU_ISH_FABRIC_CNT REG32(ISH_PMU_BASE + 0x18)
+
+#define PMU_PGCB_CLKGATE_CTRL REG32(ISH_PMU_BASE + 0x54)
+
#define PMU_VNN_REQ REG32(ISH_PMU_BASE + 0x3c)
#define VNN_REQ_IPC_HOST_WRITE BIT(3) /* Power for IPC host write */
@@ -251,6 +277,8 @@ enum ish_i2c_port {
#define MISC_DST_FILLIN_DMA(ch) REG32(DMA_MISC_BASE + 0x200 + (4 * (ch)))
#define MISC_ISH_ECC_ERR_SRESP REG32(DMA_MISC_BASE + 0x404)
#endif
+#define MISC_ISH_RTC_COUNTER0 REG32(ISH_MISC_BASE + 0x70)
+#define MISC_ISH_RTC_COUNTER1 REG32(ISH_MISC_BASE + 0x74)
/* DMA registers */
#define DMA_CH_REGS_SIZE 0x58
diff --git a/core/minute-ia/interrupts.c b/core/minute-ia/interrupts.c
index 3dbb4f85fe..cb79eb119b 100644
--- a/core/minute-ia/interrupts.c
+++ b/core/minute-ia/interrupts.c
@@ -438,6 +438,13 @@ void call_irq_service_routine(uint32_t irq)
CPRINTS("IRQ %d routine not found!", irq);
}
+void lapic_restore(void)
+{
+ LAPIC_ESR_REG = 0;
+ APIC_SPURIOUS_INT = LAPIC_SPURIOUS_INT_VECTOR | APIC_ENABLE_BIT;
+ APIC_LVT_ERROR = LAPIC_LVT_ERROR_VECTOR;
+}
+
void init_interrupts(void)
{
unsigned entry;
diff --git a/include/config.h b/include/config.h
index 15c0dcc83a..2a500e2ed9 100644
--- a/include/config.h
+++ b/include/config.h
@@ -4487,6 +4487,11 @@
#undef CONFIG_ISH_PM_D3
/*
+ * Define the following if the ip accessible power gating is required.
+ */
+#undef CONFIG_ISH_IPAPG
+
+/*
* Define the following to the number of uSeconds of elapsed time that is
* required to enter D0I2 and D0I3, if they are supported
*/