Selaa lähdekoodia

Merge branch 'ti-linux-4.19.y' of git://git.ti.com/ti-linux-kernel/ti-linux-kernel into processor-sdk-linux-4.19.y

TI-Feature: ti_linux_base-4.19
TI-Tree: git://git.ti.com/ti-linux-kernel/ti-linux-kernel.git
TI-Branch: ti-linux-4.19.y

* 'ti-linux-4.19.y' of git://git.ti.com/ti-linux-kernel/ti-linux-kernel:
  arm64: dts: ti: k3-j721e-mcu Declare 8 bit TX capability for OSPI
  arm64: dts: ti: k3-am65-mcu Declare 8 bit TX capability for OSPI
  mtd: spi-nor: cadence-quadspi: Declare Octal mode capability
  mtd: spi-nor: cadence-quadspi: Drop delayelem_ps parsing
  mtd: spi-nor: cadence-quadspi: Take care of alignment restrictions for DDR mode
  mtd: spi-nor: cadence-quadspi: Enter/exit DDR mode as required
  mtd: spi-nor: cadence-quadspi: Update PHY calibration sequence for DDR mode
  mtd: spi-nor: Introduce support for calibrating controller
  mtd: spi-nor: Add Octal DDR mode support for Micron mt35x flash
  mtd: spi-nor: Add support for Octal DDR mode
  mtd: spi-nor: Add support for statefull Octal IO mode

Signed-off-by: Jacob Stiffler <j-stiffler@ti.com>
Jacob Stiffler 6 vuotta sitten
vanhempi
commit
fd46d2eaec

+ 0 - 1
arch/arm64/boot/dts/ti/k3-am65-mcu.dtsi

@@ -382,7 +382,6 @@
 			cdns,fifo-depth = <256>;
 			cdns,fifo-width = <4>;
 			cdns,trigger-address = <0x50000000>;
-			cdns,delay-elem-ps = <80>;
 			clocks = <&k3_clks 55 5>;
 			assigned-clocks = <&k3_clks 55 5>;
 			assigned-clock-parents = <&k3_clks 55 7>;

+ 1 - 1
arch/arm64/boot/dts/ti/k3-am654-base-board.dts

@@ -499,7 +499,7 @@
 	flash@0{
 		compatible = "jedec,spi-nor";
 		reg = <0x0>;
-		spi-tx-bus-width = <1>;
+		spi-tx-bus-width = <8>;
 		spi-rx-bus-width = <8>;
 		spi-max-frequency = <50000000>;
 		spi-dqs;

+ 0 - 1
arch/arm64/boot/dts/ti/k3-j721e-mcu-wakeup.dtsi

@@ -403,7 +403,6 @@
 			cdns,fifo-depth = <256>;
 			cdns,fifo-width = <4>;
 			cdns,trigger-address = <0x0>;
-			cdns,delay-elem-ps = <80>;
 			clocks = <&k3_clks 103 0>;
 			assigned-clocks = <&k3_clks 103 0>;
 			assigned-clock-parents = <&k3_clks 103 2>;

+ 2 - 2
arch/arm64/boot/dts/ti/k3-j721e-som-p0.dtsi

@@ -230,7 +230,7 @@
 	flash@0{
 		compatible = "jedec,spi-nor";
 		reg = <0x0>;
-		spi-tx-bus-width = <1>;
+		spi-tx-bus-width = <8>;
 		spi-rx-bus-width = <8>;
 		spi-max-frequency = <50000000>;
 		spi-dqs;
@@ -238,7 +238,7 @@
 		cdns,tsd2d-ns = <60>;
 		cdns,tchsh-ns = <60>;
 		cdns,tslch-ns = <60>;
-		cdns,read-delay = <2>;
+		cdns,read-delay = <0>;
 		cdns,phy-mode;
 		#address-cells = <1>;
 		#size-cells = <1>;

+ 181 - 77
drivers/mtd/spi-nor/cadence-quadspi.c

@@ -69,6 +69,7 @@ struct cqspi_flash_pdata {
 	bool		registered;
 	bool		use_direct_mode;
 	bool		phy_mode;
+	bool		phy_calibrated;
 	bool		dqs_en;
 };
 
@@ -134,6 +135,7 @@ struct cqspi_driver_platdata {
 #define CQSPI_REG_CONFIG_CHIPSELECT_LSB		10
 #define CQSPI_REG_CONFIG_DMA_MASK		BIT(15)
 #define CQSPI_REG_CONFIG_BAUD_LSB		19
+#define CQSPI_REG_CONFIG_DTR_PROTO		BIT(24)
 #define CQSPI_REG_CONFIG_PHY_PIPELINE		BIT(25)
 #define CQSPI_REG_CONFIG_IDLE_LSB		31
 #define CQSPI_REG_CONFIG_CHIPSELECT_MASK	0xF
@@ -627,14 +629,20 @@ static int cqspi_write_setup(struct spi_nor *nor)
 
 	/* Set opcode. */
 	reg = nor->program_opcode << CQSPI_REG_WR_INSTR_OPCODE_LSB;
+	reg |= f_pdata->data_width << CQSPI_REG_WR_INSTR_TYPE_DATA_LSB;
+	reg |= f_pdata->addr_width << CQSPI_REG_WR_INSTR_TYPE_ADDR_LSB;
 	writel(reg, reg_base + CQSPI_REG_WR_INSTR);
-	reg = cqspi_calc_rdreg(nor, nor->program_opcode);
+	reg = readl(reg_base + CQSPI_REG_RD_INSTR);
+	reg &= ~(CQSPI_REG_RD_INSTR_TYPE_INSTR_MASK <<
+			CQSPI_REG_RD_INSTR_TYPE_INSTR_LSB);
+	reg |= f_pdata->inst_width << CQSPI_REG_RD_INSTR_TYPE_INSTR_LSB;
 	writel(reg, reg_base + CQSPI_REG_RD_INSTR);
 
 	reg = readl(reg_base + CQSPI_REG_SIZE);
 	reg &= ~CQSPI_REG_SIZE_ADDRESS_MASK;
 	reg |= (nor->addr_width - 1);
 	writel(reg, reg_base + CQSPI_REG_SIZE);
+
 	return 0;
 }
 
@@ -890,7 +898,7 @@ static void cqspi_controller_enable(struct cqspi_st *cqspi, bool enable)
 	writel(reg, reg_base + CQSPI_REG_CONFIG);
 }
 
-static void cqspi_phy_enable(struct spi_nor *nor, bool enable)
+static void cqspi_phy_dtr_enable(struct spi_nor *nor, bool enable)
 {
 	struct cqspi_flash_pdata *f_pdata = nor->priv;
 	struct cqspi_st *cqspi = f_pdata->cqspi;
@@ -901,88 +909,138 @@ static void cqspi_phy_enable(struct spi_nor *nor, bool enable)
 
 	if (enable)
 		reg |= (CQSPI_REG_CONFIG_PHY |
-			CQSPI_REG_CONFIG_PHY_PIPELINE);
+			CQSPI_REG_CONFIG_PHY_PIPELINE |
+			CQSPI_REG_CONFIG_DTR_PROTO);
 	else
 		reg &= ~(CQSPI_REG_CONFIG_PHY |
-				CQSPI_REG_CONFIG_PHY_PIPELINE);
+			 CQSPI_REG_CONFIG_PHY_PIPELINE |
+			 CQSPI_REG_CONFIG_DTR_PROTO);
 
 	writel(reg, reg_base + CQSPI_REG_CONFIG);
 
 	if (f_pdata->dqs_en && enable)
