minute-ia: Enable x86 core for Intel ISH

Add intial minute-IA (x86) core to to enable the FW
to boot on Intel Integrated Sensor Hub (ISH).

BUG=chrome-os-partner:51851
BRANCH=None
TEST=`make buildall -j`

Change-Id: I4dcf841766f216cd00fb1d4214fae19ba5de5603
Signed-off-by: Jaiber John <jaiber.j.john@intel.com>
Signed-off-by: Alex Brill <alexander.brill@intel.com>
Reviewed-on: https://chromium-review.googlesource.com/336443
Commit-Ready: Raj Mojumder <raj.mojumder@intel.com>
Tested-by: Raj Mojumder <raj.mojumder@intel.com>
Reviewed-by: Aaron Durbin <adurbin@chromium.org>
This commit is contained in:
Jaiber John
2016-03-31 23:34:34 +05:30
committed by chrome-bot
parent d54387c18e
commit a625b710c3
17 changed files with 1919 additions and 0 deletions

71
core/minute-ia/atomic.c Normal file
View File

@@ -0,0 +1,71 @@
/* Copyright (c) 2016 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 "atomic.h"
inline int bool_compare_and_swap_u32(uint32_t *var, uint32_t old_value,
uint32_t new_value)
{
uint32_t _old_value = old_value;
__asm__ __volatile__("cmpxchg %1, %2\n"
: "=a"(old_value)
: "r"(new_value), "m"(*var), "a" (old_value)
: "memory");
return (_old_value == old_value);
}
inline void atomic_or_u8(uint8_t *addr, uint8_t bits)
{
ATOMIC_OP(or, addr, bits);
}
inline void atomic_and_u8(uint8_t *addr, uint8_t bits)
{
ATOMIC_OP(and, addr, bits);
}
inline void atomic_clear(uint32_t volatile *addr, uint32_t bits)
{
ATOMIC_OP(btr, addr, bits >> 1);
}
inline void atomic_or(uint32_t volatile *addr, uint32_t bits)
{
ATOMIC_OP(orl, addr, bits);
}
inline void atomic_add(uint32_t volatile *addr, uint32_t value)
{
ATOMIC_OP(addl, addr, value);
}
inline void atomic_and(uint32_t volatile *addr, uint32_t value)
{
ATOMIC_OP(andl, addr, value);
}
inline void atomic_sub(uint32_t volatile *addr, uint32_t value)
{
ATOMIC_OP(subl, addr, value);
}
inline uint32_t atomic_read_clear(uint32_t volatile *addr)
{
int loc = 0;
if (*addr == 0)
return 0;
asm volatile("bsr %1, %0\n"
"lock; btr %0, %1\n"
: "=&r" (loc)
: "m" (*addr)
: "memory"
);
return (1 << loc);
}

33
core/minute-ia/atomic.h Normal file
View File

@@ -0,0 +1,33 @@
/* Copyright (c) 2016 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.
*/
/* Atomic operations for x86 */
#ifndef __CROS_EC_ATOMIC_H
#define __CROS_EC_ATOMIC_H
#include "common.h"
#include "util.h"
#define ATOMIC_OP(asm_op, a, v) do { \
__asm__ __volatile__ ( \
"lock;" #asm_op " %0, %1\n" \
: \
: "r" (v), "m" (*a) \
: "memory"); \
} while (0)
inline int bool_compare_and_swap_u32(uint32_t *var, uint32_t old_value,
uint32_t new_value);
inline void atomic_or_u8(uint8_t *var, uint8_t value);
inline void atomic_and_u8(uint8_t *var, uint8_t value);
inline void atomic_clear(uint32_t volatile *addr, uint32_t bits);
inline void atomic_or(uint32_t volatile *addr, uint32_t bits);
inline void atomic_add(uint32_t volatile *addr, uint32_t value);
inline void atomic_and(uint32_t volatile *addr, uint32_t value);
inline void atomic_sub(uint32_t volatile *addr, uint32_t value);
inline uint32_t atomic_read_clear(uint32_t volatile *addr);
#endif /* __CROS_EC_ATOMIC_H */

32
core/minute-ia/build.mk Normal file
View File

@@ -0,0 +1,32 @@
# -*- makefile -*-
# Copyright (c) 2016 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.
#
# Minute-IA core build
#
# Select Minute-IA bare-metal toolchain
CROSS_COMPILE?=i686-pc-linux-gnu-
# FPU compilation flags
CFLAGS_FPU-$(CONFIG_FPU)=
# CPU specific compilation flags
CFLAGS_CPU+=-fno-omit-frame-pointer -mno-accumulate-outgoing-args \
-ffunction-sections -fdata-sections \
-fno-builtin-printf -fno-builtin-sprintf \
-fno-stack-protector -gdwarf-2 -fno-common -ffreestanding \
-minline-all-stringops -fno-strict-aliasing
CFLAGS_CPU+=$(CFLAGS_FPU-y)
ifneq ($(CONFIG_LTO),)
CFLAGS_CPU+=-flto
LDFLAGS_EXTRA+=-flto
endif
core-y=cpu.o init.o interrupts.o atomic.o
core-$(CONFIG_COMMON_PANIC_OUTPUT)+=panic.o
core-$(CONFIG_COMMON_RUNTIME)+=switch.o task.o
core-$(CONFIG_MPU)+=mpu.o

View File

@@ -0,0 +1,15 @@
/* Copyright (c) 2016 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_CORE_H
#define __CROS_EC_CONFIG_CORE_H
/* Linker binary architecture and format */
#define BFD_ARCH "i386"
#define BFD_FORMAT "elf32-i386"
#define CONFIG_SOFTWARE_PANIC
#endif /* __CROS_EC_CONFIG_CORE_H */

15
core/minute-ia/cpu.c Normal file
View File

@@ -0,0 +1,15 @@
/* Copyright (c) 2016 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.
*
* Set up the LM2 mIA core
*/
#include <cpu.h>
void cpu_init(void)
{
/* Nothing to do now */
return;
}

13
core/minute-ia/cpu.h Normal file
View File

@@ -0,0 +1,13 @@
/* Copyright (c) 2016 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.
*
* Registers map and defintions for mIA LM2 processor
*/
#ifndef __CROS_EC_CPU_H
#define __CROS_EC_CPU_H
void cpu_init(void);
#endif /* __CROS_EC_CPU_H */

