aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorRichard Spiegel <richard.spiegel@amd.corp-partner.google.com>2019-08-21 09:19:13 -0700
committerMartin Roth <martinroth@google.com>2019-09-21 20:34:27 +0000
commite512bce18967d52675653351b7154dc1ab75341d (patch)
tree3fab28213ff19244241296d933d1a1a33261a2fa
parent524bcbb494d5486470b993d7d717234d5781da03 (diff)
soc/amd/common/block: Create new SPI code
Create a new SPI code that overrides flash operations and uses the SPI controller within the FCH to its fullest. Reference: Family 15h models 70h-7Fh BKDG revision 3.06 (public) BUG=b:136595978 TEST=Build and boot grunt using this code, with debug enabled. Check output. Change-Id: Id293fb9b2da84c4206c7a1341b64e83fc0b8d71d Signed-off-by: Richard Spiegel <richard.spiegel@silverbackltd.com> Reviewed-on: https://review.coreboot.org/c/coreboot/+/35018 Tested-by: build bot (Jenkins) <no-reply@coreboot.org> Reviewed-by: Edward O'Callaghan <quasisec@chromium.org>
-rw-r--r--src/soc/amd/common/block/include/amdblocks/fch_spi.h87
-rw-r--r--src/soc/amd/common/block/include/amdblocks/lpc.h8
-rw-r--r--src/soc/amd/common/block/spi/Kconfig11
-rw-r--r--src/soc/amd/common/block/spi/Makefile.inc30
-rw-r--r--src/soc/amd/common/block/spi/fch_spi_ctrl.c427
-rw-r--r--src/soc/amd/common/block/spi/fch_spi_flash.c246
-rw-r--r--src/soc/amd/common/block/spi/fch_spi_special.c89
-rw-r--r--src/soc/amd/common/block/spi/fch_spi_table.c83
8 files changed, 981 insertions, 0 deletions
diff --git a/src/soc/amd/common/block/include/amdblocks/fch_spi.h b/src/soc/amd/common/block/include/amdblocks/fch_spi.h
new file mode 100644
index 0000000000..24cfbfc74a
--- /dev/null
+++ b/src/soc/amd/common/block/include/amdblocks/fch_spi.h
@@ -0,0 +1,87 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2019 Silverback Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; version 2 of the License.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#ifndef _FCH_SPI_H_
+#define _FCH_SPI_H_
+
+#include <stdint.h>
+#include <stddef.h>
+
+#define GRANULARITY_TEST_4k 0x0000f000 /* bits 15-12 */
+#define WORD_TO_DWORD_UPPER(x) ((x << 16) & 0xffff0000)
+#define SPI_PAGE_WRITE 0x02
+#define SPI_WRITE_ENABLE 0x06
+#define IDCODE_CONT_LEN 0
+#define IDCODE_PART_LEN 5
+#define IDCODE_LEN (IDCODE_CONT_LEN + IDCODE_PART_LEN)
+
+/* SPI MMIO registers */
+#define SPI_CNTRL0 0x00
+#define SPI_ACCESS_MAC_ROM_EN BIT(22)
+#define SPI_RESTRICTED_CMD1 0x04
+#define SPI_RESTRICTED_CMD2 0x08
+#define SPI_CNTRL1 0x0c
+#define SPI_CMD_CODE 0x45
+#define SPI_CMD_TRIGGER 0x47
+
+/* Special SST write commands */
+#define CMD_SST_BP 0x02 /* Byte Program */
+#define CMD_SST_AAI_WP 0xad /* Auto Address Increment Word Program */
+
+#define SST_256 0x004b /* Only SST that programs 256 bytes at once */
+
+enum non_standard_spi {
+ NON_STANDARD_SPI_NONE = 0,
+ NON_STANDARD_SPI_SST,
+};
+
+struct spi_flash_table {
+ const u8 shift;
+ const u8 idcode;
+ int (*probe)(const struct spi_slave *spi, u8 *idcode,
+ struct spi_flash *flash);
+};
+
+struct spi_data {
+ const char *name;
+ u32 size;
+ u32 sector_size;
+ u32 page_size;
+ u8 status_cmd;
+ u8 erase_cmd;
+ u8 write_cmd;
+ u8 write_enable_cmd;
+ u8 read_cmd;
+ u8 read_cmd_len;
+ enum non_standard_spi non_standard;
+};
+
+void fch_spi_init(void);
+void fch_spi_flash_ops_init(struct spi_flash *flash);
+int fch_spi_flash_cmd(const void *dout, size_t bytes_out, void *din, size_t bytes_in);
+int fch_spi_flash_cmd_write(const u8 *cmd, size_t cmd_len, const void *data, size_t data_len);
+int fch_spi_wait_cmd_ready(unsigned long timeout);
+int non_standard_sst_byte_write(u32 offset, const void *buf);
+int non_standard_sst_write_aai(u32 offset, size_t len, const void *buf, size_t start);
+const struct spi_flash_table *get_spi_flash_table(int *table_size);
+const struct spi_data *get_ctrl_spi_data(void);
+
+static inline int fch_spi_enable_write(void)
+{
+ u8 cmd_enable = SPI_WRITE_ENABLE;
+ return fch_spi_flash_cmd(&cmd_enable, 1, NULL, 0);
+}
+
+#endif /* _FCH_SPI_H_ */
diff --git a/src/soc/amd/common/block/include/amdblocks/lpc.h b/src/soc/amd/common/block/include/amdblocks/lpc.h
index f956ba3aa9..11880eb3e6 100644
--- a/src/soc/amd/common/block/include/amdblocks/lpc.h
+++ b/src/soc/amd/common/block/include/amdblocks/lpc.h
@@ -90,6 +90,14 @@
#define DECODE_IO_PORT_ENABLE0_H BIT(0)
#define LPC_MEM_PORT1 0x4c
+#define ROM_PROTECT_RANGE0 0x50
+#define ROM_BASE_MASK 0xfffff000 /* bits 31-12 */
+#define ROM_RANGE_WP BIT(10)
+#define ROM_RANGE_RP BIT(9)
+#define RANGE_UNIT BIT(8)
+#define RANGE_ADDR_MASK 0x000000ff /* Range defined by bits 7-0 */
+#define ROM_PROTECT_RANGE_REG(n) (ROM_PROTECT_RANGE0 + (4 * n))
+#define MAX_ROM_PROTECT_RANGES 4
#define LPC_MEM_PORT0 0x60
/* Register 0x64 is 32-bit, composed by two 16-bit sub-registers.
diff --git a/src/soc/amd/common/block/spi/Kconfig b/src/soc/amd/common/block/spi/Kconfig
new file mode 100644
index 0000000000..785e6da6b3
--- /dev/null
+++ b/src/soc/amd/common/block/spi/Kconfig
@@ -0,0 +1,11 @@
+config SOC_AMD_COMMON_BLOCK_SPI
+ bool
+ default n
+ help
+ Select this option to add FCH SPI controller functions to the build.
+ This overwrites the structure spi_flash_ops to use FCH SPI code
+ instead of individual SPI specific code.
+
+config SOC_AMD_COMMON_BLOCK_SPI_DEBUG
+ bool
+ default n
diff --git a/src/soc/amd/common/block/spi/Makefile.inc b/src/soc/amd/common/block/spi/Makefile.inc
new file mode 100644
index 0000000000..b94eda405a
--- /dev/null
+++ b/src/soc/amd/common/block/spi/Makefile.inc
@@ -0,0 +1,30 @@
+ifeq ($(CONFIG_SOC_AMD_COMMON_BLOCK_SPI),y)
+
+bootblock-y += fch_spi_ctrl.c
+bootblock-y += fch_spi_flash.c
+bootblock-y += fch_spi_special.c
+bootblock-y += fch_spi_table.c
+romstage-y += fch_spi_ctrl.c
+romstage-y += fch_spi_flash.c
+romstage-y += fch_spi_special.c
+romstage-y += fch_spi_table.c
+verstage-y += fch_spi_ctrl.c
+verstage-y += fch_spi_flash.c
+verstage-y += fch_spi_special.c
+verstage-y += fch_spi_table.c
+postcar-y += fch_spi_ctrl.c
+postcar-y += fch_spi_flash.c
+postcar-y += fch_spi_special.c
+postcar-y += fch_spi_table.c
+ramstage-y += fch_spi_ctrl.c
+ramstage-y += fch_spi_flash.c
+ramstage-y += fch_spi_special.c
+ramstage-y += fch_spi_table.c
+ifeq ($(CONFIG_SPI_FLASH_SMM),y)
+smm-y += fch_spi_ctrl.c
+smm-y += fch_spi_flash.c
+smm-y += fch_spi_special.c
+smm-y += fch_spi_table.c
+endif
+
+endif
diff --git a/src/soc/amd/common/block/spi/fch_spi_ctrl.c b/src/soc/amd/common/block/spi/fch_spi_ctrl.c
new file mode 100644
index 0000000000..4299e4f5c3
--- /dev/null
+++ b/src/soc/amd/common/block/spi/fch_spi_ctrl.c
@@ -0,0 +1,427 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2019 Silverback Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; version 2 of the License.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <console/console.h>
+#include <spi_flash.h>
+#include <soc/southbridge.h>
+#include <soc/pci_devs.h>
+#include <amdblocks/fch_spi.h>
+#include <amdblocks/lpc.h>
+#include <drivers/spi/spi_flash_internal.h>
+#include <device/pci_ops.h>
+#include <timer.h>
+#include <lib.h>
+
+static struct spi_data ctrl_spi_data;
+static uint32_t spibar;
+
+static inline uint8_t spi_read8(uint8_t reg)
+{
+ return read8((void *)(spibar + reg));
+}
+
+static inline uint32_t spi_read32(uint8_t reg)
+{
+ return read32((void *)(spibar + reg));
+}
+
+static inline void spi_write8(uint8_t reg, uint8_t val)
+{
+ write8((void *)(spibar + reg), val);
+}
+
+static inline void spi_write32(uint8_t reg, uint32_t val)
+{
+ write32((void *)(spibar + reg), val);
+}
+
+static void dump_state(const char *str, u8 phase)
+{
+ u8 dump_size;
+ u32 addr;
+
+ if (!CONFIG(SOC_AMD_COMMON_BLOCK_SPI_DEBUG))
+ return;
+
+ printk(BIOS_DEBUG, "SPI: %s\n", str);
+ printk(BIOS_DEBUG, "Cntrl0: %x\n", spi_read32(SPI_CNTRL0));
+ printk(BIOS_DEBUG, "Status: %x\n", spi_read32(SPI_STATUS));
+
+ addr = spibar + SPI_FIFO;
+ if (phase == 0) {
+ dump_size = spi_read8(SPI_TX_BYTE_COUNT);
+ printk(BIOS_DEBUG, "TxByteCount: %x\n", dump_size);
+ printk(BIOS_DEBUG, "CmdCode: %x\n", spi_read8(SPI_CMD_CODE));
+ } else {
+ dump_size = spi_read8(SPI_RX_BYTE_COUNT);
+ printk(BIOS_DEBUG, "RxByteCount: %x\n", dump_size);
+ addr += spi_read8(SPI_TX_BYTE_COUNT);
+ }
+
+ if (dump_size > 0)
+ hexdump((void *)addr, dump_size);
+}
+
+static int wait_for_ready(void)
+{
+ const uint32_t timeout_ms = 500;
+ struct stopwatch sw;
+
+ stopwatch_init_msecs_expire(&sw, timeout_ms);
+
+ do {
+ if (!(spi_read32(SPI_STATUS) & SPI_BUSY))
+ return 0;
+ } while (!stopwatch_expired(&sw));
+
+ return -1;
+}
+
+static int execute_command(void)
+{
+ dump_state("Before execute", 0);
+
+ spi_write8(SPI_CMD_TRIGGER, SPI_CMD_TRIGGER_EXECUTE);
+
+ if (wait_for_ready())
+ printk(BIOS_ERR,
+ "FCH_SC Error: Timeout executing command\n");
+
+ dump_state("Transaction finished", 1);
+
+ return 0;
+}
+
+void spi_init(void)
+{
+ spibar = lpc_get_spibase();
+ printk(BIOS_DEBUG, "%s: Spibar at 0x%08x\n", __func__, spibar);
+}
+
+const struct spi_data *get_ctrl_spi_data(void)
+{
+ return &ctrl_spi_data;
+}
+
+static int spi_ctrlr_xfer(const void *dout, size_t bytesout, void *din, size_t bytesin)
+{
+ size_t count;
+ uint8_t cmd;
+ uint8_t *bufin = din;
+ const uint8_t *bufout = dout;
+
+ if (CONFIG(SOC_AMD_COMMON_BLOCK_SPI_DEBUG))
+ printk(BIOS_DEBUG, "%s(%zx, %zx)\n", __func__, bytesout,
+ bytesin);
+
+ /* First byte is cmd which cannot be sent through FIFO */
+ cmd = bufout[0];
+ bufout++;
+ bytesout--;
+
+ /*
+ * Check if this is a write command attempting to transfer more bytes
+ * than the controller can handle. Iterations for writes are not
+ * supported here because each SPI write command needs to be preceded
+ * and followed by other SPI commands.
+ */
+ if (bytesout + bytesin > SPI_FIFO_DEPTH) {
+ printk(BIOS_WARNING, "FCH_SC: Too much to transfer, code error!\n");
+ return -1;
+ }
+
+ if (wait_for_ready())
+ return -1;
+
+ spi_write8(SPI_CMD_CODE, cmd);
+ spi_write8(SPI_TX_BYTE_COUNT, bytesout);
+ spi_write8(SPI_RX_BYTE_COUNT, bytesin);
+
+ for (count = 0; count < bytesout; count++)
+ spi_write8(SPI_FIFO + count, bufout[count]);
+
+ if (execute_command())
+ return -1;
+
+ for (count = 0; count < bytesin; count++)
+ bufin[count] = spi_read8(SPI_FIFO + count + bytesout);
+
+ return 0;
+}
+
+static int amd_xfer_vectors(struct spi_op vectors[], size_t count)
+{
+ int ret;
+ void *din;
+ size_t bytes_in;
+
+ if (count < 1 || count > 2)
+ return -1;
+
+ /* SPI flash commands always have a command first... */
+ if (!vectors[0].dout || !vectors[0].bytesout)
+ return -1;
+ /* And not read any data during the command. */
+ if (vectors[0].din || vectors[0].bytesin)
+ return -1;
+
+ if (count == 2) {
+ /* If response bytes requested ensure the buffer is valid. */
+ if (vectors[1].bytesin && !vectors[1].din)
+ return -1;
+ /* No sends can accompany a receive. */
+ if (vectors[1].dout || vectors[1].bytesout)
+ return -1;
+ din = vectors[1].din;
+ bytes_in = vectors[1].bytesin;
+ } else {
+ din = NULL;
+ bytes_in = 0;
+ }
+
+ ret = spi_ctrlr_xfer(vectors[0].dout, vectors[0].bytesout, din, bytes_in);
+
+ if (ret) {
+ vectors[0].status = SPI_OP_FAILURE;
+ if (count == 2)
+ vectors[1].status = SPI_OP_FAILURE;
+ } else {
+ vectors[0].status = SPI_OP_SUCCESS;
+ if (count == 2)
+ vectors[1].status = SPI_OP_SUCCESS;
+ }
+
+ return ret;
+}
+
+int fch_spi_flash_cmd(const void *dout, size_t bytes_out, void *din, size_t bytes_in)
+{
+ /*
+ * SPI flash requires command-response kind of behavior. Thus, two
+ * separate SPI vectors are required -- first to transmit dout and other
+ * to receive in din.
+ */
+ struct spi_op vectors[] = {
+ [0] = { .dout = dout, .bytesout = bytes_out,
+ .din = NULL, .bytesin = 0, },
+ [1] = { .dout = NULL, .bytesout = 0,
+ .din = din, .bytesin = bytes_in },
+ };
+ size_t count = ARRAY_SIZE(vectors);
+ if (!bytes_in)
+ count = 1;
+
+ return amd_xfer_vectors(vectors, count);
+}
+
+static void set_ctrl_spi_data(struct spi_flash *flash)
+{
+ u8 cmd = SPI_PAGE_WRITE;
+
+ ctrl_spi_data.name = flash->name;
+ ctrl_spi_data.size = flash->size;
+ ctrl_spi_data.sector_size = flash->sector_size;
+ ctrl_spi_data.status_cmd = flash->status_cmd;
+ ctrl_spi_data.erase_cmd = flash->erase_cmd;
+ ctrl_spi_data.write_enable_cmd = SPI_WRITE_ENABLE;
+
+ if (flash->vendor == VENDOR_ID_SST) {
+ ctrl_spi_data.non_standard = NON_STANDARD_SPI_SST;
+ if ((flash->model & 0x00ff) == SST_256)
+ ctrl_spi_data.page_size = 256;
+ else {
+ ctrl_spi_data.page_size = 2;
+ cmd = CMD_SST_AAI_WP;
+ }
+ } else {
+ ctrl_spi_data.page_size = flash->page_size;
+ ctrl_spi_data.non_standard = NON_STANDARD_SPI_NONE;
+ }
+ ctrl_spi_data.write_cmd = cmd;
+
+ if (CONFIG(SPI_FLASH_NO_FAST_READ)) {
+ ctrl_spi_data.read_cmd_len = 4;
+ ctrl_spi_data.read_cmd = CMD_READ_ARRAY_SLOW;
+ } else {
+ ctrl_spi_data.read_cmd_len = 5;
+ ctrl_spi_data.read_cmd = CMD_READ_ARRAY_FAST;
+ }
+}
+
+static int fch_spi_flash_probe(const struct spi_slave *spi, struct spi_flash *flash)
+{
+ int ret, i, shift, table_size;
+ u8 idcode[IDCODE_LEN], *idp, cmd = CMD_READ_ID;
+ const struct spi_flash_table *flash_ptr = get_spi_flash_table(&table_size);
+
+ /* Read the ID codes */
+ ret = fch_spi_flash_cmd(&cmd, 1, idcode, sizeof(idcode));
+ if (ret)
+ return -1;
+
+ if (CONFIG(SOC_AMD_COMMON_BLOCK_SPI_DEBUG)) {
+ printk(BIOS_SPEW, "SF: Got idcode: ");
+ for (i = 0; i < sizeof(idcode); i++)
+ printk(BIOS_SPEW, "%02x ", idcode[i]);
+ printk(BIOS_SPEW, "\n");
+ }
+
+ /* count the number of continuation bytes */
+ for (shift = 0, idp = idcode; shift < IDCODE_CONT_LEN && *idp == 0x7f;
+ ++shift, ++idp)
+ continue;
+
+ printk(BIOS_INFO, "Manufacturer: %02x\n", *idp);
+
+ /* search the table for matches in shift and id */
+ for (i = 0; i < table_size; ++i) {
+ if (flash_ptr->shift == shift && flash_ptr->idcode == *idp) {
+ /* we have a match, call probe */
+ if (flash_ptr->probe(spi, idp, flash) == 0) {
+ flash->vendor = idp[0];
+ flash->model = (idp[1] << 8) | idp[2];
+ set_ctrl_spi_data(flash);
+ fch_spi_flash_ops_init(flash);
+ return 0;
+ }
+ }
+ flash_ptr++;
+ }
+
+ /* No match, return error. */
+ return -1;
+}
+
+static int protect_a_range(u32 value)
+{
+ u32 reg32;
+ u8 n;
+
+ /* find a free protection register */
+ for (n = 0; n < MAX_ROM_PROTECT_RANGES; n++) {
+ reg32 = pci_read_config32(SOC_LPC_DEV, ROM_PROTECT_RANGE_REG(n));
+ if (!reg32)
+ break;
+ }
+ if (n == MAX_ROM_PROTECT_RANGES)
+ return -1; /* no free range */
+
+ pci_write_config32(SOC_LPC_DEV, ROM_PROTECT_RANGE_REG(n), value);
+ return 0;
+}
+
+/*
+ * Protect range of SPI flash defined by region using the SPI flash controller.
+ *
+ * Note: Up to 4 ranges can be protected, though if a particular region requires more than one
+ * range, total number of regions decreases accordingly. Each range can be programmed to 4KiB or
+ * 64KiB granularity.
+ *
+ * Warning: If more than 1 region needs protection, and they need mixed protections (read/write)
+ * than start with the region that requires the most protection. After the restricted commands
+ * have been written, they can't be changed (write once). So if first region is write protection
+ * and second region is read protection, it's best to define first region as read and write
+ * protection.
+ */
+static int fch_spi_flash_protect(const struct spi_flash *flash, const struct region *region,
+ const enum ctrlr_prot_type type)
+{
+ int ret;
+ u32 reg32, rom_base, range_base;
+ size_t addr, len, gran_value, total_ranges, range;
+ bool granularity_64k = true; /* assume 64k granularity */
+
+ addr = region->offset;
+ len = region->size;
+
+ reg32 = pci_read_config32(SOC_LPC_DEV, ROM_ADDRESS_RANGE2_START);
+ rom_base = WORD_TO_DWORD_UPPER(reg32);
+ if (addr < rom_base)
+ return -1;
+ range_base = addr % rom_base;
+
+ /* Define granularity to be used */
+ if (GRANULARITY_TEST_4k & range_base)
+ granularity_64k = false; /* use 4K granularity */
+ if (GRANULARITY_TEST_4k & len)
+ granularity_64k = false; /* use 4K granularity */
+
+ /* Define the first range and total number of ranges required */
+ if (granularity_64k) {
+ gran_value = 0x00010000; /* 64 KiB */
+ range_base = range_base >> 16;
+ } else {
+ gran_value = 0x00001000; /* 4 KiB */
+ range_base = range_base >> 12;
+ }
+ total_ranges = len / gran_value;
+ range_base &= RANGE_ADDR_MASK;
+
+ /* Create reg32 to be written into a range register and program required ranges */
+ reg32 = rom_base & ROM_BASE_MASK;
+ reg32 |= range_base;
+ if (granularity_64k)
+ reg32 |= RANGE_UNIT;
+ if (type & WRITE_PROTECT)
+ reg32 |= ROM_RANGE_WP;
+ if (type & READ_PROTECT)
+ reg32 |= ROM_RANGE_RP;
+
+ for (range = 0; range < total_ranges; range++) {
+ ret = protect_a_range(reg32);
+ if (ret)
+ return ret;
+ /*
+ * Next range (lower 8 bits). Range points to the start address of a region.
+ * The range value must be multiplied by the granularity (which is also the
+ * size of the region) to get the actual offset from the SPI start address.
+ */
+ reg32++;
+ }
+
+ /* define commands to be blocked if in range */
+ reg32 = 0;
+ if (type & WRITE_PROTECT) {
+ reg32 |= (ctrl_spi_data.write_enable_cmd << 24);
+ reg32 |= (ctrl_spi_data.write_cmd << 16);
+ reg32 |= (ctrl_spi_data.erase_cmd << 8);
+ }
+ if (type & READ_PROTECT)
+ reg32 |= ctrl_spi_data.read_cmd;
+
+ /* Final steps to protect region */
+ pci_write_config32(SOC_LPC_DEV, SPI_RESTRICTED_CMD1, reg32);
+ reg32 = spi_read32(SPI_CNTRL0);
+ reg32 &= ~SPI_ACCESS_MAC_ROM_EN;
+ spi_write32(SPI_CNTRL0, reg32);
+
+ return 0;
+}
+
+const struct spi_ctrlr fch_spi_flash_ctrlr = {
+ .max_xfer_size = SPI_FIFO_DEPTH,
+ .flash_probe = fch_spi_flash_probe,
+ .flash_protect = fch_spi_flash_protect,
+};
+
+const struct spi_ctrlr_buses spi_ctrlr_bus_map[] = {
+ {
+ .ctrlr = &fch_spi_flash_ctrlr,
+ .bus_start = 0,
+ .bus_end = 0,
+ },
+};
+
+const size_t spi_ctrlr_bus_map_count = ARRAY_SIZE(spi_ctrlr_bus_map);
diff --git a/src/soc/amd/common/block/spi/fch_spi_flash.c b/src/soc/amd/common/block/spi/fch_spi_flash.c
new file mode 100644
index 0000000000..40dd0e2996
--- /dev/null
+++ b/src/soc/amd/common/block/spi/fch_spi_flash.c
@@ -0,0 +1,246 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2019 Silverback Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; version 2 of the License.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <console/console.h>
+#include <spi_flash.h>
+#include <soc/southbridge.h>
+#include <amdblocks/fch_spi.h>
+#include <drivers/spi/spi_flash_internal.h>
+#include <timer.h>
+#include <string.h>
+
+static void spi_flash_addr(u32 addr, u8 *cmd)
+{
+ /* cmd[0] is actual command */
+ cmd[1] = addr >> 16;
+ cmd[2] = addr >> 8;
+ cmd[3] = addr >> 0;
+}
+
+static int crop_chunk(unsigned int cmd_len, unsigned int buf_len)
+{
+ return min((SPI_FIFO_DEPTH - (cmd_len - 1)), buf_len);
+}
+
+int fch_spi_flash_cmd_write(const u8 *cmd, size_t cmd_len, const void *data, size_t data_len)
+{
+ int ret;
+ u8 buff[SPI_FIFO_DEPTH + 1];
+
+ if ((cmd_len + data_len) > SPI_FIFO_DEPTH)
+ return -1;
+ memcpy(buff, cmd, cmd_len);
+ memcpy(buff + cmd_len, data, data_len);
+
+ ret = fch_spi_flash_cmd(buff, cmd_len + data_len, NULL, 0);
+ if (ret) {
+ printk(BIOS_WARNING, "FCH_SF: Failed to send write command (%zu bytes): %d\n",
+ data_len, ret);
+ }
+
+ return ret;
+}
+
+static int fch_spi_flash_status(const struct spi_flash *flash, uint8_t *reg)
+{
+ int ret;
+ u8 status, cmd = CMD_READ_STATUS;
+
+ ret = fch_spi_flash_cmd(&cmd, 1, &status, 1);
+ if (!ret)
+ *reg = status;
+ return ret;
+}
+
+int fch_spi_wait_cmd_ready(unsigned long timeout)
+{
+ struct mono_time current, end;
+ int ret;
+ u8 status;
+
+ timer_monotonic_get(&current);
+ end = current;
+ mono_time_add_msecs(&end, timeout);
+
+ do {
+ ret = fch_spi_flash_status(NULL, &status);
+ if (ret)
+ return -1;
+ if ((status & STATUS_WIP) == 0)
+ return 0;
+ timer_monotonic_get(&current);
+ } while (!mono_time_after(&current, &end));
+
+ printk(BIOS_DEBUG, "FCH_SF: timeout at %ld msec\n", timeout);
+ return -1;
+}
+
+static int fch_spi_flash_erase(const struct spi_flash *flash, uint32_t offset, size_t len)
+{
+ u32 start, end, erase_size;
+ const struct spi_data *spi_data_ptr = get_ctrl_spi_data();
+ int ret = -1;
+ u8 cmd[4];
+
+ erase_size = spi_data_ptr->sector_size;
+ if (offset % erase_size || len % erase_size) {
+ printk(BIOS_WARNING, "%s: Erase offset/length not multiple of erase size\n",
+ spi_data_ptr->name);
+ return -1;
+ }
+ if (len == 0) {
+ printk(BIOS_WARNING, "%s: Erase length cannot be 0\n", spi_data_ptr->name);
+ return -1;
+ }
+
+ cmd[0] = spi_data_ptr->erase_cmd;
+ start = offset;
+ end = start + len;
+
+ while (offset < end) {
+ spi_flash_addr(offset, cmd);
+ offset += erase_size;
+
+#if CONFIG(SOC_AMD_COMMON_BLOCK_SPI_DEBUG)
+ printk(BIOS_DEBUG, "FCH_SF: erase %2x %2x %2x %2x (%x)\n", cmd[0], cmd[1],
+ cmd[2], cmd[3], offset);
+#endif
+ ret = fch_spi_enable_write();
+ if (ret)
+ goto out;
+
+ ret = fch_spi_flash_cmd_write(cmd, sizeof(cmd), NULL, 0);
+ if (ret)
+ goto out;
+
+ ret = fch_spi_wait_cmd_ready(SPI_FLASH_PAGE_ERASE_TIMEOUT_MS);
+ if (ret)
+ goto out;
+ }
+
+ printk(BIOS_DEBUG, "%s: Successfully erased %zu bytes @ %#x\n", spi_data_ptr->name, len,
+ start);
+
+out:
+ return ret;
+}
+
+static int fch_spi_flash_read(const struct spi_flash *flash, uint32_t offset, size_t len,
+ void *buf)
+{
+ const struct spi_data *spi_data_ptr = get_ctrl_spi_data();
+ uint8_t *data = buf;
+ int ret;
+ size_t xfer_len;
+ u8 cmd[5];
+
+ cmd[0] = spi_data_ptr->read_cmd;
+ cmd[4] = 0;
+ while (len) {
+ xfer_len = crop_chunk(spi_data_ptr->read_cmd_len, len);
+ spi_flash_addr(offset, cmd);
+ ret = fch_spi_flash_cmd(cmd, spi_data_ptr->read_cmd_len, data, xfer_len);
+ if (ret) {
+ printk(BIOS_WARNING,
+ "FCH_SF: Failed to send read command %#.2x(%#x, %#zx): %d\n",
+ cmd[0], offset, xfer_len, ret);
+ return ret;
+ }
+ offset += xfer_len;
+ data += xfer_len;
+ len -= xfer_len;
+ }
+ return 0;
+}
+
+static int fch_spi_flash_write(const struct spi_flash *flash, uint32_t offset, size_t len,
+ const void *buf)
+{
+ unsigned long byte_addr;
+ unsigned long page_size;
+ const struct spi_data *spi_data_ptr = get_ctrl_spi_data();
+ size_t chunk_len;
+ size_t actual, start = 0;
+ int ret = 0;
+ u8 cmd[4];
+
+ page_size = spi_data_ptr->page_size;
+ if (spi_data_ptr->non_standard == NON_STANDARD_SPI_SST) {
+ if (offset % 2) {
+ ret = non_standard_sst_byte_write(offset, buf);
+ len--;
+ start++;
+ offset++;
+ if (ret)
+ return ret;
+ }
+ if (page_size == 2)
+ return non_standard_sst_write_aai(offset, len, buf, start);
+ }
+
+ for (actual = start; actual < len; actual += chunk_len) {
+ byte_addr = offset % page_size;
+ chunk_len = min(len - actual, page_size - byte_addr);
+ chunk_len = crop_chunk(sizeof(cmd), chunk_len);
+
+ cmd[0] = spi_data_ptr->write_cmd;
+ cmd[1] = (offset >> 16) & 0xff;
+ cmd[2] = (offset >> 8) & 0xff;
+ cmd[3] = offset & 0xff;
+#if CONFIG(SOC_AMD_COMMON_BLOCK_SPI_DEBUG)
+ printk(BIOS_DEBUG, "PP: 0x%p => cmd = { 0x%02x 0x%02x%02x%02x } chunk_len = %zu"
+ "\n", buf + actual, cmd[0], cmd[1], cmd[2], cmd[3], chunk_len);
+#endif
+
+ ret = fch_spi_enable_write();
+ if (ret < 0) {
+ printk(BIOS_WARNING, "%s: Enabling Write failed\n", spi_data_ptr->name);
+ goto out;
+ }
+
+ ret = fch_spi_flash_cmd_write(cmd, sizeof(cmd), buf + actual, chunk_len);
+ if (ret < 0) {
+ printk(BIOS_WARNING, "%s: Page Program failed\n", spi_data_ptr->name);
+ goto out;
+ }
+
+ ret = fch_spi_wait_cmd_ready(SPI_FLASH_PROG_TIMEOUT_MS);
+ if (ret)
+ goto out;
+
+ offset += chunk_len;
+ }
+
+#if CONFIG(SOC_AMD_COMMON_BLOCK_SPI_DEBUG)
+ printk(BIOS_DEBUG, "%s: Successfully programmed %zu bytes @ 0x%lx\n",
+ spi_data_ptr->name, len, (unsigned long)(offset - len));
+#endif
+ ret = 0;
+
+out:
+ return ret;
+}
+
+static const struct spi_flash_ops fch_spi_flash_ops = {
+ .read = fch_spi_flash_read,
+ .write = fch_spi_flash_write,
+ .erase = fch_spi_flash_erase,
+ .status = fch_spi_flash_status,
+};
+
+void fch_spi_flash_ops_init(struct spi_flash *flash)
+{
+ flash->ops = &fch_spi_flash_ops;
+}
diff --git a/src/soc/amd/common/block/spi/fch_spi_special.c b/src/soc/amd/common/block/spi/fch_spi_special.c
new file mode 100644
index 0000000000..456a3896f5
--- /dev/null
+++ b/src/soc/amd/common/block/spi/fch_spi_special.c
@@ -0,0 +1,89 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2019 Silverback Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; version 2 of the License.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <console/console.h>
+#include <spi-generic.h>
+#include <amdblocks/fch_spi.h>
+#include <string.h>
+
+int non_standard_sst_byte_write(u32 offset, const void *buf)
+{
+ int ret;
+ u8 cmd[4] = {
+ CMD_SST_BP,
+ offset >> 16,
+ offset >> 8,
+ offset,
+ };
+
+ ret = fch_spi_enable_write();
+ if (ret)
+ return ret;
+
+ ret = fch_spi_flash_cmd_write(cmd, sizeof(cmd), buf, 1);
+ if (ret)
+ return ret;
+
+ return fch_spi_wait_cmd_ready(SPI_FLASH_PROG_TIMEOUT_MS);
+}
+
+int non_standard_sst_write_aai(u32 offset, size_t len, const void *buf, size_t start)
+{
+ size_t actual, cmd_len;
+ int ret = 0;
+ u8 cmd[4];
+
+ ret = fch_spi_enable_write();
+ if (ret)
+ goto done;
+
+ cmd_len = 4;
+ cmd[0] = CMD_SST_AAI_WP;
+ cmd[1] = offset >> 16;
+ cmd[2] = offset >> 8;
+ cmd[3] = offset;
+
+ for (actual = start; actual < len - 1; actual += 2) {
+#if CONFIG(SOC_AMD_COMMON_BLOCK_SPI_DEBUG)
+ printk(BIOS_DEBUG, "PP: 0x%p => cmd = { 0x%02x 0x%06lx }"
+ " chunk_len = 2\n",
+ buf + actual, cmd[0], (offset + actual));
+#endif
+
+ ret = fch_spi_enable_write();
+ if (ret < 0) {
+ printk(BIOS_WARNING, "SF: Enabling Write failed\n");
+ break;
+ }
+
+ ret = fch_spi_flash_cmd_write(cmd, cmd_len, buf + actual, 2);
+ if (ret < 0) {
+ printk(BIOS_WARNING, "SF: SST word Program failed\n");
+ break;
+ }
+
+ ret = fch_spi_wait_cmd_ready(SPI_FLASH_PROG_TIMEOUT_MS);
+ if (ret)
+ break;
+
+ offset += 2;
+ cmd_len = 1;
+ }
+ /* If there is a single trailing byte, write it out */
+ if (!ret && actual != len)
+ ret = non_standard_sst_byte_write(offset, buf + actual);
+done:
+ return ret;
+}
diff --git a/src/soc/amd/common/block/spi/fch_spi_table.c b/src/soc/amd/common/block/spi/fch_spi_table.c
new file mode 100644
index 0000000000..8c0108a6e5
--- /dev/null
+++ b/src/soc/amd/common/block/spi/fch_spi_table.c
@@ -0,0 +1,83 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2019 Silverback Ltd.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; version 2 of the License.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <spi_flash.h>
+#include <amdblocks/fch_spi.h>
+#include <drivers/spi/spi_flash_internal.h>
+
+/*
+ * The following table holds all device probe functions
+ *
+ * shift: number of continuation bytes before the ID
+ * idcode: the expected IDCODE or 0xff for non JEDEC devices
+ * probe: the function to call
+ *
+ * Non JEDEC devices should be ordered in the table such that
+ * the probe functions with best detection algorithms come first.
+ *
+ * Several matching entries are permitted, they will be tried
+ * in sequence until a probe function returns non NULL.
+ *
+ * IDCODE_CONT_LEN may be redefined if a device needs to declare a
+ * larger "shift" value. IDCODE_PART_LEN generally shouldn't be
+ * changed. This is the max number of bytes probe functions may
+ * examine when looking up part-specific identification info.
+ *
+ * Probe functions will be given the idcode buffer starting at their
+ * manu id byte (the "idcode" in the table below). In other words,
+ * all of the continuation bytes will be skipped (the "shift" below).
+ */
+
+const struct spi_flash_table flashes[] = {
+ /* Keep it sorted by define name */
+#if CONFIG(SPI_FLASH_ADESTO)
+ { 0, VENDOR_ID_ADESTO, spi_flash_probe_adesto, },
+#endif
+#if CONFIG(SPI_FLASH_AMIC)
+ { 0, VENDOR_ID_AMIC, spi_flash_probe_amic, },
+#endif
+#if CONFIG(SPI_FLASH_ATMEL)
+ { 0, VENDOR_ID_ATMEL, spi_flash_probe_atmel, },
+#endif
+#if CONFIG(SPI_FLASH_EON)
+ { 0, VENDOR_ID_EON, spi_flash_probe_eon, },
+#endif
+#if CONFIG(SPI_FLASH_GIGADEVICE)
+ { 0, VENDOR_ID_GIGADEVICE, spi_flash_probe_gigadevice, },
+#endif
+#if CONFIG(SPI_FLASH_MACRONIX)
+ { 0, VENDOR_ID_MACRONIX, spi_flash_probe_macronix, },
+#endif
+#if CONFIG(SPI_FLASH_SPANSION)
+ { 0, VENDOR_ID_SPANSION, spi_flash_probe_spansion, },
+#endif
+#if CONFIG(SPI_FLASH_SST)
+ { 0, VENDOR_ID_SST, spi_flash_probe_sst, },
+#endif
+#if CONFIG(SPI_FLASH_STMICRO)
+ { 0, VENDOR_ID_STMICRO, spi_flash_probe_stmicro, },
+ { 0, VENDOR_ID_STMICRO_FF, spi_flash_probe_stmicro, },
+#endif
+#if CONFIG(SPI_FLASH_WINBOND)
+ { 0, VENDOR_ID_WINBOND, spi_flash_probe_winbond, },
+#endif
+ /* Keep it sorted by best detection */
+};
+
+const struct spi_flash_table *get_spi_flash_table(int *table_size)
+{
+ *table_size = (int)ARRAY_SIZE(flashes);
+ return &flashes[0];
+}