Initial sources import 3/3

source files mainly done by Vincent.

Signed-off-by: Vincent Palatin <vpalatin@chromium.org>

Change-Id: Ic2d1becd400c9b4b4a14d4a243af1bdf77d9c1e2
This commit is contained in:
Vincent Palatin
2011-12-07 18:58:43 +00:00
parent 6396911897
commit e24fa592d2
47 changed files with 2948 additions and 0 deletions

6
.gitignore vendored Normal file
View File

@@ -0,0 +1,6 @@
*.map
*.bin
*.elf
build/
*.swp
*.pyc

33
Makefile Normal file
View File

@@ -0,0 +1,33 @@
# Copyright (c) 2010 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.
#
# Embedded Controller firmware build system
#
BOARD ?= bds
PROJECT?=ec
# output directory for build objects
out?=build/$(BOARD)
# Get build configuration from sub-directories
include board/$(BOARD)/build.mk
include chip/$(CHIP)/build.mk
include common/build.mk
include test/build.mk
include util/build.mk
objs_from_dir=$(foreach obj,$(2), $(out)/$(1)/$(obj))
# Get all sources to build
all-objs=$(call objs_from_dir,chip/$(CHIP),$(chip-objs))
all-objs+=$(call objs_from_dir,board/$(BOARD),$(board-objs))
all-objs+=$(call objs_from_dir,common,$(common-objs))
all-objs+=$(call objs_from_dir,test,$($(PROJECT)-objs))
dirs=chip/$(CHIP) board/$(BOARD) common test util
includes=include $(dirs)
include Makefile.toolchain
include Makefile.rules

91
Makefile.rules Normal file
View File

@@ -0,0 +1,91 @@
# Copyright (c) 2010 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.
#
# Embedded Controller firmware build system - common targets
#
objs := $(all-objs)
deps := $(objs:%.o=%.o.d)
all-utils := $(foreach u,$(util-bin),$(out)/util/$(u))
# Create output directories if necessary
_dir_create := $(foreach d,$(dirs),$(shell [ -d $(out)/$(d) ] || mkdir -p $(out)/$(d)))
section = $(subst .,,$(suffix $(1)))
# Decrease verbosity unless you pass V=1
quiet = $(if $(V),,@echo ' $(2)' $(subst $(out)/,,$@) ; )$(cmd_$(1))
silent = $(if $(V),,1>/dev/null)
# commands to build all targets
cmd_lds = $(CPP) -P -C -MMD -MF $@.d -MT $@ $(CPPFLAGS) \
-DSECTION=$(call section,$*) $< -o $@
cmd_obj_to_bin = $(OBJCOPY) --gap-fill=0xff -O binary $^ $@
cmd_flat_to_obj = $(CC) -T $(out)/firmware_image.lds -nostdlib $(CPPFLAGS) \
-DPROJECT=$* -Wl,--build-id=none -o $@ $<
cmd_elf_to_flat = $(OBJCOPY) -O binary $^ $@
cmd_elf_to_dis = $(OBJDUMP) -D $< > $@
cmd_elf = $(LD) $(LDFLAGS) $(objs) -o $@ -T $< -Map $(out)/$*.map
cmd_c_to_o = $(CC) $(CFLAGS) -MMD -MF $@.d -c $< -o $@
cmd_c_to_host = $(HOSTCC) $(HOST_CFLAGS) -MMD -MF $@.d $< -o $@
cmd_qemu = ./util/run_qemu_test --image=build/$(BOARD)/$*/$*.bin test/$*.py $(silent)
.PHONY: all tests utils
all: $(out)/$(PROJECT).bin $(foreach s,A B RO,$(out)/$(PROJECT).$(s).dis) utils
utils: $(all-utils)
test-targets=$(foreach t,$(test-list),test-$(t))
qemu-test-targets=$(foreach t,$(test-list),qemu-$(t))
.PHONY: $(qemu-test-target) $(test-targets)
$(test-targets): test-%:
@set -e ; \
echo " BUILD $(out)/$*" ; \
$(MAKE) -s BOARD=$(BOARD) PROJECT=$* out=$(out)/$*
$(qemu-test-targets): qemu-%: test-%
$(call quiet,qemu,TEST )
tests: $(test-targets)
qemu-tests: $(qemu-test-targets)
$(out)/firmware_image.lds: common/firmware_image.lds.S
$(call quiet,lds,LDS )
$(out)/%.lds: chip/$(CHIP)/ec.lds.S
$(call quiet,lds,LDS )
$(out)/%.bin: $(out)/%.obj
$(call quiet,obj_to_bin,OBJCOPY)
$(out)/%.obj: common/firmware_image.S $(out)/firmware_image.lds \
$(out)/%.RO.flat $(out)/%.A.flat $(out)/%.B.flat
$(call quiet,flat_to_obj,CAT )
$(out)/%.dis: $(out)/%.elf
$(call quiet,elf_to_dis,OBJDUMP)
$(out)/%.flat: $(out)/%.elf
$(call quiet,elf_to_flat,OBJCOPY)
$(out)/%.elf: $(out)/%.lds $(objs)
$(call quiet,elf,LD )
$(out)/%.o:%.c
$(call quiet,c_to_o,CC )
$(out)/%.o:%.S
$(call quiet,c_to_o,AS )
$(all-utils): $(out)/%:%.c
$(call quiet,c_to_host,HOSTCC )
.PHONY: clean
clean:
-rm -rf $(out)
.SECONDARY:
-include $(deps)

29
Makefile.toolchain Normal file
View File

@@ -0,0 +1,29 @@
# Copyright (c) 2010 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.
#
# Toolchain configuration build system
#
# Toolchain configuration
CROSS_COMPILE ?= armv7a-cros-linux-gnueabi-
CC=$(CROSS_COMPILE)gcc
CPP=$(CROSS_COMPILE)cpp
LD=$(CROSS_COMPILE)ld
OBJCOPY=$(CROSS_COMPILE)objcopy
OBJDUMP=$(CROSS_COMPILE)objdump
HOSTCC?=gcc
CFLAGS_WARN=-Wall -Wundef -Wstrict-prototypes -Wno-trigraphs \
-fno-strict-aliasing -fno-common \
-Werror-implicit-function-declaration -Wno-format-security \
-fno-delete-null-pointer-checks -Wdeclaration-after-statement \
-Wno-pointer-sign -fno-strict-overflow -fconserve-stack
CFLAGS_DEBUG= -g
CFLAGS_INCLUDE=$(foreach i,$(includes),-I$(i) )
CFLAGS_DEFINE=-DOUTDIR=$(out) -DCHIP=$(CHIP) -DTASKFILE=$(PROJECT).tasklist
CPPFLAGS=$(CFLAGS_DEFINE) $(CFLAGS_INCLUDE)
CFLAGS=$(CPPFLAGS) $(CFLAGS_CPU) $(CFLAGS_DEBUG) $(CFLAGS_WARN)
HOST_CFLAGS=$(CPPFLAGS) -O3 $(CFLAGS_DEBUG) $(CFLAGS_WARN)
LDFLAGS=-nostdlib -X

63
board/bds/board.c Normal file
View File

@@ -0,0 +1,63 @@
/* Stellaris EKB-LM4F-EAC pins multiplexing */
#include "board.h"
#include "registers.h"
#include "util.h"
void configure_board(void)
{
/* Enable all of the GPIO modules : GPIOA to GPIOQ */
LM4_SYSTEM_RCGCGPIO = 0x7fff;
/* GPIOA muxing :
* pins 0/1 : UART0 = function 1
* pins 2/3/4/5 : SSI0 = function 2
* pin 6 : GPIO = function 0 (SD card CS -- open drain)
* pin 7 : GPIO = function 0 (user LED)
*/
LM4_GPIO_PCTL(A) = 0x00222211;
LM4_GPIO_AFSEL(A) = 0x3f;
LM4_GPIO_DEN(A) = 0xff;
LM4_GPIO_PDR(A) = 0x00;
LM4_GPIO_PUR(A) = 0x3c;
LM4_GPIO_DIR(A) = 0xc0;
LM4_GPIO_ODR(A) = 0x40;
LM4_GPIO_DR2R(A) = 0xc3;
LM4_GPIO_DR8R(A) = 0x3c;
LM4_GPIO_DATA_BITS(A, 0x100) = 0x40;
LM4_GPIO_DATA_BITS(A, 0x200) = 0;
/* GPIOB muxing
* pin 0 : GPIO = function 0 (USB ID)
* pin 1 : USB digital (VBus sense)
*/
LM4_GPIO_DEN(B) |= 0x01;
LM4_GPIO_AFSEL(B)|= 0x01;
/* GPIOC muxing
* pins 0/1/2/3 : JTAG (default config)
* pin 4 : GPIO = function 0 (OLED +15v power enable)
* pin 6 : USB digital (USB power enable)
* pin 7 : USB digital (USB current overflow)
*/
LM4_GPIO_PCTL(C) = 0x88001111;
LM4_GPIO_AFSEL(C) = 0xcf;
LM4_GPIO_DEN(C) = 0xdf;
LM4_GPIO_DIR(C) = 0x10;
LM4_GPIO_DATA_BITS(C, 0x40) = 0;
/* GPIOD muxing
* pins 0/1/2/3/4 : GPIO = function 0 (buttons up,down,left,right,select)
* pin 5 : GPIO = function 0 (OLED d/Cn)
* pin 6 : GPIO = function 0 (OLED reset)
*/
LM4_GPIO_DEN(D) = 0x7f;
LM4_GPIO_DIR(D) = 0x60;
LM4_GPIO_PUR(D) = 0x1f;
/* GPIOE muxing
* pin 3 : Analog function : AIN0 ADC (potentiometer)
* pin 6/7: USB analog
*/
LM4_GPIO_AMSEL(E) = 0x8;
}

7
board/bds/build.mk Normal file
View File

@@ -0,0 +1,7 @@
#
# Board specific files build
# the IC is TI Stellaris LM4
CHIP:=lm4
board-objs=board.o

21
board/bds/ec.tasklist Normal file
View File

@@ -0,0 +1,21 @@
/* Copyright (c) 2011 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.
*/
/**
* List of enabled tasks in the priority order
*
* The first one has the lowest priority.
*
* For each task, use the macro TASK(n, r, d) where :
* 'n' in the name of the task
* 'r' in the main routine of the task
* 'd' in an opaque parameter passed to the routine at startup
*/
#define CONFIG_TASK_LIST \
TASK(BLINK, UserLedBlink, NULL) \
TASK(KEYSCAN, keyboard_scan_task, NULL) \
TASK(CONSOLE, console_task, NULL) \
TASK(HOSTCMD, host_command_task, NULL) \
TASK(I8042CMD, i8042_command_task, NULL)

18
board/link/board.c Normal file
View File

@@ -0,0 +1,18 @@
/* EC for Link mainboard pins multiplexing */
#include "board.h"
#include "registers.h"
#include "util.h"
void configure_board(void)
{
/* Enable all of the GPIO modules : GPIOA to GPIOQ */
LM4_SYSTEM_RCGCGPIO = 0x7fff;
/* GPIOA muxing :
* pins 0/1 : UART0 = function 1
*/
LM4_GPIO_PCTL(A) = 0x00000011;
LM4_GPIO_AFSEL(A) = 0x03;
LM4_GPIO_DEN(A) = 0x03;
}

7
board/link/build.mk Normal file
View File