160
core/minute-ia/ec.lds.S Normal file
View File

@@ -0,0 +1,160 @@
/* Copyright (c) 2016 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 "config.h"
#include "rsa.h"
OUTPUT_FORMAT(BFD_FORMAT, BFD_FORMAT, BFD_FORMAT)
OUTPUT_ARCH(BFD_ARCH)
ENTRY(reset)
SECTIONS
{
. = CONFIG_ISH_BOOT_START; /* ISH SRAM (640KB) begins at 0xFF000000 */
/* .init section should be first, since it contains the boot code */
.init : { *(.init*); }
.text : { *(.text.*); }
.text.unlikely : { *(.text.unlikely*); }
. = ALIGN(4);
.rodata : {
/* Symbols defined here are declared in link_defs.h */
__irqprio = .;
KEEP(*(.rodata.irqprio))
__irqprio_end = .;
__irq_data = .;
KEEP(*(.rodata.irqs))
__irq_data_end = .;
. = ALIGN(4);
__cmds = .;
KEEP(*(SORT(.rodata.cmds*)))
__cmds_end = .;
. = ALIGN(4);
__extension_cmds = .;
KEEP(*(.rodata.extensioncmds))
__extension_cmds_end = .;
. = ALIGN(4);
__hcmds = .;
KEEP(*(.rodata.hcmds))
__hcmds_end = .;
. = ALIGN(4);
__mkbp_evt_srcs = .;
KEEP(*(.rodata.evtsrcs))
__mkbp_evt_srcs_end = .;
. = ALIGN(4);
__hooks_init = .;
KEEP(*(.rodata.HOOK_INIT))
__hooks_init_end = .;
__hooks_pre_freq_change = .;
KEEP(*(.rodata.HOOK_PRE_FREQ_CHANGE))
__hooks_pre_freq_change_end = .;
__hooks_freq_change = .;
KEEP(*(.rodata.HOOK_FREQ_CHANGE))
__hooks_freq_change_end = .;
__hooks_sysjump = .;
KEEP(*(.rodata.HOOK_SYSJUMP))
__hooks_sysjump_end = .;
__hooks_chipset_pre_init = .;
KEEP(*(.rodata.HOOK_CHIPSET_PRE_INIT))
__hooks_chipset_pre_init_end = .;
__hooks_chipset_startup = .;
KEEP(*(.rodata.HOOK_CHIPSET_STARTUP))
__hooks_chipset_startup_end = .;
__hooks_chipset_resume = .;
KEEP(*(.rodata.HOOK_CHIPSET_RESUME))
__hooks_chipset_resume_end = .;
__hooks_chipset_suspend = .;
KEEP(*(.rodata.HOOK_CHIPSET_SUSPEND))
__hooks_chipset_suspend_end = .;
__hooks_chipset_shutdown = .;
KEEP(*(.rodata.HOOK_CHIPSET_SHUTDOWN))
__hooks_chipset_shutdown_end = .;
__hooks_chipset_reset = .;
KEEP(*(.rodata.HOOK_CHIPSET_RESET))
__hooks_chipset_reset_end = .;
__hooks_ac_change = .;
KEEP(*(.rodata.HOOK_AC_CHANGE))
__hooks_ac_change_end = .;
__hooks_lid_change = .;
KEEP(*(.rodata.HOOK_LID_CHANGE))
__hooks_lid_change_end = .;
__hooks_pwrbtn_change = .;
KEEP(*(.rodata.HOOK_POWER_BUTTON_CHANGE))
__hooks_pwrbtn_change_end = .;
__hooks_charge_state_change = .;
KEEP(*(.rodata.HOOK_CHARGE_STATE_CHANGE))
__hooks_charge_state_change_end = .;
__hooks_battery_soc_change = .;
KEEP(*(.rodata.HOOK_BATTERY_SOC_CHANGE))
__hooks_battery_soc_change_end = .;
__hooks_tick = .;
KEEP(*(.rodata.HOOK_TICK))
__hooks_tick_end = .;
__hooks_second = .;
KEEP(*(.rodata.HOOK_SECOND))
__hooks_second_end = .;
__deferred_funcs = .;
KEEP(*(.rodata.deferred))
__deferred_funcs_end = .;
. = ALIGN(4);
KEEP(*(.rodata.*))
}
.data : {
__data_start = .;
*(.data.*);
__data_end = .;
}
. = ALIGN(4);
.note.gnu.build-id : { *(.note.gnu.build-id); }
.bss : {
__bss_start = .;
*(.bss*);
*(COMMON*);
# Reserve space for deferred function firing times. Each time
# is a uint64_t, each func is a 32-bit pointer, thus the scaling
# factor of two. The 8 byte alignment of uint64_t is required
# by the ABI.
. = ALIGN(8);
__deferred_until = .;
. += (__deferred_funcs_end - __deferred_funcs) * (8 / 4);
__deferred_until_end = .;
__bss_end = .;
__bss_size_words = (__bss_end - __bss_start) / 4;
}
def_irq_low = ABSOLUTE(default_int_handler) & 0xFFFF;
def_irq_high = ABSOLUTE(default_int_handler) >> 16;
}

View File

@@ -0,0 +1,37 @@
/* Copyright (c) 2016 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.
*/
/* Math utility functions for minute-IA */
#ifndef __CROS_EC_MATH_H
#define __CROS_EC_MATH_H
#ifdef CONFIG_FPU
static inline float sqrtf(float v)
{
float root;
asm volatile(
"fsqrt %0, %1"
: "=w" (root)
: "w" (v)
);
return root;
}
static inline float fabsf(float v)
{
float root;
asm volatile(
"fabs %0, %1"
: "=w" (root)
: "w" (v)
);
return root;
}
#endif /* CONFIG_FPU */
#endif /* __CROS_EC_MATH_H */

334
core/minute-ia/init.S Normal file
View File