-		cqspi_readdata_capture(cqspi, !cqspi->rclk_en, 0, true);
+		cqspi_readdata_capture(cqspi, !cqspi->rclk_en,
+				       0, true);
 	else
 		cqspi_readdata_capture(cqspi, !cqspi->rclk_en,
 				       f_pdata->read_delay, false);
+
+	cqspi_wait_idle(cqspi);
 }
 
-/* Configure OSPI PHY to be in PHY Master mode */
-static void cqspi_config_phy(struct spi_nor *nor)
+static void cqspi_phy_dll_config(struct cqspi_st *cqspi, u8 tx_dly, u8 rx_dly)
+{
+	void __iomem *reg_base = cqspi->iobase;
+	u32 reg;
+
+	reg = readl(reg_base + CQSPI_REG_PHY_CONFIGURATION);
+	reg &= ~CQSPI_REG_PHY_CONFIGURATION_TX_DLL_MASK;
+	reg |= tx_dly << CQSPI_REG_PHY_CONFIGURATION_TX_DLL_SHIFT;
+
+	reg &= ~CQSPI_REG_PHY_CONFIGURATION_RX_DLL_MASK;
+	reg |= rx_dly;
+	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
+
+	reg &= ~CQSPI_REG_PHY_CONFIGURATION_DLL_RESYNC;
+	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
+	reg |= CQSPI_REG_PHY_CONFIGURATION_DLL_RESYNC;
+	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
+	/* Make sure 0->1 transition of DLL resync bit is triggered */
+	wmb();
+	/* satisfy wait for 20 reference clock cycles @166MHz clock */
+	udelay(1);
+}
+
+/* Configure OSPI PHY in Master Bypass mode */
+static int cqspi_calibrate_phy(struct spi_nor *nor, void *calib_data,
+			       size_t len)
 {
 	struct cqspi_flash_pdata *f_pdata = nor->priv;
+	u8 rx_dly_start[CQSPI_MAX_RX_DLL_DELAY + 1];
 	struct cqspi_st *cqspi = f_pdata->cqspi;
-	unsigned int ref_clk_mhz;
+	u8 tx_dly_start = 0xff, tx_dly_end = 0;
 	void __iomem *reg_base = cqspi->iobase;
-	u8 init_delay;
-	u32 delayelements;
+	u8 tx_dly = 0, rx_dly = 0;
+	char *read_data;
+	int ret = 0;
 	u32 reg;
 
+	read_data = kmalloc(len, GFP_KERNEL);
+	if (!read_data)
+		return -ENOMEM;
+
+	memset(rx_dly_start, 0xff, sizeof(rx_dly_start));
+
 	reg = readl(reg_base + CQSPI_REG_CONFIG);
 	/* Reset PHY */
 	reg &= ~(CQSPI_REG_CONFIG_PHY | CQSPI_REG_CONFIG_PHY_PIPELINE);
 	writel(reg, reg_base + CQSPI_REG_CONFIG);
-	reg |= CQSPI_REG_CONFIG_PHY;
-	writel(reg, reg_base + CQSPI_REG_CONFIG);
+	cqspi_phy_dtr_enable(nor, true);
 
-	if (f_pdata->dqs_en)
-		cqspi_readdata_capture(cqspi, !cqspi->rclk_en, 0, true);
-	else
-		cqspi_readdata_capture(cqspi, !cqspi->rclk_en,
-				       f_pdata->read_delay, false);
+	/* Find range of TX DLL values which have at least one passing RX
+	 * DLL value
+	 */
+	while (tx_dly <= CQSPI_MAX_RX_DLL_DELAY) {
+		rx_dly = 0;
 
-	/* Disable PHY Master Bypass mode */
-	reg = readl(reg_base + CQSPI_REG_PHY_MASTER_CONTROL);
-	reg &= ~CQSPI_REG_PHY_MASTER_BYPASS_MODE;
-	writel(reg, reg_base + CQSPI_REG_PHY_MASTER_CONTROL);
+		while (rx_dly <= CQSPI_MAX_RX_DLL_DELAY) {
+			cqspi_phy_dll_config(cqspi, tx_dly, rx_dly);
 
-	/* Reset DLLs */
-	reg = readl(reg_base + CQSPI_REG_PHY_CONFIGURATION);
-	reg &= ~CQSPI_REG_PHY_CONFIGURATION_DLL_RESET;
-	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
+			nor->read(nor, 0, len, read_data);
 
-	/* Initial delay = 25% of (SPI_REFCLK / delay element) */
-	ref_clk_mhz = cqspi->master_ref_clk_hz / 1000000;
-	delayelements = 1000000 / ref_clk_mhz; // MHz to ps
-	delayelements /= cqspi->delayelem_ps;
-	init_delay = delayelements / 4;
-	reg = readl(reg_base + CQSPI_REG_PHY_MASTER_CONTROL);
-	reg &= ~CQSPI_REG_PHY_MASTER_CONTROL_INIT_DELAY_MASK;
-	reg |= init_delay;
-	writel(reg, reg_base + CQSPI_REG_PHY_MASTER_CONTROL);
-
-	/* Resync DLLs and deassert reset */
-	reg &= ~CQSPI_REG_PHY_CONFIGURATION_DLL_RESYNC;
-	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
-	reg |= (CQSPI_REG_PHY_CONFIGURATION_DLL_RESYNC |
-			CQSPI_REG_PHY_CONFIGURATION_DLL_RESET);
-	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
-	cqspi_wait_for_bit(reg_base + CQSPI_REG_DLL_OBS_LOWER,
-			   CQSPI_REG_DLL_OBS_LOWER_LOCK, false);
+			if (!memcmp(read_data, calib_data, len)) {
+				if (tx_dly_start == 0xff)
+					tx_dly_start = tx_dly;
+				rx_dly_start[tx_dly] = rx_dly;
+				break;
+			}
+			rx_dly++;
+		}
+		if (tx_dly_start != 0xff && rx_dly_start[tx_dly] == 0xff) {
+			tx_dly_end = tx_dly - 1;
+			break;
+		}
+		tx_dly++;
+	}
 
-	/* Set initial TX DLL delay value */
-	reg = readl(reg_base + CQSPI_REG_PHY_CONFIGURATION);
-	reg &= ~CQSPI_REG_PHY_CONFIGURATION_TX_DLL_MASK;
-	reg |= (init_delay << CQSPI_REG_PHY_CONFIGURATION_TX_DLL_SHIFT);
-	/* Set initial RX DLL delay value */
-	reg &= ~CQSPI_REG_PHY_CONFIGURATION_RX_DLL_MASK;
-	reg |= init_delay;
-	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
+	if (tx_dly_start == 0xff) {
+		ret = -EINVAL;
+		goto disable_phy;
+	}
+	/* Choose mid value from range of passing TX DLL values */
+	tx_dly = (tx_dly_start + tx_dly_end) / 2;
+	dev_dbg(nor->dev, "TX DLL valid range %x...%x\n",
+		tx_dly_start, tx_dly_end);
+	rx_dly = rx_dly_start[tx_dly];
+
+	/* For the chosen TX DLL value, find range of passing RX DLL
+	 * values
+	 */
+	while (rx_dly <= CQSPI_MAX_RX_DLL_DELAY) {
+		cqspi_phy_dll_config(cqspi, tx_dly, rx_dly);
 
-	reg &= ~CQSPI_REG_PHY_CONFIGURATION_DLL_RESYNC;
-	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
-	reg |= CQSPI_REG_PHY_CONFIGURATION_DLL_RESYNC;
-	writel(reg, reg_base + CQSPI_REG_PHY_CONFIGURATION);
-	/* satisfy wait for 20 reference clock cycles @1MHz clock */
-	usleep_range(50, 100);
+		nor->read(nor, 0, len, read_data);
+
+		if (memcmp(read_data, calib_data, len))
+			break;
+		rx_dly++;
+	}
+
+	dev_dbg(nor->dev, "RX DLL valid range %x...%x\n",
+		rx_dly_start[tx_dly], rx_dly - 1);
+	/* Choose mid value from range of passing RX DLL values */
+	rx_dly = (rx_dly_start[tx_dly] + rx_dly - 1) / 2;
+
+	dev_dbg(nor->dev, "Calibrating DLLs to (%x, %x)\n", tx_dly, rx_dly);
+	/* Set the chosen TX and RX DLL value pair */
+	cqspi_phy_dll_config(cqspi, tx_dly, rx_dly);
+
+	f_pdata->phy_calibrated = true;
+disable_phy:
+	cqspi_phy_dtr_enable(nor, false);
+	kfree(read_data);
+
+	return ret;
 }
 
 static void cqspi_configure(struct spi_nor *nor)