@@ -0,0 +1,7 @@
#
# Board specific files build
# the IC is TI Stellaris LM4
CHIP:=lm4
board-objs=board.o

20
board/link/ec.tasklist Normal file
View File

@@ -0,0 +1,20 @@
/* Copyright (c) 2011 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.
*/
/**
* List of enabled tasks in the priority order
*
* The first one has the lowest priority.
*
* For each task, use the macro TASK(n, r, d) where :
* 'n' in the name of the task
* 'r' in the main routine of the task
* 'd' in an opaque parameter passed to the routine at startup
*/
#define CONFIG_TASK_LIST \
TASK(BLINK, UserLedBlink, NULL) \
TASK(CONSOLE, console_task, NULL) \
TASK(HOSTCMD, host_command_task, NULL) \
TASK(I8042CMD, i8042_command_task, NULL)

65
chip/lm4/atomic.h Normal file
View File

@@ -0,0 +1,65 @@
/* Copyright (c) 2011 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 ARMv7 */
#ifndef __ATOMIC_H
#define __ATOMIC_H
/**
* Implements atomic arithmetic operations on 32-bit integers.
*
* It used load/store exclusive.
* If you write directly the integer used as an atomic variable,
* you must either clear explicitly the exclusive monitor (using clrex)
* or do it in exception context (which clears the monitor).
*/
#define ATOMIC_OP(asm_op,a,v) do { \
uint32_t reg0, reg1; \
\
__asm__ __volatile__("1: ldrex %0, [%2]\n" \
#asm_op" %0, %0, %3\n" \
" strex %1, %0, [%2]\n" \
" teq %1, #0\n" \
" bne 1b" \
: "=&r" (reg0), "=&r" (reg1) \
: "r" (a), "r" (v) : "cc"); \
} while (0);
static inline void atomic_clear(uint32_t *addr, uint32_t bits)
{
ATOMIC_OP(bic, addr, bits);
}
static inline void atomic_or(uint32_t *addr, uint32_t bits)
{
ATOMIC_OP(orr, addr, bits);
}
static inline void atomic_add(uint32_t *addr, uint32_t value)
{
ATOMIC_OP(add, addr, value);
}
static inline void atomic_sub(uint32_t *addr, uint32_t value)
{
ATOMIC_OP(sub, addr, value);
}
static inline uint32_t atomic_read_clear(uint32_t *addr)
{
uint32_t ret, tmp;
__asm__ __volatile__(" mov %3, #0\n"
"1: ldrex %0, [%2]\n"
" strex %1, %3, [%2]\n"
" teq %1, #0\n"
" bne 1b"
: "=&r" (ret), "=&r" (tmp)
: "r" (addr), "r" (0) : "cc");
return ret;
}
#endif /* __ATOMIC_H */

10
chip/lm4/build.mk Normal file
View File

@@ -0,0 +1,10 @@
#
# LM4 chip specific files build
#
# CPU specific compilation flags
CFLAGS_CPU=-mcpu=cortex-m4 -mthumb -Os -mno-sched-prolog
chip-objs=init.o panic.o switch.o task.o timer.o pwm.o i2c.o adc.o
chip-objs+=clock.o gpio.o system.o lpc.o uart.o x86_power.o
chip-objs+=flash.o watchdog.o eeprom.o keyboard_scan.o temp_sensor.o

199
chip/lm4/clock.c Normal file
View File

@@ -0,0 +1,199 @@
/* Copyright (c) 2011 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.
*/
/* Clocks and power management settings */
#include <stdint.h>
#include "board.h"
#include "clock.h"
#include "config.h"
#include "console.h"
#include "gpio.h"
#include "task.h"
#include "timer.h"
#include "uart.h"
#include "registers.h"
#include "util.h"
/**
* Idle task
* executed when no task are ready to be scheduled
*/
void __idle(void)
{
while (1) {
/* wait for the irq event */
asm("wfi");
/* TODO more power management here */
}
}
/* simple busy waiting before clocks are initialized */
static void wait_cycles(uint32_t cycles)
{
asm("1: subs %0, #1\n"
" bne 1b\n" :: "r"(cycles));
}
/**
* Function to measure baseline for power consumption.
*
* Levels :
* 0 : CPU running in tight loop
* 1 : CPU running in tight loop but peripherals gated
* 2 : CPU in sleep mode
* 3 : CPU in sleep mode and peripherals gated
* 4 : CPU in deep sleep mode
* 5 : CPU in deep sleep mode and peripherals gated
*/
static int command_sleep(int argc, char **argv)
{
int level = 0;
int clock = 0;
uint32_t uartibrd = 0;
uint32_t uartfbrd = 0;
if (argc >= 2) {
level = strtoi(argv[1], NULL, 10);
}
if (argc >= 3) {
clock = strtoi(argv[2], NULL, 10);
}
/* remove LED current sink */
gpio_set(EC_GPIO_DEBUG_LED, 0);
uart_printf("Going to sleep : level %d clock %d...\n", level, clock);
uart_flush_output();
/* clock setting */
if (clock) {
/* Use ROM code function to set the clock */
void **func_table = (void **)*(uint32_t *)0x01000044;
void (*rom_clock_set)(uint32_t rcc) = func_table[23];
/* disable interrupts */
asm volatile("cpsid i");
switch (clock) {
case 1: /* 16MHz IOSC */
uartibrd = 17;
uartfbrd = 23;
rom_clock_set(0x00000d51);
break;
case 2: /* 1MHz IOSC */
uartibrd = 1;
uartfbrd = 5;
rom_clock_set(0x07C00d51);
break;
case 3: /* 30 kHz */
uartibrd = 0;
uartfbrd = 0;
rom_clock_set(0x00000d71);
break;
}
/* TODO: move this to the UART module; ugly to have
UARTisms here. Also note this only fixes UART0,
not UART1. */
if (uartfbrd) {
/* Disable the port via UARTCTL and add HSE */
LM4_UART_CTL(0) = 0x0320;
/* Set the baud rate divisor */
LM4_UART_IBRD(0) = uartibrd;
LM4_UART_FBRD(0) = uartfbrd;
/* Poke UARTLCRH to make the new divisor take effect. */
LM4_UART_LCRH(0) = LM4_UART_LCRH(0);
/* Enable the port */
LM4_UART_CTL(0) |= 0x0001;
}
asm volatile("cpsie i");
}
if (uartfbrd) {
uart_printf("We are still alive. RCC=%08x\n", LM4_SYSTEM_RCC);
uart_flush_output();
}
asm volatile("cpsid i");
/* gate peripheral clocks */
if (level & 1) {
LM4_SYSTEM_RCGCTIMER = 0;
LM4_SYSTEM_RCGCGPIO = 0;
LM4_SYSTEM_RCGCDMA = 0;
LM4_SYSTEM_RCGCUART = 0;
LM4_SYSTEM_RCGCLPC = 0;
LM4_SYSTEM_RCGCWTIMER = 0;
}
/* set deep sleep bit */
if (level >= 4)
LM4_SCB_SYSCTRL |= 0x4;
/* go to low power mode (forever ...) */
if (level > 1)
while (1)
asm("wfi");
else
while(1);
return EC_SUCCESS;
}
static const struct console_command clock_commands[] = {
{"sleep", command_sleep}
};
static const struct console_group clock_group = {
"Clock", clock_commands, ARRAY_SIZE(clock_commands)
};
static void clock_init_pll(uint32_t value)
{
/**
* at startup, OSCSRC is PIOSC (precision internal oscillator)
* PLL and PLL2 are in power-down
*/
/* PLL already setup */
if (LM4_SYSTEM_PLLSTAT & 1)
return;
/* Put a bypass on the system clock PLLs, no divider */
LM4_SYSTEM_RCC = (LM4_SYSTEM_RCC | 0x800) & ~0x400000;
LM4_SYSTEM_RCC2 = (LM4_SYSTEM_RCC2 | 0x800) & ~0x80000000;
/* Enable main and precision internal oscillators */
LM4_SYSTEM_RCC &= ~0x3;
/* wait 1 million CPU cycles */
wait_cycles(512 * 1024);
/* clear PLL lock flag (aka PLLLMIS) */
LM4_SYSTEM_MISC = 0x40;
/* clear powerdown / set XTAL frequency and divider */
LM4_SYSTEM_RCC = (LM4_SYSTEM_RCC & ~0x07c027c0) | (value & 0x07c007c0);
/* wait 32 CPU cycles */
wait_cycles(16);
/* wait for PLL to lock */
while (!(LM4_SYSTEM_RIS & 0x40));
/* Remove bypass on PLL and set oscillator source to main */
LM4_SYSTEM_RCC = LM4_SYSTEM_RCC & ~0x830;
}
int clock_init(void)
{
/* Use 66.667Mhz clock from PLL */
BUILD_ASSERT(CPU_CLOCK == 66666667);
/* CPU clock = PLL/3 ; System clock = PLL
* Osc source = main OSC ; external crystal = 16 Mhz
*/
clock_init_pll(0x01400540);
#ifdef CONFIG_DEBUG
/* Register our internal commands */
console_register_commands(&clock_group);
#endif
return EC_SUCCESS;
}

19
chip/lm4/config.h Normal file
View File

@@ -0,0 +1,19 @@
/* Memory mapping */
#define CONFIG_FLASH_BASE 0x00000000
#define CONFIG_FLASH_SIZE 0x00040000
#define CONFIG_FLASH_BANK_SIZE 0x2000
#define CONFIG_RAM_BASE 0x20000000
#define CONFIG_RAM_SIZE 0x00008000
/* Size of one firmware image in flash */
#define CONFIG_FW_IMAGE_SIZE (32 * 1024)
#define CONFIG_FW_RO_OFF 0
#define CONFIG_FW_A_OFF CONFIG_FW_IMAGE_SIZE
#define CONFIG_FW_B_OFF (2 * CONFIG_FW_IMAGE_SIZE)
/* System stack size */
#define CONFIG_STACK_SIZE 4096
/* build with assertions and debug messages */
#define CONFIG_DEBUG

45
chip/lm4/ec.lds.S Normal file
View File

@@ -0,0 +1,45 @@
#include "config.h"
#define CONFIG_FW_SECT_OFF(section) CONFIG_FW_##section##_OFF
#define CONFIG_FW_BASE(section) (CONFIG_FLASH_BASE + CONFIG_FW_SECT_OFF(section))
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
OUTPUT_ARCH(arm)
ENTRY(reset)
MEMORY
{
FLASH (rx) : ORIGIN = CONFIG_FW_BASE(SECTION), LENGTH = CONFIG_FW_IMAGE_SIZE
IRAM (rw) : ORIGIN = CONFIG_RAM_BASE, LENGTH = CONFIG_RAM_SIZE
}
SECTIONS
{
.text : {
OUTDIR/chip/CHIP/init.o (.text)
*(.text)
} > FLASH
. = ALIGN(4);
.rodata : {
__irqprio = .;
*(.rodata.irqprio)
__irqprio_end = .;
*(.rodata*)
. = ALIGN(4);
} > FLASH
__ro_end = . ;
.data : AT(ADDR(.rodata) + SIZEOF(.rodata)) {
. = ALIGN(4);
__data_start = .;
*(.data.tasks)
*(.data)
. = ALIGN(4);
__data_end = .;
} > IRAM
.bss : {
. = ALIGN(4);
__bss_start = .;
*(.bss)
. = ALIGN(4);
__bss_end = .;
} > IRAM
/DISCARD/ : { *(.ARM.*) }
}