@@ -0,0 +1,334 @@
/* Copyright (c) 2016 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.
*
* ISH minute-IA CPU initialization
*/
#include "config.h"
#include "interrupts.h"
.global __idt
# GDT is loaded by ISH ROM. The FW code retains the same GDT
# and hence the same segment selector
.set code_seg, 0x8
.section .text.vecttable
# Macro that defines an interrupt descriptor
.macro interrupt_descriptor
.word def_irq_low # low 16 bits of default_int_handler
.word code_seg
.byte 0
.byte IDT_FLAGS
.word def_irq_high # high 16 bits of default_int_handler
.endm
.align 32
# Static Interrupt descriptor table (vectors 0-255), all vectors initialized
# to default_int_handler. DECLARE_IRQ() remaps to the appropriate handler.
__idt:
interrupt_descriptor # 0 - Divide error
interrupt_descriptor # 1 - Debug
interrupt_descriptor # 2 - NMI interrupt
interrupt_descriptor # 3 - Breakpoint
interrupt_descriptor # 4 - Overflow
interrupt_descriptor # 5 - Bound range exceeded
interrupt_descriptor # 6 - Invalid opcode
interrupt_descriptor # 7 - Device not available
interrupt_descriptor # 8 - Double fault
interrupt_descriptor # 9 - Coprocessor overrun
interrupt_descriptor # 10 - Invalid TSS
interrupt_descriptor # 11 - Segment not present
interrupt_descriptor # 12 - Stack segment fault
interrupt_descriptor # 13 - General protection
interrupt_descriptor # 14 - Page fault
interrupt_descriptor # 15 - Reserved
interrupt_descriptor # 16 - Floating point error
interrupt_descriptor # 17 - Alignment check
interrupt_descriptor # 18 - Machine check
interrupt_descriptor # 19 - SIMD floating-point exception
interrupt_descriptor # 20 - Virtualization exception
interrupt_descriptor # 21..31 - Reserved
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 32..255 - User-defined, Maskable Interrupts
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 64
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 96
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 128
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 160
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 192
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 224
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor
interrupt_descriptor # 255
#.section .data
__idt_ptr:
.word 2047 # Table size in bytes, count from 0
# (8N - 1). N = 256 - the number of vectors
.long __idt # Base address of IDT
.section .init
.code32
# The .init section is mapped to linear address 0xFF000000, the SRAM start.
# ISH BUP (bring-up) downloads ISH FW to ISH SRAM and jumps to start address.
.global reset
# Entry point - core is already set to 32-bit linear mode by ISH ROM
reset:
# Disabling interrupts initially. It will be enabled when tasks start
cli
# Clear .bss section.
xorl %eax, %eax
cld
movl $__bss_start, %edi
movl $__bss_size_words, %ecx
rep stosl
# System stack is within .bss, already cleared
movl $stack_end, %esp
# Load IDT
lidt __idt_ptr
#ifdef CONFIG_FPU
fninit
#endif
# Jump to C code
jmp main
# Reserve space for system stack
.section .bss.system_stack
stack_start:
.space CONFIG_STACK_SIZE, 0
stack_end:
.global stack_end

150
core/minute-ia/interrupts.c Normal file
View File

@@ -0,0 +1,150 @@
/* Copyright (c) 2016 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.
*
* Set up the LM2 mIA core & interrupts
*/
#include "common.h"
#include "util.h"
#include "interrupts.h"
#include "registers.h"
#include "task_defs.h"
#include "irq_handler.h"
#include "console.h"
/* Console output macros */
#define CPUTS(outstr) cputs(CC_SYSTEM, outstr)
#define CPRINTF(format, args...) cprintf(CC_SYSTEM, format, ## args)
#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ## args)
/* The IDT - initialized in init.S */
extern IDT_entry __idt[NUM_VECTORS];
/* To count the interrupt nesting depth. Usually it is not nested */
volatile uint32_t __in_isr;
void write_ioapic_reg(const uint32_t reg, const uint32_t val)
{
REG32(IOAPIC_IDX) = (uint8_t)reg;
REG32(IOAPIC_WDW) = val;
}
uint32_t read_ioapic_reg(const uint32_t reg)
{
REG32(IOAPIC_IDX) = (uint8_t)reg;
return REG32(IOAPIC_WDW);
}
void set_ioapic_redtbl_raw(const unsigned irq, const uint32_t val)
{
const uint32_t redtbl_lo = IOAPIC_IOREDTBL + 2 * irq;
const uint32_t redtbl_hi = redtbl_lo + 1;
write_ioapic_reg(redtbl_lo, val);
write_ioapic_reg(redtbl_hi, DEST_APIC_ID);
}
void unmask_interrupt(uint32_t irq)
{
uint32_t val;
const uint32_t redtbl_lo = IOAPIC_IOREDTBL + 2 * irq;
val = read_ioapic_reg(redtbl_lo);
val &= ~IOAPIC_REDTBL_MASK;
set_ioapic_redtbl_raw(irq, val);
}
void mask_interrupt(uint32_t irq)
{
uint32_t val;
const uint32_t redtbl_lo = IOAPIC_IOREDTBL + 2 * irq;
val = read_ioapic_reg(redtbl_lo);
val |= IOAPIC_REDTBL_MASK;
set_ioapic_redtbl_raw(irq, val);
}
/* Maps IRQs to vectors. To be programmed in IOAPIC redirection table */
static const irq_desc_t system_irqs[] = {
LEVEL_INTR(ISH30_I2C0_IRQ, ISH30_I2C0_VEC),
LEVEL_INTR(ISH30_I2C1_IRQ, ISH30_I2C1_VEC),
LEVEL_INTR(ISH30_I2C2_IRQ, ISH30_I2C2_VEC),
LEVEL_INTR(ISH30_IPC_HOST2ISH_IRQ, ISH30_IPC_VEC),
LEVEL_INTR(ISH30_HPET_TIMER0_IRQ, ISH30_HPET_TIMER0_VEC),
LEVEL_INTR(ISH30_HPET_TIMER1_IRQ, ISH30_HPET_TIMER1_VEC),
};
void set_interrupt_gate(uint8_t num, isr_handler_t func, uint8_t flags)
{
uint16_t code_segment;
uint32_t base = (uint32_t) func;
__idt[num].ISR_low = (uint16_t) (base & USHRT_MAX);
__idt[num].ISR_high = (uint16_t) ((base >> 16UL) & USHRT_MAX);
/* When the flat model is used the CS will never change. */
__asm volatile ("mov %%cs, %0":"=r" (code_segment));
__idt[num].segment_selector = code_segment;
__idt[num].zero = 0;
__idt[num].flags = flags;
}
void unhandled_vector(void)
{
uint32_t vec = 0xff, i;
uint32_t ioapic_icr_last = LAPIC_ISR_REG; /* In service register */
/* Scan ISRs */
for (i = 7; i >= 0; i--, ioapic_icr_last -= 0x10) {
asm("movl (%1), %0\n" : "=&r" (vec) : "r" (ioapic_icr_last));
if (vec) {
vec = (32 * __fls(vec)) + i;
break;
}
}
CPRINTF("Ignoring vector 0x%0x!\n", vec);
asm("" : : "a" (vec));
}
/* This needs to be moved to link_defs.h */
extern const struct irq_data __irq_data[], __irq_data_end[];
void init_interrupts(void)
{
unsigned entry;
const struct irq_data *p = __irq_data;
unsigned num_system_irqs = ARRAY_SIZE(system_irqs);
unsigned max_entries = (read_ioapic_reg(IOAPIC_VERSION) >> 16) & 0xff;
/* Setup gates for IRQs declared by drivers using DECLARE_IRQ */
for (; p < __irq_data_end; p++)
set_interrupt_gate(IRQ_TO_VEC(p->irq), p->routine, IDT_FLAGS);
/* Mask all interrupts by default in IOAPIC */
for (entry = 0; entry < max_entries; entry++)
set_ioapic_redtbl_raw(entry, IOAPIC_REDTBL_MASK);
/* Enable pre-defined interrupts */
for (entry = 0; entry < num_system_irqs; entry++)
set_ioapic_redtbl_raw(system_irqs[entry].irq,
system_irqs[entry].vector |
IOAPIC_REDTBL_DELMOD_FIXED |
IOAPIC_REDTBL_DESTMOD_PHYS |
IOAPIC_REDTBL_MASK |
system_irqs[entry].polarity |
system_irqs[entry].trigger);
set_interrupt_gate(ISH_TS_VECTOR, __switchto, IDT_FLAGS);
/* Note: At reset, ID field is already set to 0 in APIC ID register */
/* Enable the APIC, mapping the spurious interrupt at the same time. */
APIC_SPURIOUS_INT = LAPIC_SPURIOUS_INT_VECTOR | APIC_ENABLE_BIT;
/* Set timer error vector. */
APIC_LVT_ERROR = LAPIC_LVT_ERROR_VECTOR;
}

