summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorShawn Nematbakhsh <shawnn@chromium.org>2017-10-26 08:18:52 -0700
committerChromeOS Commit Bot <chromeos-commit-bot@chromium.org>2017-10-30 17:04:21 +0000
commitd018798cedf2de0d10fbb660ff447db5afdc1cfe (patch)
tree6f9815b342a8a5d71bd3345f0d6e5fc2f86fbca1
parentef0d3c8a5f3b6ad6a74b9892269cb4a90e281967 (diff)
downloadchrome-ec-d018798cedf2de0d10fbb660ff447db5afdc1cfe.tar.gz
cleanup: Remove cr50 board
cr50 is failing with a build-time assertion that isn't meaningful to common servo_v4 code, remove it to fix the build. This is surely leaving around unused code / CONFIGs, do not port to master. BUG=None BRANCH=servo TEST=`make buildall -j` Change-Id: Idf3c1ffd7cd8cacf450f3e0bab45cc0ad22f4de6 Reviewed-on: https://chromium-review.googlesource.com/739986 Reviewed-by: Shawn N <shawnn@chromium.org> Tested-by: Shawn N <shawnn@chromium.org> Commit-Queue: Shawn N <shawnn@chromium.org>
-rw-r--r--board/cr50/board.c803
-rw-r--r--board/cr50/board.h238
-rw-r--r--board/cr50/build.mk86
-rw-r--r--board/cr50/ec.tasklist22
-rw-r--r--board/cr50/gpio.inc138
-rw-r--r--board/cr50/rdd.c332
-rw-r--r--board/cr50/tpm2/NVMem.c214
-rw-r--r--board/cr50/tpm2/aes.c457
-rw-r--r--board/cr50/tpm2/ecc.c592
-rw-r--r--board/cr50/tpm2/ecies.c126
-rw-r--r--board/cr50/tpm2/endian.h11
-rw-r--r--board/cr50/tpm2/endorsement.c752
-rw-r--r--board/cr50/tpm2/hash.c355
-rw-r--r--board/cr50/tpm2/hash_data.c11
-rw-r--r--board/cr50/tpm2/hkdf.c93
-rw-r--r--board/cr50/tpm2/manufacture.c43
-rw-r--r--board/cr50/tpm2/platform.c62
-rw-r--r--board/cr50/tpm2/post_reset.c38
-rw-r--r--board/cr50/tpm2/rsa.c1084
-rw-r--r--board/cr50/tpm2/stubs.c110
-rw-r--r--board/cr50/tpm2/trng.c11
-rw-r--r--board/cr50/tpm2/upgrade.c9
-rw-r--r--board/cr50/usb_i2c.c93
-rw-r--r--board/cr50/usb_spi.c170
-rw-r--r--board/cr50/wp.c329
25 files changed, 0 insertions, 6179 deletions
diff --git a/board/cr50/board.c b/board/cr50/board.c
deleted file mode 100644
index 0f801de447..0000000000
--- a/board/cr50/board.c
+++ /dev/null
@@ -1,803 +0,0 @@
-/* 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 <endian.h>
-
-#include "clock.h"
-#include "common.h"
-#include "console.h"
-#include "dcrypto/dcrypto.h"
-#include "device_state.h"
-#include "ec_version.h"
-#include "extension.h"
-#include "flash_config.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "i2cs.h"
-#include "init_chip.h"
-#include "nvmem.h"
-#include "rdd.h"
-#include "registers.h"
-#include "signed_header.h"
-#include "spi.h"
-#include "system.h"
-#include "task.h"
-#include "tpm_registers.h"
-#include "trng.h"
-#include "uartn.h"
-#include "usb_descriptor.h"
-#include "usb_hid.h"
-#include "usb_spi.h"
-#include "usb_i2c.h"
-#include "util.h"
-
-/* Define interrupt and gpio structs */
-#include "gpio_list.h"
-
-#include "cryptoc/sha.h"
-
-/*
- * Need to include Implementation.h here to make sure that NVRAM size
- * definitions match across different git repos.
- *
- * MAX() definition from include/utils.h does not work in Implementation.h, as
- * it is used in a preprocessor expression there;
- *
- * SHA_DIGEST_SIZE is defined to be the same in both git repos, but using
- * different expressions.
- *
- * To untangle compiler errors let's just undefine MAX() and SHA_DIGEST_SIZE
- * here, as nether is necessary in this case: all we want from
- * Implementation.h at this point is the definition for NV_MEMORY_SIZE.
- */
-#undef MAX
-#undef SHA_DIGEST_SIZE
-#include "Implementation.h"
-
-#define NVMEM_CR50_SIZE 300
-#define NVMEM_TPM_SIZE ((sizeof((struct nvmem_partition *)0)->buffer) \
- - NVMEM_CR50_SIZE)
-
-/*
- * Make sure NV memory size definition in Implementation.h matches reality. It
- * should be set to
- *
- * NVMEM_PARTITION_SIZE - NVMEM_CR50_SIZE - 8
- */
-BUILD_ASSERT(NVMEM_TPM_SIZE == NV_MEMORY_SIZE);
-
-/* NvMem user buffer lengths table */
-uint32_t nvmem_user_sizes[NVMEM_NUM_USERS] = {
- NVMEM_TPM_SIZE,
- NVMEM_CR50_SIZE
-};
-
-/* Board specific configuration settings */
-static uint32_t board_properties;
-static uint8_t reboot_request_posted;
-
-/* I2C Port definition */
-const struct i2c_port_t i2c_ports[] = {
- {"master", I2C_PORT_MASTER, 100,
- GPIO_I2C_SCL_INA, GPIO_I2C_SDA_INA},
-};
-const unsigned int i2c_ports_used = ARRAY_SIZE(i2c_ports);
-
-void post_reboot_request(void)
-{
- /* Reboot the device next time TPM reset is requested. */
- reboot_request_posted = 1;
-}
-
-/*
- * There's no way to trigger on both rising and falling edges, so force a
- * compiler error if we try. The workaround is to use the pinmux to connect
- * two GPIOs to the same input and configure each one for a separate edge.
- */
-#define GPIO_INT(name, pin, flags, signal) \
- BUILD_ASSERT(((flags) & GPIO_INT_BOTH) != GPIO_INT_BOTH);
-#include "gpio.wrap"
-
-static void init_pmu(void)
-{
- clock_enable_module(MODULE_PMU, 1);
-
- /* This boot sequence may be a result of previous soft reset,
- * in which case the PMU low power sequence register needs to
- * be reset. */
- GREG32(PMU, LOW_POWER_DIS) = 0;
-
- /* Enable wakeup interrupt */
- task_enable_irq(GC_IRQNUM_PMU_INTR_WAKEUP_INT);
- GWRITE_FIELD(PMU, INT_ENABLE, INTR_WAKEUP, 1);
-}
-
-void pmu_wakeup_interrupt(void)
-{
- int exiten, wakeup_src;
- int plt_rst_asserted;
-
- delay_sleep_by(1 * MSEC);
-
- wakeup_src = GR_PMU_EXITPD_SRC;
-
- /* Clear interrupt state */
- GWRITE_FIELD(PMU, INT_STATE, INTR_WAKEUP, 1);
-
- /* Clear pmu reset */
- GWRITE(PMU, CLRRST, 1);
-
- if (wakeup_src & GC_PMU_EXITPD_SRC_PIN_PD_EXIT_MASK) {
- /*
- * If any wake pins are edge triggered, the pad logic latches
- * the wakeup. Clear EXITEN0 to reset the wakeup logic.
- */
- exiten = GREG32(PINMUX, EXITEN0);
- GREG32(PINMUX, EXITEN0) = 0;
- GREG32(PINMUX, EXITEN0) = exiten;
-
- /*
- * Delay sleep long enough for a SPI slave transaction to start
- * or for the system to be reset.
- */
- delay_sleep_by(3 * MINUTE);
-
- /*
- * If sys_rst_l or plt_rst_l (if signal is present) is
- * configured to wake on low and the signal is low, then call
- * sys_rst_asserted
- */
- plt_rst_asserted = board_properties & BOARD_USE_PLT_RESET ?
- !gpio_get_level(GPIO_PLT_RST_L) : 0;
- if ((!gpio_get_level(GPIO_SYS_RST_L_IN) &&
- GREAD_FIELD(PINMUX, EXITINV0, DIOM0)) || (plt_rst_asserted
- && GREAD_FIELD(PINMUX, EXITINV0, DIOM3)))
- sys_rst_asserted(GPIO_SYS_RST_L_IN);
- }
-
- /* Trigger timer0 interrupt */
- if (wakeup_src & GC_PMU_EXITPD_SRC_TIMELS0_PD_EXIT_TIMER0_MASK)
- task_trigger_irq(GC_IRQNUM_TIMELS0_TIMINT0);
-
- /* Trigger timer1 interrupt */
- if (wakeup_src & GC_PMU_EXITPD_SRC_TIMELS0_PD_EXIT_TIMER1_MASK)
- task_trigger_irq(GC_IRQNUM_TIMELS0_TIMINT1);
-}
-DECLARE_IRQ(GC_IRQNUM_PMU_INTR_WAKEUP_INT, pmu_wakeup_interrupt, 1);
-
-void board_configure_deep_sleep_wakepins(void)
-{
- /*
- * Disable the i2c and spi slave wake sources since the TPM is
- * not being used and reenable them in their init functions on
- * resume.
- */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOA12, 0); /* SPS_CS_L */
- /* TODO remove i2cs wake event */
-
- /* Remove the pulldown on EC uart tx and disable the input */
- GWRITE_FIELD(PINMUX, DIOB5_CTL, PD, 0);
- GWRITE_FIELD(PINMUX, DIOB5_CTL, IE, 0);
-
- /*
- * DIOA3 is GPIO_DETECT_AP which is used to detect if the AP is in S0.
- * If the AP is in s0, cr50 should not be in deep sleep so wake up.
- */
- GWRITE_FIELD(PINMUX, EXITEDGE0, DIOA3, 1); /* edge sensitive */
- GWRITE_FIELD(PINMUX, EXITINV0, DIOA3, 0); /* wake on high */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOA3, 1); /* GPIO_DETECT_AP */
-
- /*
- * Whether it is a short pulse or long one waking on the rising edge is
- * fine because the goal of sys_rst is to reset the TPM and after
- * resuming from deep sleep the TPM will be reset. Cr50 doesn't need to
- * read the low value and then reset.
- *
- * Configure cr50 to resume on the rising edge of sys_rst_l
- */
- /* Disable sys_rst_l as a wake pin */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOM0, 0);
- /* Reconfigure and reenable it. */
- GWRITE_FIELD(PINMUX, EXITEDGE0, DIOM0, 1); /* edge sensitive */
- GWRITE_FIELD(PINMUX, EXITINV0, DIOM0, 0); /* wake on high */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOM0, 1); /* enable powerdown exit */
-
- /*
- * If the board includes plt_rst_l, configure Cr50 to resume on the
- * rising edge of this signal.
- */
- if (system_get_board_properties() & BOARD_USE_PLT_RESET) {
- /* Disable sys_rst_l as a wake pin */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOM3, 0);
- /* Reconfigure and reenable it. */
- GWRITE_FIELD(PINMUX, EXITEDGE0, DIOM3, 1); /* edge sensitive */
- GWRITE_FIELD(PINMUX, EXITINV0, DIOM3, 0); /* wake on high */
- /* enable powerdown exit */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOM3, 1);
- }
-}
-
-static void init_interrupts(void)
-{
- int i;
- uint32_t exiten = GREG32(PINMUX, EXITEN0);
-
- /* Clear wake pin interrupts */
- GREG32(PINMUX, EXITEN0) = 0;
- GREG32(PINMUX, EXITEN0) = exiten;
-
- /* Enable all GPIO interrupts */
- for (i = 0; i < gpio_ih_count; i++)
- if (gpio_list[i].flags & GPIO_INT_ANY)
- gpio_enable_interrupt(i);
-}
-
-static void configure_board_specific_gpios(void)
-{
- /* Add a pullup to sys_rst_l */
- if (system_get_board_properties() & BOARD_NEEDS_SYS_RST_PULL_UP)
- GWRITE_FIELD(PINMUX, DIOM0_CTL, PU, 1);
-
- /* Connect PLT_RST_L signal to the pinmux */
- if (system_get_board_properties() & BOARD_USE_PLT_RESET) {
- /* Signal using GPIO1 pin 10 for DIOA13 */
- GWRITE(PINMUX, GPIO1_GPIO10_SEL, GC_PINMUX_DIOM3_SEL);
- /* Enbale the input */
- GWRITE_FIELD(PINMUX, DIOM3_CTL, IE, 1);
-
- /* Set power down for the equivalent of DIO_WAKE_FALLING */
- /* Set to be edge sensitive */
- GWRITE_FIELD(PINMUX, EXITEDGE0, DIOM3, 1);
- /* Select failling edge polarity */
- GWRITE_FIELD(PINMUX, EXITINV0, DIOM3, 1);
- /* Enable powerdown exit on DIOM3 */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOM3, 1);
- }
-}
-
-/* Initialize board. */
-static void board_init(void)
-{
- configure_board_specific_gpios();
- init_pmu();
- init_interrupts();
- init_trng();
- init_jittery_clock(1);
- init_runlevel(PERMISSION_MEDIUM);
- /* Initialize NvMem partitions */
- nvmem_init();
-
- /* Enable write protect on production images. Disable it on dev */
- GREG32(RBOX, EC_WP_L) = !console_is_restricted();
-
- /* Indication that firmware is running, for debug purposes. */
- GREG32(PMU, PWRDN_SCRATCH16) = 0xCAFECAFE;
-}
-DECLARE_HOOK(HOOK_INIT, board_init, HOOK_PRIO_DEFAULT);
-
-#if defined(CONFIG_USB)
-const void * const usb_strings[] = {
- [USB_STR_DESC] = usb_string_desc,
- [USB_STR_VENDOR] = USB_STRING_DESC("Google Inc."),
- [USB_STR_PRODUCT] = USB_STRING_DESC("Cr50"),
- [USB_STR_VERSION] = USB_STRING_DESC(CROS_EC_VERSION32),
- [USB_STR_CONSOLE_NAME] = USB_STRING_DESC("Shell"),
- [USB_STR_BLOB_NAME] = USB_STRING_DESC("Blob"),
- [USB_STR_HID_KEYBOARD_NAME] = USB_STRING_DESC("PokeyPokey"),
- [USB_STR_AP_NAME] = USB_STRING_DESC("AP"),
- [USB_STR_EC_NAME] = USB_STRING_DESC("EC"),
- [USB_STR_UPGRADE_NAME] = USB_STRING_DESC("Firmware upgrade"),
- [USB_STR_SPI_NAME] = USB_STRING_DESC("AP EC upgrade"),
- [USB_STR_SERIALNO] = USB_STRING_DESC(DEFAULT_SERIALNO),
- [USB_STR_I2C_NAME] = USB_STRING_DESC("I2C"),
-};
-BUILD_ASSERT(ARRAY_SIZE(usb_strings) == USB_STR_COUNT);
-#endif
-
-/* SPI devices */
-const struct spi_device_t spi_devices[] = {
- [CONFIG_SPI_FLASH_PORT] = {0, 2, GPIO_COUNT}
-};
-const unsigned int spi_devices_used = ARRAY_SIZE(spi_devices);
-
-int flash_regions_to_enable(struct g_flash_region *regions,
- int max_regions)
-{
- /*
- * This needs to account for two regions: the "other" RW partition and
- * the NVRAM in TOP_B.
- *
- * When running from RW_A the two regions are adjacent, but it is
- * simpler to keep function logic the same and always configure two
- * separate regions.
- */
-
- if (max_regions < 3)
- return 0;
-
- /* Enable access to the other RW image... */
- if (system_get_image_copy() == SYSTEM_IMAGE_RW)
- /* Running RW_A, enable RW_B */
- regions[0].reg_base = CONFIG_MAPPED_STORAGE_BASE +
- CONFIG_RW_B_MEM_OFF;
- else
- /* Running RW_B, enable RW_A */
- regions[0].reg_base = CONFIG_MAPPED_STORAGE_BASE +
- CONFIG_RW_MEM_OFF;
- /* Size is the same */
- regions[0].reg_size = CONFIG_RW_SIZE;
- regions[0].reg_perms = FLASH_REGION_EN_ALL;
-
- /* Enable access to the NVRAM partition A region */
- regions[1].reg_base = CONFIG_MAPPED_STORAGE_BASE +
- CONFIG_FLASH_NVMEM_OFFSET_A;
- regions[1].reg_size = NVMEM_PARTITION_SIZE;
- regions[1].reg_perms = FLASH_REGION_EN_ALL;
-
- /* Enable access to the NVRAM partition B region */
- regions[2].reg_base = CONFIG_MAPPED_STORAGE_BASE +
- CONFIG_FLASH_NVMEM_OFFSET_B;
- regions[2].reg_size = NVMEM_PARTITION_SIZE;
- regions[2].reg_perms = FLASH_REGION_EN_ALL;
-
- return 3;
-}
-
-#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ## args)
-
-/* This is the interrupt handler to react to SYS_RST_L_IN */
-void sys_rst_asserted(enum gpio_signal signal)
-{
- /*
- * Cr50 drives SYS_RST_L in certain scenarios, in those cases
- * this signal's assertion should be ignored here.
- */
- CPRINTS("%s from %d", __func__, signal);
- if (usb_spi_update_in_progress() ||
- tpm_is_resetting()) {
- CPRINTS("%s ignored", __func__);
- return;
- }
-
- if (reboot_request_posted)
- system_reset(SYSTEM_RESET_HARD); /* This will never return. */
-
- /* Re-initialize the TPM software state */
- tpm_reset(0, 0);
-}
-
-void assert_sys_rst(void)
-{
- /*
- * We don't have a good (any?) way to easily look up the pinmux/gpio
- * assignments in gpio.inc, so they're hard-coded in this routine. This
- * assertion is just to ensure it hasn't changed.
- */
- ASSERT(GREAD(PINMUX, GPIO0_GPIO4_SEL) == GC_PINMUX_DIOM0_SEL);
-
- /* Set SYS_RST_L_OUT as an output, connected to the pad */
- GWRITE(PINMUX, DIOM0_SEL, GC_PINMUX_GPIO0_GPIO4_SEL);
- gpio_set_flags(GPIO_SYS_RST_L_OUT, GPIO_OUT_HIGH);
-
- /* Assert it */
- gpio_set_level(GPIO_SYS_RST_L_OUT, 0);
-}
-
-void deassert_sys_rst(void)
-{
- ASSERT(GREAD(PINMUX, GPIO0_GPIO4_SEL) == GC_PINMUX_DIOM0_SEL);
-
- /* Deassert SYS_RST_L */
- gpio_set_level(GPIO_SYS_RST_L_OUT, 1);
-
- /* Set SYS_RST_L_OUT as an input, disconnected from the pad */
- gpio_set_flags(GPIO_SYS_RST_L_OUT, GPIO_INPUT);
- GWRITE(PINMUX, DIOM0_SEL, 0);
-}
-
-int is_sys_rst_asserted(void)
-{
- return (GREAD(PINMUX, DIOM0_SEL) == GC_PINMUX_GPIO0_GPIO4_SEL)
-#ifdef CONFIG_CMD_GPIO_EXTENDED
- && (gpio_get_flags(GPIO_SYS_RST_L_OUT) & GPIO_OUTPUT)
-#endif
- && (gpio_get_level(GPIO_SYS_RST_L_OUT) == 0);
-}
-
-void assert_ec_rst(void)
-{
- GWRITE(RBOX, ASSERT_EC_RST, 1);
-}
-void deassert_ec_rst(void)
-{
- GWRITE(RBOX, ASSERT_EC_RST, 0);
-}
-
-int is_ec_rst_asserted(void)
-{
- return GREAD(RBOX, ASSERT_EC_RST);
-}
-
-void nvmem_compute_sha(uint8_t *p_buf, int num_bytes,
- uint8_t *p_sha, int sha_len)
-{
- uint8_t sha1_digest[SHA_DIGEST_SIZE];
- /*
- * Taking advantage of the built in dcrypto engine to generate
- * a CRC-like value that can be used to validate contents of an
- * NvMem partition. Only using the lower 4 bytes of the sha1 hash.
- */
- DCRYPTO_SHA1_hash((uint8_t *)p_buf,
- num_bytes,
- sha1_digest);
- memcpy(p_sha, sha1_digest, sha_len);
-}
-
-static int device_state_changed(enum device_type device,
- enum device_state state)
-{
- int state_changed = state != device_states[device].last_known_state;
-
- device_set_state(device, state);
-
- /*
- * We've determined the device state, so cancel any deferred callbacks.
- */
- hook_call_deferred(device_states[device].deferred, -1);
-
- return state_changed;
-}
-
-/*
- * If the UART is enabled we cant tell anything about the
- * servo state, so disable servo detection.
- */
-static int servo_state_unknown(void)
-{
- if (uartn_enabled(UART_EC)) {
- device_set_state(DEVICE_SERVO, DEVICE_STATE_UNKNOWN);
- return 1;
- }
- return 0;
-}
-
-static int device_powered_off(enum device_type device, int uart)
-{
- if (device_get_state(device) == DEVICE_STATE_ON)
- return EC_ERROR_UNKNOWN;
-
- if (!device_state_changed(device, DEVICE_STATE_OFF))
- return EC_ERROR_UNKNOWN;
-
- if (uart) {
- /* Disable RX and TX on the UART peripheral */
- uartn_disable(uart);
-
- /* Disconnect the TX pin from the UART peripheral */
- uartn_tx_disconnect(uart);
- }
- return EC_SUCCESS;
-}
-
-static void servo_deferred(void)
-{
- if (servo_state_unknown())
- return;
-
- device_powered_off(DEVICE_SERVO, 0);
-}
-DECLARE_DEFERRED(servo_deferred);
-
-static void ap_deferred(void)
-{
- if (device_powered_off(DEVICE_AP, UART_AP) == EC_SUCCESS)
- hook_notify(HOOK_CHIPSET_SHUTDOWN);
-}
-DECLARE_DEFERRED(ap_deferred);
-
-static void ec_deferred(void)
-{
- device_powered_off(DEVICE_EC, UART_EC);
-}
-DECLARE_DEFERRED(ec_deferred);
-
-struct device_config device_states[] = {
- [DEVICE_SERVO] = {
- .deferred = &servo_deferred_data,
- .detect = GPIO_DETECT_SERVO,
- .name = "Servo"
- },
- [DEVICE_AP] = {
- .deferred = &ap_deferred_data,
- .detect = GPIO_DETECT_AP,
- .name = "AP"
- },
- [DEVICE_EC] = {
- .deferred = &ec_deferred_data,
- .detect = GPIO_DETECT_EC,
- .name = "EC"
- },
-};
-BUILD_ASSERT(ARRAY_SIZE(device_states) == DEVICE_COUNT);
-
-/* Returns EC_SUCCESS if the device state changed to on */
-static int device_powered_on(enum device_type device, int uart)
-{
- /* Update the device state */
- if (!device_state_changed(device, DEVICE_STATE_ON))
- return EC_ERROR_UNKNOWN;
-
- /* Enable RX and TX on the UART peripheral */
- uartn_enable(uart);
-
- /* Connect the TX pin to the UART TX Signal */
- if (device_get_state(DEVICE_SERVO) != DEVICE_STATE_ON &&
- !uartn_enabled(uart))
- uartn_tx_connect(uart);
-
- return EC_SUCCESS;
-}
-
-static void servo_attached(void)
-{
- if (servo_state_unknown())
- return;
-
- /* Update the device state */
- device_state_changed(DEVICE_SERVO, DEVICE_STATE_ON);
-
- /* Disconnect AP and EC UART when servo is attached */
- uartn_tx_disconnect(UART_AP);
- uartn_tx_disconnect(UART_EC);
-
- /* Disconnect i2cm interface to ina */
- usb_i2c_board_disable(0);
-}
-
-void device_state_on(enum gpio_signal signal)
-{
- gpio_disable_interrupt(signal);
-
- switch (signal) {
- case GPIO_DETECT_AP:
- if (device_powered_on(DEVICE_AP, UART_AP) == EC_SUCCESS)
- hook_notify(HOOK_CHIPSET_RESUME);
- break;
- case GPIO_DETECT_EC:
- device_powered_on(DEVICE_EC, UART_EC);
- break;
- case GPIO_DETECT_SERVO:
- servo_attached();
- break;
- default:
- CPRINTS("Device not supported");
- return;
- }
-}
-
-void board_update_device_state(enum device_type device)
-{
- if (device == DEVICE_SERVO && servo_state_unknown())
- return;
-
- /*
- * If the device is currently on set its state immediately. If it
- * thinks the device is powered off debounce the signal.
- */
- if (gpio_get_level(device_states[device].detect))
- device_state_on(device_states[device].detect);
- else {
- device_set_state(device, DEVICE_STATE_UNKNOWN);
-
- gpio_enable_interrupt(device_states[device].detect);
-
- /*
- * The signal is low now, but the detect signals are on UART RX
- * which may be receiving something. Wait long enough for an
- * entire data chunk to be sent to declare that the device is
- * off. If the detect signal remains low for 100us then the
- * signal is low because the device is off.
- */
- hook_call_deferred(device_states[device].deferred, 100);
- }
-}
-
-void disable_int_ap_l(void)
-{
- /*
- * If I2C TPM is configured then the INT_AP_L signal is used as
- * a low pulse trigger to sync I2C transactions with the
- * host. By default Cr50 is driving this line high, but when the
- * AP powers off, the 1.8V rail that it's pulled up to will be
- * off and cause exessive power to be consumed by the Cr50. Set
- * INT_AP_L as an input while the AP is powered off.
- */
- gpio_set_flags(GPIO_INT_AP_L, GPIO_INPUT);
-}
-DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, disable_int_ap_l, HOOK_PRIO_DEFAULT);
-
-void enable_int_ap_l(void)
-{
- /*
- * AP is powering up, set the I2C host sync signal to output and set
- * it high which is the default level.
- */
- gpio_set_flags(GPIO_INT_AP_L, GPIO_OUT_HIGH);
- gpio_set_level(GPIO_INT_AP_L, 1);
-}
-DECLARE_HOOK(HOOK_CHIPSET_RESUME, enable_int_ap_l, HOOK_PRIO_DEFAULT);
-
-void system_init_board_properties(void)
-{
- uint32_t properties;
-
- properties = GREG32(PMU, LONG_LIFE_SCRATCH1);
-
- /*
- * This must be a power on reset or maybe restart due to a software
- * update from a version not setting the register.
- */
- if (!properties || system_get_reset_flags() & RESET_FLAG_HARD) {
- /*
- * Reset the properties, because after a hard reset the register
- * won't be cleared.
- */
- properties = 0;
-
- /* Read DIOA1 strap pin */
- if (gpio_get_level(GPIO_STRAP0)) {
- /* Strap is pulled high -> Kevin SPI TPM option */
- properties |= BOARD_SLAVE_CONFIG_SPI;
- /* Add an internal pull up on sys_rst_l */
- /*
- * TODO(crosbug.com/p/56945): Remove once SYS_RST_L can
- * be pulled up externally.
- */
- properties |= BOARD_NEEDS_SYS_RST_PULL_UP;
- } else {
- /* Strap is low -> Reef I2C TPM option */
- properties |= BOARD_SLAVE_CONFIG_I2C;
- /* One PHY is connected to the AP */
- properties |= BOARD_USB_AP;
- /*
- * Platform reset is present and will need to be
- * configured as a an falling edge interrupt.
- */
- properties |= BOARD_USE_PLT_RESET;
- }
-
- /*
- * Now save the properties value for future use.
- *
- * First enable write access to the LONG_LIFE_SCRATCH1 register.
- */
- GWRITE_FIELD(PMU, LONG_LIFE_SCRATCH_WR_EN, REG1, 1);
- /* Save properties in LONG_LIFE register */
- GREG32(PMU, LONG_LIFE_SCRATCH1) = properties;
- /* Disabel write access to the LONG_LIFE_SCRATCH1 register */
- GWRITE_FIELD(PMU, LONG_LIFE_SCRATCH_WR_EN, REG1, 0);
- }
-
- /* Save this configuration setting */
- board_properties = properties;
-}
-
-uint32_t system_board_properties_callback(void)
-{
- return board_properties;
-}
-
-void i2cs_set_pinmux(void)
-{
- /* Connect I2CS SDA/SCL output to A1/A9 pads */
- GWRITE(PINMUX, DIOA1_SEL, GC_PINMUX_I2CS0_SDA_SEL);
- GWRITE(PINMUX, DIOA9_SEL, GC_PINMUX_I2CS0_SCL_SEL);
- /* Connect A1/A9 pads to I2CS input SDA/SCL */
- GWRITE(PINMUX, I2CS0_SDA_SEL, GC_PINMUX_DIOA1_SEL);
- GWRITE(PINMUX, I2CS0_SCL_SEL, GC_PINMUX_DIOA9_SEL);
- /* Enable SDA/SCL inputs from A1/A9 pads */
- GWRITE_FIELD(PINMUX, DIOA1_CTL, IE, 1); /* I2CS_SDA */
- GWRITE_FIELD(PINMUX, DIOA9_CTL, IE, 1); /* I2CS_SCL */
-
- /* Allow I2CS_SCL to wake from sleep */
- GWRITE_FIELD(PINMUX, EXITEDGE0, DIOA9, 1); /* edge sensitive */
- GWRITE_FIELD(PINMUX, EXITINV0, DIOA9, 1); /* wake on low */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOA9, 1); /* enable powerdown exit */
-
- /* Allow I2CS_SDA to wake from sleep */
- GWRITE_FIELD(PINMUX, EXITEDGE0, DIOA1, 1); /* edge sensitive */
- GWRITE_FIELD(PINMUX, EXITINV0, DIOA1, 1); /* wake on low */
- GWRITE_FIELD(PINMUX, EXITEN0, DIOA1, 1); /* enable powerdown exit */
-}
-
-/* Determine key type based on the key ID. */
-static const char *key_type(uint32_t key_id)
-{
-
- /*
- * It is a mere convention, but all prod keys are required to have key
- * IDs such, that bit D2 is set, and all dev keys are required to have
- * key IDs such, that bit D2 is not set.
- *
- * This convention is enforced at the key generation time.
- */
- if (key_id & (1 << 2))
- return "prod";
- else
- return "dev";
-}
-
-static int command_sysinfo(int argc, char **argv)
-{
- enum system_image_copy_t active;
- uintptr_t vaddr;
- const struct SignedHeader *h;
-
- ccprintf("Reset flags: 0x%08x (", system_get_reset_flags());
- system_print_reset_flags();
- ccprintf(")\n");
-
- ccprintf("Chip: %s %s %s\n", system_get_chip_vendor(),
- system_get_chip_name(), system_get_chip_revision());
-
- active = system_get_ro_image_copy();
- vaddr = get_program_memory_addr(active);
- h = (const struct SignedHeader *)vaddr;
- ccprintf("RO keyid: 0x%08x(%s)\n", h->keyid, key_type(h->keyid));
-
- active = system_get_image_copy();
- vaddr = get_program_memory_addr(active);
- h = (const struct SignedHeader *)vaddr;
- ccprintf("RW keyid: 0x%08x(%s)\n", h->keyid, key_type(h->keyid));
-
- ccprintf("DEV_ID: 0x%08x 0x%08x\n",
- GREG32(FUSE, DEV_ID0), GREG32(FUSE, DEV_ID1));
-
- return EC_SUCCESS;
-}
-DECLARE_SAFE_CONSOLE_COMMAND(sysinfo, command_sysinfo,
- NULL,
- "Print system info");
-
-/*
- * SysInfo command:
- * There are no input args.
- * Output is this struct, all fields in network order.
- */
-struct sysinfo_s {
- uint32_t ro_keyid;
- uint32_t rw_keyid;
- uint32_t dev_id0;
- uint32_t dev_id1;
-} __packed;
-
-static enum vendor_cmd_rc vc_sysinfo(enum vendor_cmd_cc code,
- void *buf,
- size_t input_size,
- size_t *response_size)
-{
- enum system_image_copy_t active;
- uintptr_t vaddr;
- const struct SignedHeader *h;
- struct sysinfo_s *sysinfo = buf;
-
- active = system_get_ro_image_copy();
- vaddr = get_program_memory_addr(active);
- h = (const struct SignedHeader *)vaddr;
- sysinfo->ro_keyid = htobe32(h->keyid);
-
- active = system_get_image_copy();
- vaddr = get_program_memory_addr(active);
- h = (const struct SignedHeader *)vaddr;
- sysinfo->rw_keyid = htobe32(h->keyid);
-
- sysinfo->dev_id0 = htobe32(GREG32(FUSE, DEV_ID0));
- sysinfo->dev_id1 = htobe32(GREG32(FUSE, DEV_ID1));
-
- *response_size = sizeof(*sysinfo);
- return VENDOR_RC_SUCCESS;
-}
-DECLARE_VENDOR_COMMAND(VENDOR_CC_SYSINFO, vc_sysinfo);
diff --git a/board/cr50/board.h b/board/cr50/board.h
deleted file mode 100644
index 295a6ddf0c..0000000000
--- a/board/cr50/board.h
+++ /dev/null
@@ -1,238 +0,0 @@
-/* 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_BOARD_H
-#define __CROS_EC_BOARD_H
-
-/*
- * The default watchdog timeout is 1.6 seconds, but there are some legitimate
- * flash-intensive TPM operations that actually take close to that long to
- * complete. Make sure we don't trigger the watchdog accidentally if the timing
- * is just a little off.
- */
-#undef CONFIG_WATCHDOG_PERIOD_MS
-#define CONFIG_WATCHDOG_PERIOD_MS 5000
-
-/* Features that we don't want */
-#undef CONFIG_CMD_LID_ANGLE
-#undef CONFIG_CMD_POWERINDEBUG
-#undef CONFIG_DMA_DEFAULT_HANDLERS
-#undef CONFIG_FMAP
-#undef CONFIG_HIBERNATE
-#undef CONFIG_LID_SWITCH
-#undef CONFIG_CMD_SYSINFO
-#undef CONFIG_CMD_SYSJUMP
-#undef CONFIG_CMD_SYSLOCK
-
-#ifndef CR50_DEV
-/* Disable stuff that should only be in debug builds */
-#undef CONFIG_CMD_MD
-#undef CONFIG_CMD_RW
-#undef CONFIG_CMD_SLEEPMASK
-#undef CONFIG_CMD_WAITMS
-#undef CONFIG_FLASH
-#endif
-
-/* Flash configuration */
-#undef CONFIG_FLASH_PSTATE
-/* TODO(crosbug.com/p/44745): Bringup only! Do the right thing for real! */
-#define CONFIG_WP_ALWAYS
-/* TODO(crosbug.com/p/44745): For debugging only */
-#define CONFIG_CMD_FLASH
-
-/* We're using TOP_A for partition 0, TOP_B for partition 1 */
-#define CONFIG_FLASH_NVMEM
-/* Offset to start of NvMem area from base of flash */
-#define CONFIG_FLASH_NVMEM_OFFSET_A (CFG_TOP_A_OFF)
-#define CONFIG_FLASH_NVMEM_OFFSET_B (CFG_TOP_B_OFF)
-/* Address of start of Nvmem area */
-#define CONFIG_FLASH_NVMEM_BASE_A (CONFIG_PROGRAM_MEMORY_BASE + \
- CONFIG_FLASH_NVMEM_OFFSET_A)
-#define CONFIG_FLASH_NVMEM_BASE_B (CONFIG_PROGRAM_MEMORY_BASE + \
- CONFIG_FLASH_NVMEM_OFFSET_B)
-/* Size partition in NvMem */
-#define NVMEM_PARTITION_SIZE CFG_TOP_SIZE
-/* Size in bytes of NvMem area */
-#define CONFIG_FLASH_NVMEM_SIZE (CFG_TOP_SIZE * NVMEM_NUM_PARTITIONS)
-
-
-/* Go to sleep when nothing else is happening */
-#define CONFIG_LOW_POWER_IDLE
-
-/* Detect the states of other devices */
-#define CONFIG_DEVICE_STATE
-
-/* Enable debug cable detection */
-#define CONFIG_RDD
-
-/* USB configuration */
-#define CONFIG_USB
-#define CONFIG_USB_CONSOLE
-#define CONFIG_USB_I2C
-#define CONFIG_USB_INHIBIT_INIT
-#define CONFIG_USB_SELECT_PHY
-#define CONFIG_USB_SPI
-#define CONFIG_USB_SERIALNO
-#define DEFAULT_SERIALNO "0"
-
-#define CONFIG_STREAM_USART
-#define CONFIG_STREAM_USB
-
-/* Enable Case Closed Debugging */
-#define CONFIG_CASE_CLOSED_DEBUG
-
-#define CONFIG_USB_PID 0x5014
-#define CONFIG_USB_SELF_POWERED
-
-#undef CONFIG_USB_MAXPOWER_MA
-#define CONFIG_USB_MAXPOWER_MA 0
-
-/* Enable SPI Master (SPI) module */
-#define CONFIG_SPI_MASTER
-#define CONFIG_SPI_MASTER_NO_CS_GPIOS
-#define CONFIG_SPI_MASTER_CONFIGURE_GPIOS
-#define CONFIG_SPI_FLASH_PORT 0
-
-/* Enable SPI Slave (SPS) module */
-#define CONFIG_SPS
-#define CONFIG_TPM_SPS
-
-#define CONFIG_RBOX
-
-/* We don't need to send events to the AP */
-#undef CONFIG_HOSTCMD_EVENTS
-
-/* Make most commands restricted */
-#define CONFIG_CONSOLE_COMMAND_FLAGS
-#define CONFIG_RESTRICTED_CONSOLE_COMMANDS
-#define CONFIG_CONSOLE_COMMAND_FLAGS_DEFAULT CMD_FLAG_RESTRICTED
-
-/* Include crypto stuff, both software and hardware. */
-#define CONFIG_DCRYPTO
-
-#ifndef __ASSEMBLER__
-
-#include "gpio_signal.h"
-
-/* USB string indexes */
-enum usb_strings {
- USB_STR_DESC = 0,
- USB_STR_VENDOR,
- USB_STR_PRODUCT,
- USB_STR_VERSION,
- USB_STR_CONSOLE_NAME,
- USB_STR_BLOB_NAME,
- USB_STR_HID_KEYBOARD_NAME,
- USB_STR_AP_NAME,
- USB_STR_EC_NAME,
- USB_STR_UPGRADE_NAME,
- USB_STR_SPI_NAME,
- USB_STR_SERIALNO,
- USB_STR_I2C_NAME,
-
- USB_STR_COUNT
-};
-
-/* Device indexes */
-enum device_type {
- DEVICE_AP = 0,
- DEVICE_EC,
- DEVICE_SERVO,
-
- DEVICE_COUNT
-};
-
-/* USB SPI device indexes */
-enum usb_spi {
- USB_SPI_DISABLE = 0,
- USB_SPI_AP,
- USB_SPI_EC,
-};
-
-void board_configure_deep_sleep_wakepins(void);
-/* Interrupt handler */
-void sys_rst_asserted(enum gpio_signal signal);
-void device_state_on(enum gpio_signal signal);
-void post_reboot_request(void);
-
-/* Special controls over EC and AP */
-void assert_sys_rst(void);
-void deassert_sys_rst(void);
-int is_sys_rst_asserted(void);
-void assert_ec_rst(void);
-void deassert_ec_rst(void);
-int is_ec_rst_asserted(void);
-
-#endif /* !__ASSEMBLER__ */
-
-/* USB interface indexes (use define rather than enum to expand them) */
-#define USB_IFACE_CONSOLE 0
-#define USB_IFACE_AP 1
-#define USB_IFACE_EC 2
-#define USB_IFACE_UPGRADE 3
-#define USB_IFACE_SPI 4
-#define USB_IFACE_I2C 5
-#define USB_IFACE_COUNT 6
-
-/* USB endpoint indexes (use define rather than enum to expand them) */
-#define USB_EP_CONTROL 0
-#define USB_EP_CONSOLE 1
-#define USB_EP_AP 2
-#define USB_EP_EC 3
-#define USB_EP_UPGRADE 4
-#define USB_EP_SPI 5
-#define USB_EP_I2C 6
-#define USB_EP_COUNT 7
-
-/* UART indexes (use define rather than enum to expand them) */
-#define UART_CR50 0
-#define UART_AP 1
-#define UART_EC 2
-
-#define UARTN UART_CR50
-
-/* TODO(crosbug.com/p/56540): Remove this when UART0_RX works everywhere */
-#define GC_UART0_RX_DISABLE
-
-/*
- * This would be a low hanging fruit if there is a need to reduce memory
- * footprint. Having a large buffer helps not to drop debug outputs generated
- * before console is initialized, but this is not really necessary in a
- * production device.
- */
-#undef CONFIG_UART_TX_BUF_SIZE
-#define CONFIG_UART_TX_BUF_SIZE 4096
-
-#define CC_DEFAULT (CC_ALL & ~CC_MASK(CC_TPM))
-
-/* Nv Memory users */
-#ifndef __ASSEMBLER__
-enum nvmem_users {
- NVMEM_TPM = 0,
- NVMEM_CR50,
- NVMEM_NUM_USERS
-};
-#endif
-
-/*
- * Let's be on the lookout for stack overflow, while debugging.
- *
- * TODO(vbendeb): remove this before finalizing the code.
- */
-#define CONFIG_DEBUG_STACK_OVERFLOW
-#define CONFIG_RW_B
-
-/* Firmware upgrade options. */
-#define CONFIG_NON_HC_FW_UPDATE
-#define CONFIG_USB_FW_UPDATE
-
-#define CONFIG_I2C
-#define CONFIG_I2C_MASTER
-#define CONFIG_I2C_SLAVE
-#define CONFIG_TPM_I2CS
-
-#define I2C_PORT_MASTER 0
-
-#endif /* __CROS_EC_BOARD_H */
diff --git a/board/cr50/build.mk b/board/cr50/build.mk
deleted file mode 100644
index 48fb0c2a92..0000000000
--- a/board/cr50/build.mk
+++ /dev/null
@@ -1,86 +0,0 @@
-# -*- 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 build requirements
-
-# Define the SoC used by this board
-CHIP:=g
-CHIP_FAMILY:=cr50
-CHIP_VARIANT ?= cr50_fpga
-
-# This file is included twice by the Makefile, once to determine the CHIP info
-# and then again after defining all the CONFIG_ and HAS_TASK variables. We use
-# a guard so that recipe definitions and variable extensions only happen the
-# second time.
-ifeq ($(BOARD_MK_INCLUDED_ONCE),)
-BOARD_MK_INCLUDED_ONCE=1
-SIG_EXTRA = --cros
-else
-
-# Need to generate a .hex file
-all: hex
-
-# The simulator components have their own subdirectory
-CFLAGS += -I$(realpath chip/$(CHIP)/dcrypto)
-CFLAGS += -I$(realpath $(BDIR)/tpm2)
-dirs-y += chip/$(CHIP)/dcrypto
-dirs-y += $(BDIR)/tpm2
-
-# Objects that we need to build
-board-y = board.o
-board-${CONFIG_RDD} += rdd.o
-board-${CONFIG_USB_SPI} += usb_spi.o
-board-${CONFIG_USB_I2C} += usb_i2c.o
-board-y += tpm2/NVMem.o
-board-y += tpm2/aes.o
-board-y += tpm2/ecc.o
-board-y += tpm2/ecies.o
-board-y += tpm2/endorsement.o
-board-y += tpm2/hash.o
-board-y += tpm2/hash_data.o
-board-y += tpm2/hkdf.o
-board-y += tpm2/manufacture.o
-board-y += tpm2/platform.o
-board-y += tpm2/post_reset.o
-board-y += tpm2/rsa.o
-board-y += tpm2/stubs.o
-board-y += tpm2/trng.o
-board-y += tpm2/upgrade.o
-board-y += wp.o
-
-# Build and link with an external library
-EXTLIB := $(realpath ../../third_party/tpm2)
-CFLAGS += -I$(EXTLIB)
-
-# For the benefit of the tpm2 library.
-INCLUDE_ROOT := $(abspath ./include)
-CFLAGS += -I$(INCLUDE_ROOT)
-CPPFLAGS += -I$(abspath ./builtin)
-CPPFLAGS += -I$(abspath ./chip/$(CHIP))
-# For core includes
-CPPFLAGS += -I$(abspath .)
-CPPFLAGS += -I$(abspath $(BDIR))
-CPPFLAGS += -I$(abspath ./test)
-
-# Make sure the context of the software sha256 implementation fits. If it ever
-# increases, a compile time assert will fire in tpm2/hash.c.
-CFLAGS += -DUSER_MIN_HASH_STATE_SIZE=112
-# Configure TPM2 headers accordingly.
-CFLAGS += -DEMBEDDED_MODE=1
-# Configure cryptoc headers to handle unaligned accesses.
-CFLAGS += -DSUPPORT_UNALIGNED=1
-
-# Add dependencies on that library
-$(out)/RW/ec.RW.elf $(out)/RW/ec.RW_B.elf: LDFLAGS_EXTRA += -L$(out)/tpm2 -ltpm2
-$(out)/RW/ec.RW.elf $(out)/RW/ec.RW_B.elf: $(out)/tpm2/libtpm2.a
-
-#$(out)/RW/ec.RW_B.elf: $(out)/tpm2/libtpm2.a LDFLAGS_EXTRA += -L$(out)/tpm2 -ltpm2
-
-# Force the external build each time, so it can look for changed sources.
-.PHONY: $(out)/tpm2/libtpm2.a
-$(out)/tpm2/libtpm2.a:
- $(MAKE) obj=$(realpath $(out))/tpm2 EMBEDDED_MODE=1 OBJ_PREFIX=Tpm2_ -C $(EXTLIB)
-
-endif # BOARD_MK_INCLUDED_ONCE is nonempty
diff --git a/board/cr50/ec.tasklist b/board/cr50/ec.tasklist
deleted file mode 100644
index b22bc4e158..0000000000
--- a/board/cr50/ec.tasklist
+++ /dev/null
@@ -1,22 +0,0 @@
-/* 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, CONFIG_STACK_SIZE) \
- TASK_NOTEST(TPM, tpm_task, NULL, 8192) \
- TASK_ALWAYS(CONSOLE, console_task, NULL, TASK_STACK_SIZE)
diff --git a/board/cr50/gpio.inc b/board/cr50/gpio.inc
deleted file mode 100644
index d129763c09..0000000000
--- a/board/cr50/gpio.inc
+++ /dev/null
@@ -1,138 +0,0 @@
-/* -*- mode:c -*-
- * Copyright (c) 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-/* Declare symbolic names for all the GPIOs that we care about.
- * Note: Those with interrupt handlers must be declared first. */
-
-/*
- * We can assert SYS_RST_L but so can the EC, so we need react if it's pulled
- * low. The ARM core can't trigger an interrupt if it's driving it as an output
- * so we attach two internal GPIOs to the same pad.
- */
-GPIO_INT(SYS_RST_L_IN, PIN(1, 0), GPIO_INT_FALLING, sys_rst_asserted)
-GPIO_INT(PLT_RST_L, PIN(1, 10), GPIO_INT_FALLING, sys_rst_asserted)
-GPIO_INT(DETECT_AP, PIN(1, 1), GPIO_INT_HIGH, device_state_on)
-GPIO_INT(DETECT_EC, PIN(1, 2), GPIO_INT_HIGH, device_state_on)
-GPIO_INT(DETECT_SERVO, PIN(1, 3), GPIO_INT_HIGH | GPIO_PULL_DOWN,
- device_state_on)
-
-/* Pull this low to interrupt the AP */
-GPIO(INT_AP_L, PIN(0, 0), GPIO_OUT_HIGH)
-
-/* Use these to take over the AP & EC flash (only when AP & EC are off!) */
-GPIO(EC_FLASH_SELECT, PIN(0, 1), GPIO_OUT_LOW)
-GPIO(AP_FLASH_SELECT, PIN(0, 2), GPIO_OUT_LOW)
-
-/* Pull this low to reset the AP. (We reset the EC with the RBOX.) */
-GPIO(SYS_RST_L_OUT, PIN(0, 4), GPIO_INPUT)
-
-/* Indicate to EC when CCD is enabled. EC can pull this down too, to tell us if
- * it decided instead. The pullup is on the EC's side. */
-GPIO(CCD_MODE_L, PIN(0, 5), GPIO_ODR_HIGH)
-
-/* Battery present signal is active low */
-GPIO(BATT_PRES_L, PIN(0, 6), GPIO_INPUT)
-
-/* GPIOs used to tristate the SPI bus */
-GPIO(SPI_MOSI, PIN(0, 7), GPIO_INPUT)
-GPIO(SPI_CLK, PIN(0, 8), GPIO_INPUT)
-GPIO(SPI_CS_L, PIN(0, 9), GPIO_INPUT)
-
-/* GPIOs used for Cr50 strapping options */
-GPIO(STRAP0, PIN(0, 10), GPIO_INPUT)
-
-/* Control the load switch powering the INA 3.3V rail */
-GPIO(EN_PP3300_INA_L, PIN(0, 11), GPIO_ODR_HIGH)
-/* GPIOs used for I2CM pins for INAs */
-GPIO(I2C_SCL_INA, PIN(0, 12), GPIO_INPUT)
-GPIO(I2C_SDA_INA, PIN(0, 13), GPIO_INPUT)
-
-/* Unimplemented signals which we need to emulate for now */
-/* TODO(wfrichar): Half the boards don't use this signal. Take it out. */
-UNIMPLEMENTED(ENTERING_RW)
-
-/*
- * If we are included by generic GPIO code that doesn't know about the PINMUX
- * macro we need to provide an empty definition so that the invocations don't
- * interfere with other GPIO processing.
- */
-#ifndef PINMUX
-#define PINMUX(...)
-#endif
-
-/* GPIOs - mark outputs as inputs too, to read back from the driven pad */
-PINMUX(GPIO(INT_AP_L), A5, DIO_INPUT) /* DIOB7 is p_digitial_od */
- /* We can't pull it up */
-PINMUX(GPIO(EC_FLASH_SELECT), B2, DIO_INPUT)
-PINMUX(GPIO(AP_FLASH_SELECT), B3, DIO_INPUT)
-PINMUX(GPIO(EN_PP3300_INA_L), B7, DIO_INPUT)
-PINMUX(GPIO(SYS_RST_L_IN), M0, DIO_WAKE_FALLING)
-PINMUX(GPIO(SYS_RST_L_OUT), M0, DIO_INPUT)
-PINMUX(GPIO(CCD_MODE_L), M1, DIO_INPUT)
-PINMUX(GPIO(BATT_PRES_L), M2, 0)
-PINMUX(GPIO(STRAP0), A1, DIO_INPUT)
-PINMUX(GPIO(I2C_SCL_INA), B0, DIO_INPUT)
-PINMUX(GPIO(I2C_SDA_INA), B1, DIO_INPUT)
-/* UARTs */
-PINMUX(FUNC(UART0_TX), A0, DIO_OUTPUT) /* Cr50 console */
-PINMUX(FUNC(UART0_RX), A13, DIO_INPUT | DIO_WAKE_FALLING)
-/*
- * UART1_TX and UART2_TX are configured in usart.c. They are not set as outputs
- * here in order to avoid interfering with servo. They can be controlled using
- * the 'uart' console command.
- * UART1_TX = DIOA7 AP console
- * UART2_TX = DIOB5 EC console
- */
-PINMUX(FUNC(UART1_RX), A3, DIO_INPUT) /* AP console */
-PINMUX(FUNC(UART2_RX), B6, DIO_INPUT) /* EC console */
-/*
- * Monitor UART RX/TX signals to detect state changes on the EC, AP, and servo.
- *
- * The idle state of the RX signals when the AP or EC are powered on is high.
- * When they are not powered, the signals will remain low. When servo is
- * connected it drives the TX signals high. The servo TX signals are wired
- * to cr50's. Because the two device TX signals are directly wired together,
- * driving the cr50 uart TX at the same time as servo is driving those pins may
- * damage both servo and cr50.
- */
-PINMUX(GPIO(DETECT_AP), A3, DIO_INPUT)
-PINMUX(GPIO(DETECT_EC), B6, DIO_INPUT)
-PINMUX(GPIO(DETECT_SERVO), B5, DIO_INPUT)
-
-/*
- * I2CS pins are bi-directional and would be configured here as shown. However,
- * A1 is also used as a strapping option GPIO input which is configured
- * above. If a board is configured (via the strapping pins) to support the I2CS
- * interface, then the connection of A1 and A9 to/from the I2C0_SDA and I2C0_SCL
- * lines is done in the function i2cs_set_pinmux() which lives in board.c.
- *
- * PINMUX(FUNC(I2C0_SCL), A9, DIO_INPUT)
- * PINMUX(FUNC(I2C0_SDA), A1, DIO_INPUT)
-*/
-
-/*
- * Both SPI master and slave buses are wired directly to specific pads
- *
- * If CONFIG_SPS is defined, these pads are used:
- * DIOA2 = SPS_MOSI (input)
- * DIOA6 = SPS_CLK (input)
- * DIOA10 = SPS_MISO (output)
- * DIOA12 = SPS_CS_L (input)
- * The digital inputs are enabled in sps.c
- *
- * If CONFIG_SPI_MASTER is defined, these pads are used:
- * DIOA4 = SPI_MOSI (output)
- * DIOA8 = SPI_CLK (output)
- * DIOA11 = SPI_MISO (input)
- * DIOA14 = SPI_CS_L (output)
- * The pads are only connected to the peripheral outputs when SPI is enabled to
- * avoid interfering with other things on the board.
- * Note: Double-check to be sure these are configured in spi_master.c
- */
-PINMUX(GPIO(SPI_MOSI), A4, DIO_OUTPUT)
-PINMUX(GPIO(SPI_CLK), A8, DIO_OUTPUT)
-PINMUX(GPIO(SPI_CS_L), A14, DIO_OUTPUT)
-#undef PINMUX
diff --git a/board/cr50/rdd.c b/board/cr50/rdd.c
deleted file mode 100644
index 1275b0dcde..0000000000
--- a/board/cr50/rdd.c
+++ /dev/null
@@ -1,332 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "case_closed_debug.h"
-#include "console.h"
-#include "device_state.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "rbox.h"
-#include "rdd.h"
-#include "registers.h"
-#include "system.h"
-#include "uartn.h"
-#include "usb_api.h"
-#include "usb_i2c.h"
-
-#define CPRINTS(format, args...) cprints(CC_USB, format, ## args)
-
-static int ec_uart_enabled, enable_usb_wakeup;
-static int usb_is_initialized;
-
-struct uart_config {
- const char *name;
- enum device_type device;
- int tx_signal;
-};
-
-static struct uart_config uarts[] = {
- [UART_AP] = {"AP", DEVICE_AP, GC_PINMUX_UART1_TX_SEL},
- [UART_EC] = {"EC", DEVICE_EC, GC_PINMUX_UART2_TX_SEL},
-};
-
-static int ccd_is_enabled(void)
-{
- return ccd_get_mode() == CCD_MODE_ENABLED;
-}
-
-int is_utmi_wakeup_allowed(void)
-{
- return enable_usb_wakeup;
-}
-
-
-/* If the UART TX is enabled the pinmux select will have a non-zero value */
-int uartn_enabled(int uart)
-{
- if (uart == UART_AP)
- return GREAD(PINMUX, DIOA7_SEL);
- return GREAD(PINMUX, DIOB5_SEL);
-}
-
-/**
- * Connect the UART pin to the given signal
- *
- * @param uart the uart peripheral number
- * @param signal the pinmux selector value for the gpio or peripheral
- * function. 0 to disable the output.
- */
-static void uart_select_tx(int uart, int signal)
-{
- if (uart == UART_AP) {
- GWRITE(PINMUX, DIOA7_SEL, signal);
- } else {
- GWRITE(PINMUX, DIOB5_SEL, signal);
-
- /* Remove the pulldown when we are driving the signal */
- GWRITE_FIELD(PINMUX, DIOB5_CTL, PD, signal ? 0 : 1);
- }
-}
-
-static int servo_is_connected(void)
-{
- return device_get_state(DEVICE_SERVO) == DEVICE_STATE_ON;
-}
-
-void uartn_tx_connect(int uart)
-{
- if (uart == UART_EC && !ec_uart_enabled)
- return;
-
- if (!ccd_is_enabled())
- return;
-
- if (servo_is_connected()) {
- CPRINTS("Servo is attached cannot enable %s UART",
- uarts[uart].name);
- return;
- }
-
- if (device_get_state(uarts[uart].device) == DEVICE_STATE_ON)
- uart_select_tx(uart, uarts[uart].tx_signal);
- else if (!uartn_enabled(uart))
- CPRINTS("%s is powered off", uarts[uart].name);
-}
-
-void uartn_tx_disconnect(int uart)
-{
- /* If servo is connected disable UART */
- if (servo_is_connected())
- ec_uart_enabled = 0;
-
- /* Disconnect the TX pin from UART peripheral */
- uart_select_tx(uart, 0);
-}
-
-void rdd_attached(void)
-{
- /* Indicate case-closed debug mode (active low) */
- gpio_set_level(GPIO_CCD_MODE_L, 0);
-
- /* Enable CCD */
- ccd_set_mode(CCD_MODE_ENABLED);
-
- enable_usb_wakeup = 1;
-
- uartn_tx_connect(UART_AP);
-}
-
-void rdd_detached(void)
-{
- /* Disconnect from AP and EC UART TX peripheral from gpios */
- uartn_tx_disconnect(UART_EC);
- uartn_tx_disconnect(UART_AP);
-
- /* Done with case-closed debug mode */
- gpio_set_level(GPIO_CCD_MODE_L, 1);
-
- enable_usb_wakeup = 0;
- ec_uart_enabled = 0;
-
- /* Disable CCD */
- ccd_set_mode(CCD_MODE_DISABLED);
-}
-
-void ccd_phy_init(int enable_ccd)
-{
- uint32_t properties = system_get_board_properties();
- /*
- * For boards that have one phy connected to the AP and one to the
- * external port PHY0 is for the AP and PHY1 is for CCD.
- */
- uint32_t which_phy = enable_ccd ? USB_SEL_PHY1 : USB_SEL_PHY0;
-
- /*
- * TODO: if both PHYs are connected to the external port select the
- * PHY based on the detected polarity
- */
- usb_select_phy(which_phy);
-
- /*
- * If the usb is going to be initialized on the AP PHY, but the AP is
- * off, wait until HOOK_CHIPSET_RESUME to initialize usb.
- */
- if (!enable_ccd && device_get_state(DEVICE_AP) != DEVICE_STATE_ON) {
- usb_is_initialized = 0;
- return;
- }
-
- /*
- * If the board has the non-ccd phy connected to the AP initialize the
- * phy no matter what. Otherwise only initialized the phy if ccd is
- * enabled.
- */
- if ((properties & BOARD_USB_AP) || enable_ccd) {
- usb_init();
- usb_is_initialized = 1;
- }
-}
-
-void disable_ap_usb(void)
-{
- if ((system_get_board_properties() & BOARD_USB_AP) &&
- !ccd_is_enabled() && usb_is_initialized) {
- usb_release();
- usb_is_initialized = 0;
- }
-}
-DECLARE_HOOK(HOOK_CHIPSET_SHUTDOWN, disable_ap_usb, HOOK_PRIO_DEFAULT);
-
-void enable_ap_usb(void)
-{
- if ((system_get_board_properties() & BOARD_USB_AP) &&
- !ccd_is_enabled() && !usb_is_initialized) {
- usb_is_initialized = 1;
- usb_init();
- }
-}
-DECLARE_HOOK(HOOK_CHIPSET_RESUME, enable_ap_usb, HOOK_PRIO_DEFAULT);
-
-static int command_ccd(int argc, char **argv)
-{
- int val;
-
- if (argc > 1) {
- if (!strcasecmp("uart", argv[1]) && argc > 2) {
- if (!parse_bool(argv[2], &val))
- return EC_ERROR_PARAM2;
-
- if (val) {
- ec_uart_enabled = 1;
- uartn_tx_connect(UART_EC);
- } else {
- ec_uart_enabled = 0;
- uartn_tx_disconnect(UART_EC);
- }
- } else if (!strcasecmp("i2c", argv[1]) && argc > 2) {
- if (!parse_bool(argv[2], &val))
- return EC_ERROR_PARAM2;
-
- if (val) {
- usb_i2c_board_enable();
- ccprintf("CCD: i2c enabled\n");
- } else {
- usb_i2c_board_disable(0);
- ccprintf("CCD: i2c disabled\n");
- }
- } else if (argc == 2) {
- if (!parse_bool(argv[1], &val))
- return EC_ERROR_PARAM1;
-
- if (val)
- rdd_attached();
- else
- rdd_detached();
- } else
- return EC_ERROR_PARAM1;
- }
-
- ccprintf("CCD: %s\nAP UART: %s\nEC UART: %s\n",
- ccd_is_enabled() ? " enabled" : "disabled",
- uartn_enabled(UART_AP) ? " enabled" : "disabled",
- uartn_enabled(UART_EC) ? " enabled" : "disabled");
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(ccd, command_ccd,
- "[uart|i2c] [<BOOLEAN>]",
- "Get/set the case closed debug state");
-
-static int command_sys_rst(int argc, char **argv)
-{
- int val;
-
- if (argc > 1) {
- if (!strcasecmp("pulse", argv[1])) {
- ccprintf("Pulsing AP reset\n");
- assert_sys_rst();
- usleep(200);
- deassert_sys_rst();
- } else if (parse_bool(argv[1], &val)) {
- if (val)
- assert_sys_rst();
- else
- deassert_sys_rst();
- } else
- return EC_ERROR_PARAM1;
- }
-
- ccprintf("SYS_RST_L is %s\n", is_sys_rst_asserted() ?
- "asserted" : "deasserted");
-
- return EC_SUCCESS;
-
-}
-DECLARE_SAFE_CONSOLE_COMMAND(sysrst, command_sys_rst,
- "[pulse | <BOOLEAN>]",
- "Assert/deassert SYS_RST_L to reset the AP");
-
-static int command_ec_rst(int argc, char **argv)
-{
- int val;
-
- if (argc > 1) {
- if (!strcasecmp("pulse", argv[1])) {
- ccprintf("Pulsing EC reset\n");
- assert_ec_rst();
- usleep(200);
- deassert_ec_rst();
- } else if (parse_bool(argv[1], &val)) {
- if (val)
- assert_ec_rst();
- else
- deassert_ec_rst();
- } else
- return EC_ERROR_PARAM1;
- }
-
- ccprintf("EC_RST_L is %s\n", is_ec_rst_asserted() ?
- "asserted" : "deasserted");
-
- return EC_SUCCESS;
-}
-DECLARE_SAFE_CONSOLE_COMMAND(ecrst, command_ec_rst,
- "[pulse | <BOOLEAN>]",
- "Assert/deassert EC_RST_L to reset the EC (and AP)");
-
-static int command_powerbtn(int argc, char **argv)
-{
- char *e;
- int ms = 200;
-
- if (argc > 1) {
- if (!strcasecmp("pulse", argv[1])) {
- if (argc == 3) {
- ms = strtoi(argv[2], &e, 0);
- if (*e)
- return EC_ERROR_PARAM2;
- }
-
- ccprintf("Force %dms power button press\n", ms);
-
- rbox_powerbtn_press();
- msleep(ms);
- rbox_powerbtn_release();
- } else if (!strcasecmp("press", argv[1])) {
- rbox_powerbtn_press();
- } else if (!strcasecmp("release", argv[1])) {
- rbox_powerbtn_release();
- } else
- return EC_ERROR_PARAM1;
- }
-
- ccprintf("powerbtn: %s\n",
- rbox_powerbtn_override_is_enabled() ? "forced press" :
- rbox_powerbtn_is_pressed() ? "pressed\n" : "released\n");
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(powerbtn, command_powerbtn,
- "[pulse [ms] | press | release]",
- "get/set the state of the power button");
diff --git a/board/cr50/tpm2/NVMem.c b/board/cr50/tpm2/NVMem.c
deleted file mode 100644
index 7874a89e86..0000000000
--- a/board/cr50/tpm2/NVMem.c
+++ /dev/null
@@ -1,214 +0,0 @@
-/* Copyright 2015 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.
- *
- * The function prototypes were extracted from the TCG Published
- * Trusted Platform Module Library
- * Part 4: Supporting Routines
- * Family "2.0"
- * Level 00 Revision 01.16
- * October 30, 2014
- */
-
-#include <string.h>
-
-#include "PlatformData.h"
-#include "TpmError.h"
-#include "assert.h"
-#include "nvmem.h"
-
-/* Local state */
-#ifndef CONFIG_FLASH_NVMEM
-static unsigned char s_NV[NV_MEMORY_SIZE];
-#endif
-static BOOL s_NvIsAvailable;
-static BOOL s_NV_unrecoverable;
-static BOOL s_NV_recoverable;
-
-/*
- * This function is used by the simulator to set the error flags in the NV
- * subsystem to simulate an error in the NV loading process.
- */
-void _plat__NvErrors(BOOL recoverable, BOOL unrecoverable)
-{
- s_NV_unrecoverable = unrecoverable;
- s_NV_recoverable = recoverable;
-}
-
-/*
- * This function should retrieve and verify the integrity of the saved context.
- * On success, the NV content has been copied into local RAM for fast access.
- *
- * The recovery from an integrity failure depends on where the error occurred.
- * It it was in the state that is discarded by TPM Reset, then the error is
- * recoverable if the TPM is reset. Otherwise, the TPM must go into failure
- * mode.
- *
- * Return Value Meaning
- *
- * 0 if success
- * >0 if receive recoverable error
- * <0 if unrecoverable error
- */
-int _plat__NVEnable(void *platParameter)
-{
- s_NV_unrecoverable = FALSE;
- s_NV_recoverable = FALSE;
-
-#ifdef CONFIG_FLASH_NVMEM
- /* TODO: Need to define what is recoverable and unrecoverable
- * conditions with regards to NvMem module. For now, the only
- * requirement is that at Cr50 board initialization time, the
- * nvmem_init() function either detects a valid partition, or
- * determines that NvMem is fully erased and configures a valid
- * partition. Setting both variables TRUE if NvMem is not available
- */
- s_NV_recoverable = nvmem_get_error_state() != 0;
- s_NV_unrecoverable = s_NV_recoverable;
-#endif
- if (s_NV_unrecoverable)
- return -1;
- return s_NV_recoverable;
-}
-
-void _plat__NVDisable(void)
-{
- /* nothing yet */
-}
-
-/*
- * Check if NV is available
- *
- * Return Value Meaning
- *
- * 0 NV is available
- * 1 NV not available due to write failure
- * 2 NV not available due to rate limit
- */
-int _plat__IsNvAvailable(void)
-{
-
-#ifdef CONFIG_FLASH_NVMEM
- int rv;
- /*
- * sNv_IsAvailable is a state variable that can be accesed by the
- * simmulator to control access to NvMemory. This variable and
- * the on chip NvMem area must be in the correct state for NvMem
- * to be in 'NV is available' state.
- */
- rv = !s_NvIsAvailable || nvmem_get_error_state();
- return rv;
-#else
- if (!s_NvIsAvailable)
- return 1;
-
- return 0;
-#endif
-}
-
-/*
- * Read a chunk of NV memory
- */
-void _plat__NvMemoryRead(unsigned int startOffset,
- unsigned int size,
- void *data)
-{
- assert(startOffset + size <= NV_MEMORY_SIZE);
- /* Copy the data from the NV image */
-#ifdef CONFIG_FLASH_NVMEM
- nvmem_read(startOffset, size, data, NVMEM_TPM);
-#else
- memcpy(data, &s_NV[startOffset], size);
-#endif
- return;
-}
-
-/*
- * This function tests to see if the NV is different from the test value.
- * Returns true if different, false if not.
- */
-BOOL
-_plat__NvIsDifferent(unsigned int startOffset,
- unsigned int size,
- void *data)
-{
-#ifdef CONFIG_FLASH_NVMEM
- return (nvmem_is_different(startOffset, size, data, NVMEM_TPM) != 0);
-#else
- return !DCRYPTO_equals(&s_NV[startOffset], data, size);
-#endif
-}
-
-/*
- * This function is used to update NV memory. The write is to a memory copy of
- * NV. At the end of the current command, any changes are written to the actual
- * NV memory.
- */
-void _plat__NvMemoryWrite(unsigned int startOffset,
- unsigned int size,
- void *data)
-{
- assert(startOffset + size <= NV_MEMORY_SIZE);
- /* Copy the data to the NV image */
-#ifdef CONFIG_FLASH_NVMEM
- nvmem_write(startOffset, size, data, NVMEM_TPM);
-#else
- memcpy(&s_NV[startOffset], data, size);
-#endif
-}
-
-/*
- * Function: Move a chunk of NV memory from source to destination,
- * handling overlap correctly.
- */
-void _plat__NvMemoryMove(unsigned int sourceOffset,
- unsigned int destOffset,
- unsigned int size)
-{
- assert(sourceOffset + size <= NV_MEMORY_SIZE);
- assert(destOffset + size <= NV_MEMORY_SIZE);
-#ifdef CONFIG_FLASH_NVMEM
- nvmem_move(sourceOffset, destOffset, size, NVMEM_TPM);
-#else
- /* Move data in RAM */
- memmove(&s_NV[destOffset], &s_NV[sourceOffset], size);
-#endif
- return;
-}
-
-/*
- * Commit the local RAM copy to NV storage.
- *
- * Return Value Meaning
- *
- * 0 NV write success
- * non-0 NV write fail
- */
-int _plat__NvCommit(void)
-{
-#ifdef CONFIG_FLASH_NVMEM
- return nvmem_commit();
-#else
- return 0;
-#endif
-}
-
-/*
- * Set the current NV state to available. This function is for testing purpose
- * only. It is not part of the platform NV logic
- */
-void _plat__SetNvAvail(void)
-{
- s_NvIsAvailable = TRUE;
- return;
-}
-
-/*
- * Set the current NV state to unavailable. This function is for testing
- * purpose only. It is not part of the platform NV logic
- */
-void _plat__ClearNvAvail(void)
-{
- s_NvIsAvailable = FALSE;
- return;
-}
diff --git a/board/cr50/tpm2/aes.c b/board/cr50/tpm2/aes.c
deleted file mode 100644
index 164f08aeb5..0000000000
--- a/board/cr50/tpm2/aes.c
+++ /dev/null
@@ -1,457 +0,0 @@
-/* Copyright 2015 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 "CryptoEngine.h"
-#include "dcrypto.h"
-
-#include <assert.h>
-
-static CRYPT_RESULT _cpri__AESBlock(
- uint8_t *out, uint32_t len, uint8_t *in);
-
-
-CRYPT_RESULT _cpri__AESDecryptCBC(
- uint8_t *out, uint32_t num_bits, uint8_t *key, uint8_t *iv,
- uint32_t len, uint8_t *in)
-{
- CRYPT_RESULT result;
-
- if (len == 0)
- return CRYPT_SUCCESS;
- assert(key != NULL && iv != NULL && in != NULL && out != NULL);
- assert(len <= INT32_MAX);
- if (!DCRYPTO_aes_init(key, num_bits, iv, CIPHER_MODE_CBC, DECRYPT_MODE))
- return CRYPT_PARAMETER;
-
- result = _cpri__AESBlock(out, len, in);
- if (result != CRYPT_SUCCESS)
- return result;
-
- DCRYPTO_aes_read_iv(iv);
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__AESDecryptCFB(uint8_t *out, uint32_t num_bits,
- uint8_t *key, uint8_t *iv, uint32_t len,
- uint8_t *in)
-{
- if (len == 0)
- return CRYPT_SUCCESS;
- assert(key != NULL && iv != NULL && out != NULL && in != NULL);
-
- /* Initialize AES hardware. */
- if (!DCRYPTO_aes_init(key, num_bits, NULL,
- CIPHER_MODE_ECB, ENCRYPT_MODE))
- return CRYPT_PARAMETER;
-
- while (len > 0) {
- int i;
- size_t chunk_len;
- uint8_t mask[16];
-
- chunk_len = MIN(len, 16);
-
- DCRYPTO_aes_block(iv, mask);
-
- memcpy(iv, in, chunk_len);
- if (chunk_len != 16)
- memset(iv + chunk_len, 0, 16 - chunk_len);
-
- for (i = 0; i < chunk_len; i++)
- *out++ = *in++ ^ mask[i];
- len -= chunk_len;
- }
-
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__AESDecryptECB(
- uint8_t *out, uint32_t num_bits, uint8_t *key, uint32_t len,
- uint8_t *in)
-{
- assert(key != NULL);
- /* Initialize AES hardware. */
- if (!DCRYPTO_aes_init(key, num_bits, NULL,
- CIPHER_MODE_ECB, DECRYPT_MODE))
- return CRYPT_PARAMETER;
- return _cpri__AESBlock(out, len, in);
-}
-
-static CRYPT_RESULT _cpri__AESBlock(
- uint8_t *out, uint32_t len, uint8_t *in)
-{
- int32_t slen;
-
- assert(out != NULL && in != NULL && len > 0 && len <= INT32_MAX);
- slen = (int32_t) len;
- if ((slen % 16) != 0)
- return CRYPT_PARAMETER;
-
- for (; slen > 0; slen -= 16) {
- DCRYPTO_aes_block(in, out);
- in = &in[16];
- out = &out[16];
- }
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__AESEncryptCBC(
- uint8_t *out, uint32_t num_bits, uint8_t *key, uint8_t *iv,
- uint32_t len, uint8_t *in)
-{
- CRYPT_RESULT result;
-
- assert(key != NULL && iv != NULL);
- if (!DCRYPTO_aes_init(key, num_bits, iv, CIPHER_MODE_CBC, ENCRYPT_MODE))
- return CRYPT_PARAMETER;
-
- result = _cpri__AESBlock(out, len, in);
- if (result != CRYPT_SUCCESS)
- return result;
-
- DCRYPTO_aes_read_iv(iv);
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__AESEncryptCFB(
- uint8_t *out, uint32_t num_bits, uint8_t *key, uint8_t *iv,
- uint32_t len, uint8_t *in)
-{
- if (len == 0)
- return CRYPT_SUCCESS;
-
- assert(out != NULL && key != NULL && iv != NULL && in != NULL);
- assert(len <= INT32_MAX);
- if (!DCRYPTO_aes_init(key, num_bits, iv, CIPHER_MODE_CTR, ENCRYPT_MODE))
- return CRYPT_PARAMETER;
-
- for (; len >= 16; len -= 16, in += 16, out += 16) {
- DCRYPTO_aes_block(in, out);
- DCRYPTO_aes_write_iv(out);
- }
- if (len > 0) {
- uint8_t buf[16];
-
- memcpy(buf, in, len);
- memset(buf+len, 0, 16-len);
- DCRYPTO_aes_block(buf, buf);
- memcpy(out, buf, len);
- memcpy(iv, buf, len);
- memset(iv+len, 0, 16-len);
- } else {
- memcpy(iv, out-16, 16);
- }
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__AESEncryptCTR(
- uint8_t *out, uint32_t num_bits, uint8_t *key, uint8_t *iv,
- uint32_t len, uint8_t *in)
-{
- if (len == 0)
- return CRYPT_SUCCESS;
-
- assert(out != NULL && key != NULL && iv != NULL && in != NULL);
- assert(len <= INT32_MAX);
-
- if (!DCRYPTO_aes_ctr(out, key, num_bits, iv, in, len))
- return CRYPT_PARAMETER;
- else
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__AESEncryptECB(
- uint8_t *out, uint32_t num_bits, uint8_t *key, uint32_t len,
- uint8_t *in)
-{
- assert(key != NULL);
- /* Initialize AES hardware. */
- if (!DCRYPTO_aes_init(key, num_bits, NULL,
- CIPHER_MODE_ECB, ENCRYPT_MODE))
- return CRYPT_PARAMETER;
- return _cpri__AESBlock(out, len, in);
-}
-
-CRYPT_RESULT _cpri__AESEncryptOFB(
- uint8_t *out, uint32_t num_bits, uint8_t *key, uint8_t *iv,
- uint32_t len, uint8_t *in)
-{
- uint8_t *ivp;
- int32_t slen;
- int i;
-
- if (len == 0)
- return CRYPT_SUCCESS;
-
- assert(out != NULL && key != NULL && iv != NULL && in != NULL);
- assert(len <= INT32_MAX);
- slen = (int32_t) len;
- /* Initialize AES hardware. */
- if (!DCRYPTO_aes_init(key, num_bits, NULL,
- CIPHER_MODE_ECB, ENCRYPT_MODE))
- return CRYPT_PARAMETER;
-
- for (; slen > 0; slen -= 16) {
- DCRYPTO_aes_block(iv, iv);
- ivp = iv;
- for (i = (slen < 16) ? slen : 16; i > 0; i--)
- *out++ = (*ivp++ ^ *in++);
- }
- return CRYPT_SUCCESS;
-}
-
-#ifdef CRYPTO_TEST_SETUP
-
-#include "console.h"
-#include "extension.h"
-#include "hooks.h"
-#include "uart.h"
-
-enum aes_test_cipher_mode {
- TEST_MODE_ECB = 0,
- TEST_MODE_CTR = 1,
- TEST_MODE_CBC = 2,
- TEST_MODE_GCM = 3,
- TEST_MODE_OFB = 4,
- TEST_MODE_CFB = 5,
-};
-
-#define CPRINTF(format, args...) cprintf(CC_EXTENSION, format, ## args)
-
-static void aes_command_handler(void *cmd_body,
- size_t cmd_size,
- size_t *response_size)
-{
- uint8_t *key;
- uint16_t key_len;
- uint8_t iv_len;
- uint8_t *iv;
- enum aes_test_cipher_mode c_mode;
- enum encrypt_mode e_mode;
- uint8_t *cmd = (uint8_t *)cmd_body;
- int16_t data_len;
- unsigned max_data_len = *response_size;
- unsigned actual_cmd_size;
-
- /* Copy inputs into a local unaligned buffer, so as to ensure
- * that api's are memory-alignment agnostic.
- */
- struct unaligned_buf {
- uint8_t unused;
- uint8_t b[128];
- } __packed;
-
- struct unaligned_buf out_local;
- struct unaligned_buf iv_local;
- struct unaligned_buf key_local;
- struct unaligned_buf data_local;
-
- *response_size = 0;
-
- /*
- * Command structure, shared out of band with the test driver running
- * on the host:
- *
- * field | size | note
- * ================================================================
- * mode | 1 | 0 - decrypt, 1 - encrypt
- * cipher_mode | 1 | as per aes_test_cipher_mode
- * key_len | 1 | key size in bytes (16, 24 or 32)
- * key | key len | key to use
- * iv_len | 1 | either 0 or 16
- * iv | 0 or 16 | as defined by iv_len
- * text_len | 2 | size of the text to process, big endian
- * text | text_len | text to encrypt/decrypt
- */
- e_mode = *cmd++;
- c_mode = *cmd++;
- key_len = *cmd++;
-
- if ((key_len != 16) && (key_len != 24) && (key_len != 32)) {
- CPRINTF("Invalid key len %d\n", key_len * 8);
- return;
- }
- key = cmd;
- cmd += key_len;
- key_len *= 8;
- iv_len = *cmd++;
- if (iv_len && (iv_len != 16)) {
- CPRINTF("Invalid vector len %d\n", iv_len);
- return;
- }
- iv = cmd;
- cmd += iv_len;
- data_len = *cmd++;
- data_len = data_len * 256 + *cmd++;
-
- /*
- * We know that the receive buffer is at least this big, i.e. all the
- * preceding fields are guaranteed to fit.
- *
- * Now is a good time to verify overall sanity of the received
- * payload: does the actual size match the added up sizes of the
- * pieces.
- */
- actual_cmd_size = cmd - (const uint8_t *)cmd_body + data_len;
- if (actual_cmd_size != cmd_size) {
- CPRINTF("Command size mismatch: %d != %d (data len %d)\n",
- actual_cmd_size, cmd_size, data_len);
- return;
- }
-
- if (((data_len + 15) & ~15) > max_data_len) {
- CPRINTF("Response buffer too small\n");
- return;
- }
-
- if (data_len > sizeof(out_local.b)) {
- CPRINTF("Response buffer too small\n");
- return;
- }
-
- memset(out_local.b, 'A', sizeof(out_local.b));
- memcpy(iv_local.b, iv, iv_len);
- memcpy(key_local.b, key, key_len / 8);
- memcpy(data_local.b, cmd, data_len);
-
- switch (c_mode) {
- case TEST_MODE_ECB:
- if (e_mode == 0) {
- if (_cpri__AESDecryptECB(
- out_local.b, key_len, key_local.b,
- data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- } else if (e_mode == 1) {
- /* pad input data to integer block size. */
- while (data_len & 15)
- data_local.b[data_len++] = 0;
- if (_cpri__AESEncryptECB(
- out_local.b, key_len, key_local.b,
- data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- }
- break;
- case TEST_MODE_CTR:
- if (e_mode == 0) {
- if (_cpri__AESDecryptCTR(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- } else if (e_mode == 1) {
- /* pad input data to integer block size. */
- while (data_len & 15)
- data_local.b[data_len++] = 0;
- if (_cpri__AESEncryptCTR(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- }
- break;
- case TEST_MODE_CBC:
- {
- if (e_mode == 0) {
- if (_cpri__AESDecryptCBC(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- } else if (e_mode == 1) {
- if (_cpri__AESEncryptCBC(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- }
- break;
- }
- case TEST_MODE_OFB:
- if (e_mode == 0) {
- if (_cpri__AESDecryptOFB(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- } else if (e_mode == 1) {
- if (_cpri__AESEncryptOFB(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- }
- break;
- case TEST_MODE_CFB:
- {
- if (e_mode == 0) {
- if (_cpri__AESDecryptCFB(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- } else if (e_mode == 1) {
- if (_cpri__AESEncryptCFB(
- out_local.b, key_len, key_local.b,
- iv_local.b, data_len, data_local.b) ==
- CRYPT_SUCCESS) {
- *response_size = data_len;
- }
- CPRINTF("%s:%d response size %d\n",
- __func__, __LINE__, *response_size);
- }
- break;
- }
- default:
- break;
- }
-
- if (*response_size > 0) {
- int i;
-
- for (i = *response_size; i < sizeof(out_local.b); i++) {
- if (out_local.b[i] != 'A') {
- CPRINTF(
- "%s:%d output overwrite at offset %d\n",
- __func__, __LINE__, i);
- *response_size = 0;
- }
- }
-
- memcpy(cmd_body, out_local.b, *response_size);
- }
-}
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_AES, aes_command_handler);
-
-#endif /* CRYPTO_TEST_SETUP */
diff --git a/board/cr50/tpm2/ecc.c b/board/cr50/tpm2/ecc.c
deleted file mode 100644
index 0cb8493b72..0000000000
--- a/board/cr50/tpm2/ecc.c
+++ /dev/null
@@ -1,592 +0,0 @@
-/* Copyright 2015 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.
- */
-/*
- * TODO(ngm): only the NIST-P256 curve is currently supported.
- */
-
-#include "CryptoEngine.h"
-#include "TPMB.h"
-
-#include "trng.h"
-#include "util.h"
-#include "dcrypto.h"
-
-#include "cryptoc/p256.h"
-#include "cryptoc/p256_ecdsa.h"
-
-static void reverse_tpm2b(TPM2B *b)
-{
- reverse(b->buffer, b->size);
-}
-
-TPM2B_BYTE_VALUE(4);
-TPM2B_BYTE_VALUE(32);
-
-static int check_p256_param(const TPM2B_ECC_PARAMETER *a)
-{
- return a->b.size == sizeof(p256_int);
-}
-
-static int check_p256_point(const TPMS_ECC_POINT *a)
-{
- return check_p256_param(&a->x) &&
- check_p256_param(&a->y);
-}
-
-BOOL _cpri__EccIsPointOnCurve(TPM_ECC_CURVE curve_id, TPMS_ECC_POINT *q)
-{
- int result;
-
- switch (curve_id) {
- case TPM_ECC_NIST_P256:
- if (!check_p256_point(q))
- return FALSE;
-
- reverse_tpm2b(&q->x.b);
- reverse_tpm2b(&q->y.b);
-
- result = p256_is_valid_point((p256_int *) q->x.b.buffer,
- (p256_int *) q->y.b.buffer);
-
- reverse_tpm2b(&q->x.b);
- reverse_tpm2b(&q->y.b);
-
- if (result)
- return TRUE;
- else
- return FALSE;
- default:
- return FALSE;
- }
-}
-
-/* out = n1*G, or out = n2*in */
-CRYPT_RESULT _cpri__EccPointMultiply(
- TPMS_ECC_POINT *out, TPM_ECC_CURVE curve_id,
- TPM2B_ECC_PARAMETER *n1, TPMS_ECC_POINT *in, TPM2B_ECC_PARAMETER *n2)
-{
- int result;
-
- switch (curve_id) {
- case TPM_ECC_NIST_P256:
- if ((n1 != NULL && n2 != NULL) ||
- (n1 == NULL && n2 == NULL))
- /* Only one of n1 or n2 must be specified. */
- return CRYPT_PARAMETER;
- if ((n2 != NULL && in == NULL) ||
- (n2 == NULL && in != NULL))
- return CRYPT_PARAMETER;
- if (n1 != NULL && !check_p256_param(n1))
- return CRYPT_PARAMETER;
- if (in != NULL &&
- (!check_p256_point(in) ||
- !_cpri__EccIsPointOnCurve(curve_id, in)))
- return CRYPT_POINT;
- if (n2 != NULL && !check_p256_param(n2))
- return CRYPT_PARAMETER;
-
- if (n1 != NULL) {
- reverse_tpm2b(&n1->b);
-
- result = DCRYPTO_p256_base_point_mul(
- (p256_int *) out->x.b.buffer,
- (p256_int *) out->y.b.buffer,
- (p256_int *) n1->b.buffer);
-
- reverse_tpm2b(&n1->b);
- } else {
- reverse_tpm2b(&n2->b);
- reverse_tpm2b(&in->x.b);
- reverse_tpm2b(&in->y.b);
-
- result = DCRYPTO_p256_point_mul(
- (p256_int *) out->x.b.buffer,
- (p256_int *) out->y.b.buffer,
- (p256_int *) n2->b.buffer,
- (p256_int *) in->x.b.buffer,
- (p256_int *) in->y.b.buffer);
-
- reverse_tpm2b(&n2->b);
- reverse_tpm2b(&in->x.b);
- reverse_tpm2b(&in->y.b);
- }
-
- if (result) {
- out->x.b.size = sizeof(p256_int);
- out->y.b.size = sizeof(p256_int);
- reverse_tpm2b(&out->x.b);
- reverse_tpm2b(&out->y.b);
-
- return CRYPT_SUCCESS;
- } else {
- return CRYPT_NO_RESULT;
- }
- default:
- return CRYPT_PARAMETER;
- }
-}
-
-static const TPM2B_32_BYTE_VALUE ECC_TEMPLATE_EK_EXTRA = {
- .t = {32, {
- 0xC2, 0xE0, 0x31, 0x93, 0x40, 0xFB, 0x48, 0xF1,
- 0x02, 0x53, 0x9E, 0xA9, 0x83, 0x63, 0xF8, 0x1E,
- 0x2D, 0x30, 0x6E, 0x91, 0x8D, 0xD7, 0x78, 0xAB,
- 0xF0, 0x54, 0x73, 0xA2, 0xA6, 0x0D, 0xAE, 0x09,
- }
- }
-};
-
-/* Key generation based on FIPS-186.4 section B.1.2 (Key Generation by
- * Testing Candidates) */
-CRYPT_RESULT _cpri__GenerateKeyEcc(
- TPMS_ECC_POINT *q, TPM2B_ECC_PARAMETER *d,
- TPM_ECC_CURVE curve_id, TPM_ALG_ID hash_alg,
- TPM2B *seed, const char *label, TPM2B *extra, UINT32 *counter)
-{
- TPM2B_4_BYTE_VALUE marshaled_counter = { .t = {4} };
- TPM2B_32_BYTE_VALUE local_seed = { .t = {32} };
- TPM2B_4_BYTE_VALUE truncated_extra = { .t = {4} };
- TPM2B *local_extra;
- uint32_t count = 0;
- uint8_t key_bytes[P256_NBYTES];
- LITE_HMAC_CTX hmac;
-
- if (curve_id != TPM_ECC_NIST_P256)
- return CRYPT_PARAMETER;
-
- /* extra may be empty, but seed must be specified. */
- if (seed == NULL || seed->size < PRIMARY_SEED_SIZE)
- return CRYPT_PARAMETER;
-
- if (counter != NULL)
- count = *counter;
- if (count == 0)
- count++;
-
- /* Hash down the primary seed for ECC key generation, so that
- * the derivation tree is distinct from RSA key derivation. */
- DCRYPTO_HMAC_SHA256_init(&hmac, seed->buffer, seed->size);
- HASH_update(&hmac.hash, "ECC", 4);
- memcpy(local_seed.t.buffer, DCRYPTO_HMAC_final(&hmac),
- local_seed.t.size);
- /* TODO(ngm): CRBUG/P/55260: the personalize code uses only
- * the first 4 bytes of extra.
- */
- if (extra && extra->size == ECC_TEMPLATE_EK_EXTRA.b.size &&
- memcmp(extra->buffer,
- ECC_TEMPLATE_EK_EXTRA.b.buffer,
- ECC_TEMPLATE_EK_EXTRA.b.size) == 0) {
- memcpy(truncated_extra.b.buffer, extra->buffer, 4);
- local_extra = &truncated_extra.b;
- } else {
- local_extra = extra;
- }
-
- for (; count != 0; count++) {
- memcpy(marshaled_counter.t.buffer, &count, sizeof(count));
- _cpri__KDFa(hash_alg, &local_seed.b, label, local_extra,
- &marshaled_counter.b, sizeof(key_bytes) * 8, key_bytes,
- NULL, FALSE);
- if (DCRYPTO_p256_key_from_bytes(
- (p256_int *) q->x.b.buffer,
- (p256_int *) q->y.b.buffer,
- (p256_int *) d->b.buffer, key_bytes)) {
- q->x.b.size = sizeof(p256_int);
- q->y.b.size = sizeof(p256_int);
- reverse_tpm2b(&q->x.b);
- reverse_tpm2b(&q->y.b);
-
- d->b.size = sizeof(p256_int);
- reverse_tpm2b(&d->b);
-
- break;
- }
- }
- /* TODO(ngm): implement secure memset. */
- memset(local_seed.t.buffer, 0, local_seed.t.size);
-
- if (count == 0)
- FAIL(FATAL_ERROR_INTERNAL);
- if (counter != NULL)
- *counter = count;
-
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__SignEcc(
- TPM2B_ECC_PARAMETER *r, TPM2B_ECC_PARAMETER *s,
- TPM_ALG_ID scheme, TPM_ALG_ID hash_alg, TPM_ECC_CURVE curve_id,
- TPM2B_ECC_PARAMETER *d, TPM2B *digest, TPM2B_ECC_PARAMETER *k)
-{
- uint8_t digest_local[sizeof(p256_int)];
- const size_t digest_len = MIN(digest->size, sizeof(digest_local));
- p256_int p256_digest;
-
- if (curve_id != TPM_ECC_NIST_P256)
- return CRYPT_PARAMETER;
-
- switch (scheme) {
- case TPM_ALG_ECDSA:
- if (!check_p256_param(d))
- return CRYPT_PARAMETER;
- /* Trucate / zero-pad the digest as appropriate. */
- memset(digest_local, 0, sizeof(digest_local));
- memcpy(digest_local + sizeof(digest_local) - digest_len,
- digest->buffer, digest_len);
- p256_from_bin(digest_local, &p256_digest);
-
- reverse_tpm2b(&d->b);
-
- p256_ecdsa_sign((p256_int *) d->b.buffer,
- &p256_digest,
- (p256_int *) r->b.buffer,
- (p256_int *) s->b.buffer);
- reverse_tpm2b(&d->b);
-
- r->b.size = sizeof(p256_int);
- s->b.size = sizeof(p256_int);
- reverse_tpm2b(&r->b);
- reverse_tpm2b(&s->b);
-
- return CRYPT_SUCCESS;
- default:
- return CRYPT_PARAMETER;
- }
-}
-
-CRYPT_RESULT _cpri__ValidateSignatureEcc(
- TPM2B_ECC_PARAMETER *r, TPM2B_ECC_PARAMETER *s,
- TPM_ALG_ID scheme, TPM_ALG_ID hash_alg,
- TPM_ECC_CURVE curve_id, TPMS_ECC_POINT *q, TPM2B *digest)
-{
- uint8_t digest_local[sizeof(p256_int)];
- const size_t digest_len = MIN(digest->size, sizeof(digest_local));
- p256_int p256_digest;
- int result;
-
- if (curve_id != TPM_ECC_NIST_P256)
- return CRYPT_PARAMETER;
-
- switch (scheme) {
- case TPM_ALG_ECDSA:
- /* Trucate / zero-pad the digest as appropriate. */
- memset(digest_local, 0, sizeof(digest_local));
- memcpy(digest_local + sizeof(digest_local) - digest_len,
- digest->buffer, digest_len);
- p256_from_bin(digest_local, &p256_digest);
-
- reverse_tpm2b(&q->x.b);
- reverse_tpm2b(&q->y.b);
-
- reverse_tpm2b(&r->b);
- reverse_tpm2b(&s->b);
-
- result = p256_ecdsa_verify(
- (p256_int *) q->x.b.buffer,
- (p256_int *) q->y.b.buffer,
- &p256_digest,
- (p256_int *) r->b.buffer,
- (p256_int *) s->b.buffer);
-
- reverse_tpm2b(&q->x.b);
- reverse_tpm2b(&q->y.b);
-
- reverse_tpm2b(&r->b);
- reverse_tpm2b(&s->b);
-
- if (result)
- return CRYPT_SUCCESS;
- else
- return CRYPT_FAIL;
- default:
- return CRYPT_PARAMETER;
- }
-}
-
-CRYPT_RESULT _cpri__GetEphemeralEcc(TPMS_ECC_POINT *q, TPM2B_ECC_PARAMETER *d,
- TPM_ECC_CURVE curve_id)
-{
- uint8_t key_bytes[P256_NBYTES] __aligned(4);
-
- if (curve_id != TPM_ECC_NIST_P256)
- return CRYPT_PARAMETER;
-
- rand_bytes(key_bytes, sizeof(key_bytes));
-
- if (DCRYPTO_p256_key_from_bytes((p256_int *) q->x.b.buffer,
- (p256_int *) q->y.b.buffer,
- (p256_int *) d->b.buffer,
- key_bytes)) {
- q->x.b.size = sizeof(p256_int);
- q->y.b.size = sizeof(p256_int);
- reverse_tpm2b(&q->x.b);
- reverse_tpm2b(&q->y.b);
-
- d->b.size = sizeof(p256_int);
- reverse_tpm2b(&d->b);
-
- return CRYPT_SUCCESS;
- } else {
- return CRYPT_FAIL;
- }
-}
-
-#ifdef CRYPTO_TEST_SETUP
-
-#include "extension.h"
-
-enum {
- TEST_SIGN = 0,
- TEST_VERIFY = 1,
- TEST_KEYGEN = 2,
- TEST_KEYDERIVE = 3
-};
-
-struct TPM2B_ECC_PARAMETER_aligned {
- uint16_t pad;
- TPM2B_ECC_PARAMETER d;
-} __packed __aligned(4);
-
-struct TPM2B_MAX_BUFFER_aligned {
- uint16_t pad;
- TPM2B_MAX_BUFFER d;
-} __packed __aligned(4);
-
-static const struct TPM2B_ECC_PARAMETER_aligned NIST_P256_d = {
- .d = {
- .t = {32, {
- 0xfc, 0x44, 0x1e, 0x07, 0x74, 0x4e, 0x48, 0xf1,
- 0x09, 0xb7, 0xe6, 0x6b, 0x29, 0x48, 0x2f, 0x7b,
- 0x7e, 0x3e, 0xc9, 0x1f, 0xa2, 0x7f, 0xd4, 0x87,
- 0x09, 0x91, 0xb2, 0x89, 0xfe, 0xa0, 0xd2, 0x0a
- }
- }
- }
-};
-
-static const struct TPM2B_ECC_PARAMETER_aligned NIST_P256_qx = {
- .d = {
- .t = {32, {
- 0x12, 0xc3, 0xd6, 0xa2, 0x67, 0x9c, 0xa8, 0xee,
- 0x3c, 0x4d, 0x92, 0x7f, 0x20, 0x4e, 0xd5, 0xbc,
- 0xb4, 0x57, 0x7a, 0x04, 0xb0, 0xac, 0x02, 0xb2,
- 0xa3, 0x6a, 0xb3, 0xe9, 0xe1, 0x07, 0x81, 0xde
- }
- }
- }
-};
-
-static const struct TPM2B_ECC_PARAMETER_aligned NIST_P256_qy = {
- .d = {
- .t = {32, {
- 0x5c, 0x85, 0xad, 0x74, 0x13, 0x97, 0x11, 0x72,
- 0xfc, 0xa5, 0x73, 0x8f, 0xee, 0x9d, 0x0e, 0x7b,
- 0xc5, 0x9f, 0xfd, 0x8a, 0x62, 0x6d, 0x68, 0x9b,
- 0xc6, 0xcc, 0xa4, 0xb5, 0x86, 0x65, 0x52, 0x1d
- }
- }
- }
-};
-
-#define MAX_MSG_BYTES MAX_DIGEST_BUFFER
-
-static int point_equals(const TPMS_ECC_POINT *a, const TPMS_ECC_POINT *b)
-{
- int diff = 0;
-
- diff = a->x.b.size != b->x.b.size;
- diff |= a->y.b.size != b->y.b.size;
- if (!diff) {
- diff |= !DCRYPTO_equals(
- a->x.b.buffer, b->x.b.buffer, a->x.b.size);
- diff |= !DCRYPTO_equals(
- a->y.b.buffer, b->y.b.buffer, a->y.b.size);
- }
-
- return !diff;
-}
-
-static void ecc_command_handler(void *cmd_body, size_t cmd_size,
- size_t *response_size_out)
-{
- uint8_t *cmd;
- uint8_t op;
- uint8_t curve_id;
- uint8_t sign_mode;
- uint8_t hashing;
- uint16_t in_len;
- uint8_t in[MAX_MSG_BYTES];
- uint16_t digest_len;
- struct TPM2B_MAX_BUFFER_aligned digest;
- uint8_t *out = (uint8_t *) cmd_body;
- uint32_t *response_size = (uint32_t *) response_size_out;
-
- TPMS_ECC_POINT q;
- TPM2B_ECC_PARAMETER d;
- struct TPM2B_ECC_PARAMETER_aligned r;
- struct TPM2B_ECC_PARAMETER_aligned s;
-
- /* Command format.
- *
- * OFFSET FIELD
- * 0 OP
- * 1 CURVE_ID
- * 2 SIGN_MODE
- * 3 HASHING
- * 4 MSB IN LEN
- * 5 LSB IN LEN
- * 6 IN
- * 6 + IN_LEN MSB DIGEST LEN
- * 7 + IN_LEN LSB DIGEST LEN
- * 8 + IN_LEN DIGEST
- */
-
- cmd = (uint8_t *) cmd_body;
- op = *cmd++;
- curve_id = *cmd++;
- sign_mode = *cmd++;
- hashing = *cmd++;
- in_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- if (in_len > sizeof(in)) {
- *response_size = 0;
- return;
- }
- memcpy(in, cmd, in_len);
- cmd += in_len;
-
- digest_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- if (digest_len > sizeof(digest.d.t.buffer)) {
- *response_size = 0;
- return;
- }
- digest.d.t.size = digest_len;
- memcpy(digest.d.t.buffer, cmd, digest_len);
- cmd += digest_len;
-
- /* Make copies of d, and q, as const data is immutable. */
- switch (curve_id) {
- case TPM_ECC_NIST_P256:
- d = NIST_P256_d.d;
- q.x = NIST_P256_qx.d;
- q.y = NIST_P256_qy.d;
- break;
- default:
- *response_size = 0;
- return;
- }
-
- switch (op) {
- case TEST_SIGN:
- if (_cpri__SignEcc(&r.d, &s.d, sign_mode, hashing,
- curve_id, &d, &digest.d.b, NULL)
- != CRYPT_SUCCESS) {
- *response_size = 0;
- return;
- }
- memcpy(out, r.d.b.buffer, r.d.b.size);
- out += r.d.b.size;
- memcpy(out, s.d.b.buffer, s.d.b.size);
- *response_size = r.d.b.size + s.d.b.size;
- break;
- case TEST_VERIFY:
- r.d.b.size = in_len / 2;
- memcpy(r.d.b.buffer, in, r.d.b.size);
- s.d.b.size = in_len / 2;
- memcpy(s.d.b.buffer, in + r.d.b.size, s.d.b.size);
- if (_cpri__ValidateSignatureEcc(
- &r.d, &s.d, sign_mode, hashing, curve_id,
- &q, &digest.d.b) != CRYPT_SUCCESS) {
- *response_size = 0;
- } else {
- *out = 1;
- *response_size = 1;
- }
- return;
- case TEST_KEYGEN:
- {
- struct TPM2B_ECC_PARAMETER_aligned d_local;
- TPMS_ECC_POINT q_local;
-
- if (_cpri__GetEphemeralEcc(&q, &d_local.d, curve_id)
- != CRYPT_SUCCESS) {
- *response_size = 0;
- return;
- }
-
- if (_cpri__EccIsPointOnCurve(curve_id, &q) != TRUE) {
- *response_size = 0;
- return;
- }
-
- /* Verify correspondence of secret with the public point. */
- if (_cpri__EccPointMultiply(
- &q_local, curve_id, &d_local.d,
- NULL, NULL) != CRYPT_SUCCESS) {
- *response_size = 0;
- return;
- }
- if (!point_equals(&q, &q_local)) {
- *response_size = 0;
- return;
- }
- *out = 1;
- *response_size = 1;
- return;
- }
- case TEST_KEYDERIVE:
- {
- /* Random seed. */
- TPM2B_SEED seed;
- struct TPM2B_ECC_PARAMETER_aligned d_local;
- TPMS_ECC_POINT q_local;
- const char *label = "ecc_test";
-
-
- if (in_len > PRIMARY_SEED_SIZE) {
- *response_size = 0;
- return;
- }
- seed.t.size = in_len;
- memcpy(seed.t.buffer, in, in_len);
-
- if (_cpri__GenerateKeyEcc(
- &q, &d_local.d, curve_id, hashing,
- &seed.b, label, NULL, NULL) != CRYPT_SUCCESS) {
- *response_size = 0;
- return;
- }
-
- if (_cpri__EccIsPointOnCurve(curve_id, &q) != TRUE) {
- *response_size = 0;
- return;
- }
-
- /* Verify correspondence of secret with the public point. */
- if (_cpri__EccPointMultiply(
- &q_local, curve_id, &d_local.d,
- NULL, NULL) != CRYPT_SUCCESS) {
- *response_size = 0;
- return;
- }
- if (!point_equals(&q, &q_local)) {
- *response_size = 0;
- return;
- }
-
- *out = 1;
- *response_size = 1;
- return;
- }
- default:
- *response_size = 0;
- return;
- }
-}
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_ECC, ecc_command_handler);
-
-#endif /* CRYPTO_TEST_SETUP */
diff --git a/board/cr50/tpm2/ecies.c b/board/cr50/tpm2/ecies.c
deleted file mode 100644
index 6f89d79396..0000000000
--- a/board/cr50/tpm2/ecies.c
+++ /dev/null
@@ -1,126 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "dcrypto.h"
-
-#ifdef CRYPTO_TEST_SETUP
-
-#include "extension.h"
-
-enum {
- TEST_ENCRYPT = 0,
- TEST_DECRYPT = 1,
-};
-
-#define MAX_OUT_BYTES 256
-
-#define AES_BLOCK_BYTES 16
-
-static void ecies_command_handler(void *cmd_body, size_t cmd_size,
- size_t *response_size)
-{
- uint8_t *cmd = cmd_body;
- uint8_t *out = cmd_body;
-
- uint8_t op;
- uint8_t *in;
- size_t in_len;
- size_t auth_data_len;
- const uint8_t *iv;
- size_t iv_len = AES_BLOCK_BYTES;
- p256_int pub_x;
- size_t pub_x_len;
- p256_int pub_y;
- size_t pub_y_len;
- p256_int *d = &pub_x;
- const uint8_t *salt;
- size_t salt_len;
- const uint8_t *info;
- size_t info_len;
-
- /* Command format.
- *
- * WIDTH FIELD
- * 1 OP
- * 1 MSB IN LEN
- * 1 LSB IN LEN
- * IN_LEN IN
- * 1 MSB AUTH_DATA LEN
- * 1 LSB AUTH_DATA LEN
- * 16 IV
- * 1 MSB PUB_X LEN
- * 1 LSB PUB_X LEN
- * PUB_X_LEN PUB_X
- * 1 MSB PUB_Y LEN
- * 1 LSB PUB_Y LEN
- * PUB_Y_LEN PUB_Y
- * 1 MSB SALT LEN
- * 1 LSB SALT LEN
- * SALT_LEN SALT
- * 1 MSB INFO LEN
- * 1 LSB INFO LEN
- * INFO_LEN INFO
- */
-
- op = *cmd++;
- in_len = ((size_t) cmd[0]) << 8 | cmd[1];
- cmd += 2;
- in = cmd;
- cmd += in_len;
-
- auth_data_len = ((size_t) cmd[0]) << 8 | cmd[1];
- cmd += 2;
-
- iv = cmd;
- cmd += iv_len;
-
- pub_x_len = ((size_t) cmd[0]) << 8 | cmd[1];
- cmd += 2;
- p256_from_bin(cmd, &pub_x);
- cmd += pub_x_len;
-
- pub_y_len = ((size_t) cmd[0]) << 8 | cmd[1];
- cmd += 2;
- if (pub_y_len)
- p256_from_bin(cmd, &pub_y);
- cmd += pub_y_len;
-
- salt_len = ((size_t) cmd[0]) << 8 | cmd[1];
- cmd += 2;
- salt = cmd;
- cmd += salt_len;
-
- info_len = ((size_t) cmd[0]) << 8 | cmd[1];
- cmd += 2;
- info = cmd;
- cmd += info_len;
-
- switch (op) {
- case TEST_ENCRYPT:
- *response_size = DCRYPTO_ecies_encrypt(
- in, MAX_OUT_BYTES, in, in_len,
- auth_data_len, iv,
- &pub_x, &pub_y, salt, salt_len,
- info, info_len);
- break;
- case TEST_DECRYPT:
- *response_size = DCRYPTO_ecies_decrypt(
- in, MAX_OUT_BYTES, in, in_len,
- auth_data_len, iv,
- d, salt, salt_len,
- info, info_len);
- break;
- default:
- *response_size = 0;
- }
-
- if (*response_size > 0)
- memmove(out, in, *response_size);
-}
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_ECIES, ecies_command_handler);
-
-#endif /* CRYPTO_TEST_SETUP */
-
diff --git a/board/cr50/tpm2/endian.h b/board/cr50/tpm2/endian.h
deleted file mode 100644
index b5b64d3bea..0000000000
--- a/board/cr50/tpm2/endian.h
+++ /dev/null
@@ -1,11 +0,0 @@
-/* Copyright 2015 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 __EC_BOARD_CR50_TPM2_ENDIAN_H
-#define __EC_BOARD_CR50_TPM2_ENDIAN_H
-
-#include "byteorder.h"
-
-#endif /* __EC_BOARD_CR50_TPM2_ENDIAN_H */
diff --git a/board/cr50/tpm2/endorsement.c b/board/cr50/tpm2/endorsement.c
deleted file mode 100644
index 3b4f0d99c6..0000000000
--- a/board/cr50/tpm2/endorsement.c
+++ /dev/null
@@ -1,752 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "TPM_Types.h"
-#include "TpmBuildSwitches.h"
-#include "CryptoEngine.h"
-#include "CpriECC_fp.h"
-#include "CpriRSA_fp.h"
-#include "tpm_types.h"
-
-#include "Global.h"
-#include "Hierarchy_fp.h"
-#include "InternalRoutines.h"
-#include "Manufacture_fp.h"
-#include "NV_Write_fp.h"
-#include "NV_DefineSpace_fp.h"
-
-#include "console.h"
-#include "extension.h"
-#include "flash.h"
-#include "flash_config.h"
-#include "flash_info.h"
-#include "printf.h"
-#include "registers.h"
-#include "tpm_manufacture.h"
-#include "tpm_registers.h"
-
-#include "dcrypto.h"
-
-#include <cryptoc/sha256.h>
-
-#include <endian.h>
-#include <string.h>
-
-#define CPRINTF(format, args...) cprintf(CC_EXTENSION, format, ## args)
-
-#define EK_CERT_NV_START_INDEX 0x01C00000
-#define INFO1_EPS_SIZE PRIMARY_SEED_SIZE
-#define INFO1_EPS_OFFSET FLASH_INFO_MANUFACTURE_STATE_OFFSET
-#define AES256_BLOCK_CIPHER_KEY_SIZE 32
-
-#define RO_CERTS_START_ADDR 0x43800
-#define RO_CERTS_REGION_SIZE 0x0800
-
-enum cros_perso_component_type {
- CROS_PERSO_COMPONENT_TYPE_EPS = 128,
- CROS_PERSO_COMPONENT_TYPE_RSA_CERT = 129,
- CROS_PERSO_COMPONENT_TYPE_P256_CERT = 130
-};
-
-struct cros_perso_response_component_info_v0 {
- uint16_t component_size;
- uint8_t component_type;
- uint8_t reserved[5];
-} __packed; /* Size: 8B */
-
-/* key_id: key for which this is the certificate */
-/* cert_len: length of the following certificate */
-/* cert: the certificate bytes */
-struct cros_perso_certificate_response_v0 {
- uint8_t key_id[4];
- uint32_t cert_len;
- uint8_t cert[0];
-} __packed; /* Size: 8B */
-
-/* Personalization response. */
-BUILD_ASSERT(sizeof(struct cros_perso_response_component_info_v0) == 8);
-BUILD_ASSERT(sizeof(struct cros_perso_certificate_response_v0) == 8);
-
-/* This is a fixed seed (and corresponding certificates) for use in a
- * developer environment. Use of this fixed seed will be triggered if
- * the HMAC on the certificate region (i.e. read-only certificates
- * written at manufacture) fails to verify.
- *
- * The HMAC verification failure itself only occurs in the event that
- * RO & RW are signed in a mode that does correspond to the
- * manufacture process, i.e. a PRODUCTION mode chip installed with DEV
- * signed RO/RW (or vice-versa) or a PRODUCTION signed RO and DEV
- * signed RW (or vice-versa).
- *
- * The fixed seed and its corresponding certificates are not trusted
- * by production infrastructure, and are hence useful for development
- * and testing.
- */
-const uint8_t FIXED_ENDORSEMENT_SEED[PRIMARY_SEED_SIZE] = {
- 0x1c, 0xb0, 0xde, 0x0e, 0x96, 0xe5, 0x58, 0xb0,
- 0xad, 0x1d, 0x3a, 0x08, 0x22, 0x41, 0x7f, 0x45,
- 0x37, 0xe7, 0x17, 0x42, 0x5d, 0x87, 0xc4, 0x77,
- 0xf2, 0x97, 0xf8, 0xdd, 0xb9, 0xa0, 0xe5, 0x3a
-};
-
-const uint8_t FIXED_RSA_ENDORSEMENT_CERT[1007] = {
- 0x30, 0x82, 0x03, 0xeb, 0x30, 0x82, 0x02, 0xd3, 0xa0, 0x03, 0x02, 0x01,
- 0x02, 0x02, 0x10, 0x57, 0xd7, 0x5a, 0xbc, 0x74, 0xa8, 0x2e, 0x11, 0x9c,
- 0x73, 0x70, 0x2d, 0x3e, 0x15, 0xdf, 0x4e, 0x30, 0x0d, 0x06, 0x09, 0x2a,
- 0x86, 0x48, 0x86, 0xf7, 0x0d, 0x01, 0x01, 0x0b, 0x05, 0x00, 0x30, 0x81,
- 0x80, 0x31, 0x0b, 0x30, 0x09, 0x06, 0x03, 0x55, 0x04, 0x06, 0x13, 0x02,
- 0x55, 0x53, 0x31, 0x13, 0x30, 0x11, 0x06, 0x03, 0x55, 0x04, 0x08, 0x0c,
- 0x0a, 0x43, 0x61, 0x6c, 0x69, 0x66, 0x6f, 0x72, 0x6e, 0x69, 0x61, 0x31,
- 0x14, 0x30, 0x12, 0x06, 0x03, 0x55, 0x04, 0x0a, 0x0c, 0x0b, 0x47, 0x6f,
- 0x6f, 0x67, 0x6c, 0x65, 0x20, 0x49, 0x6e, 0x63, 0x2e, 0x31, 0x24, 0x30,
- 0x22, 0x06, 0x03, 0x55, 0x04, 0x0b, 0x0c, 0x1b, 0x45, 0x6e, 0x67, 0x69,
- 0x6e, 0x65, 0x65, 0x72, 0x69, 0x6e, 0x67, 0x20, 0x61, 0x6e, 0x64, 0x20,
- 0x44, 0x65, 0x76, 0x65, 0x6c, 0x6f, 0x70, 0x6d, 0x65, 0x6e, 0x74, 0x31,
- 0x20, 0x30, 0x1e, 0x06, 0x03, 0x55, 0x04, 0x03, 0x0c, 0x17, 0x43, 0x52,
- 0x4f, 0x53, 0x20, 0x54, 0x50, 0x4d, 0x20, 0x44, 0x45, 0x56, 0x20, 0x45,
- 0x4b, 0x20, 0x52, 0x4f, 0x4f, 0x54, 0x20, 0x43, 0x41, 0x30, 0x1e, 0x17,
- 0x0d, 0x31, 0x36, 0x31, 0x30, 0x32, 0x30, 0x30, 0x30, 0x34, 0x39, 0x33,
- 0x36, 0x5a, 0x17, 0x0d, 0x32, 0x36, 0x31, 0x30, 0x31, 0x38, 0x30, 0x30,
- 0x34, 0x39, 0x33, 0x36, 0x5a, 0x30, 0x00, 0x30, 0x82, 0x01, 0x22, 0x30,
- 0x0d, 0x06, 0x09, 0x2a, 0x86, 0x48, 0x86, 0xf7, 0x0d, 0x01, 0x01, 0x01,
- 0x05, 0x00, 0x03, 0x82, 0x01, 0x0f, 0x00, 0x30, 0x82, 0x01, 0x0a, 0x02,
- 0x82, 0x01, 0x01, 0x00, 0xae, 0x3f, 0x7e, 0x66, 0x78, 0x26, 0x7a, 0x38,
- 0x93, 0xaf, 0x9c, 0xe4, 0x2c, 0x3c, 0x9e, 0x11, 0xb7, 0xae, 0x2f, 0x71,
- 0x8d, 0x4f, 0x2e, 0x3f, 0xd2, 0x35, 0x18, 0xb0, 0x27, 0x04, 0x4e, 0x04,
- 0x66, 0xb2, 0x16, 0xd4, 0xa8, 0xfc, 0x51, 0x60, 0x1b, 0x05, 0x1c, 0x02,
- 0xb5, 0x77, 0x1b, 0xf6, 0x40, 0xc4, 0x0e, 0x01, 0xbf, 0x70, 0xc1, 0x68,
- 0x53, 0x8b, 0x20, 0x4c, 0xa3, 0x39, 0x09, 0xd4, 0x4e, 0x28, 0x7c, 0x1d,
- 0xda, 0x57, 0x5c, 0x41, 0xae, 0x9b, 0xf3, 0xd5, 0xd3, 0x46, 0x12, 0x3d,
- 0x43, 0xcc, 0x39, 0x29, 0x79, 0x9d, 0xe5, 0x87, 0x84, 0x22, 0x85, 0x4b,
- 0x49, 0x35, 0x16, 0x4f, 0x3b, 0xdd, 0xd8, 0xaf, 0xe3, 0x99, 0xfa, 0x37,
- 0xaf, 0xbd, 0xa9, 0x38, 0xb4, 0x47, 0x58, 0x1e, 0x71, 0xb2, 0x46, 0xf2,
- 0x14, 0x85, 0x43, 0x12, 0x55, 0x8b, 0xc3, 0x5b, 0x78, 0x86, 0xd0, 0x0b,
- 0x08, 0x87, 0x1d, 0xf7, 0x4c, 0x69, 0x47, 0x91, 0xd1, 0x16, 0x5c, 0x0e,
- 0xf7, 0x0d, 0xad, 0x4a, 0x2d, 0xd8, 0x74, 0xe2, 0x89, 0xe1, 0xaf, 0xd7,
- 0x54, 0xb6, 0xe0, 0x36, 0x76, 0x7b, 0xd4, 0x6d, 0x50, 0x64, 0x13, 0x5b,
- 0x86, 0xa8, 0xa7, 0xee, 0xed, 0xf9, 0x50, 0x4d, 0xac, 0x1d, 0x1f, 0x9c,
- 0x1b, 0x58, 0x19, 0xa5, 0x20, 0x19, 0x75, 0xb7, 0xcf, 0xf6, 0x37, 0x59,
- 0x2a, 0xc7, 0x5b, 0x14, 0x51, 0xe6, 0x64, 0x70, 0xcc, 0x0e, 0x90, 0x9f,
- 0xe8, 0xf3, 0xc5, 0x95, 0x41, 0x74, 0x24, 0xb4, 0x6d, 0x37, 0x4a, 0x90,
- 0x17, 0x0e, 0x11, 0xea, 0xde, 0x74, 0x0e, 0x05, 0x4d, 0x1f, 0x9c, 0x11,
- 0xea, 0x06, 0xbd, 0x90, 0x9a, 0x9f, 0x44, 0x55, 0x0f, 0x93, 0x82, 0x96,
- 0xfc, 0x29, 0xb7, 0x26, 0x5e, 0x01, 0x25, 0x55, 0x4b, 0x80, 0xda, 0xd6,
- 0x2d, 0xe0, 0xd9, 0x65, 0xcf, 0xcb, 0x7a, 0x2b, 0x02, 0x03, 0x01, 0x00,
- 0x01, 0xa3, 0x81, 0xdf, 0x30, 0x81, 0xdc, 0x30, 0x0e, 0x06, 0x03, 0x55,
- 0x1d, 0x0f, 0x01, 0x01, 0xff, 0x04, 0x04, 0x03, 0x02, 0x00, 0x20, 0x30,
- 0x51, 0x06, 0x03, 0x55, 0x1d, 0x11, 0x01, 0x01, 0xff, 0x04, 0x47, 0x30,
- 0x45, 0xa4, 0x43, 0x30, 0x41, 0x31, 0x16, 0x30, 0x14, 0x06, 0x05, 0x67,
- 0x81, 0x05, 0x02, 0x01, 0x0c, 0x0b, 0x69, 0x64, 0x3a, 0x34, 0x37, 0x34,
- 0x46, 0x34, 0x46, 0x34, 0x37, 0x31, 0x0f, 0x30, 0x0d, 0x06, 0x05, 0x67,
- 0x81, 0x05, 0x02, 0x02, 0x0c, 0x04, 0x48, 0x31, 0x42, 0x32, 0x31, 0x16,
- 0x30, 0x14, 0x06, 0x05, 0x67, 0x81, 0x05, 0x02, 0x03, 0x0c, 0x0b, 0x69,
- 0x64, 0x3a, 0x30, 0x30, 0x31, 0x33, 0x30, 0x30, 0x33, 0x37, 0x30, 0x0c,
- 0x06, 0x03, 0x55, 0x1d, 0x13, 0x01, 0x01, 0xff, 0x04, 0x02, 0x30, 0x00,
- 0x30, 0x13, 0x06, 0x03, 0x55, 0x1d, 0x20, 0x04, 0x0c, 0x30, 0x0a, 0x30,
- 0x08, 0x06, 0x06, 0x67, 0x81, 0x0c, 0x01, 0x02, 0x02, 0x30, 0x1f, 0x06,
- 0x03, 0x55, 0x1d, 0x23, 0x04, 0x18, 0x30, 0x16, 0x80, 0x14, 0xd5, 0xfd,
- 0x4b, 0xf1, 0xbe, 0x05, 0xfb, 0x13, 0x28, 0xe2, 0x5f, 0x39, 0xd3, 0x9d,
- 0x70, 0x4a, 0x48, 0x91, 0x6b, 0xb0, 0x30, 0x10, 0x06, 0x03, 0x55, 0x1d,
- 0x25, 0x04, 0x09, 0x30, 0x07, 0x06, 0x05, 0x67, 0x81, 0x05, 0x08, 0x01,
- 0x30, 0x21, 0x06, 0x03, 0x55, 0x1d, 0x09, 0x04, 0x1a, 0x30, 0x18, 0x30,
- 0x16, 0x06, 0x05, 0x67, 0x81, 0x05, 0x02, 0x10, 0x31, 0x0d, 0x30, 0x0b,
- 0x0c, 0x03, 0x32, 0x2e, 0x30, 0x02, 0x01, 0x00, 0x02, 0x01, 0x10, 0x30,
- 0x0d, 0x06, 0x09, 0x2a, 0x86, 0x48, 0x86, 0xf7, 0x0d, 0x01, 0x01, 0x0b,
- 0x05, 0x00, 0x03, 0x82, 0x01, 0x01, 0x00, 0x4c, 0x65, 0x3f, 0x58, 0x73,
- 0xb6, 0x21, 0x72, 0xb3, 0x2c, 0xc3, 0x94, 0xf4, 0xb3, 0xe0, 0x74, 0xa3,
- 0x2e, 0x47, 0xa7, 0x63, 0x12, 0xa3, 0x0f, 0xc5, 0x18, 0x45, 0x06, 0xab,
- 0xa9, 0xba, 0x64, 0xf0, 0xeb, 0x18, 0x7c, 0xba, 0x57, 0x09, 0xd0, 0x11,
- 0x60, 0x6f, 0xbd, 0x52, 0x73, 0xab, 0x39, 0x81, 0x29, 0xab, 0x78, 0x84,
- 0xec, 0x00, 0xe3, 0x87, 0xec, 0xf1, 0x7d, 0x2e, 0x15, 0x3f, 0xad, 0x1b,
- 0x3a, 0x3f, 0x03, 0x53, 0x91, 0xee, 0x72, 0x7a, 0x87, 0x74, 0xa8, 0x09,
- 0x7d, 0x83, 0x37, 0x0d, 0x46, 0x22, 0x12, 0xf3, 0x79, 0x61, 0xaf, 0x80,
- 0xf3, 0xf4, 0x76, 0x7d, 0xbd, 0xb3, 0x1f, 0x87, 0xb8, 0x66, 0xc9, 0x24,
- 0x15, 0xe9, 0xc7, 0x5b, 0x19, 0xdf, 0x04, 0x0a, 0x47, 0xec, 0x88, 0x46,
- 0x7f, 0x20, 0x6c, 0x4b, 0x23, 0xdb, 0x65, 0x67, 0x54, 0xde, 0x3a, 0xc3,
- 0x64, 0xbb, 0x77, 0x4d, 0x6d, 0x4b, 0x1e, 0x43, 0x9a, 0x35, 0x20, 0x7e,
- 0x28, 0xce, 0x4e, 0xe5, 0xb7, 0x0b, 0xae, 0xd0, 0x26, 0xc0, 0xac, 0x2f,
- 0x79, 0x35, 0x71, 0xbd, 0x74, 0x68, 0x8d, 0x51, 0x6f, 0x84, 0x4d, 0xaa,
- 0xca, 0x0d, 0xf0, 0xa8, 0x41, 0x5c, 0xa9, 0x6e, 0x3b, 0x70, 0x15, 0x73,
- 0x8d, 0xf0, 0x70, 0xd3, 0xb3, 0x0e, 0xa7, 0x3a, 0x34, 0x12, 0xd2, 0x1e,
- 0xa4, 0x18, 0x4c, 0x31, 0xee, 0x26, 0x44, 0x24, 0xe0, 0xa5, 0xca, 0x56,
- 0x5d, 0x76, 0x9e, 0xf4, 0x9a, 0x6e, 0x2b, 0xd6, 0x4a, 0xe9, 0x47, 0xd9,
- 0x29, 0x94, 0x2d, 0x23, 0xf7, 0xbb, 0x13, 0x0c, 0x48, 0x73, 0x93, 0xe3,
- 0x49, 0xc7, 0xd8, 0xca, 0x5d, 0x63, 0xf5, 0x68, 0xb2, 0xe9, 0x1a, 0xe6,
- 0x87, 0x39, 0xf8, 0x12, 0xa7, 0x5c, 0xb2, 0x6e, 0x04, 0xd0, 0x73, 0x3a,
- 0x05, 0x77, 0xc0, 0x9f, 0x23, 0xa7, 0x1a, 0x71, 0x38, 0x55, 0x70
-};
-
-const uint8_t FIXED_ECC_ENDORSEMENT_CERT[804] = {
- 0x30, 0x82, 0x03, 0x20, 0x30, 0x82, 0x02, 0x08, 0xa0, 0x03, 0x02, 0x01,
- 0x02, 0x02, 0x10, 0x67, 0x02, 0x3f, 0x35, 0xc3, 0x17, 0xad, 0xcf, 0x0a,
- 0x76, 0xed, 0x50, 0x17, 0xd8, 0x4e, 0x50, 0x30, 0x0d, 0x06, 0x09, 0x2a,
- 0x86, 0x48, 0x86, 0xf7, 0x0d, 0x01, 0x01, 0x0b, 0x05, 0x00, 0x30, 0x81,
- 0x80, 0x31, 0x0b, 0x30, 0x09, 0x06, 0x03, 0x55, 0x04, 0x06, 0x13, 0x02,
- 0x55, 0x53, 0x31, 0x13, 0x30, 0x11, 0x06, 0x03, 0x55, 0x04, 0x08, 0x0c,
- 0x0a, 0x43, 0x61, 0x6c, 0x69, 0x66, 0x6f, 0x72, 0x6e, 0x69, 0x61, 0x31,
- 0x14, 0x30, 0x12, 0x06, 0x03, 0x55, 0x04, 0x0a, 0x0c, 0x0b, 0x47, 0x6f,
- 0x6f, 0x67, 0x6c, 0x65, 0x20, 0x49, 0x6e, 0x63, 0x2e, 0x31, 0x24, 0x30,
- 0x22, 0x06, 0x03, 0x55, 0x04, 0x0b, 0x0c, 0x1b, 0x45, 0x6e, 0x67, 0x69,
- 0x6e, 0x65, 0x65, 0x72, 0x69, 0x6e, 0x67, 0x20, 0x61, 0x6e, 0x64, 0x20,
- 0x44, 0x65, 0x76, 0x65, 0x6c, 0x6f, 0x70, 0x6d, 0x65, 0x6e, 0x74, 0x31,
- 0x20, 0x30, 0x1e, 0x06, 0x03, 0x55, 0x04, 0x03, 0x0c, 0x17, 0x43, 0x52,
- 0x4f, 0x53, 0x20, 0x54, 0x50, 0x4d, 0x20, 0x44, 0x45, 0x56, 0x20, 0x45,
- 0x4b, 0x20, 0x52, 0x4f, 0x4f, 0x54, 0x20, 0x43, 0x41, 0x30, 0x1e, 0x17,
- 0x0d, 0x31, 0x36, 0x31, 0x30, 0x32, 0x30, 0x30, 0x30, 0x34, 0x39, 0x33,
- 0x36, 0x5a, 0x17, 0x0d, 0x32, 0x36, 0x31, 0x30, 0x31, 0x38, 0x30, 0x30,
- 0x34, 0x39, 0x33, 0x36, 0x5a, 0x30, 0x00, 0x30, 0x59, 0x30, 0x13, 0x06,
- 0x07, 0x2a, 0x86, 0x48, 0xce, 0x3d, 0x02, 0x01, 0x06, 0x08, 0x2a, 0x86,
- 0x48, 0xce, 0x3d, 0x03, 0x01, 0x07, 0x03, 0x42, 0x00, 0x04, 0x6e, 0xcc,
- 0xf0, 0x96, 0x69, 0x9b, 0x3f, 0xea, 0x95, 0xb7, 0xd5, 0x00, 0x27, 0x20,
- 0x81, 0x8e, 0x57, 0x00, 0x6f, 0x67, 0x98, 0xce, 0x8e, 0xdf, 0xc7, 0xda,
- 0xae, 0xa8, 0xa3, 0xed, 0x3e, 0x7a, 0xb3, 0x27, 0xbf, 0x92, 0xee, 0xb2,
- 0xa2, 0x76, 0x81, 0xc1, 0x71, 0x4d, 0x8c, 0xa8, 0x9d, 0xfd, 0x8e, 0xd0,
- 0x29, 0xb5, 0x01, 0x20, 0xec, 0x78, 0xc0, 0x17, 0x8f, 0xf6, 0xf8, 0x67,
- 0x5f, 0xe8, 0xa3, 0x81, 0xdf, 0x30, 0x81, 0xdc, 0x30, 0x0e, 0x06, 0x03,
- 0x55, 0x1d, 0x0f, 0x01, 0x01, 0xff, 0x04, 0x04, 0x03, 0x02, 0x00, 0x20,
- 0x30, 0x51, 0x06, 0x03, 0x55, 0x1d, 0x11, 0x01, 0x01, 0xff, 0x04, 0x47,
- 0x30, 0x45, 0xa4, 0x43, 0x30, 0x41, 0x31, 0x16, 0x30, 0x14, 0x06, 0x05,
- 0x67, 0x81, 0x05, 0x02, 0x01, 0x0c, 0x0b, 0x69, 0x64, 0x3a, 0x34, 0x37,
- 0x34, 0x46, 0x34, 0x46, 0x34, 0x37, 0x31, 0x0f, 0x30, 0x0d, 0x06, 0x05,
- 0x67, 0x81, 0x05, 0x02, 0x02, 0x0c, 0x04, 0x48, 0x31, 0x42, 0x32, 0x31,
- 0x16, 0x30, 0x14, 0x06, 0x05, 0x67, 0x81, 0x05, 0x02, 0x03, 0x0c, 0x0b,
- 0x69, 0x64, 0x3a, 0x30, 0x30, 0x31, 0x33, 0x30, 0x30, 0x33, 0x37, 0x30,
- 0x0c, 0x06, 0x03, 0x55, 0x1d, 0x13, 0x01, 0x01, 0xff, 0x04, 0x02, 0x30,
- 0x00, 0x30, 0x13, 0x06, 0x03, 0x55, 0x1d, 0x20, 0x04, 0x0c, 0x30, 0x0a,
- 0x30, 0x08, 0x06, 0x06, 0x67, 0x81, 0x0c, 0x01, 0x02, 0x02, 0x30, 0x1f,
- 0x06, 0x03, 0x55, 0x1d, 0x23, 0x04, 0x18, 0x30, 0x16, 0x80, 0x14, 0xd5,
- 0xfd, 0x4b, 0xf1, 0xbe, 0x05, 0xfb, 0x13, 0x28, 0xe2, 0x5f, 0x39, 0xd3,
- 0x9d, 0x70, 0x4a, 0x48, 0x91, 0x6b, 0xb0, 0x30, 0x10, 0x06, 0x03, 0x55,
- 0x1d, 0x25, 0x04, 0x09, 0x30, 0x07, 0x06, 0x05, 0x67, 0x81, 0x05, 0x08,
- 0x01, 0x30, 0x21, 0x06, 0x03, 0x55, 0x1d, 0x09, 0x04, 0x1a, 0x30, 0x18,
- 0x30, 0x16, 0x06, 0x05, 0x67, 0x81, 0x05, 0x02, 0x10, 0x31, 0x0d, 0x30,
- 0x0b, 0x0c, 0x03, 0x32, 0x2e, 0x30, 0x02, 0x01, 0x00, 0x02, 0x01, 0x10,
- 0x30, 0x0d, 0x06, 0x09, 0x2a, 0x86, 0x48, 0x86, 0xf7, 0x0d, 0x01, 0x01,
- 0x0b, 0x05, 0x00, 0x03, 0x82, 0x01, 0x01, 0x00, 0x21, 0xab, 0x9e, 0x92,
- 0x4d, 0xb0, 0x50, 0x04, 0xeb, 0x2b, 0xb6, 0xcc, 0x87, 0x8c, 0xa8, 0x27,
- 0xe3, 0x5a, 0xbf, 0x03, 0x5d, 0xb1, 0x4d, 0x24, 0xda, 0xdf, 0x44, 0xdb,
- 0x4a, 0x37, 0x5c, 0x3e, 0x70, 0xf3, 0x35, 0x5d, 0x26, 0x2e, 0xaa, 0x85,
- 0xc6, 0xbe, 0x1c, 0x9d, 0x1e, 0x5f, 0xf6, 0x6c, 0xb8, 0x94, 0x41, 0x25,
- 0x20, 0x55, 0x28, 0x53, 0x55, 0x67, 0x9a, 0xb5, 0xfb, 0x6b, 0x57, 0x09,
- 0xf0, 0x5b, 0xe2, 0x66, 0xc5, 0xe8, 0xd1, 0x9e, 0xb8, 0xb7, 0xed, 0xd8,
- 0x41, 0xb5, 0xbd, 0x44, 0xd9, 0x53, 0xab, 0x2d, 0x17, 0x4c, 0x73, 0x05,
- 0x19, 0x2c, 0x9d, 0x18, 0x98, 0xd8, 0x55, 0xbe, 0xbd, 0xb6, 0xa5, 0xf6,
- 0x5f, 0x3d, 0x70, 0x98, 0xd6, 0xd0, 0xcf, 0x1c, 0x0d, 0xc6, 0x78, 0x6d,
- 0x2e, 0x9c, 0x44, 0xf6, 0x9e, 0x0a, 0x80, 0x12, 0xcd, 0x9b, 0x4b, 0x1f,
- 0xbc, 0xfe, 0xe7, 0x3f, 0x45, 0x81, 0x78, 0x43, 0x40, 0xf2, 0xb0, 0x6b,
- 0x2c, 0x23, 0xc8, 0xc8, 0x57, 0xc6, 0x33, 0x08, 0x3e, 0x17, 0x43, 0x16,
- 0xf0, 0x3f, 0xbf, 0x24, 0x54, 0xba, 0xe6, 0x85, 0x4c, 0xc8, 0x2e, 0x7f,
- 0x88, 0x41, 0x6c, 0x4e, 0x03, 0xa6, 0x35, 0x00, 0x4d, 0xdb, 0x65, 0x68,
- 0x78, 0x01, 0x40, 0xc6, 0xa0, 0x95, 0xd9, 0xe9, 0x27, 0xe1, 0x90, 0x20,
- 0xc8, 0xe6, 0xa7, 0x7c, 0x4d, 0x9c, 0x1c, 0x44, 0x47, 0xfe, 0x9e, 0xc9,
- 0x25, 0x7a, 0x07, 0xa9, 0x86, 0x60, 0x58, 0x18, 0x1c, 0x16, 0x18, 0x7e,
- 0x04, 0xd6, 0x5a, 0xb6, 0xcb, 0xb6, 0xa6, 0x0f, 0xd9, 0x42, 0xf3, 0x19,
- 0x8c, 0xbe, 0x26, 0x98, 0xdd, 0x07, 0x05, 0x76, 0xc0, 0xf9, 0xa4, 0xeb,
- 0x53, 0xff, 0x13, 0x27, 0x61, 0x87, 0x66, 0x99, 0x76, 0x9c, 0x5f, 0x03,
- 0x52, 0x95, 0x13, 0x6e, 0xb7, 0x33, 0x1f, 0x8d, 0xc6, 0x22, 0xd8, 0xe4
-};
-
-/* Test endorsement CA root. */
-static const uint32_t TEST_ENDORSEMENT_CA_RSA_N[64] = {
- 0xfa3b34ed, 0x3c59ad05, 0x912d6623, 0x83302402,
- 0xd43b6755, 0x5777021a, 0xaf37e9a1, 0x45c0e8ad,
- 0x9728f946, 0x4391523d, 0xdf7a9164, 0x88f1a9ae,
- 0x036c557e, 0x5d9df43e, 0x3e65de68, 0xe172008a,
- 0x709dc81f, 0x27a75fe0, 0x3e77f89e, 0x4f400ecc,
- 0x51a17dae, 0x2ff9c652, 0xd1d83cdb, 0x20d26349,
- 0xbbad71dd, 0x30051b2b, 0x276b2459, 0x809bb8e1,
- 0xb8737049, 0xdbe94466, 0x8287072b, 0x070ef311,
- 0x6e2a26de, 0x29d69f11, 0x96463d95, 0xb4dc6950,
- 0x097d4dfe, 0x1b4a88cc, 0xbd6b50c8, 0x9f7a5b34,
- 0xda22c199, 0x9d1ac04b, 0x136af5e5, 0xb1a0e824,
- 0x4a065b34, 0x1f67fb46, 0xa1f91ab1, 0x27bb769f,
- 0xb704c992, 0xb669cbf4, 0x9299bb6c, 0xcb1b2208,
- 0x2dc0d9db, 0xe1513e13, 0xc7f24923, 0xa74c6bcc,
- 0xca1a9a69, 0x1b994244, 0x4f64b0d9, 0x78607fd6,
- 0x486fb315, 0xa1098c31, 0x5dc50dd6, 0xcdc10874
-};
-
-/* Production endorsement CA root. */
-static const uint32_t PROD_ENDORSEMENT_CA_RSA_N[64] = {
- 0xeb6a07bf, 0x6cf8eca6, 0x4756e85e, 0x2fc3874c,
- 0xa4c23e87, 0xc364dffe, 0x2a2ddb95, 0x2f7f0e1e,
- 0xdb485bd8, 0xce8aa808, 0xe062001b, 0x187811c3,
- 0x0e400462, 0xb7097a01, 0xb988152b, 0xba9d058a,
- 0x814b6691, 0xc70a694f, 0x8108c7f0, 0x4c7a1f33,
- 0x5cfda48e, 0xef303dbc, 0x84f5a3ea, 0x14607435,
- 0xc72f1e60, 0x345d0b38, 0x0ac16927, 0xbdf903c7,
- 0x11b660ed, 0x21ebfe0e, 0x8c8b303c, 0xd6eff6cb,
- 0x76156bf7, 0x57735ce4, 0x8b7a87ed, 0x7a757188,
- 0xd4fb3eb0, 0xc67fa05d, 0x163f0cf5, 0x69d8abf3,
- 0xec105749, 0x1de78f37, 0xb885a62f, 0x81344a82,
- 0x390df2b7, 0x58a7c56a, 0xa938f471, 0x506ee7d4,
- 0x2ca0f2a3, 0x2aa5392c, 0x39052797, 0x199e837c,
- 0x0d367b81, 0xb7bbff6f, 0x0ea99f5f, 0xfbac0d2a,
- 0x7bbe018d, 0x265fc995, 0x34f73008, 0x5e2cd747,
- 0x42096e33, 0x0c15f816, 0xffa7f7d2, 0xbd6f0198
-};
-
-static const struct RSA TEST_ENDORSEMENT_CA_RSA_PUB = {
- .e = RSA_F4,
- .N = {
- .dmax = sizeof(TEST_ENDORSEMENT_CA_RSA_N) / sizeof(uint32_t),
- .d = (struct access_helper *) TEST_ENDORSEMENT_CA_RSA_N,
- },
- .d = {
- .dmax = 0,
- .d = NULL,
- },
-};
-
-static const struct RSA PROD_ENDORSEMENT_CA_RSA_PUB = {
- .e = RSA_F4,
- .N = {
- .dmax = sizeof(PROD_ENDORSEMENT_CA_RSA_N) / sizeof(uint32_t),
- .d = (struct access_helper *) PROD_ENDORSEMENT_CA_RSA_N,
- },
- .d = {
- .dmax = 0,
- .d = NULL,
- },
-};
-
-static int validate_cert(
- const struct cros_perso_response_component_info_v0 *cert_info,
- const struct cros_perso_certificate_response_v0 *cert,
- const uint8_t eps[PRIMARY_SEED_SIZE])
-{
- if (cert_info->component_type != CROS_PERSO_COMPONENT_TYPE_RSA_CERT &&
- cert_info->component_type !=
- CROS_PERSO_COMPONENT_TYPE_P256_CERT)
- return 0; /* Invalid component type. */
-
- /* TODO(ngm): verify key_id against HIK/FRK0. */
- if (cert->cert_len > MAX_NV_BUFFER_SIZE)
- return 0;
-
- /* Verify certificate signature; accept either root CA.
- * Getting here implies that the previous mac check on the
- * endorsement seed passed, and that one of these two CA
- * certificates serve as roots for the installed endorsement
- * certificate.
- */
- return DCRYPTO_x509_verify(cert->cert, cert->cert_len,
- &PROD_ENDORSEMENT_CA_RSA_PUB) ||
- DCRYPTO_x509_verify(cert->cert, cert->cert_len,
- &TEST_ENDORSEMENT_CA_RSA_PUB);
-}
-
-static int store_cert(enum cros_perso_component_type component_type,
- const uint8_t *cert, size_t cert_len)
-{
- const uint32_t rsa_ek_nv_index = EK_CERT_NV_START_INDEX;
- const uint32_t ecc_ek_nv_index = EK_CERT_NV_START_INDEX + 1;
- uint32_t nv_index;
- NV_DefineSpace_In define_space;
- TPMA_NV space_attributes;
- NV_Write_In in;
-
- /* Clear up structures potentially uszed only partially. */
- memset(&define_space, 0, sizeof(define_space));
- memset(&space_attributes, 0, sizeof(space_attributes));
- memset(&in, 0, sizeof(in));
-
- /* Indicate that a system reset has occurred, and currently
- * running with Platform auth.
- */
- HierarchyStartup(SU_RESET);
-
- if (component_type == CROS_PERSO_COMPONENT_TYPE_RSA_CERT)
- nv_index = rsa_ek_nv_index;
- else /* P256 certificate. */
- nv_index = ecc_ek_nv_index;
-
- /* EK Credential attributes specified in the "TCG PC Client
- * Platform, TPM Profile (PTP) Specification" document.
- */
- /* REQUIRED: Writeable under platform auth. */
- space_attributes.TPMA_NV_PPWRITE = 1;
- /* OPTIONAL: Write-once; space must be deleted to be re-written. */
- space_attributes.TPMA_NV_WRITEDEFINE = 1;
- /* REQUIRED: Space created with platform auth. */
- space_attributes.TPMA_NV_PLATFORMCREATE = 1;
- /* REQUIRED: Readable under empty password? */
- space_attributes.TPMA_NV_AUTHREAD = 1;
- /* REQUIRED: Disable dictionary attack protection. */
- space_attributes.TPMA_NV_NO_DA = 1;
-
- define_space.authHandle = TPM_RH_PLATFORM;
- define_space.auth.t.size = 0;
- define_space.publicInfo.t.size = sizeof(
- define_space.publicInfo.t.nvPublic);
- define_space.publicInfo.t.nvPublic.nvIndex = nv_index;
- define_space.publicInfo.t.nvPublic.nameAlg = TPM_ALG_SHA256;
- define_space.publicInfo.t.nvPublic.attributes = space_attributes;
- define_space.publicInfo.t.nvPublic.authPolicy.t.size = 0;
- define_space.publicInfo.t.nvPublic.dataSize = cert_len;
-
- /* Define the required space first. */
- if (TPM2_NV_DefineSpace(&define_space) != TPM_RC_SUCCESS)
- return 0;
-
- /* TODO(ngm): call TPM2_NV_WriteLock(nvIndex) on tpm_init();
- * this prevents delete?
- */
-
- in.nvIndex = nv_index;
- in.authHandle = TPM_RH_PLATFORM;
- in.data.t.size = cert_len;
- memcpy(in.data.t.buffer, cert, cert_len);
- in.offset = 0;
-
- if (TPM2_NV_Write(&in) != TPM_RC_SUCCESS)
- return 0;
- if (NvCommit())
- return 1;
- return 0;
-}
-
-static uint32_t hw_key_ladder_step(uint32_t cert)
-{
- uint32_t itop;
-
- GREG32(KEYMGR, SHA_ITOP) = 0; /* clear status */
-
- GREG32(KEYMGR, SHA_USE_CERT_INDEX) =
- (cert << GC_KEYMGR_SHA_USE_CERT_INDEX_LSB) |
- GC_KEYMGR_SHA_USE_CERT_ENABLE_MASK;
-
- GREG32(KEYMGR, SHA_CFG_EN) =
- GC_KEYMGR_SHA_CFG_EN_INT_EN_DONE_MASK;
- GREG32(KEYMGR, SHA_TRIG) =
- GC_KEYMGR_SHA_TRIG_TRIG_GO_MASK;
-
- do {
- itop = GREG32(KEYMGR, SHA_ITOP);
- } while (!itop);
-
- GREG32(KEYMGR, SHA_ITOP) = 0; /* clear status */
-
- return !!GREG32(KEYMGR, HKEY_ERR_FLAGS);
-}
-
-
-#define KEYMGR_CERT_0 0
-#define KEYMGR_CERT_3 3
-#define KEYMGR_CERT_4 4
-#define KEYMGR_CERT_5 5
-#define KEYMGR_CERT_7 7
-#define KEYMGR_CERT_15 15
-#define KEYMGR_CERT_20 20
-#define KEYMGR_CERT_25 25
-#define KEYMGR_CERT_26 26
-
-#define K_CROS_FW_MAJOR_VERSION 0
-static const uint8_t k_cr50_max_fw_major_version = 254;
-
-static int compute_frk2(uint8_t frk2[AES256_BLOCK_CIPHER_KEY_SIZE])
-{
- int i;
-
- /* TODO(ngm): reading ITOP in hw_key_ladder_step hangs on
- * second run of this function (i.e. install of ECC cert,
- * which re-generates FRK2) unless the SHA engine is reset.
- */
- GREG32(KEYMGR, SHA_TRIG) =
- GC_KEYMGR_SHA_TRIG_TRIG_RESET_MASK;
-
- if (hw_key_ladder_step(KEYMGR_CERT_0))
- return 0;
-
- /* Derive HC_PHIK --> Deposited into ISR0 */
- if (hw_key_ladder_step(KEYMGR_CERT_3))
- return 0;
-
- /* Cryptographically mix OBS-FBS --> Deposited into ISR1 */
- if (hw_key_ladder_step(KEYMGR_CERT_4))
- return 0;
-
- /* Derive HIK_RT --> Deposited into ISR0 */
- if (hw_key_ladder_step(KEYMGR_CERT_5))
- return 0;
-
- /* Derive BL_HIK --> Deposited into ISR0 */
- if (hw_key_ladder_step(KEYMGR_CERT_7))
- return 0;
-
- /* Generate FRK2 by executing certs 15, 20, 25, and 26 */
- if (hw_key_ladder_step(KEYMGR_CERT_15))
- return 0;
-
- if (hw_key_ladder_step(KEYMGR_CERT_20))
- return 0;
-
- for (i = 0; i < k_cr50_max_fw_major_version -
- K_CROS_FW_MAJOR_VERSION; i++) {
- if (hw_key_ladder_step(KEYMGR_CERT_25))
- return 0;
- }
- if (hw_key_ladder_step(KEYMGR_CERT_26))
- return 0;
- memcpy(frk2, (void *) GREG32_ADDR(KEYMGR, HKEY_FRR0),
- AES256_BLOCK_CIPHER_KEY_SIZE);
- return 1;
-}
-
-static void flash_info_read_enable(void)
-{
- /* Enable R access to INFO. */
- GREG32(GLOBALSEC, FLASH_REGION7_BASE_ADDR) = FLASH_INFO_MEMORY_BASE +
- FLASH_INFO_MANUFACTURE_STATE_OFFSET;
- GREG32(GLOBALSEC, FLASH_REGION7_SIZE) =
- FLASH_INFO_MANUFACTURE_STATE_SIZE - 1;
- GREG32(GLOBALSEC, FLASH_REGION7_CTRL) =
- GC_GLOBALSEC_FLASH_REGION7_CTRL_EN_MASK |
- GC_GLOBALSEC_FLASH_REGION7_CTRL_RD_EN_MASK;
-}
-
-static void flash_info_read_disable(void)
-{
- GREG32(GLOBALSEC, FLASH_REGION7_CTRL) = 0;
-}
-
-static void flash_cert_region_enable(void)
-{
- /* Enable R access to CERT block. */
- GREG32(GLOBALSEC, FLASH_REGION6_BASE_ADDR) = RO_CERTS_START_ADDR;
- GREG32(GLOBALSEC, FLASH_REGION6_SIZE) =
- RO_CERTS_REGION_SIZE - 1;
- GREG32(GLOBALSEC, FLASH_REGION6_CTRL) =
- GC_GLOBALSEC_FLASH_REGION6_CTRL_EN_MASK |
- GC_GLOBALSEC_FLASH_REGION6_CTRL_RD_EN_MASK;
-}
-
-/* EPS is stored XOR'd with FRK2, so make sure that the sizes match. */
-BUILD_ASSERT(AES256_BLOCK_CIPHER_KEY_SIZE == PRIMARY_SEED_SIZE);
-static int get_decrypted_eps(uint8_t eps[PRIMARY_SEED_SIZE])
-{
- int i;
- uint8_t frk2[AES256_BLOCK_CIPHER_KEY_SIZE];
-
- CPRINTF("%s: getting eps\n", __func__);
- if (!compute_frk2(frk2))
- return 0;
-
- /* Setup flash region mapping. */
- flash_info_read_enable();
-
- for (i = 0; i < INFO1_EPS_SIZE; i += sizeof(uint32_t)) {
- uint32_t word;
-
- if (flash_physical_info_read_word(
- INFO1_EPS_OFFSET + i, &word) != EC_SUCCESS) {
- memset(frk2, 0, sizeof(frk2));
- return 0; /* Flash read INFO1 failed. */
- }
- memcpy(eps + i, &word, sizeof(word));
- }
-
- /* Remove flash region mapping. */
- flash_info_read_disable();
-
- /* One-time-pad decrypt EPS. */
- for (i = 0; i < PRIMARY_SEED_SIZE; i++)
- eps[i] ^= frk2[i];
-
- memset(frk2, 0, sizeof(frk2));
- return 1;
-}
-
-static int store_eps(const uint8_t eps[PRIMARY_SEED_SIZE])
-{
- /* gp is a TPM global state structure, declared in Global.h. */
- memcpy(gp.EPSeed.t.buffer, eps, PRIMARY_SEED_SIZE);
-
- /* Persist the seed to flash. */
- NvWriteReserved(NV_EP_SEED, &gp.EPSeed);
- return NvCommit();
-}
-
-static void endorsement_complete(void)
-{
- CPRINTF("%s(): SUCCESS\n", __func__);
-}
-
-static int install_fixed_certs(void)
-{
- if (!store_eps(FIXED_ENDORSEMENT_SEED))
- return 0;
-
- if (!store_cert(CROS_PERSO_COMPONENT_TYPE_RSA_CERT,
- FIXED_RSA_ENDORSEMENT_CERT,
- sizeof(FIXED_RSA_ENDORSEMENT_CERT)))
- return 0;
-
- if (!store_cert(CROS_PERSO_COMPONENT_TYPE_P256_CERT,
- FIXED_ECC_ENDORSEMENT_CERT,
- sizeof(FIXED_ECC_ENDORSEMENT_CERT)))
- return 0;
-
- return 1;
-}
-
-static int handle_cert(
- const struct cros_perso_response_component_info_v0 *cert_info,
- const struct cros_perso_certificate_response_v0 *cert,
- const uint8_t *eps)
-{
-
- /* Write RSA / P256 endorsement certificate. */
- if (!validate_cert(cert_info, cert, eps))
- return 0;
-
- /* TODO(ngm): verify that storage succeeded. */
- if (!store_cert(cert_info->component_type, cert->cert,
- cert->cert_len)) {
- CPRINTF("%s(): cert storage failed, type: %d\n", __func__,
- cert_info->component_type);
- return 0; /* Internal failure. */
- }
-
- return 1;
-}
-
-int tpm_endorse(void)
-{
- struct ro_cert_response {
- uint8_t key_id[4];
- uint32_t cert_len;
- uint8_t cert[0];
- } __packed;
-
- struct ro_cert {
- const struct cros_perso_response_component_info_v0 cert_info;
- const struct ro_cert_response cert_response;
- } __packed;
-
- /* 2-kB RO cert region is setup like so:
- *
- * | struct ro_cert | rsa_cert | struct ro_cert | ecc_cert |
- *
- * last 32 bytes is hmac over (2048 - 32) preceding bytes.
- * using hmac(eps, "RSA", 4) as key
- */
- const uint8_t *p = (const uint8_t *) RO_CERTS_START_ADDR;
- const uint32_t *c = (const uint32_t *) RO_CERTS_START_ADDR;
- const struct ro_cert *rsa_cert;
- const struct ro_cert *ecc_cert;
- int result = 0;
- uint8_t eps[PRIMARY_SEED_SIZE];
-
- LITE_HMAC_CTX hmac;
-
- flash_cert_region_enable();
-
- /* First boot, certs not yet installed. */
- if (*c == 0xFFFFFFFF)
- return 0;
-
- if (!get_decrypted_eps(eps)) {
- CPRINTF("%s(): failed to read eps\n", __func__);
- return 0;
- }
-
- /* Unpack rsa cert struct. */
- rsa_cert = (const struct ro_cert *) p;
- /* Sanity check cert region contents. */
- if ((2 * sizeof(struct ro_cert)) +
- rsa_cert->cert_response.cert_len > RO_CERTS_REGION_SIZE)
- return 0;
-
- /* Unpack ecc cert struct. */
- ecc_cert = (const struct ro_cert *) (p + sizeof(struct ro_cert) +
- rsa_cert->cert_response.cert_len);
- /* Sanity check cert region contents. */
- if ((2 * sizeof(struct ro_cert)) +
- rsa_cert->cert_response.cert_len +
- ecc_cert->cert_response.cert_len > RO_CERTS_REGION_SIZE)
- return 0;
-
- /* Verify expected component types. */
- if (rsa_cert->cert_info.component_type !=
- CROS_PERSO_COMPONENT_TYPE_RSA_CERT) {
- return 0;
- }
- if (ecc_cert->cert_info.component_type !=
- CROS_PERSO_COMPONENT_TYPE_P256_CERT) {
- return 0;
- }
-
- do {
- /* Check cert region hmac.
- *
- * This will fail if we are not running w/ expected keyladder.
- */
- DCRYPTO_HMAC_SHA256_init(&hmac, eps, sizeof(eps));
- HASH_update(&hmac.hash, "RSA", 4);
- DCRYPTO_HMAC_SHA256_init(&hmac, DCRYPTO_HMAC_final(&hmac), 32);
- HASH_update(&hmac.hash, p, RO_CERTS_REGION_SIZE - 32);
- if (!DCRYPTO_equals(p + RO_CERTS_REGION_SIZE - 32,
- DCRYPTO_HMAC_final(&hmac), 32)) {
- CPRINTF("%s: bad cert region hmac; falling back\n"
- " to fixed endorsement\n", __func__);
-
- /* HMAC verification failure indicates either
- * a manufacture fault, or mis-match in
- * production mode and currently running
- * firmware (e.g. PRODUCTION mode chip, now
- * flashed with DEV mode firmware.
- *
- * In either case, fall back to a fixed
- * endorsement seed, which will not be trusted
- * by production infrastructure.
- */
- if (!install_fixed_certs()) {
- CPRINTF("%s: failed to install fixed "
- "endorsement certs; \n"
- " unknown endorsement state\n",
- __func__);
- }
-
- /* TODO(ngm): is this state considered
- * endorsement failure?
- */
- break;
- }
-
- if (!handle_cert(
- &rsa_cert->cert_info,
- (struct cros_perso_certificate_response_v0 *)
- &rsa_cert->cert_response, eps)) {
- CPRINTF("%s: Failed to process RSA cert\n", __func__);
- break;
- }
- CPRINTF("%s: RSA cert install success\n", __func__);
-
- if (!handle_cert(
- &ecc_cert->cert_info,
- (struct cros_perso_certificate_response_v0 *)
- &ecc_cert->cert_response, eps)) {
- CPRINTF("%s: Failed to process ECC cert\n", __func__);
- break;
- }
- CPRINTF("%s: ECC cert install success\n", __func__);
-
- /* Copy EPS from INFO1 to flash data region. */
- if (!store_eps(eps)) {
- CPRINTF("%s(): eps storage failed\n", __func__);
- break;
- }
-
- /* Mark as endorsed. */
- endorsement_complete();
-
- /* Chip has been marked as manufactured. */
- result = 1;
- } while (0);
-
- memset(eps, 0, sizeof(eps));
- return result;
-}
diff --git a/board/cr50/tpm2/hash.c b/board/cr50/tpm2/hash.c
deleted file mode 100644
index a11fb9e450..0000000000
--- a/board/cr50/tpm2/hash.c
+++ /dev/null
@@ -1,355 +0,0 @@
-/* Copyright 2015 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 "CryptoEngine.h"
-
-#include "util.h"
-#include "dcrypto.h"
-
-static const HASH_INFO *lookup_hash_info(TPM_ALG_ID alg)
-{
- int i;
- const int num_algs = ARRAY_SIZE(g_hashData);
-
- for (i = 0; i < num_algs - 1; i++) {
- if (g_hashData[i].alg == alg)
- return &g_hashData[i];
- }
- return &g_hashData[num_algs - 1];
-}
-
-TPM_ALG_ID _cpri__GetContextAlg(CPRI_HASH_STATE *hash_state)
-{
- return hash_state->hashAlg;
-}
-
-TPM_ALG_ID _cpri__GetHashAlgByIndex(uint32_t index)
-{
- if (index >= HASH_COUNT)
- return TPM_ALG_NULL;
- return g_hashData[index].alg;
-}
-
-uint16_t _cpri__GetDigestSize(TPM_ALG_ID alg)
-{
- return lookup_hash_info(alg)->digestSize;
-}
-
-uint16_t _cpri__GetHashBlockSize(TPM_ALG_ID alg)
-{
- return lookup_hash_info(alg)->blockSize;
-}
-
-BUILD_ASSERT(sizeof(LITE_SHA256_CTX) == USER_MIN_HASH_STATE_SIZE);
-BUILD_ASSERT(sizeof(CPRI_HASH_STATE) == sizeof(EXPORT_HASH_STATE));
-void _cpri__ImportExportHashState(CPRI_HASH_STATE *osslFmt,
- EXPORT_HASH_STATE *externalFmt,
- IMPORT_EXPORT direction)
-{
- if (direction == IMPORT_STATE)
- memcpy(osslFmt, externalFmt, sizeof(CPRI_HASH_STATE));
- else
- memcpy(externalFmt, osslFmt, sizeof(CPRI_HASH_STATE));
-}
-
-uint16_t _cpri__HashBlock(TPM_ALG_ID alg, uint32_t in_len, uint8_t *in,
- uint32_t out_len, uint8_t *out)
-{
- uint8_t digest[SHA_DIGEST_MAX_BYTES];
- const uint16_t digest_len = _cpri__GetDigestSize(alg);
-
- if (digest_len == 0)
- return 0;
-
- switch (alg) {
- case TPM_ALG_SHA1:
- DCRYPTO_SHA1_hash(in, in_len, digest);
- break;
-
- case TPM_ALG_SHA256:
- DCRYPTO_SHA256_hash(in, in_len, digest);
- break;
-/* TODO: add support for SHA384 and SHA512
- *
- * case TPM_ALG_SHA384:
- * DCRYPTO_SHA384_hash(in, in_len, p);
- * break;
- * case TPM_ALG_SHA512:
- * DCRYPTO_SHA512_hash(in, in_len, p);
- * break; */
- default:
- FAIL(FATAL_ERROR_INTERNAL);
- break;
- }
-
- out_len = MIN(out_len, digest_len);
- memcpy(out, digest, out_len);
- return out_len;
-}
-
-BUILD_ASSERT(sizeof(struct HASH_CTX) <=
- sizeof(((CPRI_HASH_STATE *)0)->state));
-uint16_t _cpri__StartHash(TPM_ALG_ID alg, BOOL sequence,
- CPRI_HASH_STATE *state)
-{
- struct HASH_CTX *ctx = (struct HASH_CTX *) state->state;
- uint16_t result;
-
- switch (alg) {
- case TPM_ALG_SHA1:
- DCRYPTO_SHA1_init(ctx, sequence);
- result = HASH_size(ctx);
- break;
- case TPM_ALG_SHA256:
- DCRYPTO_SHA256_init(ctx, sequence);
- result = HASH_size(ctx);
- break;
-/* TODO: add support for SHA384 and SHA512
- * case TPM_ALG_SHA384:
- * DCRYPTO_SHA384_init(in, in_len, p);
- * break;
- * case TPM_ALG_SHA512:
- * DCRYPTO_SHA512_init(in, in_len, p);
- * break; */
- default:
- result = 0;
- break;
- }
-
- if (result > 0)
- state->hashAlg = alg;
-
- return result;
-}
-
-void _cpri__UpdateHash(CPRI_HASH_STATE *state, uint32_t in_len,
- BYTE *in)
-{
- struct HASH_CTX *ctx = (struct HASH_CTX *) state->state;
-
- HASH_update(ctx, in, in_len);
-}
-
-uint16_t _cpri__CompleteHash(CPRI_HASH_STATE *state,
- uint32_t out_len, uint8_t *out)
-{
- struct HASH_CTX *ctx = (struct HASH_CTX *) state->state;
-
- out_len = MIN(HASH_size(ctx), out_len);
- memcpy(out, HASH_final(ctx), out_len);
- return out_len;
-}
-
-#ifdef CRYPTO_TEST_SETUP
-
-#include "console.h"
-#include "extension.h"
-#include "shared_mem.h"
-
-#define CPRINTF(format, args...) cprintf(CC_EXTENSION, format, ## args)
-
-struct test_context {
- int context_handle;
- CPRI_HASH_STATE hstate;
-};
-
-static struct {
- int current_context_count;
- int max_contexts;
- struct test_context *contexts;
-} hash_test_db;
-
-struct test_context *find_context(int handle)
-{
- int i;
-
- for (i = 0; i < hash_test_db.current_context_count; i++)
- if (hash_test_db.contexts[i].context_handle == handle)
- return hash_test_db.contexts + i;
- return NULL;
-}
-
-static void process_start(TPM_ALG_ID alg, int handle, void *response_body,
- size_t *response_size)
-{
- uint8_t *response = response_body;
- struct test_context *new_context;
-
- if (find_context(handle)) {
- *response = EXC_HASH_DUPLICATED_HANDLE;
- *response_size = 1;
- return;
- }
-
- if (!hash_test_db.max_contexts) {
- /* Check how many contexts could possible fit. */
- hash_test_db.max_contexts = shared_mem_size() /
- sizeof(struct test_context);
- }
-
- if (!hash_test_db.contexts)
- shared_mem_acquire(shared_mem_size(),
- (char **)&hash_test_db.contexts);
-
- if (!hash_test_db.contexts ||
- (hash_test_db.current_context_count == hash_test_db.max_contexts)) {
- *response = EXC_HASH_TOO_MANY_HANDLES;
- *response_size = 1;
- return;
- }
-
- new_context = hash_test_db.contexts +
- hash_test_db.current_context_count++;
- new_context->context_handle = handle;
- _cpri__StartHash(alg, 0, &new_context->hstate);
-}
-
-static void process_continue(int handle, void *cmd_body, uint16_t text_len,
- void *response_body, size_t *response_size)
-{
- struct test_context *context = find_context(handle);
-
- if (!context) {
- *((uint8_t *)response_body) = EXC_HASH_UNKNOWN_CONTEXT;
- *response_size = 1;
- return;
- }
-
- _cpri__UpdateHash(&context->hstate, text_len, cmd_body);
-}
-
-static void process_finish(int handle, void *response_body,
- size_t *response_size)
-{
- struct test_context *context = find_context(handle);
-
- if (!context) {
- *((uint8_t *)response_body) = EXC_HASH_UNKNOWN_CONTEXT;
- *response_size = 1;
- return;
- }
-
- /* There for sure is enough room in the TPM buffer. */
- *response_size = _cpri__CompleteHash(&context->hstate,
- SHA_DIGEST_MAX_BYTES,
- response_body);
-
- /* drop this context from the database. */
- hash_test_db.current_context_count--;
- if (!hash_test_db.current_context_count) {
- shared_mem_release(hash_test_db.contexts);
- return;
- }
-
- /* Nothing to do, if the deleted context is the last one in memory. */
- if (context == (hash_test_db.contexts +
- hash_test_db.current_context_count))
- return;
-
- memcpy(context,
- hash_test_db.contexts + hash_test_db.current_context_count,
- sizeof(*context));
-}
-
-static void hash_command_handler(void *cmd_body,
- size_t cmd_size,
- size_t *response_size)
-{
- int mode;
- int hash_mode;
- int handle;
- uint16_t text_len;
- uint8_t *cmd;
- size_t response_room = *response_size;
- TPM_ALG_ID alg;
-
- cmd = cmd_body;
-
- /*
- * Empty response is sent as a success indication when the digest is
- * not yet expected (i.e. in response to 'start' and 'cont' commands,
- * as defined below).
- *
- * Single byte responses indicate errors, test successes are
- * communicated as responses of the size of the appropriate digests.
- */
- *response_size = 0;
-
- /*
- * Command structure, shared out of band with the test driver running
- * on the host:
- *
- * field | size | note
- * ===================================================================
- * mode | 1 | 0 - start, 1 - cont., 2 - finish, 3 - single
- * hash_mode | 1 | 0 - sha1, 1 - sha256
- * handle | 1 | seassion handle, ignored in 'single' mode
- * text_len | 2 | size of the text to process, big endian
- * text | text_len | text to hash
- */
-
- mode = *cmd++;
- hash_mode = *cmd++;
- handle = *cmd++;
- text_len = *cmd++;
- text_len = text_len * 256 + *cmd++;
-
- switch (hash_mode) {
- case 0:
- alg = TPM_ALG_SHA1;
- break;
- case 1:
- alg = TPM_ALG_SHA256;
- break;
-
- default:
- return;
- }
-
- switch (mode) {
- case 0: /* Start a new hash context. */
- process_start(alg, handle, cmd_body, response_size);
- if (*response_size)
- break; /* Something went wrong. */
- process_continue(handle, cmd, text_len,
- cmd_body, response_size);
- break;
-
- case 1:
- process_continue(handle, cmd, text_len,
- cmd_body, response_size);
- break;
-
- case 2:
- process_continue(handle, cmd, text_len,
- cmd_body, response_size);
- if (*response_size)
- break; /* Something went wrong. */
-
- process_finish(handle, cmd_body, response_size);
- CPRINTF("%s:%d response size %d\n", __func__, __LINE__,
- *response_size);
- break;
-
- case 3: /* Process a buffer in a single shot. */
- if (!text_len)
- break;
- /*
- * Error responses are just 1 byte in size, valid responses
- * are of various hash sizes.
- */
- *response_size = _cpri__HashBlock(alg, text_len,
- cmd, response_room, cmd_body);
- CPRINTF("%s:%d response size %d\n", __func__,
- __LINE__, *response_size);
- break;
- default:
- break;
- }
-}
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_HASH, hash_command_handler);
-
-#endif /* CRYPTO_TEST_SETUP */
diff --git a/board/cr50/tpm2/hash_data.c b/board/cr50/tpm2/hash_data.c
deleted file mode 100644
index 6e6ad8aa4d..0000000000
--- a/board/cr50/tpm2/hash_data.c
+++ /dev/null
@@ -1,11 +0,0 @@
-/* Copyright 2015 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 "CryptoEngine.h"
-
-/*
- * This is unfortunate, but this is the only way to bring in necessary data
- * from the TPM2 library, as this file is not compiled in embedded mode.
- */
-#include "CpriHashData.c"
diff --git a/board/cr50/tpm2/hkdf.c b/board/cr50/tpm2/hkdf.c
deleted file mode 100644
index dcc494af16..0000000000
--- a/board/cr50/tpm2/hkdf.c
+++ /dev/null
@@ -1,93 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "dcrypto.h"
-
-#ifdef CRYPTO_TEST_SETUP
-
-#include "extension.h"
-
-enum {
- TEST_RFC = 0,
-};
-
-#define MAX_OKM_BYTES 1024
-
-static void hkdf_command_handler(void *cmd_body,
- size_t cmd_size,
- size_t *response_size)
-{
- uint8_t *cmd;
- uint8_t *out;
- uint8_t op;
- size_t salt_len;
- const uint8_t *salt;
- size_t IKM_len;
- const uint8_t *IKM;
- size_t info_len;
- const uint8_t *info;
- size_t OKM_len;
- uint8_t OKM[MAX_OKM_BYTES];
-
- /* Command format.
- *
- * WIDTH FIELD
- * 1 OP
- * 1 MSB SALT LEN
- * 1 LSB SALT LEN
- * SALT_LEN SALT
- * 1 MSB IKM LEN
- * 1 LSB IKM LEN
- * IKM_LEN IKM
- * 1 MSB INFO LEN
- * 1 LSB INFO LEN
- * INFO_LEN INFO
- * 1 MSB OKM LEN
- * 1 LSB OKM LEN
- */
- cmd = (uint8_t *) cmd_body;
- out = (uint8_t *) cmd_body;
- op = *cmd++;
-
- salt_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- salt = cmd;
- cmd += salt_len;
-
- IKM_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- IKM = cmd;
- cmd += IKM_len;
-
- info_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- info = cmd;
- cmd += info_len;
-
- OKM_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
-
- if (OKM_len > MAX_OKM_BYTES) {
- *response_size = 0;
- return;
- }
-
- switch (op) {
- case TEST_RFC:
- if (DCRYPTO_hkdf(OKM, OKM_len, salt, salt_len,
- IKM, IKM_len, info, info_len)) {
- memcpy(out, OKM, OKM_len);
- *response_size = OKM_len;
- } else {
- *response_size = 0;
- }
- break;
- default:
- *response_size = 0;
- }
-}
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_HKDF, hkdf_command_handler);
-
-#endif /* CRYPTO_TEST_SETUP */
diff --git a/board/cr50/tpm2/manufacture.c b/board/cr50/tpm2/manufacture.c
deleted file mode 100644
index b2c214c38e..0000000000
--- a/board/cr50/tpm2/manufacture.c
+++ /dev/null
@@ -1,43 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "console.h"
-#include "tpm_manufacture.h"
-
-#include "Global.h"
-#include "NV_fp.h"
-#include "Platform.h"
-#include "TPM_Types.h"
-#include "TpmBuildSwitches.h"
-#include "tpm_types.h"
-
-#define CPRINTF(format, args...) cprintf(CC_EXTENSION, format, ## args)
-
-#define EK_CERT_NV_START_INDEX 0x01C00000
-
-int tpm_manufactured(void)
-{
- uint32_t nv_ram_index;
- const uint32_t rsa_ek_nv_index = EK_CERT_NV_START_INDEX;
- const uint32_t ecc_ek_nv_index = EK_CERT_NV_START_INDEX + 1;
-
- /*
- * If nvram_index (value written at NV RAM offset of zero) is all
- * ones, or either endorsement certificate is not installed, consider
- * the chip un-manufactured.
- *
- * Thus, wiping flash NV ram allows to re-manufacture the chip.
- */
- _plat__NvMemoryRead(0, sizeof(nv_ram_index), &nv_ram_index);
- if ((nv_ram_index == ~0) ||
- (NvIsUndefinedIndex(rsa_ek_nv_index) == TPM_RC_SUCCESS) ||
- (NvIsUndefinedIndex(ecc_ek_nv_index) == TPM_RC_SUCCESS)) {
- CPRINTF("%s: NOT manufactured\n", __func__);
- return 0;
- }
-
- CPRINTF("%s: manufactured\n", __func__);
- return 1;
-}
diff --git a/board/cr50/tpm2/platform.c b/board/cr50/tpm2/platform.c
deleted file mode 100644
index 7c98c353a0..0000000000
--- a/board/cr50/tpm2/platform.c
+++ /dev/null
@@ -1,62 +0,0 @@
-/* Copyright 2015 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 "Platform.h"
-#include "TPM_Types.h"
-
-#include "trng.h"
-#include "util.h"
-#include "version.h"
-
-uint16_t _cpri__GenerateRandom(size_t random_size,
- uint8_t *buffer)
-{
- rand_bytes(buffer, random_size);
- return random_size;
-}
-
-/*
- * Return the pointer to the character immediately after the first dash
- * encountered in the passed in string, or NULL if there is no dashes in the
- * string.
- */
-static const char *char_after_dash(const char *str)
-{
- char c;
-
- do {
- c = *str++;
-
- if (c == '-')
- return str;
- } while (c);
-
- return NULL;
-}
-
-/*
- * The properly formatted build_info string has the ec code SHA1 after the
- * first dash, and tpm2 code sha1 after the second dash.
- */
-
-void _plat__GetFwVersion(uint32_t *firmwareV1, uint32_t *firmwareV2)
-{
- const char *ver_str = char_after_dash(build_info);
-
- /* Just in case the build_info string is misformatted. */
- *firmwareV1 = 0;
- *firmwareV2 = 0;
-
- if (!ver_str)
- return;
-
- *firmwareV1 = strtoi(ver_str, NULL, 16);
-
- ver_str = char_after_dash(ver_str);
- if (!ver_str)
- return;
-
- *firmwareV2 = strtoi(ver_str, NULL, 16);
-}
diff --git a/board/cr50/tpm2/post_reset.c b/board/cr50/tpm2/post_reset.c
deleted file mode 100644
index cfb3608462..0000000000
--- a/board/cr50/tpm2/post_reset.c
+++ /dev/null
@@ -1,38 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-
-#include "config.h"
-#include "board.h"
-#include "console.h"
-#include "extension.h"
-#include "system.h"
-
-#define CPRINTS(format, args...) cprints(CC_SYSTEM, format, ## args)
-
-void post_reset_command_handler(void *body,
- size_t cmd_size,
- size_t *response_size)
-{
- *response_size = 1;
- ((uint8_t *)body)[0] = 0;
- post_reboot_request();
-}
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_POST_RESET, post_reset_command_handler);
-
-static enum vendor_cmd_rc immediate_reset(enum vendor_cmd_cc code,
- void *buf,
- size_t input_size,
- size_t *response_size)
-{
- CPRINTS("%s: rebooting on host's request", __func__);
- cflush(); /* Let the console drain. */
- system_reset(SYSTEM_RESET_HARD); /* This will never return. */
-
- /* Never reached. */
- return VENDOR_RC_SUCCESS;
-}
-DECLARE_VENDOR_COMMAND(VENDOR_CC_IMMEDIATE_RESET, immediate_reset);
diff --git a/board/cr50/tpm2/rsa.c b/board/cr50/tpm2/rsa.c
deleted file mode 100644
index e0bf3559e6..0000000000
--- a/board/cr50/tpm2/rsa.c
+++ /dev/null
@@ -1,1084 +0,0 @@
-/* Copyright 2015 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 "CryptoEngine.h"
-#include "Global.h"
-#include "Hierarchy_fp.h"
-
-#include "dcrypto.h"
-#include "trng.h"
-
-#include <assert.h>
-
-TPM2B_BYTE_VALUE(4);
-TPM2B_BYTE_VALUE(32);
-
-static void reverse_tpm2b(TPM2B *b)
-{
- reverse(b->buffer, b->size);
-}
-
-static int check_key(const RSA_KEY *key)
-{
- if (key->publicKey->size & 0x3)
- /* Only word-multiple sizes supported. */
- return 0;
- return 1;
-}
-
-static int check_encrypt_params(TPM_ALG_ID padding_alg, TPM_ALG_ID hash_alg,
- enum padding_mode *padding,
- enum hashing_mode *hashing)
-{
- /* Initialize hashing for all padding types */
- *hashing = HASH_SHA1;
-
- if (padding_alg == TPM_ALG_RSAES) {
- *padding = PADDING_MODE_PKCS1;
- } else if (padding_alg == TPM_ALG_OAEP) {
- /* Only SHA1 and SHA256 supported with OAEP. */
- if (hash_alg == TPM_ALG_SHA256)
- *hashing = HASH_SHA256;
- else if (hash_alg != TPM_ALG_SHA1)
- /* Unsupported hash algorithm. */
- return 0;
- *padding = PADDING_MODE_OAEP;
- } else if (padding_alg == TPM_ALG_NULL) {
- *padding = PADDING_MODE_NULL;
- } else {
- return 0; /* Unsupported padding mode. */
- }
- return 1;
-}
-
-static int check_sign_params(TPM_ALG_ID padding_alg, TPM_ALG_ID hash_alg,
- enum padding_mode *padding,
- enum hashing_mode *hashing)
-{
- if (padding_alg == TPM_ALG_RSASSA ||
- padding_alg == TPM_ALG_RSAPSS) {
- if (hash_alg == TPM_ALG_SHA1)
- *hashing = HASH_SHA1;
- else if (hash_alg == TPM_ALG_SHA256)
- *hashing = HASH_SHA256;
- else
- return 0;
- if (padding_alg == TPM_ALG_RSASSA)
- *padding = PADDING_MODE_PKCS1;
- else
- *padding = PADDING_MODE_PSS;
- } else {
- return 0;
- }
- return 1;
-}
-
-CRYPT_RESULT _cpri__EncryptRSA(uint32_t *out_len, uint8_t *out,
- RSA_KEY *key, TPM_ALG_ID padding_alg,
- uint32_t in_len, uint8_t *in,
- TPM_ALG_ID hash_alg, const char *label)
-{
- struct RSA rsa;
- enum padding_mode padding;
- enum hashing_mode hashing;
- int result;
-
- if (!check_key(key))
- return CRYPT_FAIL;
- if (!check_encrypt_params(padding_alg, hash_alg, &padding, &hashing))
- return CRYPT_FAIL;
-
- reverse_tpm2b(key->publicKey);
- rsa.e = key->exponent;
- rsa.N.dmax = key->publicKey->size / sizeof(uint32_t);
- rsa.N.d = (struct access_helper *) &key->publicKey->buffer;
- rsa.d.dmax = 0;
- rsa.d.d = NULL;
-
- result = DCRYPTO_rsa_encrypt(&rsa, out, out_len, in, in_len, padding,
- hashing, label);
-
- reverse_tpm2b(key->publicKey);
-
- if (result)
- return CRYPT_SUCCESS;
- else
- return CRYPT_FAIL;
-}
-
-CRYPT_RESULT _cpri__DecryptRSA(uint32_t *out_len, uint8_t *out,
- RSA_KEY *key, TPM_ALG_ID padding_alg,
- uint32_t in_len, uint8_t *in,
- TPM_ALG_ID hash_alg, const char *label)
-{
- struct RSA rsa;
- enum padding_mode padding;
- enum hashing_mode hashing;
- int result;
-
- if (!check_key(key))
- return CRYPT_FAIL;
- if (!check_encrypt_params(padding_alg, hash_alg, &padding, &hashing))
- return CRYPT_FAIL;
-
- reverse_tpm2b(key->publicKey);
- reverse_tpm2b(key->privateKey);
-
- rsa.e = key->exponent;
- rsa.N.dmax = key->publicKey->size / sizeof(uint32_t);
- rsa.N.d = (struct access_helper *) &key->publicKey->buffer;
- rsa.d.dmax = key->privateKey->size / sizeof(uint32_t);
- rsa.d.d = (struct access_helper *) &key->privateKey->buffer;
-
- result = DCRYPTO_rsa_decrypt(&rsa, out, out_len, in, in_len, padding,
- hashing, label);
-
- reverse_tpm2b(key->publicKey);
- reverse_tpm2b(key->privateKey);
-
- if (result)
- return CRYPT_SUCCESS;
- else
- return CRYPT_FAIL;
-}
-
-CRYPT_RESULT _cpri__SignRSA(uint32_t *out_len, uint8_t *out,
- RSA_KEY *key, TPM_ALG_ID padding_alg,
- TPM_ALG_ID hash_alg, uint32_t in_len, uint8_t *in)
-{
- struct RSA rsa;
- enum padding_mode padding;
- enum hashing_mode hashing;
- int result;
-
- if (!check_key(key))
- return CRYPT_FAIL;
- if (!check_sign_params(padding_alg, hash_alg, &padding, &hashing))
- return CRYPT_FAIL;
-
- reverse_tpm2b(key->publicKey);
- reverse_tpm2b(key->privateKey);
-
- rsa.e = key->exponent;
- rsa.N.dmax = key->publicKey->size / sizeof(uint32_t);
- rsa.N.d = (struct access_helper *) &key->publicKey->buffer;
- rsa.d.dmax = key->privateKey->size / sizeof(uint32_t);
- rsa.d.d = (struct access_helper *) &key->privateKey->buffer;
-
- /* TPM2 wrapper function fails to initialize out_len! */
- *out_len = key->publicKey->size;
- result = DCRYPTO_rsa_sign(&rsa, out, out_len, in, in_len,
- padding, hashing);
-
- reverse_tpm2b(key->publicKey);
- reverse_tpm2b(key->privateKey);
-
- if (result)
- return CRYPT_SUCCESS;
- else
- return CRYPT_FAIL;
-}
-
-CRYPT_RESULT _cpri__ValidateSignatureRSA(
- RSA_KEY *key, TPM_ALG_ID padding_alg, TPM_ALG_ID hash_alg,
- uint32_t digest_len, uint8_t *digest, uint32_t sig_len,
- uint8_t *sig, uint16_t salt_len)
-{
- struct RSA rsa;
- enum padding_mode padding;
- enum hashing_mode hashing;
- int result;
-
- if (!check_key(key))
- return CRYPT_FAIL;
- if (!check_sign_params(padding_alg, hash_alg, &padding, &hashing))
- return CRYPT_FAIL;
-
- reverse_tpm2b(key->publicKey);
-
- rsa.e = key->exponent;
- rsa.N.dmax = key->publicKey->size / sizeof(uint32_t);
- rsa.N.d = (struct access_helper *) &key->publicKey->buffer;
- rsa.d.dmax = 0;
- rsa.d.d = NULL;
-
- result = DCRYPTO_rsa_verify(&rsa, digest, digest_len, sig, sig_len,
- padding, hashing);
-
- reverse_tpm2b(key->publicKey);
-
- if (result)
- return CRYPT_SUCCESS;
- else
- return CRYPT_FAIL;
-}
-
-CRYPT_RESULT _cpri__TestKeyRSA(TPM2B *d_buf, uint32_t e,
- TPM2B *N_buf, TPM2B *p_buf, TPM2B *q_buf)
-{
- struct LITE_BIGNUM N;
- struct LITE_BIGNUM p;
- struct LITE_BIGNUM q;
- struct LITE_BIGNUM d;
- int result;
-
- if (!p_buf)
- return CRYPT_PARAMETER;
- if (q_buf && p_buf->size != q_buf->size)
- return CRYPT_PARAMETER;
- if (N_buf->size != p_buf->size * 2)
- return CRYPT_PARAMETER; /* Insufficient output buffer space. */
- if (N_buf->size > RSA_MAX_BYTES)
- return CRYPT_PARAMETER; /* Unsupported key size. */
-
- DCRYPTO_bn_wrap(&N, N_buf->buffer, N_buf->size);
- DCRYPTO_bn_wrap(&p, p_buf->buffer, p_buf->size);
- reverse_tpm2b(N_buf);
- reverse_tpm2b(p_buf);
- if (q_buf) {
- DCRYPTO_bn_wrap(&q, q_buf->buffer, q_buf->size);
- reverse_tpm2b(q_buf);
- }
- /* d_buf->size may be uninitialized. */
- DCRYPTO_bn_wrap(&d, d_buf->buffer, N_buf->size);
-
- result = DCRYPTO_rsa_key_compute(&N, &d, &p, q_buf ? &q : NULL, e);
-
- reverse_tpm2b(N_buf);
- reverse_tpm2b(p_buf);
- if (q_buf)
- reverse_tpm2b(q_buf);
-
- if (result) {
- d_buf->size = N_buf->size;
- reverse_tpm2b(d_buf);
- return CRYPT_SUCCESS;
- } else {
- return CRYPT_FAIL;
- }
-}
-
-/* Each 1024-bit prime generation attempt fails with probability
- * ~0.5%. Setting an upper limit on the attempts allows for an
- * application to display a message and then reattempt.
- * TODO(ngm): tweak this value along with performance improvements. */
-#define MAX_GENERATE_ATTEMPTS 3
-
-static int generate_prime(struct LITE_BIGNUM *b, TPM_ALG_ID hashing,
- TPM2B *seed, const char *label, TPM2B *extra,
- uint32_t *counter)
-{
- TPM2B_4_BYTE_VALUE marshaled_counter = { .t = {4} };
- uint32_t i;
-
- for (i = 0; i < MAX_GENERATE_ATTEMPTS; i++) {
- UINT32_TO_BYTE_ARRAY(*counter, marshaled_counter.t.buffer);
- _cpri__KDFa(hashing, seed, label, extra, &marshaled_counter.b,
- bn_bits(b), (uint8_t *) b->d, NULL, FALSE);
-
- (*counter)++; /* Mark as used. */
- if (DCRYPTO_bn_generate_prime(b))
- return 1;
- }
-
- return 0;
-}
-
-#ifdef CRYPTO_TEST_SETUP
-static const uint8_t VERIFY_SEED[32] = {
- 0x54, 0xef, 0xe3, 0xe9, 0x1e, 0xfa, 0xad, 0x9b,
- 0x18, 0x3f, 0x27, 0x12, 0xfd, 0xe7, 0xfb, 0xc6,
- 0x60, 0xcc, 0x34, 0x05, 0x00, 0x7d, 0x21, 0x6e,
- 0xc2, 0x1e, 0x78, 0xbe, 0x61, 0xc8, 0x41, 0x99
-};
-#endif
-
-/* The array below represents the output of ObjectComputeName() when
- * applied to the TPMT_PUBLIC RSA template described in the TPM 2.0
- * EK Credential Profile specification: https://goo.gl/rbE6q7
- */
-static const uint8_t TPM2_RSA_EK_NAME_TEMPLATE[] = {
- /* TPM_ALG_SHA256 in big endian. */
- 0x00, 0x0b,
- /* SHA256 digest of the default template TPMT_PUBLIC. */
- 0x32, 0x50, 0x39, 0x29, 0xa1, 0x28, 0x7e, 0xed,
- 0xaa, 0x3e, 0x89, 0xd9, 0x32, 0xf9, 0xb5, 0x1a,
- 0x6f, 0x92, 0xab, 0xd0, 0xfa, 0x57, 0x72, 0x1f,
- 0xfa, 0x6f, 0xc0, 0x41, 0xe0, 0x4f, 0x74, 0x98
-};
-BUILD_ASSERT(sizeof(TPM2_RSA_EK_NAME_TEMPLATE) == 2 + SHA256_DIGEST_SIZE);
-
-/* The array below represents the 'name' (corresponding to the
- * parameter extra) used by the CR50 certificate authority when
- * generating the endorsement certificate.
- */
-static const uint8_t TPM2_RSA_EK_NAME_CR50[] = {
- 0x68, 0xd1, 0xa2, 0x41, 0xfb, 0x27, 0x2f, 0x03,
- 0x90, 0xbf, 0xd0, 0x42, 0x8d, 0xad, 0xee, 0xb0,
- 0x2b, 0xf4, 0xa1, 0xcd, 0x46, 0xab, 0x6c, 0x39,
- 0x1b, 0xa3, 0x1f, 0x51, 0x87, 0x06, 0x8e, 0x6a
-};
-BUILD_ASSERT(sizeof(TPM2_RSA_EK_NAME_CR50) == SHA256_DIGEST_SIZE);
-
-CRYPT_RESULT _cpri__GenerateKeyRSA(
- TPM2B *N_buf, TPM2B *p_buf, uint16_t num_bits,
- uint32_t e_buf, TPM_ALG_ID hashing, TPM2B *seed,
- const char *label, TPM2B *extra, uint32_t *counter_in)
-{
- const char *label_p = "RSA p!";
- const char *label_q = "RSA q!";
- /* Numbers from NIST SP800-57.
- * Fallback conservatively for keys larger than 2048 bits. */
- const uint32_t security_strength =
- num_bits <= 1024 ? 80 :
- num_bits <= 2048 ? 112 :
- 256;
-
- const uint16_t num_bytes = num_bits / 8;
- uint8_t q_buf[RSA_MAX_BYTES / 2];
-
- struct LITE_BIGNUM e;
- struct LITE_BIGNUM p;
- struct LITE_BIGNUM q;
- struct LITE_BIGNUM N;
-
- uint32_t counter = 0;
- TPM2B_32_BYTE_VALUE local_seed = { .t = {32} };
- TPM2B_32_BYTE_VALUE local_extra = { .t = {32} };
-
- const TPM2B_SEED *endorsement_seed = HierarchyGetPrimarySeed(
- TPM_RH_ENDORSEMENT);
-
- if (num_bits & 0xF)
- return CRYPT_FAIL;
- if (num_bytes > RSA_MAX_BYTES)
- return CRYPT_FAIL;
- /* Seed size must be at least 2*security_strength per TPM 2.0 spec. */
- if (seed == NULL || seed->size * 8 < 2 * security_strength)
- return CRYPT_FAIL;
-
- /* When generating the endorsement primary key (based on the
- * TPM 2.0 standard template, swap in the vendor specific
- * template instead.
- */
- if (extra->size == sizeof(TPM2_RSA_EK_NAME_TEMPLATE) &&
- DCRYPTO_equals(extra->buffer, TPM2_RSA_EK_NAME_TEMPLATE,
- sizeof(TPM2_RSA_EK_NAME_TEMPLATE)) &&
- seed == &endorsement_seed->b) {
- memcpy(local_extra.b.buffer, TPM2_RSA_EK_NAME_CR50,
- sizeof(TPM2_RSA_EK_NAME_CR50));
- extra = &local_extra.b;
- }
-
- /* Hash down the primary seed for RSA key generation, so that
- * the derivation tree is distinct from ECC key derivation.
- */
-#ifdef CRYPTO_TEST_SETUP
- if (seed->size == sizeof(VERIFY_SEED) &&
- DCRYPTO_equals(seed->buffer, VERIFY_SEED, seed->size)) {
- /* Test seed has already been hashed down. */
- memcpy(local_seed.t.buffer, seed->buffer, seed->size);
- } else
-#endif
- {
- LITE_HMAC_CTX hmac;
-
- DCRYPTO_HMAC_SHA256_init(&hmac, seed->buffer, seed->size);
- HASH_update(&hmac.hash, "RSA", 4);
- memcpy(local_seed.t.buffer, DCRYPTO_HMAC_final(&hmac),
- local_seed.t.size);
- }
-
- if (e_buf == 0)
- e_buf = RSA_F4;
-
- DCRYPTO_bn_wrap(&e, &e_buf, sizeof(e_buf));
- DCRYPTO_bn_wrap(&p, p_buf->buffer, num_bytes / 2);
- DCRYPTO_bn_wrap(&q, q_buf, num_bytes / 2);
-
- if (label == NULL)
- label = label_p;
-
- /* The manufacture process uses a counter of 1, whereas the
- * TPM2.0 library (CryptGenerateKeyRSA) passes in a counter
- * value of 0. Having that the counter always start at least
- * at 1 ensures that endorsement keys are correctly generated.
- * For non-endorsement keys, the counter value used is
- * immaterial, as the generation process remains deterministic.
- */
- if (counter_in != NULL)
- counter = *counter_in;
- counter++;
-
- if (!generate_prime(&p, hashing, &local_seed.b, label, extra,
- &counter)) {
- if (counter_in != NULL)
- *counter_in = counter;
- /* TODO(ngm): implement secure memset. */
- memset(local_seed.t.buffer, 0, local_seed.t.size);
- return CRYPT_FAIL;
- }
-
- if (label == label_p)
- label = label_q;
- if (!generate_prime(&q, hashing, &local_seed.b, label, extra,
- &counter)) {
- if (counter_in != NULL)
- *counter_in = counter;
- /* TODO(ngm): implement secure memset. */
- memset(local_seed.t.buffer, 0, local_seed.t.size);
- return CRYPT_FAIL;
- }
-
- if (counter_in != NULL)
- *counter_in = counter;
- N_buf->size = num_bytes;
- p_buf->size = num_bytes / 2;
- DCRYPTO_bn_wrap(&N, N_buf->buffer, num_bytes);
- DCRYPTO_bn_mul(&N, &p, &q);
- reverse_tpm2b(N_buf);
- reverse_tpm2b(p_buf);
- /* TODO(ngm): replace with secure memset. */
- memset(q_buf, 0, sizeof(q_buf));
- memset(local_seed.t.buffer, 0, local_seed.t.size);
- return CRYPT_SUCCESS;
-}
-
-#ifdef CRYPTO_TEST_SETUP
-
-#include "extension.h"
-
-enum {
- TEST_RSA_ENCRYPT = 0,
- TEST_RSA_DECRYPT = 1,
- TEST_RSA_SIGN = 2,
- TEST_RSA_VERIFY = 3,
- TEST_RSA_KEYGEN = 4,
- TEST_RSA_KEYTEST = 5,
- TEST_BN_PRIMEGEN = 6,
- TEST_X509_VERIFY = 7,
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_768_N = {
- .t = {96, {
- 0xb0, 0xdb, 0xed, 0x46, 0xd9, 0x32, 0xf0, 0x7c,
- 0xd4, 0x20, 0x23, 0xd2, 0x35, 0x5a, 0x86, 0x17,
- 0xdb, 0x24, 0x72, 0x36, 0x33, 0x3b, 0xc2, 0x64,
- 0x8b, 0xa4, 0x49, 0x6e, 0x74, 0xfe, 0xfa, 0xd2,
- 0x82, 0x0c, 0xc4, 0x12, 0x3a, 0x48, 0x67, 0xe1,
- 0x15, 0xcc, 0x94, 0xdf, 0x44, 0x1b, 0x4e, 0xc0,
- 0x18, 0xba, 0x46, 0x1b, 0x51, 0x2c, 0xe2, 0x0f,
- 0xc0, 0x32, 0x77, 0xed, 0x5f, 0x8b, 0xe5, 0xa3,
- 0x00, 0xe6, 0x3c, 0x2d, 0xa7, 0x10, 0x89, 0x53,
- 0xa8, 0x2b, 0x33, 0x74, 0x38, 0xf7, 0x36, 0x00,
- 0xfd, 0xdd, 0x5b, 0xbd, 0x7b, 0xc1, 0x7c, 0xe1,
- 0x75, 0x90, 0x2b, 0x78, 0x2d, 0x39, 0x85, 0x69
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_768_D = {
- .t = {96, {
- 0xae, 0xad, 0xb9, 0x50, 0x25, 0x8c, 0x1b, 0x5c,
- 0x9f, 0x42, 0xd3, 0x3e, 0x76, 0x75, 0xdf, 0x45,
- 0x46, 0xab, 0x5b, 0xa6, 0xce, 0xb9, 0x72, 0x49,
- 0x4e, 0x66, 0xc8, 0x24, 0x31, 0xa7, 0xf9, 0x61,
- 0xdb, 0x12, 0xf2, 0xc1, 0x32, 0x11, 0x7b, 0x90,
- 0x23, 0xb0, 0xb9, 0x45, 0x3f, 0x06, 0x5d, 0xa2,
- 0xd7, 0x35, 0x0f, 0xdd, 0xfc, 0x03, 0xdf, 0x8d,
- 0x91, 0x6b, 0x83, 0xf9, 0x59, 0xee, 0x67, 0x1e,
- 0x1a, 0x20, 0x9e, 0x8b, 0xf8, 0xf6, 0xe2, 0xb2,
- 0xf5, 0x29, 0x71, 0x4c, 0x22, 0x54, 0xcf, 0x7e,
- 0x97, 0xbc, 0x70, 0x24, 0xdd, 0x6d, 0x52, 0xfe,
- 0x17, 0xd9, 0xd6, 0x41, 0x7b, 0x76, 0x40, 0x01
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_768_P = {
- .t = {48, {
- 0xd6, 0x09, 0x64, 0xc8, 0xf3, 0x5c, 0x02, 0xc7,
- 0xc6, 0x47, 0x4e, 0x7f, 0x43, 0x9d, 0x31, 0x46,
- 0x7a, 0x33, 0x85, 0xa0, 0xa4, 0x16, 0xea, 0x22,
- 0x7b, 0xcd, 0x64, 0x9b, 0x50, 0xec, 0xa7, 0x2f,
- 0x7e, 0xcf, 0xeb, 0x69, 0x29, 0x34, 0x8e, 0xb7,
- 0xb5, 0xb3, 0xba, 0x7f, 0x9b, 0x01, 0x7d, 0x69
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_768_Q = {
- .t = {48, {
- 0xd3, 0x88, 0x92, 0x2d, 0xd5, 0xc6, 0x29, 0xf4,
- 0xf0, 0x2e, 0x61, 0xf0, 0x60, 0xad, 0xa9, 0x46,
- 0x11, 0xa9, 0x0c, 0x69, 0x14, 0x31, 0x09, 0x36,
- 0x8b, 0x70, 0x1b, 0x11, 0x9b, 0x26, 0x39, 0x34,
- 0x34, 0xfd, 0xf1, 0x9a, 0x89, 0x51, 0x63, 0x0a,
- 0xc6, 0x60, 0x0b, 0xba, 0x18, 0x8e, 0xc8, 0x01
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_1024_N = {
- .t = {128, {
- 0xdf, 0x4e, 0xaf, 0x73, 0x45, 0x94, 0x98, 0x34,
- 0x30, 0x7e, 0x26, 0xad, 0x40, 0x83, 0xf9, 0x17,
- 0x21, 0xb0, 0x4e, 0x1b, 0x0d, 0x6a, 0x44, 0xce,
- 0x4e, 0x3e, 0x2e, 0x72, 0x4c, 0x97, 0xdf, 0x89,
- 0x8a, 0x39, 0x10, 0x25, 0xae, 0x20, 0x4c, 0xf2,
- 0x3b, 0x20, 0xb2, 0xa5, 0x10, 0xdd, 0xb2, 0x6b,
- 0x62, 0x4e, 0xa6, 0x9f, 0x92, 0x4a, 0xd9, 0x86,
- 0x97, 0xcc, 0x70, 0x20, 0x3b, 0x6a, 0x32, 0x63,
- 0xca, 0x7f, 0x59, 0xfb, 0x57, 0xb6, 0xa9, 0x99,
- 0xe9, 0xd0, 0x2e, 0x0f, 0x1c, 0xd4, 0x7d, 0x8b,
- 0xa0, 0xbd, 0x0f, 0xd2, 0xd5, 0x3b, 0x1f, 0x11,
- 0xb4, 0x6a, 0x94, 0xcf, 0x4f, 0x0a, 0x2b, 0x44,
- 0xe7, 0xfa, 0x6b, 0x24, 0x91, 0xb4, 0x82, 0x1f,
- 0xf6, 0x75, 0xb6, 0x91, 0xc5, 0xa0, 0xf6, 0x2f,
- 0xd5, 0xff, 0x10, 0x73, 0x9b, 0x34, 0xf6, 0x7a,
- 0x88, 0x23, 0xa9, 0x42, 0x3c, 0xa8, 0x24, 0x91
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_1024_D = {
- .t = {128, {
- 0x9a, 0x6d, 0x85, 0xf4, 0x07, 0xa8, 0x6d, 0x61,
- 0x9a, 0x2f, 0x83, 0x7b, 0xc8, 0xe3, 0xfb, 0x7c,
- 0xbd, 0xb5, 0x79, 0x2e, 0x48, 0x26, 0xb7, 0x92,
- 0x9c, 0x95, 0x6f, 0xf5, 0x67, 0x76, 0x98, 0x06,
- 0x3b, 0xea, 0x9e, 0x7a, 0x10, 0x63, 0x12, 0x13,
- 0x6a, 0x44, 0x80, 0x86, 0x9a, 0x95, 0x56, 0x6f,
- 0xe0, 0xba, 0x57, 0x8c, 0x7e, 0xd4, 0xf8, 0x7d,
- 0x95, 0xb8, 0xb1, 0xc9, 0xf8, 0x8c, 0xc6, 0x6e,
- 0xe5, 0x7b, 0xa0, 0xaf, 0xa0, 0x4e, 0x4e, 0x84,
- 0xd7, 0x97, 0xb9, 0x5a, 0xdd, 0x32, 0xe5, 0x2b,
- 0xe5, 0x80, 0xb3, 0xb2, 0xbf, 0x56, 0xff, 0x01,
- 0xdc, 0xe6, 0xa6, 0x6c, 0x4a, 0x81, 0x1d, 0x8f,
- 0xea, 0x4b, 0xed, 0x24, 0x08, 0xf4, 0x67, 0xaf,
- 0x0d, 0xf2, 0xfd, 0x37, 0x3f, 0x31, 0x25, 0xfa,
- 0xee, 0x35, 0xb0, 0xdb, 0x66, 0x11, 0xff, 0x49,
- 0xe1, 0xe5, 0xff, 0x1b, 0xcc, 0xc3, 0x0e, 0x09
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_1024_P = {
- .t = {64, {
- 0xf9, 0x5e, 0x79, 0x65, 0x43, 0x70, 0x40, 0x83,
- 0x50, 0x0a, 0xbb, 0x61, 0xb3, 0x87, 0x7b, 0x24,
- 0x8f, 0x2a, 0x03, 0x5b, 0xb5, 0x4b, 0x94, 0x94,
- 0x67, 0xaa, 0x98, 0xd6, 0x14, 0x40, 0x90, 0x3c,
- 0xa4, 0x0d, 0x6d, 0x58, 0x31, 0xc5, 0x42, 0xf1,
- 0x2d, 0x15, 0x0e, 0xe7, 0xcd, 0xe6, 0x3e, 0xca,
- 0xd8, 0x94, 0x37, 0xaa, 0x4c, 0xd6, 0xf3, 0x21,
- 0x2e, 0xa4, 0xfe, 0x1d, 0x79, 0x44, 0xd7, 0xb3
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_1024_Q = {
- .t = {64, {
- 0xe5, 0x3e, 0xcd, 0x4b, 0x97, 0xc5, 0x96, 0x39,
- 0x70, 0x97, 0x3a, 0x10, 0xa9, 0xc3, 0x35, 0x0a,
- 0xd6, 0x2b, 0xf5, 0x12, 0x8d, 0xb2, 0xc0, 0x0b,
- 0x1c, 0x5f, 0xa0, 0x0b, 0x86, 0x83, 0xa7, 0x90,
- 0xe9, 0xf8, 0x16, 0x92, 0x9f, 0xce, 0x13, 0x4c,
- 0x14, 0xe8, 0x9e, 0x4c, 0x24, 0xef, 0xff, 0x58,
- 0x22, 0x06, 0xf9, 0xcf, 0xfd, 0x19, 0xb7, 0x23,
- 0xf9, 0xe3, 0xb3, 0xe3, 0x7a, 0x9b, 0xb0, 0xab
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_2048_N = {
- .t = {256, {
- 0x9c, 0xd7, 0x61, 0x2e, 0x43, 0x8e, 0x15, 0xbe,
- 0xcd, 0x73, 0x9f, 0xb7, 0xf5, 0x86, 0x4b, 0xe3,
- 0x95, 0x90, 0x5c, 0x85, 0x19, 0x4c, 0x1d, 0x2e,
- 0x2c, 0xef, 0x6e, 0x1f, 0xed, 0x75, 0x32, 0x0f,
- 0x0a, 0xc1, 0x72, 0x9f, 0x0c, 0x78, 0x50, 0xa2,
- 0x99, 0x82, 0x53, 0x90, 0xbe, 0x64, 0x23, 0x49,
- 0x75, 0x7b, 0x0c, 0xeb, 0x2d, 0x68, 0x97, 0xd6,
- 0xaf, 0xb1, 0xaa, 0x2a, 0xde, 0x5e, 0x9b, 0xe3,
- 0x06, 0x0d, 0xf2, 0xac, 0xd9, 0xd7, 0x1f, 0x50,
- 0x6e, 0xc9, 0x5d, 0xeb, 0xb4, 0xf0, 0xc0, 0x98,
- 0x23, 0x04, 0x30, 0x46, 0x10, 0xdc, 0xd4, 0x6b,
- 0x57, 0xc7, 0x30, 0xc3, 0x06, 0xdd, 0xaf, 0x51,
- 0x6e, 0x40, 0x41, 0xf8, 0x10, 0xde, 0x49, 0x18,
- 0x52, 0xb3, 0x18, 0xca, 0x49, 0x50, 0xa8, 0x3a,
- 0xcd, 0xb6, 0x94, 0x7b, 0xdb, 0xf1, 0x2d, 0x05,
- 0xce, 0x57, 0x0b, 0xbe, 0x38, 0x48, 0xbb, 0xc9,
- 0xb1, 0x76, 0x36, 0xb8, 0xa8, 0xcc, 0xe2, 0x07,
- 0x5c, 0xc8, 0x7b, 0xcf, 0xcf, 0xf0, 0xfa, 0xa3,
- 0xc5, 0xd7, 0x3a, 0x5e, 0xb2, 0xf4, 0xbf, 0xea,
- 0xc2, 0xed, 0x51, 0x16, 0xa2, 0x92, 0x9c, 0x36,
- 0xa6, 0x86, 0x0e, 0x24, 0xa5, 0x66, 0x15, 0xe7,
- 0x97, 0x22, 0x50, 0x04, 0xff, 0xc9, 0x4d, 0xb0,
- 0xbc, 0x27, 0x05, 0x5e, 0x2c, 0xf7, 0xef, 0xdc,
- 0x5d, 0x58, 0xa1, 0x3b, 0x60, 0x83, 0xb7, 0x8c,
- 0xb7, 0xd0, 0x36, 0x6d, 0x55, 0x2e, 0x05, 0x23,
- 0x63, 0x74, 0x4a, 0x97, 0x37, 0xa7, 0x78, 0x40,
- 0xef, 0x3e, 0x66, 0xfd, 0xba, 0x6e, 0xb3, 0x72,
- 0x4a, 0x21, 0x82, 0x1f, 0x33, 0xad, 0x62, 0x0c,
- 0xf2, 0x1a, 0xd2, 0x6a, 0xb5, 0xa7, 0xf2, 0x51,
- 0x69, 0x1f, 0x38, 0xa5, 0x57, 0x9a, 0xc5, 0x88,
- 0x67, 0xe3, 0x11, 0xa6, 0x53, 0x4f, 0xb1, 0xe9,
- 0x07, 0x41, 0xde, 0xe8, 0xdf, 0x93, 0xa9, 0x99
- }
- }
-};
-
-static const uint8_t RSA_2048_CERT[] = {
- 0x30, 0x82, 0x03, 0x5D, 0x30, 0x82, 0x02, 0x45,
- 0xA0, 0x03, 0x02, 0x01, 0x02, 0x02, 0x09, 0x00,
- 0xCB, 0x9D, 0x38, 0x47, 0x3F, 0x4F, 0x3B, 0xC6,
- 0x30, 0x0D, 0x06, 0x09, 0x2A, 0x86, 0x48, 0x86,
- 0xF7, 0x0D, 0x01, 0x01, 0x0B, 0x05, 0x00, 0x30,
- 0x45, 0x31, 0x0B, 0x30, 0x09, 0x06, 0x03, 0x55,
- 0x04, 0x06, 0x13, 0x02, 0x41, 0x55, 0x31, 0x13,
- 0x30, 0x11, 0x06, 0x03, 0x55, 0x04, 0x08, 0x0C,
- 0x0A, 0x53, 0x6F, 0x6D, 0x65, 0x2D, 0x53, 0x74,
- 0x61, 0x74, 0x65, 0x31, 0x21, 0x30, 0x1F, 0x06,
- 0x03, 0x55, 0x04, 0x0A, 0x0C, 0x18, 0x49, 0x6E,
- 0x74, 0x65, 0x72, 0x6E, 0x65, 0x74, 0x20, 0x57,
- 0x69, 0x64, 0x67, 0x69, 0x74, 0x73, 0x20, 0x50,
- 0x74, 0x79, 0x20, 0x4C, 0x74, 0x64, 0x30, 0x1E,
- 0x17, 0x0D, 0x31, 0x36, 0x30, 0x36, 0x30, 0x38,
- 0x32, 0x33, 0x34, 0x35, 0x32, 0x33, 0x5A, 0x17,
- 0x0D, 0x31, 0x36, 0x30, 0x37, 0x30, 0x38, 0x32,
- 0x33, 0x34, 0x35, 0x32, 0x33, 0x5A, 0x30, 0x45,
- 0x31, 0x0B, 0x30, 0x09, 0x06, 0x03, 0x55, 0x04,
- 0x06, 0x13, 0x02, 0x41, 0x55, 0x31, 0x13, 0x30,
- 0x11, 0x06, 0x03, 0x55, 0x04, 0x08, 0x0C, 0x0A,
- 0x53, 0x6F, 0x6D, 0x65, 0x2D, 0x53, 0x74, 0x61,
- 0x74, 0x65, 0x31, 0x21, 0x30, 0x1F, 0x06, 0x03,
- 0x55, 0x04, 0x0A, 0x0C, 0x18, 0x49, 0x6E, 0x74,
- 0x65, 0x72, 0x6E, 0x65, 0x74, 0x20, 0x57, 0x69,
- 0x64, 0x67, 0x69, 0x74, 0x73, 0x20, 0x50, 0x74,
- 0x79, 0x20, 0x4C, 0x74, 0x64, 0x30, 0x82, 0x01,
- 0x22, 0x30, 0x0D, 0x06, 0x09, 0x2A, 0x86, 0x48,
- 0x86, 0xF7, 0x0D, 0x01, 0x01, 0x01, 0x05, 0x00,
- 0x03, 0x82, 0x01, 0x0F, 0x00, 0x30, 0x82, 0x01,
- 0x0A, 0x02, 0x82, 0x01, 0x01, 0x00, 0x9C, 0xD7,
- 0x61, 0x2E, 0x43, 0x8E, 0x15, 0xBE, 0xCD, 0x73,
- 0x9F, 0xB7, 0xF5, 0x86, 0x4B, 0xE3, 0x95, 0x90,
- 0x5C, 0x85, 0x19, 0x4C, 0x1D, 0x2E, 0x2C, 0xEF,
- 0x6E, 0x1F, 0xED, 0x75, 0x32, 0x0F, 0x0A, 0xC1,
- 0x72, 0x9F, 0x0C, 0x78, 0x50, 0xA2, 0x99, 0x82,
- 0x53, 0x90, 0xBE, 0x64, 0x23, 0x49, 0x75, 0x7B,
- 0x0C, 0xEB, 0x2D, 0x68, 0x97, 0xD6, 0xAF, 0xB1,
- 0xAA, 0x2A, 0xDE, 0x5E, 0x9B, 0xE3, 0x06, 0x0D,
- 0xF2, 0xAC, 0xD9, 0xD7, 0x1F, 0x50, 0x6E, 0xC9,
- 0x5D, 0xEB, 0xB4, 0xF0, 0xC0, 0x98, 0x23, 0x04,
- 0x30, 0x46, 0x10, 0xDC, 0xD4, 0x6B, 0x57, 0xC7,
- 0x30, 0xC3, 0x06, 0xDD, 0xAF, 0x51, 0x6E, 0x40,
- 0x41, 0xF8, 0x10, 0xDE, 0x49, 0x18, 0x52, 0xB3,
- 0x18, 0xCA, 0x49, 0x50, 0xA8, 0x3A, 0xCD, 0xB6,
- 0x94, 0x7B, 0xDB, 0xF1, 0x2D, 0x05, 0xCE, 0x57,
- 0x0B, 0xBE, 0x38, 0x48, 0xBB, 0xC9, 0xB1, 0x76,
- 0x36, 0xB8, 0xA8, 0xCC, 0xE2, 0x07, 0x5C, 0xC8,
- 0x7B, 0xCF, 0xCF, 0xF0, 0xFA, 0xA3, 0xC5, 0xD7,
- 0x3A, 0x5E, 0xB2, 0xF4, 0xBF, 0xEA, 0xC2, 0xED,
- 0x51, 0x16, 0xA2, 0x92, 0x9C, 0x36, 0xA6, 0x86,
- 0x0E, 0x24, 0xA5, 0x66, 0x15, 0xE7, 0x97, 0x22,
- 0x50, 0x04, 0xFF, 0xC9, 0x4D, 0xB0, 0xBC, 0x27,
- 0x05, 0x5E, 0x2C, 0xF7, 0xEF, 0xDC, 0x5D, 0x58,
- 0xA1, 0x3B, 0x60, 0x83, 0xB7, 0x8C, 0xB7, 0xD0,
- 0x36, 0x6D, 0x55, 0x2E, 0x05, 0x23, 0x63, 0x74,
- 0x4A, 0x97, 0x37, 0xA7, 0x78, 0x40, 0xEF, 0x3E,
- 0x66, 0xFD, 0xBA, 0x6E, 0xB3, 0x72, 0x4A, 0x21,
- 0x82, 0x1F, 0x33, 0xAD, 0x62, 0x0C, 0xF2, 0x1A,
- 0xD2, 0x6A, 0xB5, 0xA7, 0xF2, 0x51, 0x69, 0x1F,
- 0x38, 0xA5, 0x57, 0x9A, 0xC5, 0x88, 0x67, 0xE3,
- 0x11, 0xA6, 0x53, 0x4F, 0xB1, 0xE9, 0x07, 0x41,
- 0xDE, 0xE8, 0xDF, 0x93, 0xA9, 0x99, 0x02, 0x03,
- 0x01, 0x00, 0x01, 0xA3, 0x50, 0x30, 0x4E, 0x30,
- 0x1D, 0x06, 0x03, 0x55, 0x1D, 0x0E, 0x04, 0x16,
- 0x04, 0x14, 0xDF, 0xA0, 0x28, 0xD1, 0xAF, 0xB0,
- 0x55, 0xE3, 0xC1, 0xF1, 0x33, 0x28, 0xED, 0x5C,
- 0xDD, 0xC2, 0xBB, 0xBF, 0x22, 0x6E, 0x30, 0x1F,
- 0x06, 0x03, 0x55, 0x1D, 0x23, 0x04, 0x18, 0x30,
- 0x16, 0x80, 0x14, 0xDF, 0xA0, 0x28, 0xD1, 0xAF,
- 0xB0, 0x55, 0xE3, 0xC1, 0xF1, 0x33, 0x28, 0xED,
- 0x5C, 0xDD, 0xC2, 0xBB, 0xBF, 0x22, 0x6E, 0x30,
- 0x0C, 0x06, 0x03, 0x55, 0x1D, 0x13, 0x04, 0x05,
- 0x30, 0x03, 0x01, 0x01, 0xFF, 0x30, 0x0D, 0x06,
- 0x09, 0x2A, 0x86, 0x48, 0x86, 0xF7, 0x0D, 0x01,
- 0x01, 0x0B, 0x05, 0x00, 0x03, 0x82, 0x01, 0x01,
- 0x00, 0x42, 0x3D, 0x98, 0x0C, 0x98, 0x54, 0xD0,
- 0xD7, 0x7B, 0x04, 0x18, 0x5C, 0x8F, 0xD2, 0xC1,
- 0xE9, 0xB4, 0xDA, 0x13, 0x76, 0x25, 0xD8, 0x9E,
- 0x8D, 0x00, 0x4A, 0x03, 0x89, 0xF3, 0x15, 0xB0,
- 0x0A, 0x80, 0x78, 0x5A, 0xB2, 0xAA, 0xBC, 0xE5,
- 0x37, 0xF1, 0x4C, 0xAE, 0x34, 0x3B, 0xB1, 0x6B,
- 0xD9, 0xF5, 0x8E, 0xA1, 0xFE, 0xC5, 0xED, 0x2E,
- 0xA5, 0xD6, 0xA1, 0xDC, 0x13, 0xB7, 0x36, 0xEC,
- 0xC5, 0x98, 0x9F, 0xE8, 0xA3, 0x22, 0x66, 0x88,
- 0xF2, 0x94, 0x5D, 0x9C, 0x8C, 0x6F, 0xAB, 0x81,
- 0x05, 0x3D, 0xE0, 0x9E, 0x5B, 0x03, 0xA9, 0xCA,
- 0x54, 0x8F, 0xDC, 0xE2, 0xD6, 0x0E, 0xDA, 0x15,
- 0x96, 0xAF, 0x47, 0xA1, 0x99, 0xA8, 0x37, 0xD6,
- 0xED, 0xBE, 0x3F, 0x4A, 0x4A, 0x9A, 0xC0, 0x05,
- 0x77, 0x6F, 0x1E, 0x62, 0xCB, 0x11, 0x74, 0xDF,
- 0x6D, 0xB7, 0xFF, 0x42, 0x77, 0xB3, 0x29, 0x6C,
- 0x38, 0x6F, 0xBA, 0xE5, 0x5F, 0xB7, 0x23, 0x2F,
- 0x53, 0x19, 0xC0, 0x49, 0x09, 0x18, 0x50, 0x9D,
- 0x0F, 0xFE, 0x6C, 0xA4, 0xBD, 0x35, 0x2A, 0xDD,
- 0xCF, 0xF8, 0xB6, 0x42, 0x06, 0xE1, 0x53, 0xCA,
- 0xC3, 0xF6, 0xA6, 0x70, 0x82, 0x3C, 0x3B, 0x1F,
- 0x19, 0x93, 0xBE, 0xC5, 0xB8, 0x11, 0x28, 0xEC,
- 0x66, 0xB6, 0xA5, 0x3A, 0x35, 0x82, 0x17, 0x1A,
- 0x3C, 0x4E, 0x3E, 0x25, 0xFE, 0x4C, 0xA3, 0x1F,
- 0xCA, 0xFB, 0xE6, 0xF8, 0x3B, 0x61, 0xE2, 0x33,
- 0x5C, 0x89, 0x66, 0x0F, 0xFB, 0x99, 0xFE, 0xFD,
- 0xDB, 0xC2, 0xB7, 0xA8, 0xCF, 0x45, 0xC9, 0xF1,
- 0x67, 0xB8, 0xA8, 0x97, 0xF4, 0xA5, 0x90, 0xA1,
- 0x99, 0xAA, 0xA6, 0xFF, 0x47, 0x38, 0x13, 0x82,
- 0xE4, 0x81, 0x84, 0x36, 0xC3, 0x8C, 0xE5, 0xDD,
- 0x7A, 0x70, 0xF8, 0x70, 0x27, 0xFB, 0xCD, 0xC2,
- 0xA0, 0xA9, 0xC5, 0x61, 0xA4, 0x3C, 0x9D, 0x1B,
- 0x57
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_2048_D = {
- .t = {256, {
- 0x4e, 0x9d, 0x02, 0x1f, 0xdf, 0x4a, 0x8b, 0x89,
- 0xbc, 0x8f, 0x14, 0xe2, 0x6f, 0x15, 0x66, 0x5a,
- 0x67, 0x70, 0x19, 0x7f, 0xb9, 0x43, 0x56, 0x68,
- 0xfb, 0xaa, 0xf3, 0x26, 0xdb, 0xad, 0xdf, 0x6e,
- 0x7c, 0xb4, 0xa3, 0xd0, 0x26, 0xbe, 0xf3, 0xa3,
- 0xdc, 0x8f, 0xdf, 0x74, 0xf0, 0x89, 0x5e, 0xca,
- 0x86, 0x31, 0x2c, 0x33, 0x80, 0xea, 0x29, 0x19,
- 0x39, 0xad, 0x32, 0x9f, 0x14, 0x20, 0x95, 0xc0,
- 0x40, 0x1b, 0xa3, 0xa4, 0x91, 0xf7, 0xea, 0xc1,
- 0x35, 0x16, 0x87, 0x96, 0x0a, 0x76, 0x96, 0x02,
- 0x6b, 0xa2, 0xc0, 0xd3, 0x8d, 0xc6, 0x32, 0x4e,
- 0xaf, 0x8b, 0xae, 0xdc, 0x42, 0x47, 0xc1, 0x85,
- 0x6e, 0x5e, 0x94, 0xf2, 0x52, 0xfa, 0x27, 0xe7,
- 0x22, 0x24, 0x94, 0xeb, 0x67, 0xbe, 0x1e, 0xe4,
- 0x82, 0x91, 0xde, 0x71, 0x0a, 0xb8, 0x23, 0x1a,
- 0x02, 0xe7, 0xcc, 0x82, 0x06, 0xd2, 0x26, 0x15,
- 0x54, 0x97, 0x52, 0xcd, 0xf5, 0x3f, 0x6d, 0xc6,
- 0xb9, 0x70, 0x30, 0xbe, 0xc5, 0x88, 0xa6, 0xb0,
- 0x65, 0x16, 0x9c, 0x4c, 0x84, 0xe2, 0x7a, 0x6e,
- 0xe9, 0xc7, 0xbd, 0xcf, 0x45, 0x27, 0xfc, 0x19,
- 0xc6, 0x23, 0x1d, 0x2b, 0x88, 0xa2, 0x67, 0x1f,
- 0xc2, 0xd6, 0xd3, 0xa0, 0x79, 0xfb, 0xbf, 0xea,
- 0x38, 0xa8, 0xdf, 0x4f, 0xbc, 0x9b, 0x8e, 0xee,
- 0x04, 0xb7, 0x7c, 0x00, 0xd7, 0x95, 0x1a, 0x03,
- 0x82, 0x7a, 0xe8, 0x41, 0xb8, 0xb1, 0xaf, 0x7f,
- 0xf1, 0x30, 0x89, 0x56, 0x6d, 0x07, 0x11, 0x55,
- 0x79, 0xdd, 0x68, 0x0f, 0x82, 0x08, 0x5c, 0xcc,
- 0x24, 0x47, 0x54, 0x68, 0x86, 0xf1, 0xf0, 0x3f,
- 0x52, 0x10, 0xad, 0xe4, 0x16, 0x33, 0x16, 0x02,
- 0x21, 0x62, 0xe3, 0x2f, 0x5d, 0xeb, 0x22, 0x5b,
- 0x64, 0xb4, 0x29, 0x22, 0x74, 0x24, 0x29, 0xa9,
- 0x4c, 0x66, 0x84, 0x31, 0xca, 0x99, 0x95, 0xf5
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_2048_P = {
- .t = {128, {
- 0xc8, 0x80, 0x6f, 0xf6, 0x2f, 0xfb, 0x49, 0x8b,
- 0x77, 0x39, 0xe2, 0x3d, 0x3d, 0x1f, 0x4d, 0xf9,
- 0xbb, 0x54, 0x06, 0x0d, 0x71, 0xbf, 0x54, 0xb1,
- 0x1e, 0xa2, 0x20, 0x7e, 0xdd, 0xcf, 0x21, 0x16,
- 0xe9, 0xc0, 0xba, 0x94, 0x02, 0xd2, 0xa4, 0x2e,
- 0x78, 0x3c, 0xfb, 0x64, 0xa0, 0xe7, 0xe9, 0x27,
- 0x64, 0x29, 0x19, 0x74, 0xc5, 0x77, 0xbb, 0xe1,
- 0x6d, 0xb4, 0x83, 0x1d, 0x43, 0x5a, 0x80, 0x72,
- 0xec, 0x3c, 0x32, 0xc3, 0x20, 0x2c, 0xce, 0xf7,
- 0xba, 0xf6, 0xc6, 0x0c, 0xf4, 0x56, 0xfd, 0xdf,
- 0x21, 0x55, 0xf3, 0xe2, 0x56, 0x25, 0xa6, 0xb3,
- 0x96, 0xa4, 0x9c, 0xb8, 0xfd, 0x9c, 0xec, 0x87,
- 0xfa, 0xda, 0x2e, 0xa4, 0xf6, 0x0f, 0x14, 0xe6,
- 0x81, 0x22, 0x84, 0xe7, 0xc0, 0x1d, 0xd1, 0x3f,
- 0xed, 0xb0, 0xba, 0xd8, 0xe4, 0xe9, 0xd4, 0x18,
- 0x33, 0xae, 0x29, 0x51, 0x79, 0x79, 0xd1, 0x0f
- }
- }
-};
-
-static const TPM2B_PUBLIC_KEY_RSA RSA_2048_Q = {
- .t = {128, {
- 0xc8, 0x41, 0x2a, 0x42, 0xf1, 0x6a, 0x81, 0xac,
- 0x06, 0xab, 0xd0, 0xb7, 0xc0, 0xbb, 0xc6, 0x13,
- 0xdd, 0xfd, 0x5e, 0x3c, 0x77, 0xfe, 0xc1, 0x2e,
- 0x76, 0xf0, 0x94, 0xc0, 0x5d, 0x24, 0x8b, 0x30,
- 0x0d, 0xf8, 0x2a, 0xc7, 0x26, 0x78, 0x1b, 0x81,
- 0x5a, 0x42, 0x96, 0xad, 0xf7, 0x0e, 0xa4, 0x1b,
- 0x2c, 0x8f, 0x38, 0x06, 0x05, 0x8d, 0x98, 0x6e,
- 0x37, 0x65, 0xb4, 0x2c, 0x80, 0xe2, 0x38, 0xd5,
- 0x79, 0xd2, 0xea, 0x62, 0xf2, 0x32, 0xac, 0x7b,
- 0x88, 0x90, 0xc3, 0x4e, 0x9e, 0x53, 0xe5, 0x7e,
- 0xef, 0x13, 0xb1, 0xe3, 0xd5, 0x41, 0xd1, 0xa9,
- 0x15, 0x04, 0x3c, 0x61, 0x74, 0x5e, 0x1a, 0x00,
- 0x5c, 0x8a, 0x8b, 0x17, 0xd5, 0x78, 0xad, 0x5e,
- 0xe0, 0xcf, 0x35, 0x63, 0x0a, 0x95, 0x1e, 0x70,
- 0xbe, 0x97, 0xf2, 0xd3, 0x78, 0x06, 0x8a, 0x88,
- 0x9b, 0x27, 0xc8, 0xb2, 0xb1, 0x3d, 0x8a, 0xd7
- }
- }
-};
-
-#define MAX_MSG_BYTES RSA_MAX_BYTES
-#define MAX_LABEL_LEN 32
-
-/* 128-byte buffer to hold entropy for generating a
- * 2048-bit RSA key (assuming ~112 bits of security strength,
- * the TPM spec requires a seed of minimum size 28-bytes). */
-TPM2B_BYTE_VALUE(128);
-
-static void rsa_command_handler(void *cmd_body,
- size_t cmd_size,
- size_t *response_size_out)
-{
- uint8_t *cmd;
- uint8_t op;
- uint8_t padding_alg;
- uint8_t hashing_alg;
- uint16_t key_len;
- uint16_t in_len;
- uint8_t in[MAX_MSG_BYTES];
- uint16_t digest_len;
- uint8_t digest[SHA_DIGEST_MAX_BYTES];
- uint8_t *out = (uint8_t *) cmd_body;
- TPM2B_PUBLIC_KEY_RSA N;
- TPM2B_PUBLIC_KEY_RSA d;
- TPM2B_PUBLIC_KEY_RSA p;
- TPM2B_PUBLIC_KEY_RSA q;
- RSA_KEY key;
- uint32_t *response_size = (uint32_t *) response_size_out;
- TPM2B_PUBLIC_KEY_RSA rsa_d;
- TPM2B_PUBLIC_KEY_RSA rsa_n;
-
- TPM2B_128_BYTE_VALUE seed;
- uint8_t bn_buf[RSA_MAX_BYTES];
- struct LITE_BIGNUM bn;
- char label[MAX_LABEL_LEN];
-
- /* This is the SHA-256 hash of the RSA template from the TCG
- * EK Credential Profile spec.
- */
- TPM2B_32_BYTE_VALUE RSA_TEMPLATE_EK_EXTRA = {
- .t = {32, {
- 0x68, 0xd1, 0xa2, 0x41, 0xfb, 0x27, 0x2f, 0x03,
- 0x90, 0xbf, 0xd0, 0x42, 0x8d, 0xad, 0xee, 0xb0,
- 0x2b, 0xf4, 0xa1, 0xcd, 0x46, 0xab, 0x6c, 0x39,
- 0x1b, 0xa3, 0x1f, 0x51, 0x87, 0x06, 0x8e, 0x6a
- }
- }
- };
-
- assert(sizeof(size_t) == sizeof(uint32_t));
-
- /* Command format.
- *
- * OFFSET FIELD
- * 0 OP
- * 1 PADDING
- * 2 HASHING
- * 3 MSB KEY LEN
- * 4 LSB KEY LEN
- * 5 MSB IN LEN
- * 6 LSB IN LEN
- * 7 IN
- * 7 + IN_LEN MSB DIGEST LEN
- * 8 + IN_LEN LSB DIGEST LEN
- * 9 + IN_LEN DIGEST
- */
- cmd = (uint8_t *) cmd_body;
- op = *cmd++;
- padding_alg = *cmd++;
- hashing_alg = *cmd++;
- key_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- in_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- if (in_len > sizeof(in)) {
- *response_size = 0;
- return;
- }
- memcpy(in, cmd, in_len);
- if (op == TEST_RSA_VERIFY) {
- cmd += in_len;
- digest_len = ((uint16_t) (cmd[0] << 8)) | cmd[1];
- cmd += 2;
- if (digest_len > sizeof(digest)) {
- *response_size = 0;
- return;
- }
- memcpy(digest, cmd, digest_len);
- }
-
- /* Make copies of N, and d, as const data is immutable. */
- switch (key_len) {
- case 768:
- N = RSA_768_N;
- d = RSA_768_D;
- p = RSA_768_P;
- q = RSA_768_Q;
- rsa_n.b.size = RSA_768_N.b.size;
- rsa_d.b.size = RSA_768_D.b.size;
- break;
- case 1024:
- N = RSA_1024_N;
- d = RSA_1024_D;
- p = RSA_1024_P;
- q = RSA_1024_Q;
- rsa_n.b.size = RSA_1024_N.b.size;
- rsa_d.b.size = RSA_1024_D.b.size;
- break;
- case 2048:
- N = RSA_2048_N;
- d = RSA_2048_D;
- p = RSA_2048_P;
- q = RSA_2048_Q;
- rsa_n.b.size = RSA_2048_N.b.size;
- rsa_d.b.size = RSA_2048_D.b.size;
- break;
- default:
- *response_size = 0;
- return;
- }
- key.exponent = 65537;
- key.publicKey = &N.b;
- key.privateKey = &d.b;
-
- switch (op) {
- case TEST_RSA_ENCRYPT:
- if (_cpri__EncryptRSA(
- response_size, out, &key,
- padding_alg, in_len, in, hashing_alg, "")
- != CRYPT_SUCCESS)
- *response_size = 0;
- return;
- case TEST_RSA_DECRYPT:
- if (_cpri__DecryptRSA(
- response_size, out, &key,
- padding_alg, in_len, in, hashing_alg, "")
- != CRYPT_SUCCESS)
- *response_size = 0;
- return;
- case TEST_RSA_SIGN:
- if (_cpri__SignRSA(
- response_size, out, &key,
- padding_alg, hashing_alg, in_len, in)
- != CRYPT_SUCCESS)
- *response_size = 0;
- return;
- case TEST_RSA_VERIFY:
- if (_cpri__ValidateSignatureRSA(
- &key, padding_alg, hashing_alg, digest_len,
- digest, in_len, in, 0)
- != CRYPT_SUCCESS) {
- *response_size = 0;
- } else {
- *out = 1;
- *response_size = 1;
- }
- return;
- case TEST_RSA_KEYTEST:
- if (_cpri__TestKeyRSA(&rsa_d.b, 65537, &rsa_n.b, &p.b, &q.b)
- != CRYPT_SUCCESS) {
- *response_size = 0;
- return;
- }
- if (memcmp(rsa_n.b.buffer, key.publicKey->buffer,
- rsa_n.b.size) != 0 ||
- memcmp(rsa_d.b.buffer, key.privateKey->buffer,
- rsa_d.b.size) != 0) {
- *response_size = 0;
- return;
- }
-
- if (_cpri__TestKeyRSA(&rsa_d.b, 65537, key.publicKey,
- &p.b, NULL) != CRYPT_SUCCESS) {
- *response_size = 0;
- return;
- }
- if (memcmp(rsa_d.b.buffer, key.privateKey->buffer,
- rsa_d.b.size) != 0) {
- *response_size = 0;
- return;
- }
- *out = 1;
- *response_size = 1;
- return;
- case TEST_RSA_KEYGEN:
- if (in_len > MAX_LABEL_LEN - 1) {
- *response_size = 0;
- return;
- }
- N.b.size = sizeof(N.t.buffer);
- p.b.size = sizeof(p.t.buffer);
- seed.b.size = sizeof(VERIFY_SEED);
- memcpy(seed.b.buffer, VERIFY_SEED, sizeof(VERIFY_SEED));
- if (in_len > 0) {
- memcpy(label, in, in_len);
- label[in_len] = '\0';
- }
- if (_cpri__GenerateKeyRSA(
- &N.b, &p.b, key_len, RSA_F4, TPM_ALG_SHA256,
- &seed.b, in_len ? label : NULL,
- &RSA_TEMPLATE_EK_EXTRA.b, NULL)
- != CRYPT_SUCCESS) {
- *response_size = 0;
- } else {
- memcpy(out, N.b.buffer, N.b.size);
- memcpy(out + N.b.size, p.b.buffer, p.b.size);
- *response_size = N.b.size + p.b.size;
- }
- return;
- case TEST_BN_PRIMEGEN:
- if (in_len > sizeof(bn_buf)) {
- *response_size = 0;
- return;
- }
- DCRYPTO_bn_wrap(&bn, bn_buf, in_len);
- memcpy(bn_buf, in, in_len);
- if (DCRYPTO_bn_generate_prime(&bn)) {
- memcpy(out, bn.d, bn_size(&bn));
- *response_size = bn_size(&bn);
- } else {
- *response_size = 0;
- }
- return;
- case TEST_X509_VERIFY:
- {
- int result;
- struct RSA rsa;
-
- if (key.publicKey != &N.b) {
- *response_size = 0;
- return;
- }
-
- reverse_tpm2b(key.publicKey);
- rsa.e = key.exponent;
- rsa.N.dmax = key.publicKey->size / sizeof(uint32_t);
- rsa.N.d = (struct access_helper *) &key.publicKey->buffer;
- rsa.d.dmax = 0;
- rsa.d.d = NULL;
-
- result = DCRYPTO_x509_verify(RSA_2048_CERT,
- sizeof(RSA_2048_CERT), &rsa);
- reverse_tpm2b(key.publicKey);
-
- if (!result) {
- *response_size = 0;
- return;
- }
- *out = 0x01;
- *response_size = 1;
- }
- }
-}
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_RSA, rsa_command_handler);
-
-#endif /* CRYPTO_TEST_SETUP */
diff --git a/board/cr50/tpm2/stubs.c b/board/cr50/tpm2/stubs.c
deleted file mode 100644
index d3e8710604..0000000000
--- a/board/cr50/tpm2/stubs.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/* Copyright 2015 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 TPM_FAIL_C
-#include "Global.h"
-#include "CryptoEngine.h"
-
-CRYPT_RESULT _cpri__C_2_2_KeyExchange(
- TPMS_ECC_POINT * outZ1, // OUT: a computed point
- TPMS_ECC_POINT * outZ2, // OUT: and optional second point
- TPM_ECC_CURVE curveId, // IN: the curve for the computations
- TPM_ALG_ID scheme, // IN: the key exchange scheme
- TPM2B_ECC_PARAMETER * dsA, // IN: static private TPM key
- TPM2B_ECC_PARAMETER * deA, // IN: ephemeral private TPM key
- TPMS_ECC_POINT * QsB, // IN: static public party B key
- TPMS_ECC_POINT * QeB // IN: ephemeral public party B key
- )
-{
- ecprintf("%s called\n", __func__);
- return CRYPT_FAIL;
-}
-
-CRYPT_RESULT _cpri__DrbgGetPutState(
- GET_PUT direction,
- int bufferSize,
- BYTE * buffer)
-{
- /* This unction is not implemented in the TPM2 library either. */
- return CRYPT_SUCCESS;
-}
-
-CRYPT_RESULT _cpri__EccCommitCompute(
- TPMS_ECC_POINT * K, // OUT: [d]B or [r]Q
- TPMS_ECC_POINT * L, // OUT: [r]B
- TPMS_ECC_POINT * E, // OUT: [r]M
- TPM_ECC_CURVE curveId, // IN: the curve for the computations
- TPMS_ECC_POINT * M, // IN: M (optional)
- TPMS_ECC_POINT * B, // IN: B (optional)
- TPM2B_ECC_PARAMETER * d, // IN: d (required)
- TPM2B_ECC_PARAMETER * r // IN: the computed r value (required)
- )
-{
- ecprintf("%s called\n", __func__);
- return CRYPT_FAIL;
-}
-
-BOOL _cpri__Startup(
- void)
-{
- /*
- * Below is the list of functions called by the TPM2 library from
- * _cpri__Startup().
- * TODO(vbendeb): verify proper initialization.
- *
- * _cpri__HashStartup() - not doing anything for now, maybe hw
- * reinitialization is required?
- * _cpri__RsaStartup() - not sure what needs to be done in HW
- * _cpri__EccStartup() - not sure what needs to be done in HW
- * _cpri__SymStartup() - this function is emtpy in the TPM2 library
- * implementation.
- */
- return 1;
-}
-
-CRYPT_RESULT _math__Div(
- const TPM2B * n, // IN: numerator
- const TPM2B * d, // IN: denominator
- TPM2B * q, // OUT: quotient
- TPM2B * r // OUT: remainder
- )
-{
- ecprintf("%s called\n", __func__);
- return CRYPT_FAIL;
-}
-
-void __assert_func(
- const char *file,
- int line,
- const char *func,
- const char *condition
-)
-{
- /*
- * TPM2 library invokes assert from a common wrapper, which first sets
- * global variables describing the failure point and then invokes the
- * assert() macro which ends up calling this function as defined by the gcc
- * toolchain.
- *
- * For some weird reason (or maybe this is a bug), s_FailFunction is defined
- * in the tpm2 library as a 32 bit int, but on a failure the name of the
- * failing function (its first four bytes) are copiied into this variable.
- *
- * TODO(vbendeb): investigate and fix TPM2 library assert handling.
- */
- ecprintf("Failure in %s, func %s, line %d:\n%s\n",
- file,
- s_failFunction ? (const char *)&s_failFunction : func,
- s_failLine ? s_failLine : line,
- condition);
- while (1)
- ; /* Let the watchdog doo the rest. */
-}
-
-CRYPT_RESULT _cpri__InitCryptoUnits(
- FAIL_FUNCTION failFunction)
-{
- return CRYPT_SUCCESS;
-}
diff --git a/board/cr50/tpm2/trng.c b/board/cr50/tpm2/trng.c
deleted file mode 100644
index 7cce13ff1c..0000000000
--- a/board/cr50/tpm2/trng.c
+++ /dev/null
@@ -1,11 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "CryptoEngine.h"
-
-CRYPT_RESULT _cpri__StirRandom(int32_t num, uint8_t *entropy)
-{
- return CRYPT_SUCCESS; /* NO-OP on CR50. */
-}
diff --git a/board/cr50/tpm2/upgrade.c b/board/cr50/tpm2/upgrade.c
deleted file mode 100644
index b5d3692467..0000000000
--- a/board/cr50/tpm2/upgrade.c
+++ /dev/null
@@ -1,9 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "extension.h"
-#include "upgrade_fw.h"
-
-DECLARE_EXTENSION_COMMAND(EXTENSION_FW_UPGRADE, fw_upgrade_command_handler);
diff --git a/board/cr50/usb_i2c.c b/board/cr50/usb_i2c.c
deleted file mode 100644
index 8ba90c5f63..0000000000
--- a/board/cr50/usb_i2c.c
+++ /dev/null
@@ -1,93 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "console.h"
-#include "device_state.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "i2c.h"
-#include "rdd.h"
-#include "registers.h"
-#include "system.h"
-#include "timer.h"
-#include "usb_i2c.h"
-
-#define CPRINTS(format, args...) cprints(CC_USB, format, ## args)
-
-static int i2c_enabled(void)
-{
- return !gpio_get_level(GPIO_EN_PP3300_INA_L);
-}
-
-static void ina_disconnect(void)
-{
- CPRINTS("Disabling I2C");
-
- /* Disonnect I2C0 SDA/SCL output to B1/B0 pads */
- GWRITE(PINMUX, DIOB1_SEL, 0);
- GWRITE(PINMUX, DIOB0_SEL, 0);
- /* Disconnect B1/B0 pads to I2C0 input SDA/SCL */
- GWRITE(PINMUX, I2C0_SDA_SEL, 0);
- GWRITE(PINMUX, I2C0_SCL_SEL, 0);
-
- /* Disable power to INA chips */
- gpio_set_level(GPIO_EN_PP3300_INA_L, 1);
-}
-DECLARE_DEFERRED(ina_disconnect);
-
-static void ina_connect(void)
-{
- CPRINTS("Enabling I2C");
-
- /* Apply power to INA chips */
- gpio_set_level(GPIO_EN_PP3300_INA_L, 0);
- /* Allow enough time for power rail to come up */
- usleep(25);
-
- /*
- * Connect B0/B1 pads to I2C0 input SDA/SCL. Note, that the inputs
- * for these pads are already enabled for the gpio signals I2C_SCL_INA
- * and I2C_SDA_INA in gpio.inc.
- */
- GWRITE(PINMUX, I2C0_SDA_SEL, GC_PINMUX_DIOB1_SEL);
- GWRITE(PINMUX, I2C0_SCL_SEL, GC_PINMUX_DIOB0_SEL);
-
- /* Connect I2CS SDA/SCL output to B1/B0 pads */
- GWRITE(PINMUX, DIOB1_SEL, GC_PINMUX_I2C0_SDA_SEL);
- GWRITE(PINMUX, DIOB0_SEL, GC_PINMUX_I2C0_SCL_SEL);
-
- /*
- * Initialize the i2cm module after the INAs are powered and the signal
- * lines are connected.
- */
- i2cm_init();
-}
-
-void usb_i2c_board_disable(int debounce)
-{
- if (!i2c_enabled())
- return;
-
- /*
- * Wait to disable i2c in case we are doing a bunch of i2c transactions
- * in a row.
- */
- hook_call_deferred(&ina_disconnect_data, debounce ? 1 * SECOND : 0);
-}
-
-int usb_i2c_board_enable(void)
-{
- if (device_get_state(DEVICE_SERVO) != DEVICE_STATE_OFF) {
- CPRINTS("Servo is attached I2C cannot be enabled");
- usb_i2c_board_disable(0);
- return EC_ERROR_BUSY;
- }
-
- hook_call_deferred(&ina_disconnect_data, -1);
-
- if (!i2c_enabled())
- ina_connect();
- return EC_SUCCESS;
-}
diff --git a/board/cr50/usb_spi.c b/board/cr50/usb_spi.c
deleted file mode 100644
index ea9c2258ed..0000000000
--- a/board/cr50/usb_spi.c
+++ /dev/null
@@ -1,170 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "console.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "registers.h"
-#include "spi.h"
-#include "system.h"
-#include "timer.h"
-#include "usb_spi.h"
-
-#define CPRINTS(format, args...) cprints(CC_USB, format, ## args)
-
-static uint8_t update_in_progress;
-
-static void disable_ec_ap_spi(void)
-{
- /* Configure SPI GPIOs */
- gpio_set_level(GPIO_AP_FLASH_SELECT, 0);
- gpio_set_level(GPIO_EC_FLASH_SELECT, 0);
-
- /* Release AP and EC */
- deassert_ec_rst();
- deassert_sys_rst();
-}
-
-static void enable_ec_spi(void)
-{
- /* Select EC flash */
- gpio_set_level(GPIO_AP_FLASH_SELECT, 0);
- gpio_set_level(GPIO_EC_FLASH_SELECT, 1);
-
- /* Hold EC in reset. This will also hold the AP in reset. */
- assert_ec_rst();
-}
-
-static void enable_ap_spi(void)
-{
- /* Select AP flash */
- gpio_set_level(GPIO_AP_FLASH_SELECT, 1);
- gpio_set_level(GPIO_EC_FLASH_SELECT, 0);
-
- /*
- * On some systems SYS_RST_L is not level sensitive, so the only way to
- * be sure we're holding the AP in reset is to hold the EC in reset.
- */
- assert_ec_rst();
-}
-
-int usb_spi_update_in_progress(void)
-{
- return update_in_progress;
-}
-
-static void update_finished(void)
-{
- update_in_progress = 0;
-
- /*
- * The AP and EC are reset in usb_spi_enable so the TPM is in a bad
- * state. Use resetting the EC to reset the entire system including the
- * TPM.
- */
- assert_ec_rst();
- usleep(200);
- deassert_ec_rst();
-}
-DECLARE_DEFERRED(update_finished);
-
-void usb_spi_board_enable(struct usb_spi_config const *config)
-{
- hook_call_deferred(&update_finished_data, -1);
- update_in_progress = 1;
-
- disable_ec_ap_spi();
-
- if (config->state->enabled_host == USB_SPI_EC)
- enable_ec_spi();
- else if (config->state->enabled_host == USB_SPI_AP)
- enable_ap_spi();
- else {
- CPRINTS("DEVICE NOT SUPPORTED");
- return;
- }
-
- /* Connect DIO A4, A8, and A14 to the SPI peripheral */
- GWRITE(PINMUX, DIOA4_SEL, 0); /* SPI_MOSI */
- GWRITE(PINMUX, DIOA8_SEL, 0); /* SPI_CS_L */
- GWRITE(PINMUX, DIOA14_SEL, 0); /* SPI_CLK */
- /* Set SPI_CS to be an internal pull up */
- GWRITE_FIELD(PINMUX, DIOA14_CTL, PU, 1);
-
- CPRINTS("usb_spi enable %s",
- gpio_get_level(GPIO_AP_FLASH_SELECT) ? "AP" : "EC");
-
- spi_enable(CONFIG_SPI_FLASH_PORT, 1);
-}
-
-void usb_spi_board_disable(struct usb_spi_config const *config)
-{
- CPRINTS("usb_spi disable");
- spi_enable(CONFIG_SPI_FLASH_PORT, 0);
- disable_ec_ap_spi();
-
- /* Disconnect SPI peripheral to tri-state pads */
- /* Disable internal pull up */
- GWRITE_FIELD(PINMUX, DIOA14_CTL, PU, 0);
- /* TODO: Implement way to get the gpio */
- ASSERT(GREAD(PINMUX, GPIO0_GPIO7_SEL) == GC_PINMUX_DIOA4_SEL);
- ASSERT(GREAD(PINMUX, GPIO0_GPIO8_SEL) == GC_PINMUX_DIOA8_SEL);
- ASSERT(GREAD(PINMUX, GPIO0_GPIO9_SEL) == GC_PINMUX_DIOA14_SEL);
-
- /* Set SPI MOSI, CLK, and CS_L as inputs */
- GWRITE(PINMUX, DIOA4_SEL, GC_PINMUX_GPIO0_GPIO7_SEL);
- GWRITE(PINMUX, DIOA8_SEL, GC_PINMUX_GPIO0_GPIO8_SEL);
- GWRITE(PINMUX, DIOA14_SEL, GC_PINMUX_GPIO0_GPIO9_SEL);
-
- /*
- * TODO(crosbug.com/p/52366): remove once sys_rst just resets the TPM
- * instead of cr50.
- * Resetting the EC and AP cause sys_rst to be asserted currently that
- * will cause cr50 to do a soft reset. Delay the end of the transaction
- * to prevent cr50 from resetting during a series of usb_spi calls.
- */
- hook_call_deferred(&update_finished_data, 1 * SECOND);
-}
-
-int usb_spi_interface(struct usb_spi_config const *config,
- struct usb_setup_packet *req)
-{
- if (req->bmRequestType != (USB_DIR_OUT |
- USB_TYPE_VENDOR |
- USB_RECIP_INTERFACE))
- return 1;
-
- if (req->wValue != 0 ||
- req->wIndex != config->interface ||
- req->wLength != 0)
- return 1;
-
- if (!config->state->enabled_device)
- return 1;
-
- switch (req->bRequest) {
- case USB_SPI_REQ_ENABLE_AP:
- config->state->enabled_host = USB_SPI_AP;
- break;
- case USB_SPI_REQ_ENABLE_EC:
- config->state->enabled_host = USB_SPI_EC;
- break;
- case USB_SPI_REQ_ENABLE:
- CPRINTS("ERROR: Must specify target");
- case USB_SPI_REQ_DISABLE:
- config->state->enabled_host = USB_SPI_DISABLE;
- break;
-
- default:
- return 1;
- }
-
- /*
- * Our state has changed, call the deferred function to handle the
- * state change.
- */
- hook_call_deferred(config->deferred, 0);
- return 0;
-}
diff --git a/board/cr50/wp.c b/board/cr50/wp.c
deleted file mode 100644
index 28268f4cca..0000000000
--- a/board/cr50/wp.c
+++ /dev/null
@@ -1,329 +0,0 @@
-/* Copyright 2016 The Chromium OS Authors. All rights reserved.
- * Use of this source code is governed by a BSD-style license that can be
- * found in the LICENSE file.
- */
-
-#include "common.h"
-#include "console.h"
-#include "extension.h"
-#include "gpio.h"
-#include "hooks.h"
-#include "nvmem.h"
-#include "registers.h"
-#include "system.h"
-#include "task.h"
-#include "timer.h"
-#include "tpm_registers.h"
-
-#define CPRINTS(format, args...) cprints(CC_RBOX, format, ## args)
-#define CPRINTF(format, args...) cprintf(CC_RBOX, format, ## args)
-
-static int command_wp(int argc, char **argv)
-{
- int val;
-
- if (argc > 1) {
- if (!parse_bool(argv[1], &val))
- return EC_ERROR_PARAM1;
-
- /* Invert, because active low */
- GREG32(RBOX, EC_WP_L) = !val;
- }
-
- /* Invert, because active low */
- val = !GREG32(RBOX, EC_WP_L);
-
- ccprintf("Flash WP is %s\n", val ? "enabled" : "disabled");
-
- return EC_SUCCESS;
-}
-DECLARE_CONSOLE_COMMAND(wp, command_wp,
- "[<BOOLEAN>]",
- "Get/set the flash HW write-protect signal");
-
-/* When the system is locked down, provide a means to unlock it */
-#ifdef CONFIG_RESTRICTED_CONSOLE_COMMANDS
-
-/* Hand-built images may be initially unlocked; Buildbot images are not. */
-#ifdef CR50_DEV
-static int console_restricted_state;
-#else
-static int console_restricted_state = 1;
-#endif
-
-static void lock_the_console(void)
-{
- CPRINTS("The console is locked");
- console_restricted_state = 1;
-}
-
-static void unlock_the_console(void)
-{
- int rc;
-
- /* Wipe the TPM's memory and reset the TPM task. */
- rc = tpm_reset(1, 1);
- if (rc != EC_SUCCESS) {
- /*
- * If anything goes wrong (which is unlikely), we REALLY don't
- * want to unlock the console. It's possible to fail without
- * the TPM task ever running, so rebooting is probably our best
- * bet for fixing the problem.
- */
- CPRINTS("%s: Couldn't wipe nvmem! (rc %d)", __func__, rc);
- system_reset(SYSTEM_RESET_HARD);
- }
-
- CPRINTS("TPM is erased, console is unlocked");
- console_restricted_state = 0;
-}
-
-int console_is_restricted(void)
-{
- return console_restricted_state;
-}
-
-/****************************************************************************/
-/* Stuff for the unlock sequence */
-
-/*
- * The normal unlock sequence should take 5 minutes (unless the case is
- * opened). Hand-built images only need to be long enough to demonstrate that
- * they work.
- */
-#ifdef CR50_DEV
-#define UNLOCK_SEQUENCE_DURATION (10 * SECOND)
-#else
-#define UNLOCK_SEQUENCE_DURATION (300 * SECOND)
-#endif
-
-/* Max time that can elapse between power button pokes */
-static int unlock_beat;
-
-/* When will we have poked the power button for long enough? */
-static timestamp_t unlock_deadline;
-
-/* Are we expecting power button pokes? */
-static int unlock_in_progress;
-
-/* This is invoked only when the unlock sequence has ended */
-static void unlock_sequence_is_over(void)
-{
- /* Disable the power button interrupt so we aren't bothered */
- GWRITE_FIELD(RBOX, INT_ENABLE, INTR_PWRB_IN_FED, 0);
- task_disable_irq(GC_IRQNUM_RBOX0_INTR_PWRB_IN_FED_INT);
-
- if (unlock_in_progress) {
- /* We didn't poke the button fast enough */
- CPRINTS("Unlock process failed");
- } else {
- /* The last poke was after the final deadline, so we're done */
- CPRINTS("Unlock process completed successfully");
- unlock_the_console();
- }
-
- unlock_in_progress = 0;
-
- /* Allow sleeping again */
- enable_sleep(SLEEP_MASK_FORCE_NO_DSLEEP);
-}
-DECLARE_DEFERRED(unlock_sequence_is_over);
-
-static void power_button_poked(void)
-{
- if (timestamp_expired(unlock_deadline, NULL)) {
- /* We've been poking for long enough */
- unlock_in_progress = 0;
- hook_call_deferred(&unlock_sequence_is_over_data, 0);
- CPRINTS("poke: enough already", __func__);
- } else {
- /* Wait for the next poke */
- hook_call_deferred(&unlock_sequence_is_over_data, unlock_beat);
- CPRINTS("poke: not yet %.6ld", unlock_deadline);
- }
-
- GWRITE_FIELD(RBOX, INT_STATE, INTR_PWRB_IN_FED, 1);
-}
-DECLARE_IRQ(GC_IRQNUM_RBOX0_INTR_PWRB_IN_FED_INT, power_button_poked, 1);
-
-
-static void start_unlock_process(int total_poking_time, int max_poke_interval)
-{
- unlock_in_progress = 1;
-
- /* Clear any leftover power button interrupts */
- GWRITE_FIELD(RBOX, INT_STATE, INTR_PWRB_IN_FED, 1);
-
- /* Enable power button interrupt */
- GWRITE_FIELD(RBOX, INT_ENABLE, INTR_PWRB_IN_FED, 1);
- task_enable_irq(GC_IRQNUM_RBOX0_INTR_PWRB_IN_FED_INT);
-
- /* Must poke at least this often */
- unlock_beat = max_poke_interval;
-
- /* Keep poking until it's been long enough */
- unlock_deadline = get_time();
- unlock_deadline.val += total_poking_time;
-
- /* Stay awake while we're doing this, just in case. */
- disable_sleep(SLEEP_MASK_FORCE_NO_DSLEEP);
-
- /* Check progress after waiting long enough for one button press */
- hook_call_deferred(&unlock_sequence_is_over_data, unlock_beat);
-}
-
-/****************************************************************************/
-/* TPM vendor-specific commands */
-
-static enum vendor_cmd_rc vc_lock(enum vendor_cmd_cc code,
- void *buf,
- size_t input_size,
- size_t *response_size)
-{
- uint8_t *buffer = buf;
-
- if (code == VENDOR_CC_GET_LOCK) {
- /*
- * Get the state of the console lock.
- *
- * Args: none
- * Returns: one byte; true (locked) or false (unlocked)
- */
- if (input_size != 0) {
- *response_size = 0;
- return VENDOR_RC_BOGUS_ARGS;
- }
-
- buffer[0] = console_is_restricted() ? 0x01 : 0x00;
- *response_size = 1;
- return VENDOR_RC_SUCCESS;
- }
-
- if (code == VENDOR_CC_SET_LOCK) {
- /*
- * Lock the console if it isn't already. Note that there
- * intentionally isn't an unlock command. At most, we may want
- * to call start_unlock_process(), but we haven't yet decided.
- *
- * Args: none
- * Returns: none
- */
- if (input_size != 0) {
- *response_size = 0;
- return VENDOR_RC_BOGUS_ARGS;
- }
-
- lock_the_console();
- *response_size = 0;
- return VENDOR_RC_SUCCESS;
- }
-
- /* I have no idea what you're talking about */
- *response_size = 0;
- return VENDOR_RC_NO_SUCH_COMMAND;
-}
-DECLARE_VENDOR_COMMAND(VENDOR_CC_GET_LOCK, vc_lock);
-DECLARE_VENDOR_COMMAND(VENDOR_CC_SET_LOCK, vc_lock);
-
-/****************************************************************************/
-static const char warning[] = "\n\t!!! WARNING !!!\n\n"
- "\tThe AP will be impolitely shut down and the TPM persistent memory\n"
- "\tERASED before the console is unlocked. The system will reboot in\n"
- "\tnormal mode and ALL encrypted content will be LOST.\n\n"
- "\tIf this is not what you want, simply do nothing and the unlock\n"
- "\tprocess will fail.\n\n"
- "\n\t!!! WARNING !!!\n\n";
-
-static int command_lock(int argc, char **argv)
-{
- int enabled;
- int i;
-
- if (argc > 1) {
- if (!parse_bool(argv[1], &enabled))
- return EC_ERROR_PARAM1;
-
- /* Changing nothing does nothing */
- if (enabled == console_is_restricted())
- goto out;
-
- /* Locking the console is always allowed */
- if (enabled) {
- lock_the_console();
- goto out;
- }
-
- /*
- * TODO(crosbug.com/p/55322, crosbug.com/p/55728): There may be
- * other preconditions which must be satisified before
- * continuing. We can return EC_ERROR_ACCESS_DENIED if those
- * aren't met.
- */
-
- /* Don't count down if we know it's likely to fail */
- if (unlock_in_progress) {
- ccprintf("An unlock process is already in progress\n");
- return EC_ERROR_BUSY;
- }
-
- /* Warn about the side effects of wiping nvmem */
- ccputs(warning);
-
- if (gpio_get_level(GPIO_BATT_PRES_L) == 1) {
- /*
- * If the battery cable has been disconnected, we only
- * need to poke the power button once to prove physical
- * presence.
- */
- ccprintf("Tap the power button once to confirm...\n\n");
-
- /*
- * We'll be satisified with the first press (so the
- * unlock_deadine is now + 0us), but we're willing to
- * wait for up to 10 seconds for that first press to
- * happen. If we don't get one by then, the unlock will
- * fail.
- */
- start_unlock_process(0, 10 * SECOND);
-
- } else {
- /*
- * If the battery is present, the user has to sit there
- * and poke the button repeatedly until enough time has
- * elapsed.
- */
-
- ccprintf("Start poking the power button in ");
- for (i = 10; i; i--) {
- ccprintf("%d ", i);
- sleep(1);
- }
- ccprintf("go!\n");
-
- /*
- * We won't be happy until we've been poking the button
- * for a good long while, but we'll only wait a couple
- * of seconds between each press before deciding that
- * the user has given up.
- */
- start_unlock_process(UNLOCK_SEQUENCE_DURATION,
- 2 * SECOND);
-
- ccprintf("Unlock sequence starting."
- " Continue until %.6ld\n", unlock_deadline);
- }
-
- return EC_SUCCESS;
- }
-
-out:
- ccprintf("The restricted console lock is %s\n",
- console_is_restricted() ? "enabled" : "disabled");
-
- return EC_SUCCESS;
-}
-DECLARE_SAFE_CONSOLE_COMMAND(lock, command_lock,
- "[<BOOLEAN>]",
- "Get/Set the restricted console lock");
-
-#endif /* CONFIG_RESTRICTED_CONSOLE_COMMANDS */