250
chip/lm4/init.S Normal file
View File

@@ -0,0 +1,250 @@
/* Copyright (c) 2011 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.
*
* Cortex-M CPU initialization
*/
#include "config.h"
.text
.syntax unified
.code 16
.macro vector name
.long \name\()_handler
.weak \name\()_handler
.set \name\()_handler, default_handler
.endm
/* Exceptions vector */
vectors:
.long stack_end @ initial stack pointer
.long reset @ reset handler
vector nmi @ NMI handler
vector hard_fault @ HardFault handler
vector mpu_fault @ MPU fault handler
vector bus_fault @ Bus fault handler
vector usage_fault @ Usage fault handler
.long 0 @ reserved
.long 0 @ reserved
.long 0 @ reserved
.long 0 @ reserved
vector svc @ SWI
vector debug @ Debug handler
.long 0 @ reserved
vector pendsv @ PendSV handler
vector sys_tick @ SysTick handler
vector irq_0 @ IRQ 0 handler
vector irq_1 @ IRQ 1 handler
vector irq_2 @ IRQ 2 handler
vector irq_3 @ IRQ 3 handler
vector irq_4 @ IRQ 4 handler
vector irq_5 @ IRQ 5 handler
vector irq_6 @ IRQ 6 handler
vector irq_7 @ IRQ 7 handler
vector irq_8 @ IRQ 8 handler
vector irq_9 @ IRQ 9 handler
vector irq_10 @ IRQ 10 handler
vector irq_11 @ IRQ 11 handler
vector irq_12 @ IRQ 12 handler
vector irq_13 @ IRQ 13 handler
vector irq_14 @ IRQ 14 handler
vector irq_15 @ IRQ 15 handler
vector irq_16 @ IRQ 16 handler
vector irq_17 @ IRQ 17 handler
vector irq_18 @ IRQ 18 handler
vector irq_19 @ IRQ 19 handler
vector irq_20 @ IRQ 20 handler
vector irq_21 @ IRQ 21 handler
vector irq_22 @ IRQ 22 handler
vector irq_23 @ IRQ 23 handler
vector irq_24 @ IRQ 24 handler
vector irq_25 @ IRQ 25 handler
vector irq_26 @ IRQ 26 handler
vector irq_27 @ IRQ 27 handler
vector irq_28 @ IRQ 28 handler
vector irq_29 @ IRQ 29 handler
vector irq_30 @ IRQ 30 handler
vector irq_31 @ IRQ 31 handler
vector irq_32 @ IRQ 32 handler
vector irq_33 @ IRQ 33 handler
vector irq_34 @ IRQ 34 handler
vector irq_35 @ IRQ 35 handler
vector irq_36 @ IRQ 36 handler
vector irq_37 @ IRQ 37 handler
vector irq_38 @ IRQ 38 handler
vector irq_39 @ IRQ 39 handler
vector irq_40 @ IRQ 40 handler
vector irq_41 @ IRQ 41 handler
vector irq_42 @ IRQ 42 handler
vector irq_43 @ IRQ 43 handler
vector irq_44 @ IRQ 44 handler
vector irq_45 @ IRQ 45 handler
vector irq_46 @ IRQ 46 handler
vector irq_47 @ IRQ 47 handler
vector irq_48 @ IRQ 48 handler
vector irq_49 @ IRQ 49 handler
vector irq_50 @ IRQ 50 handler
vector irq_51 @ IRQ 51 handler
vector irq_52 @ IRQ 52 handler
vector irq_53 @ IRQ 53 handler
vector irq_54 @ IRQ 54 handler
vector irq_55 @ IRQ 55 handler
vector irq_56 @ IRQ 56 handler
vector irq_57 @ IRQ 57 handler
vector irq_58 @ IRQ 58 handler
vector irq_59 @ IRQ 59 handler
vector irq_60 @ IRQ 60 handler
vector irq_61 @ IRQ 61 handler
vector irq_62 @ IRQ 62 handler
vector irq_63 @ IRQ 63 handler
vector irq_64 @ IRQ 64 handler
vector irq_65 @ IRQ 65 handler
vector irq_66 @ IRQ 66 handler
vector irq_67 @ IRQ 67 handler
vector irq_68 @ IRQ 68 handler
vector irq_69 @ IRQ 69 handler
vector irq_70 @ IRQ 70 handler
vector irq_71 @ IRQ 71 handler
vector irq_72 @ IRQ 72 handler
vector irq_73 @ IRQ 73 handler
vector irq_74 @ IRQ 74 handler
vector irq_75 @ IRQ 75 handler
vector irq_76 @ IRQ 76 handler
vector irq_77 @ IRQ 77 handler
vector irq_78 @ IRQ 78 handler
vector irq_79 @ IRQ 79 handler
vector irq_80 @ IRQ 80 handler
vector irq_81 @ IRQ 81 handler
vector irq_82 @ IRQ 82 handler
vector irq_83 @ IRQ 83 handler
vector irq_84 @ IRQ 84 handler
vector irq_85 @ IRQ 85 handler
vector irq_86 @ IRQ 86 handler
vector irq_87 @ IRQ 87 handler
vector irq_88 @ IRQ 88 handler
vector irq_89 @ IRQ 89 handler
vector irq_90 @ IRQ 90 handler
vector irq_91 @ IRQ 91 handler
vector irq_92 @ IRQ 92 handler
vector irq_93 @ IRQ 93 handler
vector irq_94 @ IRQ 94 handler
vector irq_95 @ IRQ 95 handler
vector irq_96 @ IRQ 96 handler
vector irq_97 @ IRQ 97 handler
vector irq_98 @ IRQ 98 handler
vector irq_99 @ IRQ 99 handler
vector irq_100 @ IRQ 100 handler
vector irq_101 @ IRQ 101 handler
vector irq_102 @ IRQ 102 handler
vector irq_103 @ IRQ 103 handler
vector irq_104 @ IRQ 104 handler
vector irq_105 @ IRQ 105 handler
vector irq_106 @ IRQ 106 handler
vector irq_107 @ IRQ 107 handler
vector irq_108 @ IRQ 108 handler
vector irq_109 @ IRQ 109 handler
vector irq_110 @ IRQ 110 handler
vector irq_111 @ IRQ 111 handler
vector irq_112 @ IRQ 112 handler
vector irq_113 @ IRQ 113 handler
vector irq_114 @ IRQ 114 handler
vector irq_115 @ IRQ 115 handler
vector irq_116 @ IRQ 116 handler
vector irq_117 @ IRQ 117 handler
vector irq_118 @ IRQ 118 handler
vector irq_119 @ IRQ 119 handler
vector irq_120 @ IRQ 120 handler
vector irq_121 @ IRQ 121 handler
vector irq_122 @ IRQ 122 handler
vector irq_123 @ IRQ 123 handler
vector irq_124 @ IRQ 124 handler
vector irq_125 @ IRQ 125 handler
vector irq_126 @ IRQ 126 handler
vector irq_127 @ IRQ 127 handler
vector irq_128 @ IRQ 128 handler
vector irq_129 @ IRQ 129 handler
vector irq_130 @ IRQ 130 handler
vector irq_131 @ IRQ 131 handler
.rept 108
.long 0 @ IRQ 132-239: reserved
.endr
.global reset
.thumb_func
reset:
/* set the vector table on our current code */
adr r1, vectors
ldr r2, =0xE000ED08 /* VTABLE register in SCB*/
str r1, [r2]
/* Clear BSS */
mov r0, #0
ldr r1,_bss_start
ldr r2,_bss_end
bss_loop:
cmp r1, r2
it lt
strlt r0, [r1], #4
blt bss_loop
/* Copy initialized data to Internal RAM */
ldr r0,_ro_end
ldr r1,_data_start
ldr r2,_data_end
data_loop:
ldr r3, [r0], #4
cmp r1, r2
it lt
strlt r3, [r1], #4
blt data_loop
/**
* Set stack pointer
* already done my Cortex-M hardware but this allows software to jump directly
* to reset function or to run on other ARM
*/
ldr r0, =stack_end
mov sp, r0
/* jump to C code */
bl main
/* we should not return here */
/* TODO check error code ? */
fini_loop:
b fini_loop
/* default exception handler */
.thumb_func
default_handler:
b panic
_bss_start:
.long __bss_start
_bss_end:
.long __bss_end
_data_start:
.long __data_start
_data_end:
.long __data_end
_ro_end:
.long __ro_end
/* Dummy functions to avoid linker complaints */
.global __aeabi_unwind_cpp_pr0
.global __aeabi_unwind_cpp_pr1
.global __aeabi_unwind_cpp_pr2
__aeabi_unwind_cpp_pr0:
__aeabi_unwind_cpp_pr1:
__aeabi_unwind_cpp_pr2:
bx lr
.section .bss
/* Reserve space for system stack */
stack_start:
.space CONFIG_STACK_SIZE, 0
stack_end:
.globl stack_end

111
chip/lm4/panic.S Normal file
View File