View File

@@ -0,0 +1,72 @@
/* Copyright (c) 2016 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.
*
* Registers map and defintions for mIA LM2 processor
*/
#ifndef __CROS_EC_IA32_INTERRUPTS_H
#define __CROS_EC_IA32_INTERRUPTS_H
#ifndef __ASSEMBLER__
#include <stdint.h>
#define USHRT_MAX 0xFFFF
typedef struct {
unsigned irq;
unsigned trigger;
unsigned polarity;
unsigned vector;
} irq_desc_t;
#define INTR_DESC(__irq,__vector,__trig) \
{ \
.irq = __irq, \
.trigger = __trig, \
.polarity = IOAPIC_REDTBL_INTPOL_HIGH, \
.vector = __vector \
}
#define LEVEL_INTR(__irq, __vector) \
INTR_DESC(__irq, __vector, IOAPIC_REDTBL_TRIGGER_LEVEL)
#define EDGE_INTR(__irq, __vector) \
INTR_DESC(__irq, __vector, IOAPIC_REDTBL_TRIGGER_EDGE)
#endif
/* ISH has a single core processor */
#define DEST_APIC_ID 0
#define NUM_VECTORS 256
/* Default flags setting for entries in the IDT.
* 7 - Present bit
* 6:5 - Descriptor privilage level
* 4 - Storage segment (0 for interrupt gate)
* 3:0 - Gate type (1110 = Interrupt gate)
*/
#define IDT_FLAGS 0x8E
/* APIC bit definitions. */
#define APIC_DIV_16 0x03
#define APIC_ENABLE_BIT (1UL << 8UL)
#define APIC_SPURIOUS_INT REG32(LAPIC_BASE + 0xF0UL )
#define APIC_LVT_ERROR REG32(LAPIC_BASE + 0x370UL)
#ifndef __ASSEMBLER__
/* Interrupt descriptor entry */
struct IDT_entry_t {
uint16_t ISR_low; /* Low 16 bits of handler address. */
uint16_t segment_selector; /* Flat model means this is not changed. */
uint8_t zero; /* Must be set to zero. */
uint8_t flags; /* Flags for this entry. */
uint16_t ISR_high; /* High 16 bits of handler address. */
} __attribute__ ((packed));
typedef struct IDT_entry_t IDT_entry;
typedef void (*isr_handler_t) (void);
void init_interrupts(void);
void mask_interrupt(unsigned int irq);
void unmask_interrupt(unsigned int irq);
#endif
#endif /* __CROS_EC_IA32_INTERRUPTS_H */

View File

@@ -0,0 +1,62 @@
/* Copyright (c) 2016 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.
*/
/* Helper to declare IRQ handling routines */
#ifndef __CROS_EC_IRQ_HANDLER_H
#define __CROS_EC_IRQ_HANDLER_H
#include "registers.h"
struct irq_data {
void (*routine)(void);
int irq;
};
/* Helper macros to build the IRQ handler and priority struct names */
#define IRQ_HANDLER(irqname) CONCAT3(_irq_, irqname, _handler)
#define IRQ_PRIORITY(irqname) CONCAT2(prio_, irqname)
/*
* Macro to connect the interrupt handler "routine" to the irq number "irq" and
* ensure it is enabled in the interrupt controller with the right priority.
*
* Note: No 'naked' function support for x86, so function is implemented within
* __asm__
*/
#define DECLARE_IRQ(irq, routine) DECLARE_IRQ_(irq, routine, irq + 32 + 10)
/* Each irq has a irq_data structure placed in .rodata.irqs section,
* to be used for dynamically setting up interrupt gates */
#define DECLARE_IRQ_(irq, routine, vector) \
void __keep routine(void); \
void IRQ_HANDLER(irq)(void); \
__asm__ (".section .rodata.irqs\n"); \
const struct irq_data __keep CONCAT4(__irq_, irq, _, routine) \
__attribute__((section(".rodata.irqs")))= {IRQ_HANDLER(irq), irq};\
__asm__ ( \
".section .text._irq_"#irq"_handler\n" \
"_irq_"#irq"_handler:\n" \
"pusha\n" \
"add $1, __in_isr\n" \
"call "#routine"\n" \
"push $0\n" \
"push $0\n" \
"call switch_handler\n" \
"addl $0x08, %esp\n" \
"test %eax, %eax\n" \
"je 1f\n" \
"movl current_task, %eax\n" \
"movl %esp, (%eax)\n" \
"movl next_task, %eax\n" \
"movl %eax, current_task\n" \
"movl (%eax), %esp\n" \
"1:\n" \
"movl $"#vector ", (0xFEC00040)\n" \
"sub $1, __in_isr\n" \
"movl $0x00, (0xFEE000B0)\n" \
"popa\n" \
"iret\n" \
);
#endif /* __CROS_EC_IRQ_HANDLER_H */

