summaryrefslogtreecommitdiff
path: root/chip/lm4
diff options
context:
space:
mode:
Diffstat (limited to 'chip/lm4')
-rw-r--r--chip/lm4/atomic.h65
-rw-r--r--chip/lm4/build.mk10
-rw-r--r--chip/lm4/clock.c199
-rw-r--r--chip/lm4/config.h19
-rw-r--r--chip/lm4/ec.lds.S45
-rw-r--r--chip/lm4/init.S250
-rw-r--r--chip/lm4/panic.S111
-rw-r--r--chip/lm4/switch.S63
-rw-r--r--chip/lm4/task.c341
-rw-r--r--chip/lm4/timer.c279
-rw-r--r--chip/lm4/watchdog.c132
-rw-r--r--chip/lm4/watchdog.h21
12 files changed, 1535 insertions, 0 deletions
diff --git a/chip/lm4/atomic.h b/chip/lm4/atomic.h
new file mode 100644
index 0000000000..a6fff4be08
--- /dev/null
+++ b/chip/lm4/atomic.h
@@ -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 */
diff --git a/chip/lm4/build.mk b/chip/lm4/build.mk
new file mode 100644
index 0000000000..49356d2959
--- /dev/null
+++ b/chip/lm4/build.mk
@@ -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
diff --git a/chip/lm4/clock.c b/chip/lm4/clock.c
new file mode 100644
index 0000000000..b9f739d703
--- /dev/null
+++ b/chip/lm4/clock.c
@@ -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;
+}
diff --git a/chip/lm4/config.h b/chip/lm4/config.h
new file mode 100644
index 0000000000..0c2abd416a
--- /dev/null
+++ b/chip/lm4/config.h
@@ -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
diff --git a/chip/lm4/ec.lds.S b/chip/lm4/ec.lds.S
new file mode 100644
index 0000000000..17fbfcf0b9
--- /dev/null
+++ b/chip/lm4/ec.lds.S
@@ -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.*) }
+}
diff --git a/chip/lm4/init.S b/chip/lm4/init.S
new file mode 100644
index 0000000000..4d58cae563
--- /dev/null
+++ b/chip/lm4/init.S
@@ -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
+
diff --git a/chip/lm4/panic.S b/chip/lm4/panic.S
new file mode 100644
index 0000000000..4c87cac511
--- /dev/null
+++ b/chip/lm4/panic.S
@@ -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 */
diff --git a/chip/lm4/switch.S b/chip/lm4/switch.S
new file mode 100644
index 0000000000..4d974251cd
--- /dev/null
+++ b/chip/lm4/switch.S
@@ -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
+
diff --git a/chip/lm4/task.c b/chip/lm4/task.c
new file mode 100644
index 0000000000..5c4ee8780c
--- /dev/null
+++ b/chip/lm4/task.c
@@ -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;
+}
diff --git a/chip/lm4/timer.c b/chip/lm4/timer.c
new file mode 100644
index 0000000000..597c61da95
--- /dev/null
+++ b/chip/lm4/timer.c
@@ -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;
+}
diff --git a/chip/lm4/watchdog.c b/chip/lm4/watchdog.c
new file mode 100644
index 0000000000..d42716abf5
--- /dev/null
+++ b/chip/lm4/watchdog.c
@@ -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;
+}
diff --git a/chip/lm4/watchdog.h b/chip/lm4/watchdog.h
new file mode 100644
index 0000000000..75a5e0b4a5
--- /dev/null
+++ b/chip/lm4/watchdog.h
@@ -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 */