@@ -1005,9 +1063,6 @@ static void cqspi_configure(struct spi_nor *nor)
 	if (switch_cs) {
 		cqspi->current_cs = f_pdata->cs;
 		cqspi_configure_cs_and_sizes(nor);
-		if (f_pdata->phy_mode)
-			cqspi_config_phy(nor);
-		cqspi_phy_enable(nor, false);
 	}
 
 	/* Setup baudrate divisor and delays */
@@ -1045,6 +1100,24 @@ static int cqspi_set_protocol(struct spi_nor *nor, const int read)
 		case SNOR_PROTO_1_1_8:
 			f_pdata->data_width = CQSPI_INST_TYPE_OCTAL;
 			break;
+		case SNOR_PROTO_8_8_8_DTR:
+			f_pdata->inst_width = CQSPI_INST_TYPE_OCTAL;
+			f_pdata->data_width = CQSPI_INST_TYPE_OCTAL;
+			f_pdata->addr_width = CQSPI_INST_TYPE_OCTAL;
+			break;
+		default:
+			return -EINVAL;
+		}
+	} else {
+		switch (nor->write_proto) {
+		case SNOR_PROTO_1_1_1:
+			f_pdata->data_width = CQSPI_INST_TYPE_SINGLE;
+			break;
+		case SNOR_PROTO_8_8_8_DTR:
+			f_pdata->data_width = CQSPI_INST_TYPE_OCTAL;
+			f_pdata->addr_width = CQSPI_INST_TYPE_OCTAL;
+			f_pdata->inst_width = CQSPI_INST_TYPE_OCTAL;
+			break;
 		default:
 			return -EINVAL;
 		}
@@ -1071,8 +1144,14 @@ static ssize_t cqspi_write(struct spi_nor *nor, loff_t to,
 		return ret;
 
 	if (f_pdata->use_direct_mode) {
+		if (nor->mode == SPI_NOR_MODE_OPI_DTR)
+			cqspi_phy_dtr_enable(nor, true);
+
 		memcpy_toio(cqspi->ahb_base + to, buf, len);
 		ret = cqspi_wait_idle(cqspi);
+
+		if (nor->mode == SPI_NOR_MODE_OPI_DTR)
+			cqspi_phy_dtr_enable(nor, false);
 	} else {
 		ret = cqspi_indirect_write_execute(nor, to, buf, len);
 	}
@@ -1106,6 +1185,7 @@ static int cqspi_direct_read_execute(struct spi_nor *nor, u_char *buf,
 
 	if (!cqspi->rx_chan || !virt_addr_valid(buf) || len <= 16) {
 		memcpy_fromio(buf, cqspi->ahb_base + from, len);
+		cqspi_wait_idle(cqspi);
 		return 0;
 	}
 	ddev = cqspi->rx_chan->device->dev;
@@ -1162,28 +1242,29 @@ static int cqspi_direct_read_execute_phy(struct spi_nor *nor, u_char *buf,
 	u_char *dst;
 	u32 off_delta, len_delta;
 
-	/* Enable PHY and PHY pipeline mode */
-	cqspi_phy_enable(nor, true);
+	/* Enable DDR mode, PHY and PHY pipeline mode */
+	if (f_pdata->phy_calibrated)
+		cqspi_phy_dtr_enable(nor, true);
 	/*
-	 * Cadence OSPI IP requires 4 byte aligned accesses when PHY
-	 * pipeline mode is enabled. But, since on AM654 memcpy_fromio()
-	 * does either 8 byte access or single byte accesses, driver
-	 * will have to align read addresses to 8 bytes.
-	 * We convert read start address and length to 8 byte
+	 * Cadence OSPI IP requires 16 byte aligned accesses when PHY
+	 * pipeline mode is enabled in Octal DDR mode. So, driver
+	 * will have to align read addresses to 16 bytes.
+	 * We convert read start address and length to 16 byte
 	 * aligned start address and length. Then use bounce buffer for
 	 * intermediate copy and finally copy only the requested range
 	 * of data to destination buffer.
 	 */
-	if (IS_ALIGNED(from, 8) && IS_ALIGNED(len, 8) && virt_addr_valid(buf)) {
+	if (IS_ALIGNED(from, 16) && IS_ALIGNED(len, 16) &&
+	    virt_addr_valid(buf)) {
 		ret = cqspi_direct_read_execute(nor, buf, from, len);
 		goto disable_phy;
 	}
 
 	dst = cqspi->dma_bb_rx;
 
-	align_from = ALIGN_DOWN(from, 8);
+	align_from = ALIGN_DOWN(from, 16);
 	off_delta = from - align_from;
-	readsize = ALIGN(len + off_delta, 8);
+	readsize = ALIGN(len + off_delta, 16);
 	len_delta = readsize - (len + off_delta);
 
 	xfer_len = min_t(size_t, CQSPI_DMA_BUFFER_SIZE,
@@ -1213,7 +1294,9 @@ static int cqspi_direct_read_execute_phy(struct spi_nor *nor, u_char *buf,
 	}
 
 disable_phy:
-	cqspi_phy_enable(nor, false);
+	if (f_pdata->phy_calibrated)
+		cqspi_phy_dtr_enable(nor, false);
+
 	return ret;
 }
 
@@ -1231,7 +1314,7 @@ static ssize_t cqspi_read(struct spi_nor *nor, loff_t from,
 	if (ret)
 		return ret;
 
-	if (f_pdata->use_direct_mode && f_pdata->phy_mode)
+	if (f_pdata->use_direct_mode && f_pdata->phy_calibrated)
 		ret = cqspi_direct_read_execute_phy(nor, buf, from, len);
 	else if (f_pdata->use_direct_mode)
 		ret = cqspi_direct_read_execute(nor, buf, from,	len);
@@ -1287,6 +1370,13 @@ static int cqspi_read_reg(struct spi_nor *nor, u8 opcode, u8 *buf, int len)
 	int ret;
 
 	ret = cqspi_set_protocol(nor, 0);
+	if (ret)
+		return ret;
+
+	ret = cqspi_read_setup(nor);
+	if (ret)
+		return ret;
+
 	if (!ret)
 		ret = cqspi_command_read(nor, &opcode, 1, buf, len);
 
@@ -1298,9 +1388,22 @@ static int cqspi_write_reg(struct spi_nor *nor, u8 opcode, u8 *buf, int len)
 	int ret;
 
 	ret = cqspi_set_protocol(nor, 0);
+	if (ret)
+		return ret;
+
+	ret = cqspi_write_setup(nor);
+	if (ret)
+		return ret;
+
+	if (nor->mode == SPI_NOR_MODE_OPI_DTR)
+		cqspi_phy_dtr_enable(nor, true);
+
 	if (!ret)
 		ret = cqspi_command_write(nor, opcode, buf, len);
 
+	if (nor->mode == SPI_NOR_MODE_OPI_DTR)
+		cqspi_phy_dtr_enable(nor, false);
+
 	return ret;
 }
 
@@ -1367,10 +1470,6 @@ static int cqspi_of_get_pdata(struct platform_device *pdev)
 		return -ENXIO;
 	}
 
-	if (of_property_read_u32(np, "cdns,delay-elem-ps",
-				 &cqspi->delayelem_ps))
-		cqspi->delayelem_ps = 80;
-
 	cqspi->rclk_en = of_property_read_bool(np, "cdns,rclk-en");
 
 	return 0;
@@ -1514,6 +1613,11 @@ static int cqspi_setup_flash(struct cqspi_st *cqspi, struct device_node *np)
 		nor->prepare = cqspi_prep;
 		nor->unprepare = cqspi_unprep;
 
+		if (f_pdata->phy_mode) {
+			nor->calibrate = cqspi_calibrate_phy;
+			f_pdata->use_direct_mode = true;
+		}
+
 		mtd->name = devm_kasprintf(dev, GFP_KERNEL, "%s.%d",
 					   dev_name(dev), cs);
 		if (!mtd->name) {
@@ -1716,7 +1820,7 @@ static const struct cqspi_driver_platdata k2g_qspi = {
 };
 
 static const struct cqspi_driver_platdata am654_ospi = {
-	.hwcaps_mask = CQSPI_BASE_HWCAPS_MASK | SNOR_HWCAPS_READ_1_1_8,
+	.hwcaps_mask = CQSPI_BASE_HWCAPS_MASK | SNOR_HWCAPS_READ_8_8_8,
 	.quirks = CQSPI_NEEDS_WR_DELAY,
 };
 

+ 146 - 8
drivers/mtd/spi-nor/spi-nor.c

@@ -89,9 +89,11 @@ struct flash_info {
 #define NO_CHIP_ERASE		BIT(12) /* Chip does not support chip erase */
 #define SPI_NOR_SKIP_SFDP	BIT(13)	/* Skip parsing of SFDP tables */
 #define USE_CLSR		BIT(14)	/* use CLSR command */
-#define SPI_NOR_OCTAL_READ	BIT(15)	/* Flash supports Octal Read */
+#define SPI_NOR_OPI_DTR		BIT(15)	/* Flash supports Octal Read */
 
 	int	(*quad_enable)(struct spi_nor *nor);
+	int	(*change_mode)(struct spi_nor *nor, enum spi_nor_mode mode);
+	void	(*adjust_op)(struct spi_nor *nor, enum spi_nor_mode mode);
 };
 
 #define JEDEC_MFR(info)	((info)->id[0])
@@ -215,6 +217,7 @@ static inline u8 spi_nor_convert_3to4_read(u8 opcode)
 		{ SPINOR_OP_READ_1_1_1_DTR,	SPINOR_OP_READ_1_1_1_DTR_4B },
 		{ SPINOR_OP_READ_1_2_2_DTR,	SPINOR_OP_READ_1_2_2_DTR_4B },
 		{ SPINOR_OP_READ_1_4_4_DTR,	SPINOR_OP_READ_1_4_4_DTR_4B },
+		{ SPINOR_OP_READ_8_8_8_DTR,	SPINOR_OP_READ_8_8_8_DTR_4B },
 	};
 
 	return spi_nor_convert_opcode(opcode, spi_nor_3to4_read,
@@ -914,6 +917,62 @@ static int spi_nor_is_locked(struct mtd_info *mtd, loff_t ofs, uint64_t len)
 	return ret;
 }
 
+static void spi_nor_micron_adjust_op(struct spi_nor *nor,
+				     enum spi_nor_mode mode)
+{
+	if (mode == SPI_NOR_MODE_OPI_DTR) {
+		nor->reg_proto = SNOR_PROTO_8_8_8_DTR;
+		nor->read_proto = SNOR_PROTO_8_8_8_DTR;
+		nor->write_proto = SNOR_PROTO_8_8_8_DTR;
+		nor->read_dummy = 16;
+		nor->addr_width = 4;
+		nor->read_opcode = SPINOR_OP_READ_8_8_8_DTR_4B;
+	} else {
+		nor->reg_proto = SNOR_PROTO_1_1_1;
+		nor->read_proto = SNOR_PROTO_1_1_1;
+		nor->write_proto = SNOR_PROTO_1_1_1;
+		nor->read_dummy = 8;
+		nor->addr_width = 4;
+		nor->read_opcode = SPINOR_OP_READ_FAST_4B;
+	}
+}
+
+static int spi_nor_micron_set_octal_ddr_mode(struct spi_nor *nor,
+					     enum spi_nor_mode mode)
+{
+	u8 addr_width, program_opcode, vcr_val;
+	enum spi_nor_protocol write_proto;
+	int ret;
+
+	program_opcode = nor->program_opcode;
+	write_proto  = nor->write_proto;
+	addr_width = nor->addr_width;
+
+	/* Enable Octal DTR mode */
+	nor->program_opcode = SPINOR_OP_WR_VCR;
+
+	if (mode == SPI_NOR_MODE_OPI_DTR) {
+		nor->addr_width = 3;
+		vcr_val = VCR_OCTAL_DDR_EN_MICRON;
+		ret = nor->write(nor, 0x0, sizeof(vcr_val), &vcr_val);
+		if (ret < 0)
+			return ret;
+	} else {
+		nor->write_proto = SNOR_PROTO_8_8_8_DTR;
+		/* Soft reset the flash to return to SPI_NOR_MODE_SPI */
+		nor->write_reg(nor, SPINOR_OP_RESET_EN, NULL, 0);
+		udelay(1);
+		nor->write_reg(nor, SPINOR_OP_RESET_MEM, NULL, 0);
+		udelay(1);
+	}
+
+	nor->program_opcode = program_opcode;
+	nor->write_proto = write_proto;
+	nor->addr_width = addr_width;
+
+	return 0;
+}
+
 static int macronix_quad_enable(struct spi_nor *nor);
 
 /* Used when the "_ext_id" is two bytes at most */
@@ -1121,8 +1180,10 @@ static const struct flash_info spi_nor_ids[] = {
 	/* Micron */
 	{
 		"mt35xu512aba", INFO(0x2c5b1a, 0, 128 * 1024, 512,
-			SECT_4K | USE_FSR | SPI_NOR_OCTAL_READ |
+			SECT_4K | USE_FSR | SPI_NOR_OPI_DTR |
 			SPI_NOR_4B_OPCODES)
+			.change_mode = spi_nor_micron_set_octal_ddr_mode,
+			.adjust_op = spi_nor_micron_adjust_op
 	},
 
 	/* PMC */
@@ -1303,6 +1364,28 @@ static const struct flash_info *spi_nor_read_id(struct spi_nor *nor)
 	return ERR_PTR(-ENODEV);
 }
 
+static int spi_nor_select_mode(struct spi_nor *nor, enum spi_nor_mode mode)
+{
+	int ret;
+
+	if (nor->mode == mode)
+		return 0;
+
+	if (!nor->change_mode)
+		return -ENOTSUPP;
+
+	ret = nor->change_mode(nor, mode);
+	if (ret)
+		return ret;
+
+	if (nor->adjust_op)
+		nor->adjust_op(nor, mode);
+
+	nor->mode = mode;
+
+	return ret;
+}
+
 static int spi_nor_read(struct mtd_info *mtd, loff_t from, size_t len,
 			size_t *retlen, u_char *buf)
 {
@@ -1315,6 +1398,8 @@ static int spi_nor_read(struct mtd_info *mtd, loff_t from, size_t len,
 	if (ret)
 		return ret;
 
+	spi_nor_select_mode(nor, nor->preferred_mode);
+
 	while (len) {
 		loff_t addr = from;
 
@@ -1339,6 +1424,8 @@ static int spi_nor_read(struct mtd_info *mtd, loff_t from, size_t len,
 	ret = 0;
 
 read_err:
+	spi_nor_select_mode(nor, SPI_NOR_MODE_SPI);
+
 	spi_nor_unlock_and_unprep(nor, SPI_NOR_OPS_READ);
 	return ret;
 }
@@ -1819,6 +1906,7 @@ enum spi_nor_read_command_index {
 	SNOR_CMD_READ_1_8_8,
 	SNOR_CMD_READ_8_8_8,
 	SNOR_CMD_READ_1_8_8_DTR,
+	SNOR_CMD_READ_8_8_8_DTR,
 
 	SNOR_CMD_READ_MAX
 };
@@ -1903,6 +1991,8 @@ static int spi_nor_read_sfdp(struct spi_nor *nor, u32 addr,
 	nor->addr_width = 3;
 	nor->read_dummy = 8;
 
+	nor->read_proto = SNOR_PROTO_1_1_1;
+
 	while (len) {
 		ret = nor->read(nor, addr, len, (u8 *)buf);
 		if (!ret || ret > len) {
@@ -2502,11 +2592,11 @@ static int spi_nor_init_params(struct spi_nor *nor,
 					  SNOR_PROTO_1_1_4);
 	}
 
-	if (info->flags & SPI_NOR_OCTAL_READ) {
-		params->hwcaps.mask |= SNOR_HWCAPS_READ_1_1_8;
-		spi_nor_set_read_settings(&params->reads[SNOR_CMD_READ_1_1_8],
-					  0, 8, SPINOR_OP_READ_1_1_8,
-					  SNOR_PROTO_1_1_8);
+	if (info->flags & SPI_NOR_OPI_DTR) {
+		params->hwcaps.mask |= SNOR_HWCAPS_READ_8_8_8_DTR;
+		spi_nor_set_read_settings(&params->reads[SNOR_CMD_READ_8_8_8_DTR],
+					  0, 16, SPINOR_OP_READ_8_8_8_DTR,
+					  SNOR_PROTO_8_8_8_DTR);
 	}
 
 	/* Page Program settings. */
@@ -2590,6 +2680,7 @@ static int spi_nor_hwcaps_read2cmd(u32 hwcaps)
 		{ SNOR_HWCAPS_READ_1_8_8,	SNOR_CMD_READ_1_8_8 },
 		{ SNOR_HWCAPS_READ_8_8_8,	SNOR_CMD_READ_8_8_8 },
 		{ SNOR_HWCAPS_READ_1_8_8_DTR,	SNOR_CMD_READ_1_8_8_DTR },
+		{ SNOR_HWCAPS_READ_8_8_8_DTR,	SNOR_CMD_READ_8_8_8_DTR },
 	};
 
 	return spi_nor_hwcaps2cmd(hwcaps, hwcaps_read2cmd,
@@ -2690,6 +2781,43 @@ static int spi_nor_select_erase(struct spi_nor *nor,
 	return 0;
 }
 
+/* Calibrate controller for given mode */
+static int spi_nor_calibrate(struct spi_nor *nor, enum spi_nor_mode mode)
+{
+	/* Use first 16 bytes of SFDP Header as calibration data */
+	int size = sizeof(struct sfdp_parameter_header) << 1;
+	u8 addr_width = nor->addr_width;
+	u8 *calibration_data;
+	int ret;
+
+	if (!nor->calibrate)
+		return 0;
+
+	calibration_data = kmalloc(size, GFP_KERNEL);
+	if (!calibration_data)
+		return -ENOMEM;
+
+	ret = spi_nor_read_sfdp(nor, 0, size, calibration_data);
+	if (ret)
+		goto free_mem;
+
+	nor->preferred_mode = mode;
+	spi_nor_select_mode(nor, nor->preferred_mode);
+
+	nor->addr_width = 4;
+	nor->read_opcode = SPINOR_OP_RDSFDP;
+	nor->read_dummy = 8;
+
+	ret = nor->calibrate(nor, calibration_data, size);
+
+	spi_nor_select_mode(nor, SPI_NOR_MODE_SPI);
+	nor->addr_width = addr_width;
+free_mem:
+	kfree(calibration_data);
+
+	return ret;
+}
+
 static int spi_nor_setup(struct spi_nor *nor, const struct flash_info *info,
 			 const struct spi_nor_flash_parameter *params,
 			 const struct spi_nor_hwcaps *hwcaps)
@@ -2707,7 +2835,6 @@ static int spi_nor_setup(struct spi_nor *nor, const struct flash_info *info,
 	/* SPI n-n-n protocols are not supported yet. */
 	ignored_mask = (SNOR_HWCAPS_READ_2_2_2 |
 			SNOR_HWCAPS_READ_4_4_4 |
-			SNOR_HWCAPS_READ_8_8_8 |
 			SNOR_HWCAPS_PP_4_4_4 |
 			SNOR_HWCAPS_PP_8_8_8);
 	if (shared_mask & ignored_mask) {
@@ -2716,6 +2843,9 @@ static int spi_nor_setup(struct spi_nor *nor, const struct flash_info *info,
 		shared_mask &= ~ignored_mask;
 	}
 
+	nor->change_mode = info->change_mode;
+	nor->adjust_op = info->adjust_op;
+
 	/* Select the (Fast) Read command. */
 	err = spi_nor_select_read(nor, params, shared_mask);
 	if (err) {
@@ -2740,6 +2870,14 @@ static int spi_nor_setup(struct spi_nor *nor, const struct flash_info *info,
 		return err;
 	}
 
+	if (info->flags & SPI_NOR_OPI_DTR) {
+		err = spi_nor_calibrate(nor, SPI_NOR_MODE_OPI_DTR);
+		if (err) {
+			dev_err(nor->dev, "Controller calibration failed\n");
+			return err;
+		}
+	}
+
 	/* Enable Quad I/O if needed. */
 	enable_quad_io = (spi_nor_get_protocol_width(nor->read_proto) == 4 ||
 			  spi_nor_get_protocol_width(nor->write_proto) == 4);

+ 25 - 1
include/linux/mtd/spi-nor.h

@@ -92,10 +92,12 @@
 #define SPINOR_OP_READ_1_1_1_DTR	0x0d
 #define SPINOR_OP_READ_1_2_2_DTR	0xbd
 #define SPINOR_OP_READ_1_4_4_DTR	0xed
+#define SPINOR_OP_READ_8_8_8_DTR	0xfd
 
 #define SPINOR_OP_READ_1_1_1_DTR_4B	0x0e
 #define SPINOR_OP_READ_1_2_2_DTR_4B	0xbe
 #define SPINOR_OP_READ_1_4_4_DTR_4B	0xee
+#define SPINOR_OP_READ_8_8_8_DTR_4B	0xfd
 
 /* Used for SST flashes only. */
 #define SPINOR_OP_BP		0x02	/* Byte program */
@@ -122,6 +124,9 @@
 /* Used for Micron flashes only. */
 #define SPINOR_OP_RD_EVCR      0x65    /* Read EVCR register */
 #define SPINOR_OP_WD_EVCR      0x61    /* Write EVCR register */
+#define SPINOR_OP_WR_VCR       0x81	/* Write VCR register */
+#define SPINOR_OP_RESET_EN     0x66	/* Enable Soft reset */
+#define SPINOR_OP_RESET_MEM    0x99	/* Reset memory */
 
 /* Status Register bits. */
 #define SR_WIP			BIT(0)	/* Write in progress */
@@ -141,6 +146,9 @@
 /* Enhanced Volatile Configuration Register bits */
 #define EVCR_QUAD_EN_MICRON	BIT(7)	/* Micron Quad I/O */
 
+/* Micron VCR Register Settings */
+#define VCR_OCTAL_DDR_EN_MICRON	0xe7	/* Octal DDR with DQS mode */
+
 /* Flag Status Register bits */
 #define FSR_READY		BIT(7)	/* Device status, 0 = Busy, 1 = Ready */
 #define FSR_E_ERR		BIT(5)	/* Erase operation status */
@@ -198,6 +206,7 @@ enum spi_nor_protocol {
 	SNOR_PROTO_1_2_2_DTR = SNOR_PROTO_DTR(1, 2, 2),
 	SNOR_PROTO_1_4_4_DTR = SNOR_PROTO_DTR(1, 4, 4),
 	SNOR_PROTO_1_8_8_DTR = SNOR_PROTO_DTR(1, 8, 8),
+	SNOR_PROTO_8_8_8_DTR = SNOR_PROTO_DTR(8, 8, 8),
 };
 
 static inline bool spi_nor_protocol_is_dtr(enum spi_nor_protocol proto)
@@ -247,6 +256,15 @@ enum spi_nor_option_flags {
 	SNOR_F_BROKEN_RESET	= BIT(6),
 };
 
+enum spi_nor_mode {
+	SPI_NOR_MODE_SPI = 0,
+	SPI_NOR_MODE_DPI,
+	SPI_NOR_MODE_QPI,
+	SPI_NOR_MODE_OPI,
+	SPI_NOR_MODE_OPI_DTR,
+	SPI_NOR_NUM_MODES,
+};
+
 /**
  * struct flash_info - Forward declaration of a structure used internally by
  *		       spi_nor_scan()
@@ -304,6 +322,8 @@ struct spi_nor {
 	enum spi_nor_protocol	write_proto;
 	enum spi_nor_protocol	reg_proto;
 	bool			sst_write_second;
+	enum spi_nor_mode	mode;
+	enum spi_nor_mode	preferred_mode;
 	u32			flags;
 	u8			cmd_buf[SPI_NOR_MAX_CMD_SIZE];
 
@@ -316,12 +336,15 @@ struct spi_nor {
 			size_t len, u_char *read_buf);
 	ssize_t (*write)(struct spi_nor *nor, loff_t to,
 			size_t len, const u_char *write_buf);
+	int (*calibrate)(struct spi_nor *nor, void *calib_data, size_t len);
 	int (*erase)(struct spi_nor *nor, loff_t offs);
 
 	int (*flash_lock)(struct spi_nor *nor, loff_t ofs, uint64_t len);
 	int (*flash_unlock)(struct spi_nor *nor, loff_t ofs, uint64_t len);
 	int (*flash_is_locked)(struct spi_nor *nor, loff_t ofs, uint64_t len);
 	int (*quad_enable)(struct spi_nor *nor);
+	int (*change_mode)(struct spi_nor *nor, enum spi_nor_mode newmode);
+	void (*adjust_op)(struct spi_nor *nor, enum spi_nor_mode mode);
 
 	void *priv;
 };
@@ -370,11 +393,12 @@ struct spi_nor_hwcaps {
 #define SNOR_HWCAPS_READ_4_4_4		BIT(9)
 #define SNOR_HWCAPS_READ_1_4_4_DTR	BIT(10)
 
-#define SNOR_HWCPAS_READ_OCTAL		GENMASK(14, 11)
+#define SNOR_HWCPAS_READ_OCTAL		GENMASK(15, 11)
 #define SNOR_HWCAPS_READ_1_1_8		BIT(11)
 #define SNOR_HWCAPS_READ_1_8_8		BIT(12)
 #define SNOR_HWCAPS_READ_8_8_8		BIT(13)
 #define SNOR_HWCAPS_READ_1_8_8_DTR	BIT(14)
+#define SNOR_HWCAPS_READ_8_8_8_DTR	BIT(15)
 
 /*
  * Page Program capabilities.