17
core/minute-ia/mpu.c Normal file
View File

@@ -0,0 +1,17 @@
/* Copyright (c) 2013 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.
*/
/* MPU module for ISH */
#include "mpu.h"
#include "console.h"
#include "registers.h"
#include "task.h"
#include "util.h"
int mpu_pre_init(void)
{
return EC_SUCCESS;
}

72
core/minute-ia/panic.c Normal file
View File

@@ -0,0 +1,72 @@
/* Copyright (c) 2016 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 "common.h"
#include "console.h"
#include "cpu.h"
#include "host_command.h"
#include "panic.h"
#include "printf.h"
#include "system.h"
#include "task.h"
#include "timer.h"
#include "util.h"
#include "watchdog.h"
/* Whether bus fault is ignored */
static int bus_fault_ignored;
/* Panic data goes at the end of RAM. */
static struct panic_data * const pdata_ptr = PANIC_DATA_PTR;
/* Preceded by stack, rounded down to nearest 64-bit-aligned boundary */
static const uint32_t pstack_addr = (CONFIG_RAM_BASE + CONFIG_RAM_SIZE
- sizeof(struct panic_data)) & ~7;
/*
* Print panic data
*/
void panic_data_print(const struct panic_data *pdata)
{
}
void __keep report_panic(void)
{
}
/**
* Default exception handler, which reports a panic.
*
* Declare this as a naked call so we can extract raw LR and IPSR values.
*/
void __keep exception_panic(void);
void exception_panic(void)
{
}
#ifdef CONFIG_SOFTWARE_PANIC
void software_panic(uint32_t reason, uint32_t info)
{
}
void panic_set_reason(uint32_t reason, uint32_t info, uint8_t exception)
{
}
void panic_get_reason(uint32_t *reason, uint32_t *info, uint8_t *exception)
{
}
#endif
void bus_fault_handler(void)
{
if (!bus_fault_ignored)
exception_panic();
}
void ignore_bus_fault(int ignored)
{
bus_fault_ignored = ignored;
}

110
core/minute-ia/switch.S Normal file
View File

@@ -0,0 +1,110 @@
/* Copyright (c) 2016 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.
*
* x86 task swtching and interrupt handling
*/
#include "config.h"
#include "registers.h"
#include "task_defs.h"
.text
.extern current_task
.extern next_task
.global __task_start
.global __switchto
.global default_int_handler
# Start the task scheduling. Start current_task (hook_task)
# This function is not an ISR but imitates the sequence.
.align 4
.func __task_start
__task_start:
movl current_task, %eax
movl (%eax), %esp
popa
iret
.endfunc
# Default interrupt handler - to handle exceptions
# and prints error
.align 4
.func default_int_handler
default_int_handler:
pusha
add $1, __in_isr
call unhandled_vector # Handle system interrupts and
# unregistered user interrupts
cmpl $LAPIC_SPURIOUS_INT_VECTOR, %eax
je 1f # No EOI for LAPIC_SPURIOUS_INT_VECTOR
movl %eax, IOAPIC_EOI_REG # Indicate completion of servicing the
# interrupt to IOAPIC first
sub $1, __in_isr
movl $0x00, LAPIC_EOI_REG # Indicate completion of servicing the
# interrupt to LAPIC next
1:
popa
iret
.endfunc
# Switches from one task to another if ready.
# __schedule triggeres software interrupt ISH_TS_VECTOR, which is handled by
# __switchto
.align 4
.func __switchto
__switchto:
# Save current task
pusha
addl $1, __in_isr
# __schedule() copies 'resched' to %ecx and 'desched' to %edx before
# triggering ISH_TS_VECTOR
#
# Push %ecx and %edx into stack to pass them as function parameters
# to switch_handler(desched, resched)
push %ecx
push %edx
call switch_handler
addl $0x8, %esp # Clean up stack
test %eax, %eax # Check if task switch required
jz 1f
movl current_task, %eax
#ifdef CONFIG_FPU
fnsave 20(%eax) # Save current FPU context at current->fp_ctx
#endif
# Save SP of current task and switch to new task
movl %esp, (%eax)
movl next_task, %eax
movl %eax, current_task
movl (%eax), %esp
#ifdef CONFIG_FPU
frstor 20(%eax) # Restore next FPU context
#endif
1:
subl $1, __in_isr
# Indicate completion of servicing the interrupt to LAPIC.
# No IOAPIC EOI needed as this is SW triggered.
movl $0x00, LAPIC_EOI_REG
# Restore general purpose registers.
popa
iret
.endfunc

679
core/minute-ia/task.c Normal file
View File

