[coreboot-gerrit] Change in coreboot[master]: soc/intel/quark: Add SPI flash controller driver

Lee Leahy (Code Review) gerrit at coreboot.org
Thu Jun 15 22:49:45 CEST 2017


Lee Leahy has uploaded this change for review. ( https://review.coreboot.org/20231


Change subject: soc/intel/quark: Add SPI flash controller driver
......................................................................

soc/intel/quark: Add SPI flash controller driver

Add SPI driver code for the legacy SPI flash controller.

TEST=Build and run on Galileo Gen2.

Change-Id: I8f38c955d7c42a1e58728c728d0cecc36556de5c
Signed-off-by: Lee Leahy <Leroy.P.Leahy at intel.com>
---
M src/soc/intel/quark/Kconfig
M src/soc/intel/quark/Makefile.inc
M src/soc/intel/quark/include/soc/pci_devs.h
A src/soc/intel/quark/include/soc/spi.h
A src/soc/intel/quark/spi.c
A src/soc/intel/quark/spi_debug.c
6 files changed, 512 insertions(+), 0 deletions(-)



  git pull ssh://review.coreboot.org:29418/coreboot refs/changes/31/20231/1

diff --git a/src/soc/intel/quark/Kconfig b/src/soc/intel/quark/Kconfig
index e392202..bbb1927 100644
--- a/src/soc/intel/quark/Kconfig
+++ b/src/soc/intel/quark/Kconfig
@@ -36,6 +36,7 @@
 	select SOC_INTEL_COMMON
 	select SOC_INTEL_COMMON_RESET
 	select SOC_SETS_MSRS
+	select SPI_FLASH
 	select TSC_CONSTANT_RATE
 	select UART_OVERRIDE_REFCLK
 	select UDELAY_TSC
diff --git a/src/soc/intel/quark/Makefile.inc b/src/soc/intel/quark/Makefile.inc
index d0a7a93..741f5d3 100644
--- a/src/soc/intel/quark/Makefile.inc
+++ b/src/soc/intel/quark/Makefile.inc
@@ -58,6 +58,8 @@
 ramstage-y += reg_access.c
 ramstage-$(CONFIG_PLATFORM_USES_FSP2_0) += reset.c
 ramstage-y += sd.c
+ramstage-y += spi.c
+ramstage-y += spi_debug.c
 ramstage-$(CONFIG_STORAGE_TEST) += storage_test.c
 ramstage-y += tsc_freq.c
 ramstage-$(CONFIG_ENABLE_BUILTIN_HSUART1) += uart_common.c
diff --git a/src/soc/intel/quark/include/soc/pci_devs.h b/src/soc/intel/quark/include/soc/pci_devs.h
index a4e7a87..1e17402 100644
--- a/src/soc/intel/quark/include/soc/pci_devs.h
+++ b/src/soc/intel/quark/include/soc/pci_devs.h
@@ -28,6 +28,7 @@
 #define I2CGPIO_DEVID		0x0934
 #define HSUART_DEVID		0x0936
 #define EHCI_DEVID		0x0939
+#define LPC_DEVID		0X095E
 #define PCIE_PORT0_DEVID	0x11c3
 #define PCIE_PORT1_DEVID	0x11c4
 
diff --git a/src/soc/intel/quark/include/soc/spi.h b/src/soc/intel/quark/include/soc/spi.h
new file mode 100644
index 0000000..cbdb221
--- /dev/null
+++ b/src/soc/intel/quark/include/soc/spi.h
@@ -0,0 +1,94 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2017 Intel Corporation.  All rights reserved.
+ *
+ * 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 __SOC_SPI_H__
+#define __SOC_SPI_H__
+
+#include <spi_flash.h>
+#include <spi-generic.h>
+
+#define SPISTS		0x3020 /* Status register */
+#define SPICTL		0x3022 /* Control register */
+#define SPIADDR		0x3024 /* Flash chip select and 24-bit address */
+#define SPIDATA		0x3028 /* 64-byte send/receive data buffer */
+#define SPIBBAR		0x3070 /* BIOS base address */
+#define SPIPREOP	0x3074 /* Prefix opcode table */
+#define SPITYPE		0x3076 /* Opcode type table */
+#define SPIOPMENU	0x3078 /* Opcode table */
+#define SPIPBR0		0x3080 /* Protected BIOS range */
+#define SPIPBR1		0x3084
+#define SPIPBR2		0x3088
+
+struct flash_ctrlr {
+	uint8_t rsvd_0x00[0x3020];/* 0x00 */
+	uint16_t status;          /* 0x3020: Status register */
+	uint16_t control;         /* 0x3022: Control register */
+	uint32_t address;         /* 0x3024: Chip select and 24-bit address */
+	uint8_t data[64];         /* 0x3028: 64-byte send/receive data buffer */
+	uint8_t rsvd_0x68[8];     /* 0x3068 */
+	uint32_t bbar;            /* 0x3070: BIOS base address */
+	uint8_t prefix[2];        /* 0x3074: Prefix opcode table */
+	uint16_t type;            /* 0x3076: Opcode type table */
+	uint8_t opmenu[8];        /* 0x3078: Opcode table */
+	uint32_t pbr[3];          /* 0x3080: Protected BIOS range */
+};
+
+/* 0x3020: SPISTS */
+#define SPISTS_CLD		0x8000 /* Lock SPI controller configuration */
+#define SPISTS_BA		0x0008 /* Access is blocked */
+#define SPISTS_CD		0x0004 /* Cycle done */
+#define SPISTS_CIP		0x0001 /* Cycle in progress */
+
+/* 0x3022: SPICTL */
+#define SPICTL_SMIEN		0x8000 /* Assert SMI_B at cycle done */
+#define SPICTL_DC		0x4000 /* Cycle contains data */
+#define SPICTL_DBCNT		0x3f00 /* Data byte count - 1, 1 - 64 bytes */
+#define SPICTL_DBCNT_SHIFT	8
+#define SPICTL_COPTR		0x0070 /* Opcode menu index, 0 - 7 */
+#define SPICTL_COPTR_SHIFT	4
+#define SPICTL_SOPTR		0x0008 /* Prefix index, 0 - 1 */
+#define SPICTL_SOPTR_SHIFT	3
+#define SPICTL_ACS		0x0004 /* Atomic cycle sequence */
+#define SPICTL_CG		0x0002 /* Cycle go */
+#define SPICTL_AR		0x0001 /* Access request */
+
+/* 0x3076: SPITYPE */
+#define SPITYPE_ADDRESS		0x0002 /* 3-byte address required */
+#define SPITYPE_PREFIX		0x0001 /* Prefix required, write/erase cycle */
+
+/* 0x3080: PBR0
+ * 0x3084: PBR1
+ * 0x3088: PBR2 */
+#define SPIPBR_WPE		0x80000000 /* Write protect enable */
+#define SPIPBR_PRL		0x00fff000 /* Protected range limit */
+#define SPIPBR_PRB_SHIFT	12
+#define SPIPBR_PRB		0x00000fff /* Protected range base */
+
+struct spi_context {
+	volatile struct flash_ctrlr *ctrlr;
+	uint16_t control;
+	uint16_t prefix;
+};
+
+extern const struct spi_ctrlr spi_driver;
+
+void spi_bios_base(uint32_t bios_base_address);
+void spi_controller_lock(void);
+void spi_display(volatile struct flash_ctrlr *ctrlr);
+const char *spi_opcode_name(int opcode);
+int spi_protection(uint32_t address, uint32_t length);
+
+#endif /* __SOC_SPI_H__ */
diff --git a/src/soc/intel/quark/spi.c b/src/soc/intel/quark/spi.c
new file mode 100644
index 0000000..1d257a5
--- /dev/null
+++ b/src/soc/intel/quark/spi.c
@@ -0,0 +1,301 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2017 Intel Corporation.  All rights reserved.
+ *
+ * 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 <arch/io.h>
+#include <assert.h>
+#include <bootstate.h>
+#include <console/console.h>
+#include <device/pci_ids.h>
+#include <device/pci_def.h>
+#include <delay.h>
+#include <soc/pci_devs.h>
+#include <soc/QuarkNcSocId.h>
+#include <soc/spi.h>
+
+struct spi_context spi_driver_context = {
+	NULL,
+	0,
+	0
+};
+
+void spi_bios_base(uint32_t bios_base_address)
+{
+	uint32_t address;
+	volatile struct flash_ctrlr *ctrlr = spi_driver_context.ctrlr;
+
+	/* Prevent all SPI operations below this address */
+	address = 0xff000000 | bios_base_address;
+	ctrlr->bbar = address;
+}
+
+void spi_controller_lock(void)
+{
+	volatile struct flash_ctrlr *ctrlr = spi_driver_context.ctrlr;
+
+	/* Prevent BIOS and system from changing the SPI controller setup */
+	ctrlr->status |= SPISTS_CLD;
+}
+
+int spi_protection(uint32_t address, uint32_t length)
+{
+	uint32_t base;
+	volatile struct flash_ctrlr *ctrlr = spi_driver_context.ctrlr;
+	int index;
+	uint32_t limit;
+	uint32_t protect;
+	uint32_t value;
+
+	/* Determine the protection range */
+	base = address;
+	limit = address + length - 1;
+	protect = SPIPBR_WPE | (limit & SPIPBR_PRL)
+		| ((base >> SPIPBR_PRB_SHIFT) & SPIPBR_PRB);
+
+	/* Walk the list of protected areas */
+	for (index = 0; index < ARRAY_SIZE(ctrlr->pbr); index++) {
+		value = read32(&ctrlr->pbr[index]);
+
+		/* Don't duplicate if the range is already protected */
+		if (value == protect)
+			return 0;
+
+		/* Use the first free register to protect this range */
+		if ((value & SPIPBR_WPE) == 0) {
+			write32(&ctrlr->pbr[index], protect);
+			return 0;
+		}
+	}
+
+	/* No free protection range registers */
+	printk(BIOS_ERR,
+		"Failed to set protection: 0x%08x - 0x%08x, PRRs full!\n",
+				address, address + length - 1);
+	return -1;
+}
+
+static int xfer(const struct spi_slave *slave, const void *dout,
+	size_t bytesout, void *din, size_t bytesin)
+{
+	struct spi_context *context;
+	uint16_t control;
+	volatile struct flash_ctrlr *ctrlr;
+	uint8_t *data;
+	int index;
+	uint8_t opcode;
+	uint32_t status;
+	int type;
+
+	/* Locate the context structure */
+	context = &spi_driver_context;
+	ctrlr = context->ctrlr;
+
+	/* Validate the buffer sizes */
+	if (bytesin > sizeof(ctrlr->data)) {
+		printk(BIOS_ERR, "bytesin > %ld\n", sizeof(ctrlr->data));
+		goto error;
+	}
+
+	if (bytesin && (din == NULL)) {
+		printk(BIOS_ERR, "din is NULL\n");
+		goto error;
+	}
+
+	if (bytesout == 0) {
+		/* Check for a read operation */
+		if (bytesin == 0) {
+			printk(BIOS_ERR, "bytesout and bytesin == 0\n");
+			goto error;
+		}
+
+		/* Issue the read operation */
+		control = context->control;
+		control |= SPICTL_DC | ((bytesin - 1) << SPICTL_DBCNT_SHIFT);
+		goto start_cycle;
+	}
+
+	/* Locate the opcode in the opcode table */
+	data = (uint8_t *)dout;
+	opcode = *data++;
+	bytesout -= 1;
+	for (index = 0; index < sizeof(ctrlr->opmenu); index++)
+		if (opcode == ctrlr->opmenu[index])
+			break;
+
+	/* Check for a prefix byte */
+	if (index == sizeof(ctrlr->opmenu)) {
+		for (index = 0; index < sizeof(ctrlr->prefix); index++)
+			if (opcode == ctrlr->prefix[index])
+				break;
+
+		/* Handle the unknown opcode error */
+		if (index == sizeof(ctrlr->prefix)) {
+			printk(BIOS_ERR, "Unknown SPI flash opcode\n");
+			goto error;
+		}
+
+		/* Save the index for the next operation */
+		context->prefix = index;
+		return 0;
+	}
+
+	/* Get the opcode type */
+	type = (ctrlr->type >> (index * 2))
+		& (SPITYPE_ADDRESS | SPITYPE_PREFIX);
+
+	/* Determine if the opcode has an address */
+	if (type & SPITYPE_ADDRESS) {
+		if (bytesout < 3) {
+			printk(BIOS_ERR, "Missing address bytes\n");
+			goto error;
+		}
+
+		/* Use chip select 0 */
+		ctrlr->address = (data[0] << 16)
+			       | (data[1] << 8)
+			       |  data[2];
+		status = ctrlr->address;
+		data += 3;
+		bytesout -= 3;
+	}
+
+	/* Build the control value */
+	control = (index << SPICTL_COPTR_SHIFT)
+		| (context->prefix << SPICTL_SOPTR_SHIFT)
+		| SPICTL_CG | SPICTL_AR;
+	if (bytesout) {
+		memcpy((void *)&ctrlr->data[0], data, bytesout);
+		control |= SPICTL_DC | ((bytesout - 1) << SPICTL_DBCNT_SHIFT);
+	}
+
+	/* Save the control value for the read operation request */
+	if (!(type & SPITYPE_PREFIX)) {
+		context->control = control;
+		return 0;
+	}
+
+	/* Write operations require a prefix */
+	control |= SPICTL_ACS;
+
+start_cycle:
+	/* Start the SPI cycle */
+	ctrlr->control = control;
+	status = ctrlr->control;
+	context->prefix = 0;
+
+	/* Wait for the access to complete */
+	while ((status = ctrlr->status) & SPISTS_CIP)
+		udelay(1);
+
+	/* Clear any errors */
+	ctrlr->status = status;
+
+	/* Handle the blocked access error */
+	if (status & SPISTS_BA) {
+		printk(BIOS_ERR, "SPI access blocked!\n");
+		return -1;
+	}
+
+	/* Check for done */
+	if (status & SPISTS_CD) {
+		/* Return any receive data */
+		if (bytesin)
+			memcpy(din, (void *)&ctrlr->data[0], bytesin);
+		return 0;
+	}
+
+	/* Handle the timeout error */
+	printk(BIOS_ERR, "SPI transaction timeout!\n");
+
+error:
+	context->prefix = 0;
+	return -1;
+}
+
+void spi_init(void)
+{
+	uint32_t bios_control;
+	struct spi_context *context;
+	volatile struct flash_ctrlr *ctrlr;
+	device_t dev;
+	uint32_t rcba;
+
+	/* Determine the base address of the SPI flash controller */
+	context = &spi_driver_context;
+	dev = dev_find_device(PCI_VENDOR_ID_INTEL, LPC_DEVID, NULL);
+	rcba = pci_read_config32(dev, R_QNC_LPC_RCBA);
+	if (!(rcba & B_QNC_LPC_RCBA_EN)) {
+		printk(BIOS_ERR, "RBCA not enabled\n");
+		return;
+	}
+	rcba &= B_QNC_LPC_RCBA_MASK;
+	ctrlr = (volatile struct flash_ctrlr *)rcba;
+
+	/* Enable writes to the SPI flash */
+	bios_control = pci_read_config32(dev, R_QNC_LPC_BIOS_CNTL);
+	bios_control |= B_QNC_LPC_BIOS_CNTL_BIOSWE;
+	pci_write_config32(dev, R_QNC_LPC_BIOS_CNTL, bios_control);
+
+	/* Setup the SPI flash controller */
+	context->ctrlr = ctrlr;
+	ctrlr->opmenu[0] = 0x03;	/* Read */
+	ctrlr->opmenu[1] = 0x0b;	/* Read fast */
+	ctrlr->opmenu[2] = 0x05;	/* Read status */
+	ctrlr->opmenu[3] = 0x9f;	/* Read ID */
+	ctrlr->opmenu[4] = 0x02;	/* Page program */
+	ctrlr->opmenu[5] = 0x20;	/* Erase 4 KiB */
+	ctrlr->opmenu[6] = 0xd8;	/* Erase 64 KiB */
+	ctrlr->opmenu[7] = 0x01;	/* Write status */
+	ctrlr->prefix[0] = 0x50;	/* Write status enable */
+	ctrlr->prefix[1] = 0x06;	/* Write enable */
+	ctrlr->type = SPITYPE_ADDRESS                        /* Read */
+		| (SPITYPE_ADDRESS << 2)                     /* Read fast */
+		| (0 << 4)                                   /* Read status */
+		| (0 << 6)                                   /* Read ID */
+		| ((SPITYPE_ADDRESS | SPITYPE_PREFIX) << 8)  /* Page program */
+		| ((SPITYPE_ADDRESS | SPITYPE_PREFIX) << 10) /* Erase 4 KiB */
+		| ((SPITYPE_ADDRESS | SPITYPE_PREFIX) << 12) /* Erase 64 KiB */
+		| (SPITYPE_PREFIX << 14);                    /* Write status */
+}
+
+static void spi_init_cb(void *unused)
+{
+	struct spi_flash flash;
+
+	spi_init();
+	if (spi_flash_probe(0, 0, &flash)) {
+		printk(BIOS_DEBUG, "SPI flash failed initialization!\n");
+		return;
+	}
+	printk(BIOS_DEBUG, "SPI flash successfully initialized\n");
+}
+
+BOOT_STATE_INIT_ENTRY(BS_DEV_INIT, BS_ON_ENTRY, spi_init_cb, NULL);
+
+const struct spi_ctrlr spi_driver = {
+	.xfer = xfer,
+	.max_xfer_size = 64,
+	.deduct_cmd_len = false,
+};
+
+const struct spi_ctrlr_buses spi_ctrlr_bus_map[] = {
+	{
+		.ctrlr = &spi_driver,
+		.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/intel/quark/spi_debug.c b/src/soc/intel/quark/spi_debug.c
new file mode 100644
index 0000000..d229f2e
--- /dev/null
+++ b/src/soc/intel/quark/spi_debug.c
@@ -0,0 +1,113 @@
+/*
+ * This file is part of the coreboot project.
+ *
+ * Copyright (C) 2017 Intel Corporation.  All rights reserved.
+ *
+ * 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 <arch/io.h>
+#include <console/console.h>
+#include <soc/spi.h>
+
+const char *spi_opcode_name(int opcode)
+{
+	const char *op_name;
+
+	switch (opcode) {
+	default:
+		op_name = "Unknown";
+		break;
+	case 1:
+		op_name = "Write Status";
+		break;
+	case 2:
+		op_name = "Page Program";
+		break;
+	case 3:
+		op_name = "Read Data";
+		break;
+	case 5:
+		op_name = "Read Status";
+		break;
+	case 6:
+		op_name = "Write Data Enable";
+		break;
+	case 0x0b:
+		op_name = "Fast Read";
+		break;
+	case 0x20:
+		op_name = "Erase 4 KiB";
+		break;
+	case 0x50:
+		op_name = "Write Status Enable";
+		break;
+	case 0x9f:
+		op_name = "Read ID";
+		break;
+	case 0xd8:
+		op_name = "Erase 64 KiB";
+		break;
+	}
+	return op_name;
+}
+
+void spi_display(volatile struct flash_ctrlr *ctrlr)
+{
+	int index;
+	int opcode;
+	const char *op_name;
+	int prefix;
+	int status;
+	int type;
+
+	/* Display the prefixes */
+	printk(BIOS_DEBUG, "Prefix Table\n");
+	for (index = 0; index < 2; index++) {
+		prefix = ctrlr->prefix[index];
+		op_name = spi_opcode_name(prefix);
+		printk(BIOS_DEBUG, "  %d: 0x%02x (%s)\n", index, prefix,
+			op_name);
+	}
+
+	/* Display the opcodes */
+	printk(BIOS_DEBUG, "Opcode Menu\n");
+	for (index = 0; index < 8; index++) {
+		opcode = ctrlr->opmenu[index];
+		type = (ctrlr->type >> (index << 1)) & 3;
+		op_name = spi_opcode_name(opcode);
+		printk(BIOS_DEBUG, "  %d: 0x%02x (%s), %s%s\n", index, opcode,
+			op_name,
+			(type & SPITYPE_PREFIX) ? "Write" : "Read",
+			(type & SPITYPE_ADDRESS) ? ", w/3 byte address" : "");
+	}
+
+	/* Display the BIOS base address */
+	printk(BIOS_DEBUG, "0x%08x: BIOS Base Address\n", ctrlr->bbar);
+
+	/* Display the protection ranges */
+	printk(BIOS_DEBUG, "BIOS Protected Range Regsiters\n");
+	for (index = 0; index < ARRAY_SIZE(ctrlr->pbr); index++) {
+		status = ctrlr->pbr[index];
+		printk(BIOS_DEBUG, "  %d: 0x%08x: 0x%08x - 0x%08x %s\n",
+			index, status,
+			0xff000000 | (0x1000000 - CONFIG_ROM_SIZE)
+				| ((status & SPIPBR_PRB) << SPIPBR_PRB_SHIFT),
+			0xff800fff | (0x1000000 - CONFIG_ROM_SIZE)
+				| (status & SPIPBR_PRL),
+			(status & SPIPBR_WPE) ? "Protected" : "Unprotected");
+	}
+
+	/* Display locked status */
+	status = ctrlr->status;
+	printk(BIOS_DEBUG, "0x%04x: SPISTS, Tables %s\n", status,
+		(status & SPISTS_CLD) ? "Locked" : "Unlocked");
+}

-- 
To view, visit https://review.coreboot.org/20231
To unsubscribe, visit https://review.coreboot.org/settings

Gerrit-Project: coreboot
Gerrit-Branch: master
Gerrit-MessageType: newchange
Gerrit-Change-Id: I8f38c955d7c42a1e58728c728d0cecc36556de5c
Gerrit-Change-Number: 20231
Gerrit-PatchSet: 1
Gerrit-Owner: Lee Leahy <leroy.p.leahy at intel.com>



More information about the coreboot-gerrit mailing list