@@ -0,0 +1,111 @@
/* Copyright (c) 2011 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.
*
* Fatal exception handling and debug tracing
*/
#include "config.h"
.text
.syntax unified
.code 16
.macro hex_reg r, offset @ prepare to build
add r1, r3, #\offset @ .. hexadecimal string
mov r0, \r @ .. from the reg value
bl buildhex
.endm
/* fatal exception handler */
.global panic
.thumb_func
panic:
#ifndef CONFIG_DEBUG
b EcSystemReset @ Reboot the system
#else /* CONFIG_DEBUG */
/* check that the exception stack pointer is valid */
ldr r0, =CONFIG_RAM_BASE @ start of RAM
ldr r1, =CONFIG_RAM_BASE+CONFIG_RAM_SIZE @ end of RAM
mrs r12, psp @ process stack pointer
cmp r12, r0 @ is sp >= RAM start ?
it ge
cmpge r1, r12 @ is sp < RAM end ?
blt panic_print @ no => no values to read
/* output registers value */
ldr r3, =msg_excep @ pointer to the text buffer
mrs r2, ipsr @ get exception num from IPSR
bfc r2, #9, #23 @ the exception is the 3 LSB
hex_reg r2, 18 @ prepare hexa for excep number
hex_reg r4, 119 @ prepare hexa for R4
hex_reg r5, 132 @ prepare hexa for R5
hex_reg r6, 145 @ prepare hexa for R6
hex_reg r7, 156 @ prepare hexa for R7
hex_reg r8, 171 @ prepare hexa for R8
hex_reg r9, 184 @ prepare hexa for R9
hex_reg r10, 197 @ prepare hexa for R10
hex_reg r11, 210 @ prepare hexa for R11
ldmia r12!, {r4-r11} @ load saved r0-r3,r12,lr,pc,psr
hex_reg r4, 66 @ prepare hexa for R0
hex_reg r5, 79 @ prepare hexa for R1
hex_reg r6, 92 @ prepare hexa for R2
hex_reg r7, 105 @ prepare hexa for R3
hex_reg r8, 225 @ prepare hexa for R12
hex_reg r12, 238 @ prepare hexa for SP
hex_reg r9, 251 @ prepare hexa for LR
hex_reg r10, 264 @ prepare hexa for PC
hex_reg r11, 40 @ prepare hexa for xPSR
/* print exception trace */
panic_print:
ldr r0, =msg_excep @ pointer to the text buffer
bl emergency_puts @ print the banner
b system_reset @ Reboot the system
/* Helpers for exception trace */
/* print a string on the UART
* r0: asciiZ string pointer
*/
emergency_puts:
ldr r1, =0x4000c000 @ UART0 first register
1:
ldrb r3, [r0], #1 @ read one character
cmp r3, #0 @ end of the string ?
beq 3f @ if yes, return
2: /* putchar */
ldr r2, [r1, #0x18] @ read LM4_UART0_UARTFR
tst r2, #0x20 @ TX FIFO full ?
bne 2b @ if yes, wait
str r3, [r1] @ send character to UART DR
b 1b @ goto next character
3: /* flush */
ldr r2, [r1, #0x18] @ read LM4_UART0_UARTFR
tst r2, #0x8 @ TX on-going ?
bne 3b @ if yes, wait
bx lr
/* write a number in hexadecimal in a text buffer
* r0: number to print
* r1: pointer to *end* of the buffer (filled with '0')
*/
buildhex:
cmp r0, #0
it eq
bxeq lr
and r2, r0, #0xf
cmp r2, #10
ite lt
addlt r2, #'0'
addge r2, #'A'-10
strb r2, [r1],#-1
lsr r0, #4
b buildhex
.data
msg_excep: .ascii "\r\n=== EXCEPTION: 00 ====== xPSR: 00000000 ===========\r\n"
msg_reg0: .ascii "R0 :00000000 R1 :00000000 R2 :00000000 R3 :00000000\r\n"
msg_reg1: .ascii "R4 :00000000 R5 :00000000 R6 :00000000 R7 :00000000\r\n"
msg_reg2: .ascii "R8 :00000000 R9 :00000000 R10:00000000 R11:00000000\r\n"
msg_reg3: .ascii "R12:00000000 SP :00000000 LR :00000000 PC :00000000\r\n\0"
.align 4
#endif /* CONFIG_DEBUG */

63
chip/lm4/switch.S Normal file
View File

@@ -0,0 +1,63 @@
/* Copyright (c) 2011 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.
*
* Context swtching
*/
#include "config.h"
.text
.syntax unified
.code 16
/**
* Task context switching
*
* Change the task scheduled after returning from the exception.
*
* Save the registers of the current task below the exception context on
* its task, then restore the live registers of the next task and set the
* process stack pointer to the new stack.
*
* r0: pointer to the task to switch from
* r1: pointer to the task to switch to
*
* must be called from interrupt context
*
* the structure of tje saved context on the stack is :
* r0, r1, r2, r3, r12, lr, pc, psr, r4, r5, r6, r7, r8, r9, r10, r11
* exception frame <|> additional registers
*/
.global __switchto
.thumb_func
__switchto:
mrs r3, psp @ get the task stack where the context has been saved
ldr r2, [r1] @ get the new scheduled task stack pointer
stmdb r3!, {r4-r11} @ save additional r4-r7 in the task stack
ldmia r2!, {r4-r11} @ restore r4-r7 for the next task context
str r3, [r0] @ save the task stack pointer in its context
msr psp, r2 @ set the process stack pointer to exception context
bx lr @ return from exception
/**
* Start the task scheduling
*/
.global task_start
.thumb_func
task_start:
ldr r2,=scratchpad @ area used as dummy thread stack for the first switch
mov r3, #2
mov r0, #0 @ __Schedule parameter : de-schedule nothing
mov r1, #0 @ __Schedule parameter : re-schedule nothing
add r2, #17*4 @ put the pointer at the top of the stack
msr psp, r2 @ setup a thread stack up to the first context switch
isb @ ensure the write is done
msr control, r3 @ use : priv. mode / thread stack / no floating point
isb @ ensure the write is done
bl __schedule @ execute the task with the highest priority
/* we should never return here */
mov r0, #1 @ set to EC_ERROR_UNKNOWN
bx lr

341
chip/lm4/task.c Normal file
View File

@@ -0,0 +1,341 @@
/* Copyright (c) 2011 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 <stdint.h>
#include "config.h"
#include "atomic.h"
#include "console.h"
#include "task.h"
#include "timer.h"
#include "uart.h"
#include "registers.h"
#include "util.h"
/**
* Global memory size for a task : 512 bytes
* including its contexts and its stack
*/
#define TASK_SIZE_LOG2 9
#define TASK_SIZE (1<<TASK_SIZE_LOG2)
typedef union {
struct {
uint32_t sp; /* saved stack pointer for context switch */
uint32_t events; /* bitmaps of received events */
uint8_t stack[0]; /* task stack */
};
uint32_t context[TASK_SIZE/4];
} task_;
/* declare task routine prototypes */
#define TASK(n, r, d) int r(void *);
#include TASK_LIST
void __idle(void);
CONFIG_TASK_LIST
#undef TASK
extern void __switchto(task_ *from, task_ *to);
/* declare and fill the contexts for all the tasks */
#define TASK(n, r, d) { \
.context[0] = (uint32_t)(tasks + TASK_ID_##n + 1) - 64, \
.context[TASK_SIZE/4 - 8/*r0*/] = (uint32_t)d, \
/* TODO set a LR to a trap */ \
.context[TASK_SIZE/4 - 2/*pc*/] = (uint32_t)r, \
.context[TASK_SIZE/4 - 1/*psr*/] = 0x01000000 },
#include TASK_LIST
static task_ tasks[] __attribute__((section(".data.tasks")))
__attribute__((aligned(TASK_SIZE))) = {
TASK(IDLE, __idle, 0)
CONFIG_TASK_LIST
};
#undef TASK
/* reserve space to discard context on first context switch */
uint32_t scratchpad[17] __attribute__((section(".data.tasks")));
/* context switch at the next exception exit if needed */
/* TODO: who sets this back to 0 after it's set to 1? */
static int need_resched = 0;
/**
* bitmap of all tasks ready to be run
*
* Currently all tasks are enabled at startup.
*/
static unsigned tasks_ready = (1<<TASK_ID_COUNT) - 1;
static task_ *__get_current(void)
{
unsigned sp;
asm("mov %0, sp":"=r"(sp));
return (task_ *)((sp - 4) & ~(TASK_SIZE-1));
}
/**
* Return a pointer to the task preempted by the current exception
*
* designed to be called from interrupt context.
*/
static task_ *__get_task_scheduled(void)
{
unsigned sp;
asm("mrs %0, psp":"=r"(sp));
return (task_ *)((sp - 16) & ~(TASK_SIZE-1));
}
static inline task_ *__task_id_to_ptr(task_id_t id)
{
return tasks + id;
}
inline int in_interrupt_context(void)
{
int ret;
asm("mrs %0, ipsr \n" /* read exception number */
"lsl %0, #23 \n":"=r"(ret)); /* exception bits are the 9 LSB */
return ret;
}
task_id_t task_get_current(void)
{
task_id_t id = __get_current() - tasks;
if (id >= TASK_ID_COUNT)
id = TASK_ID_INVALID;
return id;
}
uint32_t *task_get_event_bitmap(task_id_t tskid)
{
task_ *tsk = __task_id_to_ptr(tskid);
return &tsk->events;
}
/**
* scheduling system call
*/
void svc_handler(int desched, task_id_t resched)
{
task_ *current, *next;
uint32_t reg;
/* push the priority to -1 until the return, to avoid being
* interrupted */
asm volatile("mov %0, #1\n"
"msr faultmask, %0" :"=r"(reg));
current = __get_task_scheduled();
if (desched && !current->events) {
/* Remove our own ready bit */
tasks_ready &= ~(1 << (current-tasks));
}
tasks_ready |= 1 << resched;
ASSERT(tasks_ready);
next = __task_id_to_ptr(31 - __builtin_clz(tasks_ready));
/* Nothing to do */
if (next == current)
return;
__switchto(current, next);
}
void __schedule(int desched, int resched)
{
register int p0 asm("r0") = desched;
register int p1 asm("r1") = resched;
/* TODO remove hardcoded opcode
* SWI not compiled properly for ARMv7-M on our current chroot toolchain
*/
asm(".hword 0xdf00 @swi 0"::"r"(p0),"r"(p1));
}
/**
* Change the task scheduled after returning from the exception.
*
* If task_send_msg has been called and has set need_resched flag,
* we re-compute which task is running and eventually swap the context
* saved on the process stack to restore the new one at exception exit.
*
* it must be called from interrupt context !
*/
void task_resched_if_needed(void *excep_return)
{
/**
* continue iff a rescheduling event happened and
* we are not called from another exception
*/
if (!need_resched || (((uint32_t)excep_return & 0xf) == 1))
return;
svc_handler(0, 0);
}
static uint32_t __wait_msg(int timeout_us, task_id_t resched)
{
task_ *tsk = __get_current();
task_id_t me = tsk - tasks;
uint32_t evt;
int ret;
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_send_msg(task_id_t tskid, task_id_t from, int wait)
{
task_ *receiver = __task_id_to_ptr(tskid);
ASSERT(receiver);
if (from == TASK_ID_CURRENT) {
from = task_get_current();
}
/* set the event bit in the receiver message bitmap */
atomic_or(&receiver->events, 1 << from);
/* Re-schedule if priorities have changed */
if (in_interrupt_context()) {
/* the receiver might run again */
tasks_ready |= 1 << tskid;
need_resched = 1;
} else {
if (wait)
return __wait_msg(-1, tskid);
else
__schedule(0, tskid);
}
return 0;
}
uint32_t task_wait_msg(int timeout_us)
{
return __wait_msg(timeout_us, TASK_ID_IDLE);
}
/**
* Enable all used IRQ in the NVIC and set their priorities
* as defined by the DECLARE_IRQ statements
*/
static void __nvic_init_irqs(void)
{
/* get the IRQ priorities section from the linker */
extern struct irq_priority __irqprio[];
extern struct irq_priority __irqprio_end[];
int irq_count = __irqprio_end - __irqprio;
int i;
for (i = 0; i < irq_count; i++) {
uint8_t irq = __irqprio[i].irq;
uint8_t prio = __irqprio[i].priority;
uint32_t prio_shift = irq % 4 * 8 + 5;
LM4_NVIC_PRI(irq / 4) =
(LM4_NVIC_PRI(irq / 4) &
~(0x7 << prio_shift)) |
(prio << prio_shift);
LM4_NVIC_EN(irq / 32) |= 1<<(irq % 32);
}
}
#ifdef CONFIG_DEBUG
/* store the task names for easier debugging */
#define TASK(n, r, d) #n,
#include TASK_LIST
static const char * const task_names[] = {
"<< idle >>",
CONFIG_TASK_LIST
};
#undef TASK
int command_task_info(int argc, char **argv)
{
int i;
for (i = 0; i < TASK_ID_COUNT; i++) {
char is_ready = (tasks_ready & (1<<i)) ? 'R' : ' ';
uart_printf("%2d %c %-16s events %08x\n", i, is_ready,
task_names[i], tasks[i].events);
}
return EC_SUCCESS;
}
static int command_task_ready(int argc, char **argv)
{
if (argc < 2) {
uart_printf("tasks_ready: 0x%08x\n", tasks_ready);
} else {
tasks_ready = strtoi(argv[1], NULL, 16);
uart_printf("Setting tasks_ready to 0x%08x\n", tasks_ready);
__schedule(0, 0);
}
return EC_SUCCESS;
}
static const struct console_command task_commands[] = {
{"taskinfo", command_task_info},
{"taskready", command_task_ready}
};
static const struct console_group task_group = {
"Task", task_commands, ARRAY_SIZE(task_commands)
};
#endif
int task_init(void)
{
/* 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)));
/* Initialize IRQs */
__nvic_init_irqs();
#ifdef CONFIG_DEBUG
/* Register our internal commands */
console_register_commands(&task_group);
#endif
return EC_SUCCESS;
}

279
chip/lm4/timer.c Normal file
View File

@@ -0,0 +1,279 @@
/* Copyright (c) 2011 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.
*/
/* Timer module for Chrome EC operating system */
#include <stdint.h>
#include "task.h"
#include "timer.h"
#include "atomic.h"
#include "board.h"
#include "console.h"
#include "uart.h"
#include "registers.h"
#include "util.h"
#define US_PER_SECOND 1000000
/* Divider to get microsecond for the clock */
#define CLOCKSOURCE_DIVIDER (CPU_CLOCK/US_PER_SECOND)
/* high word of the 64-bit timestamp counter */
static volatile uint32_t clksrc_high;
/* bitmap of currently running timers */
static uint32_t timer_running = 0;
/* deadlines of all timers */
static timestamp_t timer_deadline[TASK_ID_COUNT];
static uint32_t next_deadline = 0xffffffff;
void __hw_clock_event_set(uint32_t deadline)
{
/* set the match on the deadline */
LM4_TIMER_TAMATCHR(W0) = 0xffffffff - deadline;
/* Set the match interrupt */
LM4_TIMER_IMR(W0) |= 0x10;
}
void __hw_clock_event_clear(void)
{
/* Disable the match interrupt */
LM4_TIMER_IMR(W0) &= ~0x10;
}
static uint32_t __hw_clock_source_read(void)
{
return 0xffffffff - LM4_TIMER_TAV(W0);
}
static void expire_timer(task_id_t tskid)
{
/* we are done with this timer */
atomic_clear(&timer_running, 1<<tskid);
/* wake up the taks waiting for this timer */
task_send_msg(tskid, TASK_ID_TIMER, 0);
}
/**
* Search the next deadline and program it in the timer hardware
*
* It returns a bitmap of expired timers.
*/
static void process_timers(void)
{
uint32_t check_timer, running_t0;
timestamp_t next;
timestamp_t now;
reprocess_timers:
next.val = 0xffffffffffffffff;
now = get_time();
do {
/* read atomically the current state of timer running */
check_timer = running_t0 = timer_running;
while (check_timer) {
int tskid = 31 - __builtin_clz(check_timer);
/* timer has expired ? */
if (timer_deadline[tskid].val < now.val)
expire_timer(tskid);
else if ((timer_deadline[tskid].le.hi == now.le.hi) &&
(timer_deadline[tskid].le.lo < next.le.lo))
next.val = timer_deadline[tskid].val;
check_timer &= ~(1 << tskid);
}
/* if there is a new timer, let's retry */
} while (timer_running & ~running_t0);
if (next.le.hi == 0xffffffff) {
/* no deadline to set */
__hw_clock_event_clear();
next_deadline = 0xffffffff;
return;
}
if (next.val <= get_time().val)
goto reprocess_timers;
__hw_clock_event_set(next.le.lo);
next_deadline = next.le.lo;
//TODO narrow race: deadline might have been reached before
}
static void __hw_clock_source_irq(void)
{
uint32_t status = LM4_TIMER_RIS(W0);
/* clear interrupt */
LM4_TIMER_ICR(W0) = status;
/* free running counter as overflowed */
if (status & 0x01) {
clksrc_high++;
}
/* Find expired timers and set the new timer deadline */
process_timers();
}
DECLARE_IRQ(94, __hw_clock_source_irq, 1);
static void __hw_clock_source_init(void)
{
volatile uint32_t scratch __attribute__((unused));
/* use WTIMER0 configured as a free running counter with 1us period */
/* Enable WTIMER0 clock */
LM4_SYSTEM_RCGCWTIMER |= 1;
/* wait 3 clock cycles before using the module */
scratch = LM4_SYSTEM_RCGCWTIMER;
/* Ensure timer is disabled : TAEN = TBEN = 0 */
LM4_TIMER_CTL(W0) &= ~0x101;
/* Set overflow interrupt */
LM4_TIMER_IMR(W0) = 0x1;
/* 32-bit timer mode */
LM4_TIMER_CFG(W0) = 4;
/* set the prescaler to increment every microsecond */
LM4_TIMER_TAPR(W0) = CLOCKSOURCE_DIVIDER;
/* Periodic mode, counting down */
LM4_TIMER_TAMR(W0) = 0x22;
/* use the full 32-bits of the timer */
LM4_TIMER_TAILR(W0) = 0xffffffff;
/* Starts counting in timer A */
LM4_TIMER_CTL(W0) |= 0x1;
}
void udelay(unsigned us)
{
timestamp_t deadline = get_time();
deadline.val += us;
while (get_time().val < deadline.val) {}
}
int timer_arm(timestamp_t tstamp, task_id_t tskid)
{
ASSERT(tskid < TASK_ID_COUNT);
if (timer_running & (1<<tskid))
return EC_ERROR_BUSY;
timer_deadline[tskid] = tstamp;
atomic_or(&timer_running, 1<<tskid);
/* modify the next event if needed */
if ((tstamp.le.hi < clksrc_high) ||
((tstamp.le.hi == clksrc_high) && (tstamp.le.lo <= next_deadline)))
LM4_NVIC_SWTRIG = 94;
return EC_SUCCESS;
}
int timer_cancel(task_id_t tskid)
{
ASSERT(tskid < TASK_ID_COUNT);
atomic_clear(&timer_running, 1<<tskid);
/* don't bother about canceling the interrupt:
* it would be slow, just do it on the next IT
*/
return EC_SUCCESS;
}
void usleep(unsigned us)
{
uint32_t evt = 0;
ASSERT(us);
do {
evt |= task_wait_msg(us);
} while (!(evt & (1 << TASK_ID_TIMER)));
/* re-queue other events which happened in the meanwhile */
if (evt)
atomic_or(task_get_event_bitmap(task_get_current()),
evt & ~(1 << TASK_ID_TIMER));
}
timestamp_t get_time(void)
{
timestamp_t ts;
ts.le.hi = clksrc_high;
ts.le.lo = __hw_clock_source_read();
if (ts.le.hi != clksrc_high) {
ts.le.hi = clksrc_high;
ts.le.lo = __hw_clock_source_read();
}
return ts;
}
static int command_wait(int argc, char **argv)
{
if (argc < 2)
return EC_ERROR_INVAL;
udelay(atoi(argv[1]) * 1000);
return EC_SUCCESS;
}
static int command_get_time(int argc, char **argv)
{
timestamp_t ts = get_time();
uart_printf("Time: 0x%08x%08x us\n", ts.le.hi, ts.le.lo);
return EC_SUCCESS;
}
int command_timer_info(int argc, char **argv)
{
timestamp_t ts = get_time();
int tskid;
uart_printf("Time: 0x%08x%08x us\n"
"Deadline: 0x%08x%08x us\n"
"Active timers:\n",
ts.le.hi, ts.le.lo, clksrc_high,
0xffffffff -LM4_TIMER_TAMATCHR(W0));
for (tskid = 0; tskid < TASK_ID_COUNT; tskid++) {
if (timer_running & (1<<tskid))
uart_printf("Tsk %d tmr 0x%08x%08x\n", tskid,
timer_deadline[tskid].le.hi,
timer_deadline[tskid].le.lo);
}
return EC_SUCCESS;
}
static const struct console_command timer_commands[] = {
{"waitms", command_wait},
{"timerinfo", command_timer_info},
{"gettime", command_get_time}
};
static const struct console_group timer_group = {
"Timer", timer_commands, ARRAY_SIZE(timer_commands)
};
int timer_init(void)
{
BUILD_ASSERT(TASK_ID_COUNT < sizeof(timer_running) * 8);
__hw_clock_source_init();
/* Register our internal commands */
console_register_commands(&timer_group);
return EC_SUCCESS;
}

132
chip/lm4/watchdog.c Normal file
View File

@@ -0,0 +1,132 @@
/* Copyright (c) 2011 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.
*/
/* Watchdog driver */
#include <stdint.h>
#include "board.h"
#include "common.h"
#include "config.h"
#include "registers.h"
#include "task.h"
#include "uart.h"
#include "util.h"
/*
* We use watchdog 0 which is clocked on the system clock
* to avoid the penalty cycles on each write access
*/
/* magic value to unlock the watchdog registers */
#define LM4_WATCHDOG_MAGIC_WORD 0x1ACCE551
/* watchdog counter initial value */
static uint32_t watchdog_period;
/* console debug command prototypes */
int command_task_info(int argc, char **argv);
int command_timer_info(int argc, char **argv);
/**
* watchdog debug trace.
*
* It is triggered if the watchdog has not been reloaded after 1x the timeout
* period, after 2x the period an hardware reset is triggering.
*/
void watchdog_trace(uint32_t excep_lr, uint32_t excep_sp)
{
uint32_t psp;
uint32_t *stack;
/* we do NOT reset the watchdog interrupt here, it will be done in
* watchdog_reload() or fire the reset
* instead de-activate the interrupt in the NVIC :
* so, we will get the trace only once
*/
LM4_NVIC_DIS(0) = 1 << 18;
asm("mrs %0, psp":"=r"(psp));
if ((excep_lr & 0xf) == 1) {
/* we were already in exception context */
stack = (uint32_t *)excep_sp;
} else {
/* we were in task context */
stack = (uint32_t *)psp;
}
uart_printf("### WATCHDOG PC=%08x / LR=%08x / pSP=%08x ###\n",
stack[6], stack[5], psp);
/* ensure this debug message is always flushed to the UART */
uart_emergency_flush();
/* if we are blocked in a high priority IT handler, the following
* debug messages might not appear but they are useless in that
* situation.
*/
command_task_info(0, NULL);
command_timer_info(0, NULL);
}
void irq_18_handler(void) __attribute__((naked));
void irq_18_handler(void)
{
asm volatile("mov r0, lr\n"
"mov r1, sp\n"
"push {lr}\n"
"bl watchdog_trace\n"
"pop {lr}\n"
"mov r0, lr\n"
"b task_resched_if_needed\n");
}
const struct irq_priority prio_18 __attribute__((section(".rodata.irqprio")))
= {18, 0}; /* put the watchdog at the highest priority */
void watchdog_reload(void)
{
uint32_t status = LM4_WATCHDOG_RIS(0);
/* unlock watchdog registers */
LM4_WATCHDOG_LOCK(0) = LM4_WATCHDOG_MAGIC_WORD;
/* As we reboot only on the second time-out,
* if we have already reached 1 time-out
* we need to reset the interrupt bit.
*/
if (status)
LM4_WATCHDOG_ICR(0) = status;
/* reload the watchdog counter */
LM4_WATCHDOG_LOAD(0) = watchdog_period;
/* re-lock watchdog registers */
LM4_WATCHDOG_LOCK(0) = 0xdeaddead;
}
int watchdog_init(int period_ms)
{
volatile uint32_t scratch __attribute__((unused));
/* Enable watchdog 0 clock */
LM4_SYSTEM_RCGCWD |= 0x1;
/* wait 3 clock cycles before using the module */
scratch = LM4_SYSTEM_RCGCWD;
/* set the time-out period */
watchdog_period = period_ms * (CPU_CLOCK / 1000);
LM4_WATCHDOG_LOAD(0) = watchdog_period;
/* de-activate the watchdog when the JTAG stops the CPU */
LM4_WATCHDOG_TEST(0) |= 1 << 8;
/* reset after 2 time-out,
* activate the watchdog and lock the control register
*/
LM4_WATCHDOG_CTL(0) = 0x3;
/* lock watchdog registers against unintended accesses */
LM4_WATCHDOG_LOCK(0) = 0xdeaddead;
return EC_SUCCESS;
}

21
chip/lm4/watchdog.h Normal file
View File

@@ -0,0 +1,21 @@
/* Copyright (c) 2011 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.
*/
/* Watchdog driver */
#ifndef _WATCHDOG_H
#define _WATCHDOG_H
/* Reload the watchdog counter */
void watchdog_reload(void);
/**
* Initialize the watchdog
* with a reloading period of <period_ms> milliseconds.
* It reboots the CPU if the counter has not been reloaded for twice the period.
*/
int watchdog_init(int period_ms);
#endif /* _WATCHDOG_H */

7
common/build.mk Normal file
View File

@@ -0,0 +1,7 @@
#
# common files build
#
common-objs=main.o util.o console.o vboot.o
common-objs+=flash_commands.o host_command.o port80.o keyboard.o i8042.o
common-objs+=memory_commands.o shared_mem.o

25
common/firmware_image.S Normal file
View File

@@ -0,0 +1,25 @@
/* Copyright (c) 2011 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.
*
* Build the full image with 3 copies (Read only, A, B) of the program
*/
#include "config.h"
#define FW_FILE(builddir,proj,sect) builddir##/##proj##.##sect##.flat
#define STRINGIFY0(name) #name
#define STRINGIFY(name) STRINGIFY0(name)
#define FW_IMAGE(sect) STRINGIFY(FW_FILE(OUTDIR,PROJECT,sect))
/* Read Only firmware */
.section .image.RO, "ax"
.incbin FW_IMAGE(RO)
/* Read Write firmware copy A */
.section .image.A, "ax"
.incbin FW_IMAGE(A)
/* Read Write firmware copy B */
.section .image.B, "ax"
.incbin FW_IMAGE(B)

View File

@@ -0,0 +1,23 @@
#include "config.h"
OUTPUT_FORMAT("elf32-littlearm", "elf32-littlearm", "elf32-littlearm")
OUTPUT_ARCH(arm)
MEMORY
{
FLASH (rx) : ORIGIN = CONFIG_FLASH_BASE, LENGTH = CONFIG_FLASH_SIZE
}
SECTIONS
{
. = ALIGN(CONFIG_FLASH_BANK_SIZE);
.image.RO : AT(CONFIG_FW_RO_OFF) {
*(.image.RO)
} > FLASH
. = ALIGN(CONFIG_FLASH_BANK_SIZE);
.image.A : AT(CONFIG_FW_A_OFF) {
*(.image.A)
} > FLASH
. = ALIGN(CONFIG_FLASH_BANK_SIZE);
.image.B : AT(CONFIG_FW_B_OFF) {
*(.image.B)
} > FLASH
}

14
include/clock.h Normal file
View File

@@ -0,0 +1,14 @@
/* Copyright (c) 2011 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.
*/
/* Clocks and power management settings */
#ifndef __CLOCK_H
#define __CLOCK_H
/* set the CPU clocks and PLLs */
int clock_init(void);
#endif /* __CLOCK_H */

95
include/task.h Normal file
View File

@@ -0,0 +1,95 @@
/* Copyright (c) 2011 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 */
#ifndef __EC_TASK_H
#define __EC_TASK_H
#include "common.h"
#include "task_id.h"
/**
* Return true if we are in interrupt context
*/
inline int in_interrupt_context(void);
/**
* Send a message to a task and wake it up if it is higher priority than us
*
* tskid : identifier of the receiver task
* from : identifier of the sender of the message
* wait : after sending, de-schedule the calling task to wait for the answer
*
* returns the bitmap of events which have occured.
*
* Can be called both in interrupt context and task context.
*/
uint32_t task_send_msg(task_id_t tskid, task_id_t from, int wait);
/**
* Return the identifier of the task currently running
*
* when called in interrupt context, returns TASK_ID_INVALID
*/
task_id_t task_get_current(void);
/**
* Return a pointer to the bitmap of received events of the task.
*/
uint32_t *task_get_event_bitmap(task_id_t tsk);
/**
* Wait for the incoming next message.
*
* if an event is already pending, it returns it immediatly, else it
* de-schedules the calling task and wake up the next one in the priority order
*
* if timeout_us > 0, it also sets a timer to produce an event after the
* specified micro-second duration.
*
* returns the bitmap of received events (and clear it atomically).
*/
uint32_t task_wait_msg(int timeout_us);
/**
* Change the task scheduled after returning from the exception.
*
* If task_send_msg has been called and has set need_resched flag,
* we re-compute which task is running and eventually swap the context
* saved on the process stack to restore the new one at exception exit.
*
* it must be called from interrupt context !
* and it is designed to be the last call of the interrupt handler.
*/
void task_resched_if_needed(void *excep_return);
/* Initialize tasks and interrupt controller */
int task_init(void);
/* Start the task scheduling */
int task_start(void);
struct irq_priority {
uint8_t irq;
uint8_t priority;
};
/**
* Connect the interrupt handler "routine" to the irq number "irq" and
* ensure it is enabled in the interrupt controller with the right priority
*/
#define DECLARE_IRQ(irq, routine, priority) \
void irq_##irq##_handler(void) \
{ \
void *ret = __builtin_return_address(0); \
routine(); \
task_resched_if_needed(ret); \
} \
const struct irq_priority prio_##irq \
__attribute__((section(".rodata.irqprio"))) \
= {irq, priority}
#endif /* __EC_TASK_H */

41
include/task_id.h Normal file
View File

@@ -0,0 +1,41 @@
/* Copyright (c) 2011 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.
*/
/* define the task identifier of all compiled tasks */
#ifndef __TASK_ID_H
#define __TASK_ID_H
/* define the name of the header containing the list of tasks */
#define STRINGIFY0(name) #name
#define STRINGIFY(name) STRINGIFY0(name)
#define TASK_LIST STRINGIFY(TASKFILE)
/* Task identifier (8 bits) */
typedef uint8_t task_id_t;
/**
* enumerate all tasks in the priority order
*
* the identifier of a task can be retrieved using the following constant:
* TASK_ID_<taskname> where <taskname> is the first parameter passed to the
* TASK macro in the TASK_LIST file.
*/
#define TASK(n, r, d) TASK_ID_##n,
#include TASK_LIST
enum {
TASK_ID_IDLE,
/* CONFIG_TASK_LIST is a macro coming from the TASK_LIST file */
CONFIG_TASK_LIST
/* Number of tasks */
TASK_ID_COUNT,
/* Special task identifiers */
TASK_ID_TIMER = 0x1f, /* message from an expired timer */
TASK_ID_CURRENT = 0xfe, /* the currently running task */
TASK_ID_INVALID = 0xff /* unable to find the task */
};
#undef TASK
#endif /* __TASK_ID_H */

60
include/timer.h Normal file
View File

@@ -0,0 +1,60 @@
/* Copyright (c) 2011 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.
*/
/* Timer module for Chrome EC operating system */
#ifndef __EC_TIMER_H
#define __EC_TIMER_H
#include "common.h"
#include "task_id.h"
/* Micro-second timestamp. */
typedef union {
uint64_t val;
struct {
uint32_t lo;
uint32_t hi;
} le /* little endian words */;
} timestamp_t;
/* Initializes the Timer module. */
int timer_init(void);
/**
* Launches a one-shot timer.
*
* tstamp : timestamp in micro-seconds when the timer expires
* tskid : identifier of the task owning the timer
*/
int timer_arm(timestamp_t tstamp, task_id_t tskid);
/**
* Cancels a running timer.
*
* tskid : identifier of the task owning the timer
*/
int timer_cancel(task_id_t tskid);
/**
* Busy wait the selected number of micro-seconds
*/
void udelay(unsigned us);
/**
* Sleep during the selected number of micro-seconds
*
* The current task will be de-scheduled until the delay expired
*
* Note: if an event happens before the end of sleep, the function will return.
*/
void usleep(unsigned us);
/**
* Get the current timestamp from the system timer
*/
timestamp_t get_time(void);
#endif /* __EC_TIMER_H */

54
include/util.h Normal file
View File

@@ -0,0 +1,54 @@
/* Copyright (c) 2011 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.
*/
/* Various utility functions and macros */
#ifndef __UTIL_H
#define __UTIL_H
#include <stdint.h>
#include "config.h"
/**
* Trigger a compilation failure if the condition
* is not verified at build time.
*/
#define BUILD_ASSERT(cond) ((void)sizeof(char[1 - 2*!(cond)]))
/**
* Trigger a debug exception if the condition
* is not verified at runtime.
*/
#ifdef CONFIG_DEBUG
#define ASSERT(cond) do { \
if (!(cond)) \
__asm("bkpt"); \
} while (0);
#else
#define ASSERT(cond)
#endif
/* Standard macros / definitions */
#define ARRAY_SIZE(x) (sizeof(x) / sizeof((x)[0]))
#define MAX(a, b) ((a) > (b) ? (a) : (b))
#define MIN(a, b) ((a) < (b) ? (a) : (b))
#define NULL ((void *)0)
/* Standard library functions */
int atoi(const char *nptr);
int isdigit(int c);
int isspace(int c);
void *memcpy(void *dest, const void *src, int len);
void *memset(void *dest, int c, int len);
int strcasecmp(const char *s1, const char *s2);
int strlen(const char *s);
int strtoi(const char *nptr, char **endptr, int base);
char *strzcpy(char *dest, const char *src, int len);
int tolower(int c);
#endif /* __UTIL_H */

11
test/build.mk Normal file
View File

@@ -0,0 +1,11 @@
#
# on-board test binaries build
#
test-list=hello pingpong timer_calib timer_dos
#disable: powerdemo
pingpong-objs=pingpong.o
powerdemo-objs=powerdemo.o
timer_calib-objs=timer_calib.o
timer_dos-objs=timer_dos.o

16
test/hello.py Normal file
View File

@@ -0,0 +1,16 @@
# Copyright (c) 2011 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.
#
# Simple test as an example
#
def test(helper):
helper.wait_output("--- Chrome EC initialized! ---")
helper.wait_prompt()
helper.ec_command("version")
ro = helper.wait_output("RO version:\s*(?P<ro>\S+)", use_re=True)["ro"]
wa = helper.wait_output("RW-A version:\s*(?P<a>\S+)", use_re=True)["a"]
wb = helper.wait_output("RW-B version:\s*(?P<b>\S+)", use_re=True)["b"]
helper.trace("Version (RO/A/B) %s / %s / %s\n" % (ro, wa, wb))
return True # PASS !

21
test/hello.tasklist Normal file
View File

@@ -0,0 +1,21 @@
/* Copyright (c) 2011 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.
*/
/**
* List of enabled tasks in the priority order
*
* The first one has the lowest priority.
*
* For each task, use the macro TASK(n, r, d) where :
* 'n' in the name of the task
* 'r' in the main routine of the task
* 'd' in an opaque parameter passed to the routine at startup
*/
#define CONFIG_TASK_LIST \
TASK(BLINK, UserLedBlink, NULL) \
TASK(KEYSCAN, keyboard_scan_task, NULL) \
TASK(CONSOLE, console_task, NULL) \
TASK(HOSTCMD, host_command_task, NULL) \
TASK(I8042CMD, i8042_command_task, NULL)

43
test/pingpong.c Normal file
View File

@@ -0,0 +1,43 @@
/* Copyright (c) 2011 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.
* Copyright 2011 Google Inc.
*
* Tasks for scheduling test.
*/
#include "common.h"
#include "uart.h"
#include "task.h"
#include "timer.h"
int TaskAbc(void *data)
{
char letter = (char)(unsigned)data;
char string[2] = {letter, '\0' };
task_id_t next = task_get_current() + 1;
if (next > TASK_ID_TESTC)
next = TASK_ID_TESTA;
uart_printf("\n[starting Task %c]\n", letter);
while (1) {
uart_puts(string);
uart_flush_output();
task_send_msg(next, TASK_ID_CURRENT, 1);
}
return EC_SUCCESS;
}
int TaskTick(void *data)
{
uart_set_console_mode(1);
uart_printf("\n[starting Task T]\n");
/* Print T every tick */
while (1) {
/* Wait for timer interrupt message */
usleep(3000);
uart_puts("T\n");
}
}

27
test/pingpong.py Normal file
View File

@@ -0,0 +1,27 @@
# Copyright (c) 2011 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 test
#
import time
# Test during 5s
DURATION=5
def test(helper):
helper.wait_output("[starting Task T]")
helper.wait_output("[starting Task C]")
helper.wait_output("[starting Task B]")
helper.wait_output("[starting Task A]")
deadline = time.time() + DURATION
count = []
while time.time() < deadline:
sched = helper.wait_output("(?P<a>(?:ABC){3,200})T", use_re=True,
timeout=1)["a"]
count.append(len(sched) / 3)
helper.trace("IRQ count %d, cycles count min %d max %d\n" %
(len(count), min(count), max(count)))
return True # PASS !

15
test/pingpong.tasklist Normal file
View File

@@ -0,0 +1,15 @@
/**
* List of enabled tasks in the priority order
*
* The first one has the lowest priority.
*/
#define CONFIG_TASK_LIST \
TASK(BLINK, UserLedBlink, NULL) \
TASK(CONSOLE, console_task, NULL) \
TASK(TESTA, TaskAbc, (void *)'A') \
TASK(TESTB, TaskAbc, (void *)'B') \
TASK(TESTC, TaskAbc, (void *)'C') \
TASK(TESTT, TaskTick, (void *)'T')\
TASK(HOSTCMD, host_command_task, NULL) \
TASK(I8042CMD, i8042_command_task, NULL)

186
test/powerdemo.c Normal file
View File

@@ -0,0 +1,186 @@
/* Copyright (c) 2011 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.
*/
/* Power state machine demo module for Chrome EC */
#include "board.h"
#include "powerdemo.h"
#include "task.h"
#include "timer.h"
#include "uart.h"
#include "registers.h"
#define US_PER_SECOND 1000000
/* Divider to get microsecond for the clock */
#define CLOCKSOURCE_DIVIDER (CPU_CLOCK/US_PER_SECOND)
static volatile enum {
POWER_STATE_IDLE = 0, /* Idle */
POWER_STATE_DOWN1, /* Assert output for 1ms */
POWER_STATE_UP1, /* Deassert output for 1ms */
POWER_STATE_DOWN10, /* Assert output for 10ms */
POWER_STATE_UP5, /* Deassert output for 5ms */
POWER_STATE_DOWN15, /* Assert output for 15ms */
POWER_STATE_WAIT, /* Wait for button to be released */
POWER_STATE_DOWN2 /* Assert output for 2ms */
} state = POWER_STATE_IDLE;
/* Stops the timer. */
static void __stop_timer(void)
{
/* Disable timer A */
LM4_TIMER_CTL(W1) &= ~0x01;
/* Clear any pending interrupts */
LM4_TIMER_ICR(W1) = LM4_TIMER_RIS(W1);
}
/* Starts the timer with the specified delay. If the timer is already
* started, resets it. */
static void __start_timer(int usec)
{
/* Stop the timer, if it was started */
__stop_timer();
/* Set the delay, counting function overhead */
LM4_TIMER_TAILR(W1) = usec;
/* Start timer A */
LM4_TIMER_CTL(W1) |= 0x01;
}
static void __set_state(int new_state, int pin_value, int timeout)
{
LM4_GPIO_DATA_BITS(D, 0x08 << 2) = (pin_value ? 0x08 : 0);
if (timeout)
__start_timer(timeout);
else
__stop_timer();
state = new_state;
}
int power_demo_init(void)
{
volatile uint32_t scratch __attribute__((unused));
/* Set up TIMER1 as our state timer */
/* Enable TIMER1 clock */
LM4_SYSTEM_RCGCWTIMER |= 0x02;
/* wait 3 clock cycles before using the module */
scratch = LM4_SYSTEM_RCGCWTIMER;
/* Ensure timer is disabled : TAEN = TBEN = 0 */
LM4_TIMER_CTL(W1) &= ~0x101;
/* 32-bit timer mode */
LM4_TIMER_CFG(W1) = 4;
/* Set the prescaler to increment every microsecond */
LM4_TIMER_TAPR(W1) = CLOCKSOURCE_DIVIDER;
/* One-shot, counting down */
LM4_TIMER_TAMR(W1) = 0x01;
/* Set overflow interrupt */
LM4_TIMER_IMR(W1) = 0x1;
/* Enable clock to GPIO module D */
LM4_SYSTEM_RCGCGPIO |= 0x0008;
/* Clear GPIOAFSEL and enable digital function for pins 0-3 */
LM4_GPIO_AFSEL(D) &= ~0x0f;
LM4_GPIO_DEN(D) |= 0x0f;
/* Set pins 0-2 as input, pin 3 as output */
LM4_GPIO_DIR(D) = (LM4_GPIO_DIR(D) & ~0x0f) | 0x08;
/* Set pin 0 to edge-sensitive, both edges, pull-up */
LM4_GPIO_IS(D) &= ~0x01;
LM4_GPIO_IBE(D) |= 0x01;
LM4_GPIO_PUR(D) |= 0x01;
/* Move to idle state */
__set_state(POWER_STATE_IDLE, 1, 0);
/* Enable interrupt on pin 0 */
LM4_GPIO_IM(D) |= 0x01;
return EC_SUCCESS;
}
/* GPIO interrupt handler */
static void __gpio_d_interrupt(void)
{
uint32_t mis = LM4_GPIO_MIS(D);
/* Clear the interrupt bits we're handling */
LM4_GPIO_ICR(D) = mis;
/* Handle edges */
if (mis & 0x01) {
if (LM4_GPIO_DATA_BITS(D, 0x01 << 2)) {
if (state == POWER_STATE_WAIT)
__set_state(POWER_STATE_DOWN2, 0, 2000 - 28);
} else {
if (state == POWER_STATE_IDLE)
__set_state(POWER_STATE_DOWN1, 0, 1000 - 28);
}
}
}
DECLARE_IRQ(3, __gpio_d_interrupt, 1);
/* Timer interrupt handler */
static void __timer_w1_interrupt(void)
{
uint32_t mis = LM4_TIMER_RIS(W1);
/* Clear the interrupt reasons we're handling */
LM4_TIMER_ICR(W1) = mis;
/* Transition to next state */
switch (state) {
case POWER_STATE_IDLE:
case POWER_STATE_WAIT:
/* Ignore timer events when waiting for GPIO edges */
break;
case POWER_STATE_DOWN1:
__set_state(POWER_STATE_UP1, 1, 1000 - 28);
break;
case POWER_STATE_UP1:
__set_state(POWER_STATE_DOWN10, 0, 10000 - 228);
break;
case POWER_STATE_DOWN10:
__set_state(POWER_STATE_UP5, 1, 5000 - 128);
break;
case POWER_STATE_UP5:
__set_state(POWER_STATE_DOWN15, 0, 15000 - 328);
break;
case POWER_STATE_DOWN15:
if (LM4_GPIO_DATA_BITS(D, 0x01 << 2)) {
/* Button has already been released; go straight to
* idle */
__set_state(POWER_STATE_IDLE, 1, 0);
} else {
/* Wait for button release */
__set_state(POWER_STATE_WAIT, 1, 0);
}
break;
case POWER_STATE_DOWN2:
__set_state(POWER_STATE_IDLE, 1, 0);
break;
}
}
DECLARE_IRQ(96, __timer_w1_interrupt, 1);
int power_demo_task(void)
{
/* Initialize the peripherals */
power_demo_init();
/* suspend this task forever */
task_wait_msg(-1);
return EC_SUCCESS;
}

6
test/powerdemo.tasklist Normal file
View File

@@ -0,0 +1,6 @@
#define CONFIG_TASK_LIST \
TASK(CONSOLE, console_task, NULL) \
TASK(HOSTCMD, host_command_task, NULL) \
TASK(I8042CMD, i8042_command_task, NULL) \
TASK(POWERDEMO, power_demo_task, NULL)

55
test/timer_calib.c Normal file
View File

@@ -0,0 +1,55 @@
/* Copyright (c) 2011 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.
* Copyright 2011 Google Inc.
*
* Tasks for scheduling test.
*/
#include "common.h"
#include "uart.h"
#include "task.h"
#include "timer.h"
uint32_t difftime(timestamp_t t0, timestamp_t t1)
{
return (uint32_t)(t1.val-t0.val);
}
int timer_calib_task(void *data)
{
timestamp_t t0, t1;
unsigned d;
uart_printf("\n=== Timer calibration ===\n");
t0 = get_time();
t1 = get_time();
uart_printf("- back-to-back get_time : %d us\n", difftime(t0, t1));
/* Sleep for 5 seconds */
uart_printf("- sleep 1s :\n ");
uart_flush_output();
uart_printf("Go...");
t0 = get_time();
usleep(1000000);
t1 = get_time();
uart_printf("done. delay = %d us\n", difftime(t0, t1));
/* try small usleep */
uart_printf("- short sleep :\n");
uart_flush_output();
for (d=128 ; d > 0; d = d / 2) {
t0 = get_time();
usleep(d);
t1 = get_time();
uart_printf(" %d us => %d us\n", d, difftime(t0, t1));
uart_flush_output();
}
uart_printf("Done.\n");
/* sleep forever */
task_wait_msg(-1);
return EC_SUCCESS;
}

54
test/timer_calib.py Normal file
View File

@@ -0,0 +1,54 @@
# Copyright (c) 2011 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.
#
# Check timers behavior
#
import time
def one_pass(helper):
helper.wait_output("=== Timer calibration ===")
res = helper.wait_output("back-to-back get_time : (?P<lat>[0-9]+) us",
use_re=True)["lat"]
minlat = int(res)
helper.trace("get_time latency %d us\n" % minlat)
helper.wait_output("sleep 1s")
t0 = time.time()
second = helper.wait_output("done. delay = (?P<second>[0-9]+) us",
use_re=True)["second"]
t1 = time.time()
secondreal = t1 - t0
secondlat = int(second) - 1000000
helper.trace("1s timer latency %d us / real time %f s\n" % (secondlat,
secondreal))
us = {}
for pow2 in range(7):
delay = 1 << (7-pow2)
us[delay] = helper.wait_output("%d us => (?P<us>[0-9]+) us" % delay,
use_re=True)["us"]
helper.wait_output("Done.")
return minlat, secondlat, secondreal
def test(helper):
one_pass(helper)
helper.ec_command("reboot")
helper.wait_output("--- Chrome EC initialized! ---")
# get the timing results on the second pass
# to avoid binary translation overhead
minlat, secondlat, secondreal = one_pass(helper)
# check that the timings somewhat make sense
if minlat > 220 or secondlat > 500 or abs(secondreal-1.0) > 0.200:
helper.fail("imprecise timings " +
"(get_time %d us sleep %d us / real time %.3f s)" %
(minlat, secondlat, secondreal))
return True # PASS !

12
test/timer_calib.tasklist Normal file
View File

@@ -0,0 +1,12 @@
/**
* List of enabled tasks in the priority order
*
* The first one has the lowest priority.
*/
#define CONFIG_TASK_LIST \
TASK(BLINK, UserLedBlink, NULL) \
TASK(TESTTMR, timer_calib_task, (void *)'T')\
TASK(CONSOLE, console_task, NULL) \
TASK(HOSTCMD, host_command_task, NULL) \
TASK(I8042CMD, i8042_command_task, NULL)

39
test/timer_dos.c Normal file
View File

@@ -0,0 +1,39 @@
/* Copyright (c) 2011 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.
* Copyright 2011 Google Inc.
*
* Tasks for timer test.
*/
#include "common.h"
#include "uart.h"
#include "task.h"
#include "timer.h"
/* Linear congruential pseudo random number generator*/
static uint32_t prng(uint32_t x)
{
return 22695477 * x + 1;
}
/* period between 500us and 128ms */
#define PERIOD_US(num) (((num % 256) + 1) * 500)
int TaskTimer(void *seed)
{
uint32_t num = (uint32_t)seed;
task_id_t id = task_get_current();
uart_printf("\n[Timer task %d]\n", id);
while (1) {
/* Wait for a "random" period */
task_wait_msg(PERIOD_US(num));
uart_printf("%01d\n", id);
/* next pseudo random delay */
num = prng(num);
}
return EC_SUCCESS;
}

41
test/timer_dos.py Normal file
View File

@@ -0,0 +1,41 @@
# Copyright (c) 2011 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.
#
# Timers test
#
import time
# Test during 5s
DURATION=5
# Linear congruential pseudo random number generator*/
def prng(x):
return (22695477 * x + 1) & 0xffffffff
# period between 500us and 128ms
def period_us(num):
return (((num % 256) + 1) * 500)
# build the same pseudo random sequence as the target
def build_sequence():
#TODO
return []
def test(helper):
helper.wait_output("[Timer task ")
deadline = time.time() + DURATION
seq = []
while time.time() < deadline:
tmr = helper.wait_output("(?P<t>[0-9])", use_re=True,
timeout=1)["t"]
seq.append(tmr)
# Check the results
model = build_sequence()
#TODO
helper.trace("Got %d timer IRQ\n" % len(seq))
return True # PASS !

15
test/timer_dos.tasklist Normal file
View File

@@ -0,0 +1,15 @@
/**
* List of enabled tasks in the priority order
*
* The first one has the lowest priority.
*/
#define CONFIG_TASK_LIST \
TASK(BLINK, UserLedBlink, NULL) \
TASK(CONSOLE, console_task, NULL) \
TASK(TMRA, TaskTimer, (void *)1234) \
TASK(TMRB, TaskTimer, (void *)5678) \
TASK(TMRC, TaskTimer, (void *)8462) \
TASK(TMRD, TaskTimer, (void *)3719) \
TASK(HOSTCMD, host_command_task, NULL)\
TASK(I8042CMD, i8042_command_task, NULL)

5
util/build.mk Normal file
View File

@@ -0,0 +1,5 @@
#
# Host tools build
#
util-bin=ectool

BIN
util/qemu-system-arm Executable file

Binary file not shown.

253
util/run_qemu_test Executable file
View File

@@ -0,0 +1,253 @@
#!/usr/bin/python
# Copyright (c) 2011 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.
#
# Python wrapper script for running tests under QEMU
#
import errno
import imp
import json
import os
import optparse
import re
import signal
import socket
import subprocess
import sys
import threading
import time
QEMU_BINARY="qemu-system-arm"
QEMU_OPTIONS=["-machine","lm4f232h5","-serial","stdio","-display","none"]
def trace(msg):
sys.stdout.write(msg)
class QEMUError(Exception):
def __init__(self, value):
self.value = value
def __str__(self):
return "QEMU Error:" + repr(self.value)
class QEMUInstance:
PORT=3456
QMP_ADDR=("127.0.0.1", PORT)
def __run_qemu(self, cmdline, redirect_stdio=False):
trace("Starting QEMU binary ...\n")
if redirect_stdio:
stdin = subprocess.PIPE
stdout = subprocess.PIPE
else:
stdin = None
stdout = None
self.__qemu = subprocess.Popen(cmdline, shell=False, bufsize=16384,
stdin=stdin, stdout=stdout, close_fds=True)
trace("QEMU started pid:%d\n" % (self.__qemu.pid))
self.__qemu.wait()
trace("QEMU has terminated\n")
def __init__(self, qemu_bin, firmware, romcode = None, testmode = False):
self.__events = []
cmdline = [qemu_bin] + QEMU_OPTIONS + ["-kernel",firmware,"-qmp","tcp:%s:%d" % self.QMP_ADDR]
if romcode:
cmdline += ["-bios",romcode]
self.__sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
self.__sock.bind(self.QMP_ADDR)
self.__sock.listen(1)
self.__thr = threading.Thread(target=QEMUInstance.__run_qemu,args=(self,cmdline,testmode))
self.__thr.start()
try:
trace("Waiting for QEMU connection ...\n")
self.__sock, _ = self.__sock.accept()
self.__sockfd = self.__sock.makefile()
except socket.error:
raise QEMUError('Cannot connect to QMP server')
version = self.__json_recv()
if version is None or not version.has_key('QMP'):
raise QEMUError('Not QMP support')
# Test basic communication with QMP
resp = self.send_qmp('qmp_capabilities')
if not "return" in resp:
raise QEMUError('QMP not working properly')
trace("QMP connected\n")
def __json_recv(self, only_event=False):
while True:
data = self.__sockfd.readline()
if not data:
return
return json.loads(data)
def send_qmp(self, name, args=None):
qmp_cmd = { 'execute': name }
if args:
qmp_cmd['arguments'] = args
try:
self.__sock.sendall(json.dumps(qmp_cmd))
except socket.error, err:
if err[0] == errno.EPIPE:
return
raise QEMUError("Error on QMP socket:" + err)
return self.__json_recv()
def serial_readline(self):
return self.__qemu.stdout.readline()
def serial_write(self, string):
self.__qemu.stdin.write(string)
self.__qemu.stdin.flush()
def get_event(self, blocking=True):
if not blocking:
self.__sock.setblocking(0)
try:
val = self.__json_recv()
except socket.error, err:
if err[0] == errno.EAGAIN:
# Nothing available
return None
if not blocking:
self.__sock.setblocking(1)
return val
def close(self):
# Try to terminate QEMU gracefully
if self.__qemu.poll() == None:
self.send_qmp("quit")
time.sleep(0.1)
# Force termination if the process is still here :
if self.__qemu.poll() == None:
self.__qemu.terminate()
self.__thr.join()
self.__sock.close()
self.__sockfd.close()
class TestFailure(Exception):
def __init__(self, reason):
self.value = reason
def __str__(self):
return "reason:" + repr(self.value)
class EcTest:
def __init__(self, qemu_bin, firmware, romcode, test):
self.__qemu_bin = qemu_bin
self.__firmware = firmware
self.__romcode = romcode
self.__test = test
def timeout_handler(self, signum, frame):
raise TestFailure("Timeout waiting for %s" % self.__timeout_reason)
def wait_output(self, string, use_re = False, timeout = 5):
self.__timeout_reason = string
old_handler = signal.signal(signal.SIGALRM, lambda
s,f:self.timeout_handler(s,f))
if use_re:
regexp = re.compile(string)
signal.alarm(timeout)
while True:
ln = self.__qemu.serial_readline()
trace("[EC]%s" % ln)
if use_re:
res = regexp.search(ln)
if res:
signal.alarm(0)
signal.signal(signal.SIGALRM, old_handler)
return res.groupdict()
else:
if string in ln:
signal.alarm(0)
signal.signal(signal.SIGALRM, old_handler)
return
def wait_prompt(self):
self.wait_output("> ")
def ec_command(self, cmd):
self.__qemu.serial_write(cmd + '\r\n')
def trace(self, msg):
trace(msg)
def report(self, msg):
sys.stderr.write(" === TEST %s ===\n" % msg)
def fail(self, msg):
raise TestFailure(msg)
def run_test(self):
try:
self.__qemu = QEMUInstance(self.__qemu_bin, self.__firmware,
self.__romcode, True)
except QEMUError as e:
self.report("QEMU FATAL ERROR: " + e.value)
return 1
testmod = imp.load_module("testmodule", file(self.__test,"r"),
self.__test, (".py","r",imp.PY_SOURCE))
self.report("RUN: %s" % os.path.basename(self.__test))
try:
res = testmod.test(self)
except TestFailure as e:
res = False
self.report("FAIL: %s" % e.value)
self.__qemu.close()
if res:
self.report("PASS")
return 0
return 1
def run_interactive(qemu_bin, firmware, romcode):
try:
qemu = QEMUInstance(qemu_bin, firmware, romcode, False)
except QEMUError as e:
sys.stderr.write('FATAL: %s\n' % e.value)
return 1
# Dummy testing code : TODO remove
#print qemu.send_qmp("query-commands")
#print qemu.send_qmp("human-monitor-command",
# { 'command-line': "sendkey ctrl-alt-f1 50",'cpu-index': 0 })
while True:
msg = qemu.get_event()
trace("[EVENT]%s\n" % msg)
if msg.has_key("event") and msg["event"] == "RESET":
break
qemu.close()
return 0
def parse_cmdline(basedir):
parser = optparse.OptionParser("usage: %prog [options] [testname]")
parser.add_option("-b", "--board", dest="board", default="bds",
help="board to use")
parser.add_option("-i", "--image", dest="image",
help="firmware image filename")
parser.add_option("-r", "--rom", dest="romcode",
default=os.path.join(basedir,"util","rom_lm4fs1ge5bb.bin"),
help="ROM code image filename")
parser.add_option("-q", "--qemu", dest="qemu_bin",
default=os.path.join(basedir,"util",QEMU_BINARY),
help="Qemu binary path")
(options, args) = parser.parse_args()
if options.image:
image = options.image
else:
image = os.path.join(basedir,"build",options.board,"ec.bin")
return options.qemu_bin, image,options.romcode, args
if __name__ == '__main__':
basedir = os.path.abspath(os.path.join(os.path.dirname(__file__),".."))
qemu_bin, image, romcode, tests = parse_cmdline(basedir)
if len(tests) > 0:
res = EcTest(qemu_bin, image, romcode, tests[0]).run_test()
else:
res = run_interactive(qemu_bin, image, romcode)
sys.exit(res)