@@ -0,0 +1,679 @@
/* Copyright (c) 2016 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.
*/
/* Task scheduling / events module for Chrome EC operating system */
#include "atomic.h"
#include "common.h"
#include "console.h"
#include "link_defs.h"
#include "panic.h"
#include "task.h"
#include "timer.h"
#include "util.h"
#include "task_defs.h"
#include "interrupts.h"
#include "ipc.h"
#include "hpet.h"
/* Console output macros */
#define CPUTS(outstr) cputs(CC_SYSTEM, outstr)
#define CPRINTF(format, args...) cprintf(CC_SYSTEM, format, ## args)
#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ## args)
/* Value to store in unused stack */
#define STACK_UNUSED_VALUE 0xdeadd00d
/* declare task routine prototypes */
#define TASK(n, r, d, s) int r(void *);
void __idle(void);
CONFIG_TASK_LIST
CONFIG_TEST_TASK_LIST
#undef TASK
/* This is set by interrupt handlers */
extern volatile uint32_t __in_isr;
/* Task names for easier debugging */
#define TASK(n, r, d, s) #n,
static const char * const task_names[] = {
"<< idle >>",
CONFIG_TASK_LIST
CONFIG_TEST_TASK_LIST
};
#undef TASK
#ifdef CONFIG_TASK_PROFILING
static uint64_t task_start_time; /* Time task scheduling started */
static uint64_t exc_start_time; /* Time of task->exception transition */
static uint64_t exc_end_time; /* Time of exception->task transition */
static uint64_t exc_total_time; /* Total time in exceptions */
static uint32_t svc_calls; /* Number of service calls */
static uint32_t task_switches; /* Number of times active task changed */
static uint32_t irq_dist[CONFIG_IRQ_COUNT]; /* Distribution of IRQ calls */
#endif
void __schedule(int desched, int resched);
#ifndef CONFIG_LOW_POWER_IDLE
/* Idle task. Executed when no tasks are ready to be scheduled. */
void __idle(void)
{
uint32_t idelay = 1000;
while (1) {
/*
* Wait for the next irq event. This stops the CPU clock
* (sleep / deep sleep, depending on chip config).
*
* Todo - implement sleep instead of delay
*/
udelay(idelay);
}
}
#endif /* !CONFIG_LOW_POWER_IDLE */
static void task_exit_trap(void)
{
int i = task_get_current();
cprints(CC_TASK, "Task %d (%s) exited!", i, task_names[i]);
/* Exited tasks simply sleep forever */
while (1)
task_wait_event(-1);
}
/* Startup parameters for all tasks. */
#define TASK(n, r, d, s) { \
.r0 = (uint32_t)d, \
.pc = (uint32_t)r, \
.stack_size = s, \
},
static const struct {
uint32_t r0;
uint32_t pc;
uint16_t stack_size;
} const tasks_init[] = {
TASK(IDLE, __idle, 0, IDLE_TASK_STACK_SIZE)
CONFIG_TASK_LIST
CONFIG_TEST_TASK_LIST
};
#undef TASK
/* Contexts for all tasks */
static task_ tasks[TASK_ID_COUNT];
/* Sanity checks about static task invariants */
BUILD_ASSERT(TASK_ID_COUNT <= sizeof(unsigned) * 8);
BUILD_ASSERT(TASK_ID_COUNT < (1 << (sizeof(task_id_t) * 8)));
/* Stacks for all tasks */
#define TASK(n, r, d, s) + s
uint8_t task_stacks[0
TASK(IDLE, __idle, 0, IDLE_TASK_STACK_SIZE)
CONFIG_TASK_LIST
CONFIG_TEST_TASK_LIST
] __aligned(8);
#undef TASK
task_ *current_task, *next_task;
/*
* Should IRQs chain to switch_handler()? This should be set if either of the
* following is true:
*
* 1) Task scheduling has started, and task profiling is enabled. Task
* profiling does its tracking in switch_handler().
*
* 2) An event was set by an interrupt; this could result in a higher-priority
* task unblocking. After checking for a task switch, switch_handler() will
* clear the flag (unless profiling is also enabled; then the flag remains
* set).
*/
static int need_resched_or_profiling;
/*
* Bitmap of all tasks ready to be run.
*
* Start off with only the hooks task marked as ready such that all the modules
* can do their init within a task switching context. The hooks task will then
* make a call to enable all tasks.
*/
static uint32_t tasks_ready = (1 << TASK_ID_HOOKS);
static int start_called; /* Has task swapping started */
static inline task_ *__task_id_to_ptr(task_id_t id)
{
return tasks + id;
}
void interrupt_disable(void)
{
__asm__ __volatile__ ("cli");
}
void interrupt_enable(void)
{
__asm__ __volatile__ ("sti");
}
inline int in_interrupt_context(void)
{
return !!__in_isr;
}
inline int get_interrupt_context(void)
{
return 0;
}
task_id_t task_get_current(void)
{
#ifdef CONFIG_DEBUG_BRINGUP
/* If we haven't done a context switch then our task ID isn't valid */
ASSERT(task_start_called() != 1);
#endif
return current_task - tasks;
}
uint32_t *task_get_event_bitmap(task_id_t tskid)
{
task_ *tsk = __task_id_to_ptr(tskid);
return &tsk->events;
}
int task_start_called(void)
{
return start_called;
}
/**
* Scheduling system call
*/
uint32_t switch_handler(int desched, task_id_t resched)
{
task_ *current, *next;
#ifdef CONFIG_TASK_PROFILING
int exc = get_interrupt_context();
uint64_t t;
#endif
#ifdef CONFIG_TASK_PROFILING
/*
* SVCall isn't triggered via DECLARE_IRQ(), so it needs to track its
* start time explicitly.
*/
if (exc == 0xb) {
exc_start_time = get_time().val;
svc_calls++;
}
#endif
/* Stay in hook till task_enable_all_tasks() */
if (!task_start_called() && tasks_ready > 3)
tasks_ready = 3;
current = current_task;
#ifdef CONFIG_DEBUG_STACK_OVERFLOW
if (*current->stack != STACK_UNUSED_VALUE) {
panic_printf("\n\nStack overflow in %s task!\n",
task_names[current - tasks]);
#ifdef CONFIG_SOFTWARE_PANIC
software_panic(PANIC_SW_STACK_OVERFLOW, current - tasks);
#endif
}
#endif
if (desched && !current->events) {
/*
* Remove our own ready bit (current - tasks is same as
* task_get_current())
*/
tasks_ready &= ~(1 << (current - tasks));
}
tasks_ready |= 1 << resched;
ASSERT(tasks_ready);
next = __task_id_to_ptr(__fls(tasks_ready));
#ifdef CONFIG_TASK_PROFILING
/* Track time in interrupts */
t = get_time().val;
exc_total_time += (t - exc_start_time);
/*
* Bill the current task for time between the end of the last interrupt
* and the start of this one.
*/
current->runtime += (exc_start_time - exc_end_time);
exc_end_time = t;
#else
/*
* Don't chain here from interrupts until the next time an interrupt
* sets an event.
*/
need_resched_or_profiling = 0;
#endif
/* Nothing to do */
if (next == current)
return 0;
#ifdef ISH_DEBUG
CPRINTF("[%d -> %d]\n", current - tasks, next - tasks);
#endif
/* Switch to new task */
#ifdef CONFIG_TASK_PROFILING
task_switches++;
#endif
next_task = next;
/* TS required */
return 1;
}
void __schedule(int desched, int resched)
{
__asm__ __volatile__ ("int %0"
:
: "i" (ISH_TS_VECTOR),
"d" (desched), "c" (resched)
);
}
#ifdef CONFIG_TASK_PROFILING
void __keep task_start_irq_handler(void *excep_return)
{
/*
* Get time before checking depth, in case this handler is
* pre-empted.
*/
uint64_t t = get_time().val;
int irq = get_interrupt_context() - 16;
/*
* Track IRQ distribution. No need for atomic add, because an IRQ
* can't pre-empt itself.
*/
if (irq < ARRAY_SIZE(irq_dist))
irq_dist[irq]++;
/*
* Continue iff a rescheduling event happened or profiling is active,
* and we are not called from another exception (this must match the
* logic for when we chain to svc_handler() below).
*/
if (!need_resched_or_profiling || (((uint32_t)excep_return & 0xf) == 1))
return;
exc_start_time = t;
}
#endif
void __keep task_resched_if_needed(void *excep_return)
{
/*
* Continue iff a rescheduling event happened or profiling is active,
* and we are not called from another exception.
*/
if (!need_resched_or_profiling || (((uint32_t)excep_return & 0xf) == 1))
return;
switch_handler(0, 0);
}
static uint32_t __wait_evt(int timeout_us, task_id_t resched)
{
task_ *tsk = current_task;
task_id_t me = tsk - tasks;
uint32_t evt;
int ret __attribute__((unused));
ASSERT(!in_interrupt_context());
if (timeout_us > 0) {
timestamp_t deadline = get_time();
deadline.val += timeout_us;
ret = timer_arm(deadline, me);
ASSERT(ret == EC_SUCCESS);
}
while (!(evt = atomic_read_clear(&tsk->events))) {
/* Remove ourself and get the next task in the scheduler */
__schedule(1, resched);
resched = TASK_ID_IDLE;
}
if (timeout_us > 0)
timer_cancel(me);
return evt;
}
uint32_t task_set_event(task_id_t tskid, uint32_t event, int wait)
{
task_ *receiver = __task_id_to_ptr(tskid);
if (tskid > TASK_ID_COUNT) {
receiver = current_task;
tskid = receiver - tasks;
} else {
receiver = __task_id_to_ptr(tskid);
}
ASSERT(receiver);
/* Set the event bit in the receiver message bitmap */
atomic_or(&receiver->events, event);
/* Re-schedule if priorities have changed */
if (in_interrupt_context()) {
/* The receiver might run again */
atomic_or(&tasks_ready, 1 << tskid);
#ifndef CONFIG_TASK_PROFILING
if (start_called)
need_resched_or_profiling = 1;
#endif
} else {
if (wait)
return __wait_evt(-1, tskid);
else
__schedule(0, tskid);
}
return 0;
}
uint32_t task_wait_event(int timeout_us)
{
return __wait_evt(timeout_us, TASK_ID_IDLE);
}
uint32_t task_wait_event_mask(uint32_t event_mask, int timeout_us)
{
uint64_t deadline = get_time().val + timeout_us;
uint32_t events = 0;
int time_remaining_us = timeout_us;
/* Add the timer event to the mask so we can indicate a timeout */
event_mask |= TASK_EVENT_TIMER;
while (!(events & event_mask)) {
/* Collect events to re-post later */
events |= __wait_evt(time_remaining_us, TASK_ID_IDLE);
time_remaining_us = deadline - get_time().val;
if (timeout_us > 0 && time_remaining_us <= 0) {
/* Ensure we return a TIMER event if we timeout */
events |= TASK_EVENT_TIMER;
break;
}
}
/* Re-post any other events collected */
if (events & ~event_mask)
atomic_or(&current_task->events, events & ~event_mask);
return events & event_mask;
}
void task_enable_all_tasks(void)
{
/* Mark all tasks as ready to run. */
tasks_ready = (1 << TASK_ID_COUNT) - 1;
start_called = 1;
/* The host OS driver should wait till the FW completes all hook inits.
* Otherwise, FW may fail to respond to host commands or crash when
* not fully initialized. This MNG (management) type IPC message sent
* asynchronously from the FW indicates completion of initialization.
*/
CPUTS("*** MNG FW ready ****\n");
REG32(IPC_ISH2HOST_DOORBELL) = IPC_BUILD_MNG_MSG(0x8, 1);
interrupt_enable();
/* Reschedule the highest priority task. */
__schedule(0, 0);
}
void task_enable_irq(int irq)
{
unmask_interrupt(irq);
}
void __keep task_disable_irq(int irq)
{
mask_interrupt(irq);
}
void task_clear_pending_irq(int irq)
{
}
void task_trigger_irq(int irq)
{
/* Writing to Local APIC Interrupt Command Register (ICR) causes an
* IPI (Inter-processor interrupt) on the APIC bus. Here we direct the
* IPI to originating prccessor to generate self-interrupt
*/
REG32(LAPIC_ICR_REG) = LAPIC_ICR_BITS | IRQ_TO_VEC(irq);
}
void mutex_lock(struct mutex *mtx)
{
uint32_t old_val = 0, value = 1;
uint32_t id = 1 << task_get_current();
ASSERT(id != TASK_ID_INVALID);
atomic_or(&mtx->waiters, id);
do {
__asm__ __volatile__(
"lock; cmpxchg %1, %2\n"
: "=a" (old_val)
: "r" (value), "m" (mtx->lock), "a" (old_val)
: "memory");
if (old_val != 0) {
/* Contention on the mutex */
task_wait_event_mask(TASK_EVENT_MUTEX, 0);
}
} while (old_val);
atomic_clear(&mtx->waiters, id);
}
void mutex_unlock(struct mutex *mtx)
{
uint32_t waiters = 0;
uint32_t old_val = 1, val = 0;
task_ *tsk = current_task;
__asm__ __volatile__(
"lock; cmpxchg %1, %2\n"
: "=a" (old_val)
: "r" (val), "m" (mtx->lock), "a" (old_val)
: "memory");
if (old_val == 1)
waiters = mtx->waiters;
/* else? Does unlock fail - what to do then ? */
while (waiters) {
task_id_t id = __fls(waiters);
waiters &= ~(1 << id);
/* Somebody is waiting on the mutex */
task_set_event(id, TASK_EVENT_MUTEX, 0);
}
/* Ensure no event is remaining from mutex wake-up */
atomic_clear(&tsk->events, TASK_EVENT_MUTEX);
}
void task_print_list(void)
{
int i;
ccputs("Task Ready Name Events Time (s) StkUsed\n");
for (i = 0; i < TASK_ID_COUNT; i++) {
char is_ready = (tasks_ready & (1<<i)) ? 'R' : ' ';
uint32_t *sp;
int stackused = tasks_init[i].stack_size;
for (sp = tasks[i].stack;
sp < (uint32_t *)tasks[i].sp && *sp == STACK_UNUSED_VALUE;
sp++)
stackused -= sizeof(uint32_t);
ccprintf("%4d %c %-16s %08x %11.6ld %3d/%3d\n", i, is_ready,
task_names[i], tasks[i].events, tasks[i].runtime,
stackused, tasks_init[i].stack_size);
cflush();
}
}
int command_task_info(int argc, char **argv)
{
#ifdef CONFIG_TASK_PROFILING
int total = 0;
int i;
#endif
task_print_list();
#ifdef CONFIG_TASK_PROFILING
ccputs("IRQ counts by type:\n");
cflush();
for (i = 0; i < ARRAY_SIZE(irq_dist); i++) {
if (irq_dist[i]) {
ccprintf("%4d %8d\n", i, irq_dist[i]);
total += irq_dist[i];
}
}
ccprintf("Service calls: %11d\n", svc_calls);
ccprintf("Total exceptions: %11d\n", total + svc_calls);
ccprintf("Task switches: %11d\n", task_switches);
ccprintf("Task switching started: %11.6ld s\n", task_start_time);
ccprintf("Time in tasks: %11.6ld s\n",
get_time().val - task_start_time);
ccprintf("Time in exceptions: %11.6ld s\n", exc_total_time);
#endif
return EC_SUCCESS;
}
DECLARE_CONSOLE_COMMAND(taskinfo, command_task_info,
NULL,
"Print task info",
NULL);
#ifdef CONFIG_CMD_TASKREADY
static int command_task_ready(int argc, char **argv)
{
if (argc < 2) {
ccprintf("tasks_ready: 0x%08x\n", tasks_ready);
} else {
tasks_ready = strtoi(argv[1], NULL, 16);
ccprintf("Setting tasks_ready to 0x%08x\n", tasks_ready);
__schedule(0, 0);
}
return EC_SUCCESS;
}
DECLARE_CONSOLE_COMMAND(taskready, command_task_ready,
"[setmask]",
"Print/set ready tasks",
NULL);
#endif
void task_pre_init(void)
{
int i, cs;
uint32_t *stack_next = (uint32_t *)task_stacks;
uint8_t default_fp_ctx[] = { /*Initial FP state */
0x7f, 0x03, 0xff, 0xff, 0x00, 0x00,
0xff, 0xff, 0xff, 0xff, 0xff, 0xff};
__asm__ __volatile__ ("movl %%cs, %0":"=r" (cs));
/* Fill the task memory with initial values */
for (i = 0; i < TASK_ID_COUNT; i++) {
uint32_t *sp;
/* Stack size in words */
uint32_t ssize = tasks_init[i].stack_size / 4;
tasks[i].stack = stack_next;
/*
* Update stack used by first frame: 8 words for the register
* stack, plus 8 for task context.
*/
sp = stack_next + ssize - 16;
tasks[i].sp = (uint32_t)sp;
/* Initial context on stack (see __switchto()) */
/* For POPA */
#if 0
/* For debug */
sp[0] = 0xee; /* EDI */
sp[1] = 0xe5; /* ESI */
sp[2] = 0x00; /* EBP */
sp[3] = 0x00; /* ESP - ignored anyway */
sp[4] = 0xeb1; /* EBX */
sp[5] = 0xed1; /* EDX */
sp[6] = 0xec; /* ECX */
sp[7] = 0xea; /* EAX */
#endif
/* For IRET */
sp[8] = tasks_init[i].pc; /* pc */
sp[9] = cs;
sp[10] = INITIAL_EFLAGS;
sp[11] = (uint32_t) task_exit_trap;
sp[12] = 0x00;
sp[13] = 0x00;
sp[14] = 0x00;
sp[15] = 0x00;
#ifdef CONFIG_FPU
/* Copy default x86 FPU state for each task */
memcpy(tasks[i].fp_ctx, default_fp_ctx,
sizeof(default_fp_ctx));
#endif
/* Fill unused stack; also used to detect stack overflow. */
for (sp = stack_next; sp < (uint32_t *)tasks[i].sp; sp++)
*sp = STACK_UNUSED_VALUE;
stack_next += ssize;
}
current_task = __task_id_to_ptr(1);
/* Initialize IRQs */
init_interrupts();
}
void task_clear_fp_used(void)
{
}
int task_start(void)
{
#ifdef CONFIG_TASK_PROFILING
task_start_time = exc_end_time = get_time().val;
#endif
return __task_start(&need_resched_or_profiling);
}

