summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorBill Richardson <wfrichar@chromium.org>2014-10-07 13:18:19 -0700
committerchrome-internal-fetch <chrome-internal-fetch@google.com>2014-10-31 22:32:50 +0000
commit86c7e2e90a7fd86b5f5b9e422fdbe968d30670da (patch)
tree366820de9e95fec03b142651dc3961ee9482f430
parent327bfe2e587b0e2e127ac9659bec6f7bb7a310ed (diff)
downloadchrome-ec-86c7e2e90a7fd86b5f5b9e422fdbe968d30670da.tar.gz
Add initial support for cr50 SoC
The serial console works. Nothing else is implemented yet. BUG=none BRANCH=ToT TEST=make buildall -j To build, make BOARD=cr50 hex Testing the result requires a development board. I have one. It works with HW revision m3.dist_20140918_094011 Change-Id: I718d93572d315d13e96ef6f296c3c2796e928e66 Signed-off-by: Bill Richardson <wfrichar@chromium.org> Reviewed-on: https://chromium-review.googlesource.com/226268 Reviewed-by: Randall Spangler <rspangler@chromium.org> Reviewed-by: Vincent Palatin <vpalatin@chromium.org>
-rw-r--r--Makefile.rules7
l---------board/cr50/Makefile1
-rw-r--r--board/cr50/board.c20
-rw-r--r--board/cr50/board.h34
-rw-r--r--board/cr50/build.mk10
-rw-r--r--board/cr50/ec.tasklist21
-rw-r--r--board/cr50/gpio.inc16
-rw-r--r--chip/g/build.mk11
-rw-r--r--chip/g/clock.c331
-rw-r--r--chip/g/config_chip.h50
-rw-r--r--chip/g/config_std_flash.h42
-rw-r--r--chip/g/gpio.c28
-rw-r--r--chip/g/hwtimer.c24
-rw-r--r--chip/g/jtag.c9
-rw-r--r--chip/g/registers.h219
-rw-r--r--chip/g/system.c45
-rw-r--r--chip/g/uart.c168
17 files changed, 1036 insertions, 0 deletions
diff --git a/Makefile.rules b/Makefile.rules
index 4a19e0a3b3..205c89a983 100644
--- a/Makefile.rules
+++ b/Makefile.rules
@@ -41,6 +41,7 @@ cmd_flat_to_obj = $(CC) -T $(out)/firmware_image.lds -nostdlib $(CPPFLAGS) \
-Wl,--build-id=none -o $@ $<
cmd_elf_to_flat = $(OBJCOPY) -O binary $^ $@
cmd_elf_to_dis = $(OBJDUMP) -D $< > $@
+cmd_elf_to_hex = $(OBJCOPY) -O ihex $^ $@
cmd_elf = $(LD) $(objs) $(LDFLAGS) -o $@ -T $< -Map $(out)/$*.map
cmd_exe = $(CC) $(objs) $(HOST_TEST_LDFLAGS) -o $@
cmd_c_to_o = $(CC) $(CFLAGS) -MMD -MF $@.d -c $< -o $@
@@ -81,6 +82,9 @@ proj-%:
dis-y = $(out)/$(PROJECT).RO.dis $(out)/$(PROJECT).RW.dis
dis: $(dis-y)
+hex-y = $(out)/$(PROJECT).RO.hex $(out)/$(PROJECT).RW.hex
+hex: $(hex-y)
+
utils: $(build-utils) $(host-utils)
# On board test binaries
@@ -157,6 +161,9 @@ $(out)/%.dis: $(out)/%.elf
$(out)/%.flat: $(out)/%.elf
$(call quiet,elf_to_flat,OBJCOPY)
+$(out)/%.hex: $(out)/%.elf
+ $(call quiet,elf_to_hex,OBJCOPY)
+
$(out)/%.elf: $(out)/%.lds $(objs)
$(call quiet,elf,LD )
diff --git a/board/cr50/Makefile b/board/cr50/Makefile
new file mode 120000
index 0000000000..94aaae2c4d
--- /dev/null
+++ b/board/cr50/Makefile
@@ -0,0 +1 @@
+../../Makefile \ No newline at end of file
diff --git a/board/cr50/board.c b/board/cr50/board.c
new file mode 100644
index 0000000000..4c99befe58
--- /dev/null
+++ b/board/cr50/board.c
@@ -0,0 +1,20 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#include "common.h"
+#include "gpio.h"
+#include "hooks.h"
+#include "task.h"
+#include "util.h"
+
+#include "gpio_list.h"
+
+/* Initialize board. */
+static void board_init(void)
+{
+ /* TODO(crosbug.com/p/33432): Try enabling this */
+ /* gpio_enable_interrupt(GPIO_CAMO0_BREACH_INT); */
+}
+DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_DEFAULT);
diff --git a/board/cr50/board.h b/board/cr50/board.h
new file mode 100644
index 0000000000..ab82f50a8c
--- /dev/null
+++ b/board/cr50/board.h
@@ -0,0 +1,34 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef __BOARD_H
+#define __BOARD_H
+
+/* Features that we don't want just yet */
+#undef CONFIG_CMD_LID_ANGLE
+#undef CONFIG_CMD_POWERINDEBUG
+#undef CONFIG_DMA_DEFAULT_HANDLERS
+#undef CONFIG_FLASH
+#undef CONFIG_FMAP
+#undef CONFIG_HIBERNATE
+#undef CONFIG_LID_SWITCH
+#undef CONFIG_WATCHDOG
+
+/* How do I identify nonexistant GPIOs? */
+#define DUMMY_GPIO_BANK -1
+
+/*
+ * Allow dangerous commands all the time, since we don't have a write protect
+ * switch.
+ */
+#define CONFIG_SYSTEM_UNLOCKED
+
+#ifndef __ASSEMBLER__
+
+#include "gpio_signal.h"
+
+#endif /* !__ASSEMBLER__ */
+
+#endif /* __BOARD_H */
diff --git a/board/cr50/build.mk b/board/cr50/build.mk
new file mode 100644
index 0000000000..7cb1215adb
--- /dev/null
+++ b/board/cr50/build.mk
@@ -0,0 +1,10 @@
+# -*- makefile -*-
+# Copyright (c) 2014 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.
+#
+# Board specific files build
+
+CHIP:=g
+
+board-y=board.o
diff --git a/board/cr50/ec.tasklist b/board/cr50/ec.tasklist
new file mode 100644
index 0000000000..8ff4e8234b
--- /dev/null
+++ b/board/cr50/ec.tasklist
@@ -0,0 +1,21 @@
+/* Copyright (c) 2014 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_ALWAYS(n, r, d, s) for base tasks and
+ * TASK_NOTEST(n, r, d, s) for tasks that can be excluded in test binaries,
+ * 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
+ * 's' is the stack size in bytes; must be a multiple of 8
+ */
+#define CONFIG_TASK_LIST \
+ TASK_ALWAYS(HOOKS, hook_task, NULL, TASK_STACK_SIZE) \
+ TASK_ALWAYS(CONSOLE, console_task, NULL, TASK_STACK_SIZE)
diff --git a/board/cr50/gpio.inc b/board/cr50/gpio.inc
new file mode 100644
index 0000000000..c6036a02f8
--- /dev/null
+++ b/board/cr50/gpio.inc
@@ -0,0 +1,16 @@
+/*
+ * Copyright (c) 2014 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.
+ */
+
+/* Inputs with interrupt handlers are first for efficiency */
+/* TODO(crosbug.com/p/33432): try enabling this */
+/* GPIO(CAMO0_BREACH_INT, A, 0, GPIO_INT_BOTH, button_event) */
+
+/* Outputs */
+
+/* Unimplemented signals which we need to emulate for now */
+UNIMPLEMENTED(ENTERING_RW)
+
+/* Alternate functions */
diff --git a/chip/g/build.mk b/chip/g/build.mk
new file mode 100644
index 0000000000..5263c412f2
--- /dev/null
+++ b/chip/g/build.mk
@@ -0,0 +1,11 @@
+# -*- makefile -*-
+# Copyright (c) 2014 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.
+#
+
+CORE:=cortex-m
+CFLAGS_CPU+=-march=armv7-m -mcpu=cortex-m3
+
+# Required chip modules
+chip-y=clock.o gpio.o hwtimer.o jtag.o system.o uart.o
diff --git a/chip/g/clock.c b/chip/g/clock.c
new file mode 100644
index 0000000000..691cf8ccb0
--- /dev/null
+++ b/chip/g/clock.c
@@ -0,0 +1,331 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#include "clock.h"
+#include "registers.h"
+
+/* Clock initialization taken from some example code */
+
+#define RESOLUTION 12
+#define LOAD_VAL (0x1 << 11)
+#define MAX_TRIM (7*16)
+
+static void switch_osc_to_xtl(void);
+
+static void clock_on_xo0(void)
+{
+ /* turn on xo0 clock */
+ /* don't know which control word it might be in */
+#ifdef G_PMU_PERICLKSET0_DXO0_LSB
+ G_PMU_PERICLKSET0 = (1 << G_PMU_PERICLKSET0_DXO0_LSB);
+#endif
+
+#ifdef G_PMU_PERICLKSET1_DXO0_LSB
+ G_PMU_PERICLKSET1 = (1 << G_PMU_PERICLKSET1_DXO0_LSB);
+#endif
+}
+
+/* Converts an integer setting to the RC trim code format (7, 4-bit values) */
+static unsigned val_to_trim_code(unsigned val)
+{
+ unsigned base = val / 7;
+ unsigned mod = val % 7;
+ unsigned code = 0x0;
+ int digit;
+
+ /* Increasing count from right to left */
+ for (digit = 0; digit < 7; digit++) {
+ /* Check for mod */
+ if (digit <= mod)
+ code |= ((base & 0xF) << 4 * digit);
+ else
+ code |= (((base - 1) & 0xF) << 4 * digit);
+ }
+
+ return code;
+}
+
+static unsigned calib_rc_trim(void)
+{
+ unsigned size, iter;
+ signed mid;
+ signed diff;
+
+ /* Switch to crystal for calibration. This should work since we are
+ * technically on an uncalibrated RC trim clock. */
+ switch_osc_to_xtl();
+
+ clock_on_xo0();
+
+ /* Clear the HOLD signal on dxo */
+ G_XO_OSC_CLRHOLD = G_XO_OSC_CLRHOLD_RC_TRIM_MASK;
+
+ /* Reset RC calibration counters */
+ G_XO_OSC_RC_CAL_RSTB = 0x0;
+ G_XO_OSC_RC_CAL_RSTB = 0x1;
+
+ /* Write the LOAD val */
+ G_XO_OSC_RC_CAL_LOAD = LOAD_VAL;
+
+ /* Begin binary search */
+ mid = 0;
+ size = MAX_TRIM / 2;
+ for (iter = 0; iter <= 7; iter++) {
+ /* Set the trim value */
+ G_XO_OSC_RC = val_to_trim_code(mid) << G_XO_OSC_RC_TRIM_LSB;
+
+ /* Do a calibration */
+ G_XO_OSC_RC_CAL_START = 0x1;
+
+ /* NOTE: There is a small race condition because of the delay
+ * in dregfile. The start doesn't actually appear for 2 clock
+ * cycles after the write. So, poll until done goes low. */
+ while (G_XO_OSC_RC_CAL_DONE)
+ ;
+
+ /* Wait until it's done */
+ while (!G_XO_OSC_RC_CAL_DONE)
+ ;
+
+ /* Check the counter value */
+ diff = LOAD_VAL - G_XO_OSC_RC_CAL_COUNT;
+
+ /* Test to see whether we are still outside of our desired
+ * resolution */
+ if ((diff < -RESOLUTION) || (diff > RESOLUTION))
+ mid = (diff > 0) ? (mid - size / 2) : (mid + size / 2);
+
+ size = (size + 1) >> 1; /* round up before division */
+ }
+
+ /* Set the final trim value */
+ G_XO_OSC_RC = (val_to_trim_code(mid) << G_XO_OSC_RC_TRIM_LSB) |
+ (0x1 << G_XO_OSC_RC_EN_LSB);
+
+ /* Set the HOLD signal on dxo */
+ G_XO_OSC_SETHOLD = G_XO_OSC_SETHOLD_RC_TRIM_MASK;
+
+ /* Switch back to the RC trim now that we are calibrated */
+ G_PMU_OSC_HOLD_CLR = 0x1; /* make sure the hold signal is clear */
+ G_PMU_OSC_SELECT = G_PMU_OSC_SELECT_RC_TRIM;
+ /* Make sure the hold signal is set for future power downs */
+ G_PMU_OSC_HOLD_SET = 0x1;
+
+ return mid;
+}
+
+static void switch_osc_to_rc_trim(void)
+{
+ unsigned trimmed;
+ unsigned saved_trim, fuse_trim, default_trim;
+ unsigned trim_code;
+
+ /* check which clock we are running on */
+ unsigned osc_sel = G_PMU_OSC_SELECT_STAT;
+
+ if (osc_sel == G_PMU_OSC_SELECT_RC_TRIM) {
+ /* already using the rc_trim so nothing to do here */
+ /* make sure the hold signal is set for future power downs */
+ G_PMU_OSC_HOLD_SET = 0x1;
+ return;
+ }
+
+ /* Turn on DXO clock so we can write in the trim code in */
+ clock_on_xo0();
+
+ /* disable the RC_TRIM Clock */
+ REG_WRITE_MASK(G_PMU_OSC_CTRL,
+ G_PMU_OSC_CTRL_RC_TRIM_READYB_MASK, 0x1,
+ G_PMU_OSC_CTRL_RC_TRIM_READYB_LSB);
+
+ /* power up the clock if not already powered up */
+ G_PMU_CLRDIS = 1 << G_PMU_SETDIS_RC_TRIM_LSB;
+
+ /* Try to find the trim code */
+ saved_trim = G_XO_OSC_RC_STATUS;
+ fuse_trim = G_PMU_FUSE_RD_RC_OSC_26MHZ;
+ default_trim = G_XO_OSC_RC;
+
+ /* Check for the trim code in the always-on domain before looking at
+ * the fuse */
+ if (saved_trim & G_XO_OSC_RC_STATUS_EN_MASK) {
+ trim_code = (saved_trim & G_XO_OSC_RC_STATUS_TRIM_MASK)
+ >> G_XO_OSC_RC_STATUS_TRIM_LSB;
+ trimmed = 1;
+ } else if (fuse_trim & G_PMU_FUSE_RD_RC_OSC_26MHZ_EN_MASK) {
+ trim_code = (fuse_trim & G_PMU_FUSE_RD_RC_OSC_26MHZ_TRIM_MASK)
+ >> G_PMU_FUSE_RD_RC_OSC_26MHZ_TRIM_LSB;
+ trimmed = 1;
+ } else {
+ trim_code = (default_trim & G_XO_OSC_RC_TRIM_MASK)
+ >> G_XO_OSC_RC_TRIM_LSB;
+ trimmed = 0;
+ }
+
+ /* Write the trim code to dxo */
+ if (trimmed) {
+ /* clear the hold signal */
+ G_XO_OSC_CLRHOLD = 1 << G_XO_OSC_CLRHOLD_RC_TRIM_LSB;
+ G_XO_OSC_RC = (trim_code << G_XO_OSC_RC_TRIM_LSB) | /* write */
+ ((trimmed & 0x1) << G_XO_OSC_RC_EN_LSB); /* enable */
+ /* set the hold signal */
+ G_XO_OSC_SETHOLD = 1 << G_XO_OSC_SETHOLD_RC_TRIM_LSB;
+ }
+
+ /* enable the RC_TRIM Clock */
+ REG_WRITE_MASK(G_PMU_OSC_CTRL, G_PMU_OSC_CTRL_RC_TRIM_READYB_MASK,
+ 0x0, G_PMU_OSC_CTRL_RC_TRIM_READYB_LSB);
+
+ /* Switch the select signal */
+ G_PMU_OSC_HOLD_CLR = 0x1; /* make sure the hold signal is clear */
+ G_PMU_OSC_SELECT = G_PMU_OSC_SELECT_RC_TRIM;
+ /* make sure the hold signal is set for future power downs */
+ G_PMU_OSC_HOLD_SET = 0x1;
+
+ /* If we didn't find a valid trim code, then we need to calibrate */
+ if (!trimmed)
+ calib_rc_trim();
+ /* We saved the trim code and went back to the RC trim inside
+ * calib_rc_trim */
+}
+
+static void switch_osc_to_xtl(void)
+{
+ unsigned int saved_trim, fuse_trim, trim_code, final_trim;
+ unsigned int fsm_status, max_trim;
+ unsigned int fsm_done;
+ /* check which clock we are running on */
+ unsigned int osc_sel = G_PMU_OSC_SELECT_STAT;
+
+ if (osc_sel == G_PMU_OSC_SELECT_XTL) {
+ /* already using the crystal so nothing to do here */
+ /* make sure the hold signal is set for future power downs */
+ G_PMU_OSC_HOLD_SET = 0x1;
+ return;
+ }
+
+ if (osc_sel == G_PMU_OSC_SELECT_RC)
+ /* RC untrimmed clock. We must go through the trimmed clock
+ * first to avoid glitching */
+ switch_osc_to_rc_trim();
+
+ /* disable the XTL Clock */
+ REG_WRITE_MASK(G_PMU_OSC_CTRL, G_PMU_OSC_CTRL_XTL_READYB_MASK,
+ 0x1, G_PMU_OSC_CTRL_XTL_READYB_LSB);
+
+ /* power up the clock if not already powered up */
+ G_PMU_CLRDIS = 1 << G_PMU_SETDIS_XTL_LSB;
+
+ /* Try to find the trim code */
+ trim_code = 0;
+ saved_trim = G_XO_OSC_XTL_TRIM_STAT;
+ fuse_trim = G_PMU_FUSE_RD_XTL_OSC_26MHZ;
+
+ /* Check for the trim code in the always-on domain before looking at
+ * the fuse */
+ if (saved_trim & G_XO_OSC_XTL_TRIM_STAT_EN_MASK) {
+ /* nothing to do */
+ /* trim_code = (saved_trim & G_XO_OSC_XTL_TRIM_STAT_CODE_MASK)
+ >> G_XO_OSC_XTL_TRIM_STAT_CODE_LSB; */
+ /* print_trickbox_message("XTL TRIM CODE FOUND IN 3P3"); */
+ } else if (fuse_trim & G_PMU_FUSE_RD_XTL_OSC_26MHZ_EN_MASK) {
+ /* push the fuse trim code as the saved trim code */
+ /* print_trickbox_message("XTL TRIM CODE FOUND IN FUSE"); */
+ trim_code = (fuse_trim & G_PMU_FUSE_RD_XTL_OSC_26MHZ_TRIM_MASK)
+ >> G_PMU_FUSE_RD_XTL_OSC_26MHZ_TRIM_LSB;
+ /* make sure the hold signal is clear */
+ G_XO_OSC_CLRHOLD = 0x1 << G_XO_OSC_CLRHOLD_XTL_LSB;
+ G_XO_OSC_XTL_TRIM =
+ (trim_code << G_XO_OSC_XTL_TRIM_CODE_LSB) |
+ (0x1 << G_XO_OSC_XTL_TRIM_EN_LSB);
+ } else
+ /* print_trickbox_message("XTL TRIM CODE NOT FOUND"); */
+ ;
+
+ /* Run the crystal FSM to calibrate the crystal trim */
+ fsm_done = G_XO_OSC_XTL_FSM;
+ if (fsm_done & G_XO_OSC_XTL_FSM_DONE_MASK) {
+ /* If FSM done is high, it means we already ran it so let's not
+ * run it again */
+ /* DO NOTHING */
+ } else {
+ G_XO_OSC_XTL_FSM_EN = 0x0; /* reset FSM */
+ G_XO_OSC_XTL_FSM_EN = G_XO_OSC_XTL_FSM_EN_KEY;
+ while (!(fsm_done & G_XO_OSC_XTL_FSM_DONE_MASK))
+ fsm_done = G_XO_OSC_XTL_FSM;
+ }
+
+ /* Check the status and final trim value */
+ max_trim = (G_XO_OSC_XTL_FSM_CFG & G_XO_OSC_XTL_FSM_CFG_TRIM_MAX_MASK)
+ >> G_XO_OSC_XTL_FSM_CFG_TRIM_MAX_LSB;
+ final_trim = (fsm_done & G_XO_OSC_XTL_FSM_TRIM_MASK)
+ >> G_XO_OSC_XTL_FSM_TRIM_LSB;
+ fsm_status = (fsm_done & G_XO_OSC_XTL_FSM_STATUS_MASK)
+ >> G_XO_OSC_XTL_FSM_STATUS_LSB;
+
+ /* Check status bit and trim value */
+ if (fsm_status) {
+ if (final_trim >= max_trim)
+ /* print_trickbox_error("ERROR: XTL FSM status was
+ high, but final XTL trim is greater than or equal to
+ max trim"); */
+ ;
+ } else {
+ if (final_trim != max_trim)
+ /* print_trickbox_error("ERROR: XTL FSM status was low,
+ but final XTL trim does not equal max trim"); */
+ ;
+ }
+
+ /* save the trim for future powerups */
+ /* make sure the hold signal is clear (may have already been cleared) */
+ G_XO_OSC_CLRHOLD = 0x1 << G_XO_OSC_CLRHOLD_XTL_LSB;
+ G_XO_OSC_XTL_TRIM =
+ (final_trim << G_XO_OSC_XTL_TRIM_CODE_LSB) |
+ (0x1 << G_XO_OSC_XTL_TRIM_EN_LSB);
+ /* make sure the hold signal is set for future power downs */
+ G_XO_OSC_SETHOLD = 0x1 << G_XO_OSC_SETHOLD_XTL_LSB;
+
+ /* enable the XTL Clock */
+ REG_WRITE_MASK(G_PMU_OSC_CTRL, G_PMU_OSC_CTRL_XTL_READYB_MASK,
+ 0x0, G_PMU_OSC_CTRL_XTL_READYB_LSB);
+
+ /* Switch the select signal */
+ G_PMU_OSC_HOLD_CLR = 0x1; /* make sure the hold signal is clear */
+ G_PMU_OSC_SELECT = G_PMU_OSC_SELECT_XTL;
+ /* make sure the hold signal is set for future power downs */
+ G_PMU_OSC_HOLD_SET = 0x1;
+}
+
+void clock_init(void)
+{
+ /*
+ * TODO(crosbug.com/p/33432): The following comment was in the example
+ * code, but the function that's called doesn't match what it says.
+ * Investigate further.
+ */
+
+ /* Switch to crystal clock since RC clock not accurate enough */
+ switch_osc_to_rc_trim();
+}
+
+void clock_enable_module(enum module_id module, int enable)
+{
+ if (module != MODULE_UART)
+ return;
+
+ /* don't know which control word it might be in */
+#ifdef G_PMU_PERICLKSET0_DUART0_LSB
+ REG_WRITE_MASK(G_PMU_PERICLKSET0,
+ 1 << G_PMU_PERICLKSET0_DUART0_LSB, enable,
+ G_PMU_PERICLKSET0_DUART0_LSB);
+#endif
+
+#ifdef G_PMU_PERICLKSET1_DUART0_LSB
+ REG_WRITE_MASK(G_PMU_PERICLKSET1,
+ 1 << G_PMU_PERICLKSET1_DUART0_LSB, enable,
+ G_PMU_PERICLKSET0_DUART1_LSB);
+#endif
+}
diff --git a/chip/g/config_chip.h b/chip/g/config_chip.h
new file mode 100644
index 0000000000..b121638986
--- /dev/null
+++ b/chip/g/config_chip.h
@@ -0,0 +1,50 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef __CROS_EC_CONFIG_CHIP_H
+#define __CROS_EC_CONFIG_CHIP_H
+
+#include "core/cortex-m/config_core.h"
+
+/* Number of IRQ vectors on the NVIC */
+#define CONFIG_IRQ_COUNT 93
+
+/* Describe the RAM layout */
+#define CONFIG_RAM_BASE 0x10000
+#define CONFIG_RAM_SIZE 0x8000
+
+/* Describe the flash layout */
+#define CONFIG_FLASH_BASE 0x40000
+#define CONFIG_FLASH_PHYSICAL_SIZE (512 * 1024)
+/* flash chip specifics */
+/* TODO(crosbug.com/p/33432): These are probably wrong. Don't use them yet. */
+#define CONFIG_FLASH_BANK_SIZE 0x00000800 /* protect bank size */
+#define CONFIG_FLASH_ERASE_SIZE 0x00000400 /* erase bank size */
+#define CONFIG_FLASH_WRITE_SIZE 0x00000004 /* minimum write size */
+/* Size of one firmware image in flash */
+#define CONFIG_FW_IMAGE_SIZE (128 * 1024)
+/* Compute the rest of the flash params from these */
+#include "config_std_flash.h"
+
+/* Interval between HOOK_TICK notifications */
+#define HOOK_TICK_INTERVAL_MS 500
+#define HOOK_TICK_INTERVAL (HOOK_TICK_INTERVAL_MS * MSEC)
+
+/* System stack size */
+#define CONFIG_STACK_SIZE 1024
+
+/* Idle task stack size */
+#define IDLE_TASK_STACK_SIZE 256
+
+/* Default task stack size */
+#define TASK_STACK_SIZE 488
+
+/* Larger task stack size, for hook task */
+#define LARGER_TASK_STACK_SIZE 640
+
+/* Maximum number of deferrable functions */
+#define DEFERRABLE_MAX_COUNT 8
+
+#endif /* __CROS_EC_CONFIG_CHIP_H */
diff --git a/chip/g/config_std_flash.h b/chip/g/config_std_flash.h
new file mode 100644
index 0000000000..a123b6cccc
--- /dev/null
+++ b/chip/g/config_std_flash.h
@@ -0,0 +1,42 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef __CROS_EC_CONFIG_STD_FLASH_H
+#define __CROS_EC_CONFIG_STD_FLASH_H
+
+/* RO firmware must start at beginning of flash */
+#define CONFIG_FW_RO_OFF 0
+
+/*
+ * The EC uses the one bank of flash to emulate a SPI-like write protect
+ * register with persistent state.
+ */
+#define CONFIG_FW_PSTATE_SIZE CONFIG_FLASH_BANK_SIZE
+
+#ifdef CONFIG_PSTATE_AT_END
+/* PSTATE is at end of flash */
+#define CONFIG_FW_RO_SIZE CONFIG_FW_IMAGE_SIZE
+#define CONFIG_FW_PSTATE_OFF (CONFIG_FLASH_PHYSICAL_SIZE \
+ - CONFIG_FW_PSTATE_SIZE)
+/* Don't claim PSTATE is part of flash */
+#define CONFIG_FLASH_SIZE CONFIG_FW_PSTATE_OFF
+
+#else
+/* PSTATE immediately follows RO, in the first half of flash */
+#define CONFIG_FW_RO_SIZE (CONFIG_FW_IMAGE_SIZE \
+ - CONFIG_FW_PSTATE_SIZE)
+#define CONFIG_FW_PSTATE_OFF CONFIG_FW_RO_SIZE
+#define CONFIG_FLASH_SIZE CONFIG_FLASH_PHYSICAL_SIZE
+#endif
+
+/* Either way, RW firmware is one firmware image offset from the start */
+#define CONFIG_FW_RW_OFF CONFIG_FW_IMAGE_SIZE
+#define CONFIG_FW_RW_SIZE CONFIG_FW_IMAGE_SIZE
+
+/* TODO(crosbug.com/p/23796): why 2 sets of configs with the same numbers? */
+#define CONFIG_FW_WP_RO_OFF CONFIG_FW_RO_OFF
+#define CONFIG_FW_WP_RO_SIZE CONFIG_FW_RO_SIZE
+
+#endif /* __CROS_EC_CONFIG_STD_FLASH_H */
diff --git a/chip/g/gpio.c b/chip/g/gpio.c
new file mode 100644
index 0000000000..59d8d4fd4b
--- /dev/null
+++ b/chip/g/gpio.c
@@ -0,0 +1,28 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#include "common.h"
+#include "gpio.h"
+#include "hooks.h"
+
+/* TODO(crosbug.com/p/33432): We don't have any GPIOs defined yet! */
+
+test_mockable int gpio_get_level(enum gpio_signal signal)
+{
+ return 0;
+}
+
+void gpio_set_level(enum gpio_signal signal, int value)
+{
+}
+
+void gpio_pre_init(void)
+{
+}
+
+static void gpio_init(void)
+{
+}
+DECLARE_HOOK(HOOK_INIT, gpio_init, HOOK_PRIO_DEFAULT);
diff --git a/chip/g/hwtimer.c b/chip/g/hwtimer.c
new file mode 100644
index 0000000000..ec9750db0a
--- /dev/null
+++ b/chip/g/hwtimer.c
@@ -0,0 +1,24 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#include "common.h"
+#include "hwtimer.h"
+
+/* TODO(crosbug.com/p/33432): Implement these functions */
+
+uint32_t __hw_clock_event_get(void)
+{
+ return 0;
+}
+
+uint32_t __hw_clock_source_read(void)
+{
+ return 0;
+}
+
+int __hw_clock_source_init(uint32_t start_t)
+{
+ return 0;
+}
diff --git a/chip/g/jtag.c b/chip/g/jtag.c
new file mode 100644
index 0000000000..b80bca1b8d
--- /dev/null
+++ b/chip/g/jtag.c
@@ -0,0 +1,9 @@
+/* Copyright (c) 2014 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.
+ */
+
+void jtag_pre_init(void)
+{
+ /* I don't think we need this to do anything */
+}
diff --git a/chip/g/registers.h b/chip/g/registers.h
new file mode 100644
index 0000000000..a45d94914d
--- /dev/null
+++ b/chip/g/registers.h
@@ -0,0 +1,219 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#ifndef __CROS_EC_REGISTERS_H
+#define __CROS_EC_REGISTERS_H
+
+#include "common.h"
+
+
+/* Replace masked bits with val << lsb */
+#define REG_WRITE_MASK(reg, mask, val, lsb) \
+ reg = ((reg & ~mask) | ((val << lsb) & mask))
+
+/* Revision */
+#define G_REVISION_STR "A1"
+
+#define G_PINMUX_BASE_ADDR 0x40060000
+#define G_PINMUX_DIOA0_SEL REG32(G_PINMUX_BASE_ADDR + 0x0028)
+#define G_PINMUX_DIOA0_CTL REG32(G_PINMUX_BASE_ADDR + 0x002c)
+#define G_PINMUX_DIOA1_CTL REG32(G_PINMUX_BASE_ADDR + 0x0034)
+#define G_PINMUX_UART0_RX_SEL REG32(G_PINMUX_BASE_ADDR + 0x02a8)
+
+#define G_PINMUX_DIOA0_CTL_IE_LSB 0x2
+#define G_PINMUX_DIOA0_CTL_IE_MASK 0x4
+#define G_PINMUX_DIOA1_CTL_IE_LSB 0x2
+#define G_PINMUX_DIOA1_CTL_IE_MASK 0x4
+#define G_PINMUX_DIOA1_SEL 0x7
+#define G_PINMUX_UART0_TX_SEL 0x40
+
+
+#define G_PMU_BASE_ADDR 0x40000000
+#define G_PMU_CLRDIS REG32(G_PMU_BASE_ADDR + 0x0018)
+#define G_PMU_OSC_HOLD_SET REG32(G_PMU_BASE_ADDR + 0x0080)
+#define G_PMU_OSC_HOLD_CLR REG32(G_PMU_BASE_ADDR + 0x0084)
+#define G_PMU_OSC_SELECT REG32(G_PMU_BASE_ADDR + 0x0088)
+#define G_PMU_OSC_SELECT_STAT REG32(G_PMU_BASE_ADDR + 0x008c)
+#define G_PMU_OSC_CTRL REG32(G_PMU_BASE_ADDR + 0x0090)
+#define G_PMU_PERICLKSET0 REG32(G_PMU_BASE_ADDR + 0x009c)
+#define G_PMU_FUSE_RD_RC_OSC_26MHZ REG32(G_PMU_BASE_ADDR + 0x011c)
+#define G_PMU_FUSE_RD_XTL_OSC_26MHZ REG32(G_PMU_BASE_ADDR + 0x0124)
+
+#define G_PMU_FUSE_RD_RC_OSC_26MHZ_EN_MASK 0x10000000
+#define G_PMU_FUSE_RD_RC_OSC_26MHZ_TRIM_LSB 0x0
+#define G_PMU_FUSE_RD_RC_OSC_26MHZ_TRIM_MASK 0xfffffff
+#define G_PMU_FUSE_RD_XTL_OSC_26MHZ_EN_MASK 0x10
+#define G_PMU_FUSE_RD_XTL_OSC_26MHZ_TRIM_LSB 0x0
+#define G_PMU_FUSE_RD_XTL_OSC_26MHZ_TRIM_MASK 0xf
+#define G_PMU_OSC_CTRL_RC_TRIM_READYB_LSB 0x1
+#define G_PMU_OSC_CTRL_RC_TRIM_READYB_MASK 0x2
+#define G_PMU_OSC_CTRL_XTL_READYB_LSB 0x0
+#define G_PMU_OSC_CTRL_XTL_READYB_MASK 0x1
+#define G_PMU_OSC_SELECT_RC 0x3
+#define G_PMU_OSC_SELECT_RC_TRIM 0x2
+#define G_PMU_OSC_SELECT_XTL 0x0
+#define G_PMU_PERICLKSET0_DXO0_LSB 0x18
+#define G_PMU_PERICLKSET0_DUART0_LSB 0x14
+#define G_PMU_SETDIS_RC_TRIM_LSB 0xf
+#define G_PMU_SETDIS_XTL_LSB 0xe
+
+
+/* More than one UART */
+#define G_UART0_BASE_ADDR 0x40540000
+#define G_UART1_BASE_ADDR 0x40550000
+#define G_UART2_BASE_ADDR 0x40560000
+#define G_UART_BASE_ADDR_SEP 0x00010000
+static inline int g_uart_addr(int ch, int offset)
+{
+ return offset + G_UART0_BASE_ADDR + G_UART_BASE_ADDR_SEP * ch;
+}
+#define G_UARTREG(ch, offset) REG32(g_uart_addr(ch, offset))
+#define G_UART_RDATA(ch) G_UARTREG(ch, 0x0000)
+#define G_UART_WDATA(ch) G_UARTREG(ch, 0x0004)
+#define G_UART_NCO(ch) G_UARTREG(ch, 0x0008)
+#define G_UART_CTRL(ch) G_UARTREG(ch, 0x000c)
+#define G_UART_ICTRL(ch) G_UARTREG(ch, 0x0010)
+#define G_UART_STATE(ch) G_UARTREG(ch, 0x0014)
+#define G_UART_ISTATECLR(ch) G_UARTREG(ch, 0x0020)
+#define G_UART_FIFO(ch) G_UARTREG(ch, 0x0024)
+#define G_UART_RFIFO(ch) G_UARTREG(ch, 0x0028)
+
+#define G_XO0_BASE_ADDR 0x40420000
+#define G_XO_OSC_RC_CAL_RSTB REG32(G_XO0_BASE_ADDR + 0x0014)
+#define G_XO_OSC_RC_CAL_LOAD REG32(G_XO0_BASE_ADDR + 0x0018)
+#define G_XO_OSC_RC_CAL_START REG32(G_XO0_BASE_ADDR + 0x001c)
+#define G_XO_OSC_RC_CAL_DONE REG32(G_XO0_BASE_ADDR + 0x0020)
+#define G_XO_OSC_RC_CAL_COUNT REG32(G_XO0_BASE_ADDR + 0x0024)
+#define G_XO_OSC_RC REG32(G_XO0_BASE_ADDR + 0x0028)
+#define G_XO_OSC_RC_STATUS REG32(G_XO0_BASE_ADDR + 0x002c)
+#define G_XO_OSC_XTL_TRIM REG32(G_XO0_BASE_ADDR + 0x0048)
+#define G_XO_OSC_XTL_TRIM_STAT REG32(G_XO0_BASE_ADDR + 0x004c)
+#define G_XO_OSC_XTL_FSM_EN REG32(G_XO0_BASE_ADDR + 0x0050)
+#define G_XO_OSC_XTL_FSM REG32(G_XO0_BASE_ADDR + 0x0054)
+#define G_XO_OSC_XTL_FSM_CFG REG32(G_XO0_BASE_ADDR + 0x0058)
+#define G_XO_OSC_SETHOLD REG32(G_XO0_BASE_ADDR + 0x005c)
+#define G_XO_OSC_CLRHOLD REG32(G_XO0_BASE_ADDR + 0x0060)
+
+#define G_XO_OSC_CLRHOLD_RC_TRIM_LSB 0x0
+#define G_XO_OSC_CLRHOLD_RC_TRIM_MASK 0x1
+#define G_XO_OSC_CLRHOLD_XTL_LSB 0x1
+#define G_XO_OSC_RC_EN_LSB 0x1c
+#define G_XO_OSC_RC_STATUS_EN_MASK 0x10000000
+#define G_XO_OSC_RC_STATUS_TRIM_LSB 0x0
+#define G_XO_OSC_RC_STATUS_TRIM_MASK 0xfffffff
+#define G_XO_OSC_RC_TRIM_LSB 0x0
+#define G_XO_OSC_RC_TRIM_MASK 0xfffffff
+#define G_XO_OSC_SETHOLD_RC_TRIM_LSB 0x0
+#define G_XO_OSC_SETHOLD_RC_TRIM_MASK 0x1
+#define G_XO_OSC_SETHOLD_XTL_LSB 0x1
+#define G_XO_OSC_XTL_FSM_CFG_TRIM_MAX_LSB 0x0
+#define G_XO_OSC_XTL_FSM_CFG_TRIM_MAX_MASK 0xf
+#define G_XO_OSC_XTL_FSM_DONE_MASK 0x1
+#define G_XO_OSC_XTL_FSM_EN_KEY 0x60221413
+#define G_XO_OSC_XTL_FSM_STATUS_LSB 0x5
+#define G_XO_OSC_XTL_FSM_STATUS_MASK 0x20
+#define G_XO_OSC_XTL_FSM_TRIM_LSB 0x1
+#define G_XO_OSC_XTL_FSM_TRIM_MASK 0x1e
+#define G_XO_OSC_XTL_TRIM_CODE_LSB 0x0
+#define G_XO_OSC_XTL_TRIM_EN_LSB 0x4
+#define G_XO_OSC_XTL_TRIM_STAT_EN_MASK 0x10
+
+
+/* Interrupts */
+#define G_IRQNUM_CAMO0_BREACH_INT 0
+#define G_IRQNUM_FLASH0_EDONEINT 1
+#define G_IRQNUM_FLASH0_PDONEINT 2
+#define G_IRQNUM_GPIO0_GPIOCOMBINT 3
+#define G_IRQNUM_GPIO0_GPIO0INT 4
+#define G_IRQNUM_GPIO0_GPIO1INT 5
+#define G_IRQNUM_GPIO0_GPIO2INT 6
+#define G_IRQNUM_GPIO0_GPIO3INT 7
+#define G_IRQNUM_GPIO0_GPIO4INT 8
+#define G_IRQNUM_GPIO0_GPIO5INT 9
+#define G_IRQNUM_GPIO0_GPIO6INT 10
+#define G_IRQNUM_GPIO0_GPIO7INT 11
+#define G_IRQNUM_GPIO0_GPIO8INT 12
+#define G_IRQNUM_GPIO0_GPIO9INT 13
+#define G_IRQNUM_GPIO0_GPIO10INT 14
+#define G_IRQNUM_GPIO0_GPIO11INT 15
+#define G_IRQNUM_GPIO0_GPIO12INT 16
+#define G_IRQNUM_GPIO0_GPIO13INT 17
+#define G_IRQNUM_GPIO0_GPIO14INT 18
+#define G_IRQNUM_GPIO0_GPIO15INT 19
+#define G_IRQNUM_GPIO1_GPIOCOMBINT 20
+#define G_IRQNUM_GPIO1_GPIO0INT 21
+#define G_IRQNUM_GPIO1_GPIO1INT 22
+#define G_IRQNUM_GPIO1_GPIO2INT 23
+#define G_IRQNUM_GPIO1_GPIO3INT 24
+#define G_IRQNUM_GPIO1_GPIO4INT 25
+#define G_IRQNUM_GPIO1_GPIO5INT 26
+#define G_IRQNUM_GPIO1_GPIO6INT 27
+#define G_IRQNUM_GPIO1_GPIO7INT 28
+#define G_IRQNUM_GPIO1_GPIO8INT 29
+#define G_IRQNUM_GPIO1_GPIO9INT 30
+#define G_IRQNUM_GPIO1_GPIO10INT 31
+#define G_IRQNUM_GPIO1_GPIO11INT 32
+#define G_IRQNUM_GPIO1_GPIO12INT 33
+#define G_IRQNUM_GPIO1_GPIO13INT 34
+#define G_IRQNUM_GPIO1_GPIO14INT 35
+#define G_IRQNUM_GPIO1_GPIO15INT 36
+#define G_IRQNUM_I2C0_I2CINT 37
+#define G_IRQNUM_I2C1_I2CINT 38
+#define G_IRQNUM_PMU_PMUINT 39
+#define G_IRQNUM_SHA0_DSHA_INT 40
+#define G_IRQNUM_SPI0_SPITXINT 41
+#define G_IRQNUM_SPS0_CS_ASSERT_INTR 42
+#define G_IRQNUM_SPS0_CS_DEASSERT_INTR 43
+#define G_IRQNUM_SPS0_REGION0_BUF_LVL 44
+#define G_IRQNUM_SPS0_REGION1_BUF_LVL 45
+#define G_IRQNUM_SPS0_REGION2_BUF_LVL 46
+#define G_IRQNUM_SPS0_REGION3_BUF_LVL 47
+#define G_IRQNUM_SPS0_ROM_CMD_END 48
+#define G_IRQNUM_SPS0_ROM_CMD_START 49
+#define G_IRQNUM_SPS0_RXFIFO_LVL_INTR 50
+#define G_IRQNUM_SPS0_RXFIFO_OVERFLOW_INTR 51
+#define G_IRQNUM_SPS0_SPSCTRLINT0 52
+#define G_IRQNUM_SPS0_SPSCTRLINT1 53
+#define G_IRQNUM_SPS0_SPSCTRLINT2 54
+#define G_IRQNUM_SPS0_SPSCTRLINT3 55
+#define G_IRQNUM_SPS0_SPSCTRLINT4 56
+#define G_IRQNUM_SPS0_SPSCTRLINT5 57
+#define G_IRQNUM_SPS0_SPSCTRLINT6 58
+#define G_IRQNUM_SPS0_SPSCTRLINT7 59
+#define G_IRQNUM_SPS0_TXFIFO_EMPTY_INTR 60
+#define G_IRQNUM_SPS0_TXFIFO_FULL_INTR 61
+#define G_IRQNUM_SPS0_TXFIFO_LVL_INTR 62
+#define G_IRQNUM_TIMEHS0_TIMINTC 63
+#define G_IRQNUM_TIMEHS0_TIMINT1 64
+#define G_IRQNUM_TIMEHS0_TIMINT2 65
+#define G_IRQNUM_TIMEHS1_TIMINTC 66
+#define G_IRQNUM_TIMEHS1_TIMINT1 67
+#define G_IRQNUM_TIMEHS1_TIMINT2 68
+#define G_IRQNUM_TIMELS0_TIMINT0 69
+#define G_IRQNUM_TIMELS0_TIMINT1 70
+#define G_IRQNUM_UART0_RXBINT 71
+#define G_IRQNUM_UART0_RXFINT 72
+#define G_IRQNUM_UART0_RXINT 73
+#define G_IRQNUM_UART0_RXOVINT 74
+#define G_IRQNUM_UART0_RXTOINT 75
+#define G_IRQNUM_UART0_TXINT 76
+#define G_IRQNUM_UART0_TXOVINT 77
+#define G_IRQNUM_UART1_RXBINT 78
+#define G_IRQNUM_UART1_RXFINT 79
+#define G_IRQNUM_UART1_RXINT 80
+#define G_IRQNUM_UART1_RXOVINT 81
+#define G_IRQNUM_UART1_RXTOINT 82
+#define G_IRQNUM_UART1_TXINT 83
+#define G_IRQNUM_UART1_TXOVINT 84
+#define G_IRQNUM_UART2_RXBINT 85
+#define G_IRQNUM_UART2_RXFINT 86
+#define G_IRQNUM_UART2_RXINT 87
+#define G_IRQNUM_UART2_RXOVINT 88
+#define G_IRQNUM_UART2_RXTOINT 89
+#define G_IRQNUM_UART2_TXINT 90
+#define G_IRQNUM_UART2_TXOVINT 91
+#define G_IRQNUM_WATCHDOG0_WDOGINT 92
+
+#endif /* __CROS_EC_REGISTERS_H */
diff --git a/chip/g/system.c b/chip/g/system.c
new file mode 100644
index 0000000000..1124a15062
--- /dev/null
+++ b/chip/g/system.c
@@ -0,0 +1,45 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#include "system.h"
+#include "registers.h"
+
+void system_pre_init(void)
+{
+
+}
+
+/* TODO(crosbug.com/p/33432): How do we force a reset? */
+void system_reset(int flags)
+{
+
+}
+
+const char *system_get_chip_vendor(void)
+{
+ return "g";
+}
+
+const char *system_get_chip_name(void)
+{
+ return "cr50";
+}
+
+const char *system_get_chip_revision(void)
+{
+ return G_REVISION_STR;
+}
+
+/* TODO(crosbug.com/p/33432): Where can we store stuff persistently? */
+
+int system_get_vbnvcontext(uint8_t *block)
+{
+ return 0;
+}
+
+int system_set_vbnvcontext(const uint8_t *block)
+{
+ return 0;
+}
diff --git a/chip/g/uart.c b/chip/g/uart.c
new file mode 100644
index 0000000000..f8260dc9ec
--- /dev/null
+++ b/chip/g/uart.c
@@ -0,0 +1,168 @@
+/* Copyright (c) 2014 The Chromium OS Authors. All rights reserved.
+ * Use of this source code is governed by a BSD-style license that can be
+ * found in the LICENSE file.
+ */
+
+#include "clock.h"
+#include "common.h"
+#include "registers.h"
+#include "system.h"
+#include "task.h"
+#include "uart.h"
+#include "util.h"
+
+static int done_uart_init_yet;
+
+int uart_init_done(void)
+{
+ return done_uart_init_yet;
+}
+
+void uart_tx_start(void)
+{
+ /* If interrupt is already enabled, nothing to do */
+ if (G_UART_ICTRL(0) & 0x01)
+ return;
+
+ /* Do not allow deep sleep while transmit in progress */
+ disable_sleep(SLEEP_MASK_UART);
+
+ /*
+ * Re-enable the transmit interrupt, then forcibly trigger the
+ * interrupt. This works around a hardware problem with the
+ * UART where the FIFO only triggers the interrupt when its
+ * threshold is _crossed_, not just met.
+ */
+ /* TODO(crosbug.com/p/33432): Do we need this hack here? Find out. */
+ REG_WRITE_MASK(G_UART_ICTRL(0), 0x01, 0x01, 0);
+ task_trigger_irq(G_IRQNUM_UART0_TXINT);
+}
+
+void uart_tx_stop(void)
+{
+ /* Disable the TX interrupt */
+ REG_WRITE_MASK(G_UART_ICTRL(0), 0x01, 0x00, 0);
+
+ /* Re-allow deep sleep */
+ enable_sleep(SLEEP_MASK_UART);
+}
+
+int uart_tx_in_progress(void)
+{
+ /* Transmit is in progress if the TX idle bit is not set */
+ return !(G_UART_STATE(0) & 0x20);
+}
+
+void uart_tx_flush(void)
+{
+ /* Wait until TX FIFO is idle. */
+ while (uart_tx_in_progress())
+ ;
+}
+
+int uart_tx_ready(void)
+{
+ /* True if the TX buffer is not completely full */
+ return !(G_UART_STATE(0) & 0x01);
+}
+
+int uart_rx_available(void)
+{
+ /* True if the RX buffer is not completely empty. */
+ /* TODO(crosbug.com/p/33432): Ask Scott for a single bit for this. */
+ return G_UART_RFIFO(0) & 0x0fc0;
+}
+
+void uart_write_char(char c)
+{
+ /* Wait for space in transmit FIFO. */
+ while (!uart_tx_ready())
+ ;
+
+ G_UART_WDATA(0) = c;
+}
+
+int uart_read_char(void)
+{
+ return G_UART_RDATA(0);
+}
+
+void uart_disable_interrupt(void)
+{
+ task_disable_irq(G_IRQNUM_UART0_TXINT);
+ task_disable_irq(G_IRQNUM_UART0_RXINT);
+}
+
+void uart_enable_interrupt(void)
+{
+ task_enable_irq(G_IRQNUM_UART0_TXINT);
+ task_enable_irq(G_IRQNUM_UART0_RXINT);
+}
+
+/**
+ * Interrupt handlers for UART0
+ */
+void uart_ec_tx_interrupt(void)
+{
+ /* Clear transmit interrupt status */
+ G_UART_ISTATECLR(0) = 0x01;
+
+ /* Fill output FIFO */
+ uart_process_output();
+}
+DECLARE_IRQ(G_IRQNUM_UART0_TXINT, uart_ec_tx_interrupt, 1);
+
+void uart_ec_rx_interrupt(void)
+{
+ /* Clear receive interrupt status */
+ G_UART_ISTATECLR(0) = 0x02;
+
+ /* Read input FIFO until empty */
+ uart_process_input();
+}
+DECLARE_IRQ(G_IRQNUM_UART0_RXINT, uart_ec_rx_interrupt, 1);
+
+/* Constants for setting baud rate */
+#define PCLK_FREQ 26000000
+#define DEFAULT_UART_FREQ 1000000
+#define UART_NCO_WIDTH 16
+
+void uart_init(void)
+{
+ long long setting = (16 * (1 << UART_NCO_WIDTH) *
+ (long long)CONFIG_UART_BAUD_RATE / PCLK_FREQ);
+
+ /* turn on uart clock */
+ clock_enable_module(MODULE_UART, 1);
+
+ /* set up pinmux */
+ G_PINMUX_DIOA0_SEL = G_PINMUX_UART0_TX_SEL;
+ G_PINMUX_UART0_RX_SEL = G_PINMUX_DIOA1_SEL;
+
+ /* IE must be set to 1 to work as a digital pad (for any direction) */
+ /* turn on input driver (IE field) */
+ REG_WRITE_MASK(G_PINMUX_DIOA0_CTL, G_PINMUX_DIOA0_CTL_IE_MASK,
+ 1, G_PINMUX_DIOA0_CTL_IE_LSB);
+ /* turn on input driver (IE field) */
+ REG_WRITE_MASK(G_PINMUX_DIOA1_CTL, G_PINMUX_DIOA1_CTL_IE_MASK,
+ 1, G_PINMUX_DIOA1_CTL_IE_LSB);
+
+ /* set frequency */
+ G_UART_NCO(0) = setting;
+
+ /* Interrupt when RX fifo has anything, when TX fifo <= half empty */
+ /* Also reset (clear) both FIFOs */
+ G_UART_FIFO(0) = 0x63;
+
+ /* TX enable, RX enable, HW flow control disabled, no loopback */
+ G_UART_CTRL(0) = 0x03;
+
+ /* enable RX interrupts in block */
+ /* Note: doesn't do anything unless turned on in NVIC */
+ G_UART_ICTRL(0) = 0x02;
+
+ /* Enable interrupts for UART0 only */
+ uart_enable_interrupt();
+
+ done_uart_init_yet = 1;
+}