View File

@@ -0,0 +1,47 @@
/* Copyright (c) 2016 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_TASK_DEFS_H
#define __CROS_EC_TASK_DEFS_H
#define FPU_CTX_SZ 108 /* 28 bytes header + 80 bytes registers */
#define FPU_CTX_OFFSET 20 /* offsetof(task_, fp_ctx) */
#ifndef __ASSEMBLER__
typedef union {
struct {
/*
* Note that sp must be the first element in the task struct
* for __switchto() to work.
*/
uint32_t sp; /* Saved stack pointer for context switch */
uint32_t events; /* Bitmaps of received events */
uint64_t runtime; /* Time spent in task */
uint32_t *stack; /* Start of stack */
#ifdef CONFIG_FPU
uint8_t fp_ctx[FPU_CTX_SZ]; /* x87 FPU context */
#endif
};
} task_;
int __task_start(int *task_stack_ready);
void __switchto(void);
/* Only the IF bit is set so tasks start with interrupts enabled. */
#define INITIAL_EFLAGS (0x200UL)
/* LAPIC ICR bit fields
* 7:0 - vector
* 10:8 - Delivery mode (0 = fixed)
* 11 - Destination mode (0 = physical)
* 12 - Delivery status (0 = Idle)
* 14 - Level (1 = assert)
* 15 - Trigger mode (0 = edge)
* 20:18 - Destination (1 = self)
*/
#define LAPIC_ICR_BITS 0x44000
#endif /* __ASSEMBLER__ */
#endif /* __CROS_EC_TASK_DEFS_H */