[PATCH 4/4] usb: dwc3: second part of hibernation support

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

 



This patch adds the actual hibernation code, and allows it to be
enabled in the Kconfig.

When hibernation support is enabled, the controller h/w (except
for a small portion that needs to remain active) will be powered
down when the host puts the USB bus into U3/L1/L2 state, or when
the device is disconnected from the host. Unless the device has
been disconnected, the controller state must be saved to RAM
before the power is removed.

When the USB bus returns to the U0/ON state, or the device is
reconnected, the controller will be powered on, its state
restored from RAM (unless the device was disconnected), and any
endpoints that had active transfers will be restarted.

The code currently only supports the Synopsys HAPS platform.
There is some platform-specific code that will need to be
reimplemented to support other platforms.

There are a few things that remain to be done:

- Implement restart of isochronous endpoints after hibernation.
  Currently hibernation will cause those endpoints to fail after
  resume (so don't enable hibernation yet if your device has
  isoc endpoints!)

- Put the controller into hibernation immediately after the driver
  is loaded, if the device is not connected to a host. Currently
  this can sometimes cause the controller to hang, but I'm not
  sure why.

- Implement function remote wake from hibernation. This is
  different from the normal case, because the controller must be
  powered up and restored before sending the remote wake
  notification.

Signed-off-by: Paul Zimmerman <paulz@xxxxxxxxxxxx>
---
 drivers/usb/dwc3/Kconfig       |    6 +
 drivers/usb/dwc3/Makefile      |    2 +
 drivers/usb/dwc3/haps_pwrctl.c |  145 +++++++
 drivers/usb/dwc3/hibernate.c   |  896 ++++++++++++++++++++++++++++++++++++++++
 4 files changed, 1049 insertions(+), 0 deletions(-)

diff --git a/drivers/usb/dwc3/Kconfig b/drivers/usb/dwc3/Kconfig
index d8f741f..c91ad7c 100644
--- a/drivers/usb/dwc3/Kconfig
+++ b/drivers/usb/dwc3/Kconfig
@@ -25,4 +25,10 @@ config USB_DWC3_VERBOSE
 	help
 	  Say Y here to enable verbose debugging messages on DWC3 Driver.
 
+config USB_DWC3_HIBERNATION
+	bool "Enable support for Hibernation feature"
+	help
+	  Say Y here to enable support for the special Hibernation feature
+	  of the DWC USB3 controller.
+
 endif
diff --git a/drivers/usb/dwc3/Makefile b/drivers/usb/dwc3/Makefile
index e37ecd3..16c4725 100644
--- a/drivers/usb/dwc3/Makefile
+++ b/drivers/usb/dwc3/Makefile
@@ -6,6 +6,7 @@ obj-$(CONFIG_USB_DWC3)			+= dwc3.o
 dwc3-y					:= core.o
 dwc3-y					+= host.o
 dwc3-y					+= gadget.o ep0.o
+dwc3-$(CONFIG_USB_DWC3_HIBERNATION)	+= hibernate.o
 
 ifneq ($(CONFIG_DEBUG_FS),)
 	dwc3-y				+= debugfs.o
@@ -33,4 +34,5 @@ ifneq ($(CONFIG_PCI),)
 	obj-$(CONFIG_USB_DWC3)		+= dwc3-pci.o
 
 	dwc3-pci-y			:= dwc3_pci.o
+	dwc3-pci-$(CONFIG_USB_DWC3_HIBERNATION)	+= haps_pwrctl.o
 endif
diff --git a/drivers/usb/dwc3/haps_pwrctl.c b/drivers/usb/dwc3/haps_pwrctl.c
new file mode 100644
index 0000000..d83ae3e
--- /dev/null
+++ b/drivers/usb/dwc3/haps_pwrctl.c
@@ -0,0 +1,145 @@
+/**
+ * haps_pwrctl.c - DesignWare USB3 DRD Controller Power Control for HAPS
+ *
+ * Copyright (C) 2011-2012 Synopsys Incorporated
+ *
+ * Author: Paul Zimmerman <paulz@xxxxxxxxxxxx>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions, and the following disclaimer,
+ *    without modification.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ * 3. The names of the above-listed copyright holders may not be used
+ *    to endorse or promote products derived from this software without
+ *    specific prior written permission.
+ *
+ * ALTERNATIVELY, this software may be distributed under the terms of the
+ * GNU General Public License ("GPL") version 2, as published by the Free
+ * Software Foundation.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <linux/kernel.h>
+#include <linux/delay.h>
+
+#include "core.h"
+#include "io.h"
+
+#define DWC3_HAPS_GASKET_POWER_CTL		0x80004
+#define DWC3_HAPS_GASKET_POWER_DSTATE_MASK	0x3000
+#define DWC3_HAPS_GASKET_POWER_DSTATE_D3	0x3000
+#define DWC3_HAPS_GASKET_POWER_DSTATE_D0	0x0000
+
+#define DWC3_HAPS_GASKET_DEBUG			0x80010
+#define DWC3_HAPS_GASKET_DEBUG_USB_CONN_MASK	0x88
+#define DWC3_HAPS_GASKET_DEBUG_PME_INTR_MASK	0x44
+#define DWC3_HAPS_GASKET_DEBUG_DSTATE_MASK	0x33
+#define DWC3_HAPS_GASKET_DEBUG_DSTATE_D3	0x33
+#define DWC3_HAPS_GASKET_DEBUG_DSTATE_D0	0x00
+
+/*
+ * Platform-specific power control routine, for HAPS board
+ */
+void dwc3_haps_power_ctl(struct dwc3 *dwc, int on)
+{
+	u32	reg;
+	int	cnt = 0;
+
+	if (on) {
+		/*
+		 * Enable core well power
+		 */
+
+		/* This is "faked" by the FPGA */
+
+		/*
+		 * Communicate with power controller to set power state to D0
+		 */
+
+		reg = dwc3_readl(dwc->regs, DWC3_HAPS_GASKET_POWER_CTL);
+		dev_vdbg(dwc->dev, "R1=0x%08x before write\n", reg);
+		reg = (reg & ~DWC3_HAPS_GASKET_POWER_DSTATE_MASK) |
+				DWC3_HAPS_GASKET_POWER_DSTATE_D0;
+		dwc3_writel(dwc->regs, DWC3_HAPS_GASKET_POWER_CTL, reg);
+		reg = dwc3_readl(dwc->regs, DWC3_HAPS_GASKET_POWER_CTL);
+		dev_vdbg(dwc->dev, "R1=0x%08x after write\n", reg);
+
+		/*
+		 * Wait until both PMUs confirm that they have entered D0
+		 */
+
+		dev_vdbg(dwc->dev, "Asked for D0 state, awaiting response\n");
+
+		do {
+			udelay(1);
+			reg = dwc3_readl(dwc->regs, DWC3_HAPS_GASKET_DEBUG);
+			if (++cnt > 10000000) {
+				cnt = 0;
+				dev_vdbg(dwc->dev, "0x%08x\n", reg);
+			}
+		} while ((reg & DWC3_HAPS_GASKET_DEBUG_DSTATE_MASK) !=
+				DWC3_HAPS_GASKET_DEBUG_DSTATE_D0);
+	} else {
+		/*
+		 * Communicate with power controller to set power state to D3
+		 */
+
+		reg = dwc3_readl(dwc->regs, DWC3_HAPS_GASKET_POWER_CTL);
+		dev_vdbg(dwc->dev, "R1=0x%08x before write\n", reg);
+		reg = (reg & ~DWC3_HAPS_GASKET_POWER_DSTATE_MASK) |
+				DWC3_HAPS_GASKET_POWER_DSTATE_D3;
+		dwc3_writel(dwc->regs, DWC3_HAPS_GASKET_POWER_CTL, reg);
+		reg = dwc3_readl(dwc->regs, DWC3_HAPS_GASKET_POWER_CTL);
+		dev_vdbg(dwc->dev, "R1=0x%08x after write\n", reg);
+
+		/*
+		 * Wait until both PMUs confirm that they have entered D3
+		 */
+
+		dev_vdbg(dwc->dev, "Asked for D3 state, awaiting response\n");
+
+		do {
+			udelay(1);
+			reg = dwc3_readl(dwc->regs, DWC3_HAPS_GASKET_DEBUG);
+			if (++cnt >= 10000000) {
+				cnt = 0;
+				dev_vdbg(dwc->dev, "0x%08x\n", reg);
+			}
+		} while ((reg & DWC3_HAPS_GASKET_DEBUG_DSTATE_MASK) !=
+				DWC3_HAPS_GASKET_DEBUG_DSTATE_D3);
+	}
+}
+
+/*
+ * Platform-specific PME interrupt handler, for HAPS board
+ */
+int dwc3_haps_pme_intr(struct dwc3 *dwc)
+{
+	u32	reg;
+
+	dev_info(dwc->dev, "%s()\n", __func__);
+
+	reg = dwc3_readl(dwc->regs, DWC3_HAPS_GASKET_DEBUG);
+	dev_vdbg(dwc->dev, "HAPS debug reg=0x%08x\n", reg);
+
+	if ((reg & DWC3_HAPS_GASKET_DEBUG_PME_INTR_MASK) != 0)
+		return (reg & DWC3_HAPS_GASKET_DEBUG_USB_CONN_MASK) != 0;
+
+	return -1;
+}
diff --git a/drivers/usb/dwc3/hibernate.c b/drivers/usb/dwc3/hibernate.c
new file mode 100644
index 0000000..73184e6
--- /dev/null
+++ b/drivers/usb/dwc3/hibernate.c
@@ -0,0 +1,896 @@
+/**
+ * hibernate.c - DesignWare USB3 DRD Controller Hibernation Support
+ *
+ * Copyright (C) 2011-2012 Synopsys Incorporated
+ *
+ * Author: Paul Zimmerman <paulz@xxxxxxxxxxxx>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions, and the following disclaimer,
+ *    without modification.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ * 3. The names of the above-listed copyright holders may not be used
+ *    to endorse or promote products derived from this software without
+ *    specific prior written permission.
+ *
+ * ALTERNATIVELY, this software may be distributed under the terms of the
+ * GNU General Public License ("GPL") version 2, as published by the Free
+ * Software Foundation.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
+ * IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
+ * THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ * PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR
+ * CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
+ * EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO,
+ * PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
+ * PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
+ * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
+ * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+ * SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <linux/kernel.h>
+#include <linux/delay.h>
+#include <linux/slab.h>
+#include <linux/spinlock.h>
+#include <linux/interrupt.h>
+#include <linux/io.h>
+#include <linux/list.h>
+#include <linux/dma-mapping.h>
+#include <linux/kthread.h>
+#include <linux/freezer.h>
+
+#include "core.h"
+#include "gadget.h"
+#include "hibernate.h"
+#include "io.h"
+
+int dwc3_alloc_scratchpad_buffers(struct dwc3 *dwc)
+{
+	dma_addr_t	dma_adr;
+	int		hiberbufs, i;
+
+	if (!dwc3_hiber_enabled(dwc))
+		return 0;
+
+	hiberbufs = DWC3_GHWPARAMS4_HIBER_SCRATCHBUFS(dwc->hwparams.hwparams4);
+	if (hiberbufs) {
+		/* Allocate scratchpad buffer address array */
+		dwc->scratchpad_array = dma_alloc_coherent(NULL,
+			sizeof(*dwc->scratchpad_array),
+			&dwc->scratchpad_array_dma, GFP_KERNEL);
+		if (!dwc->scratchpad_array)
+			goto err;
+	}
+
+	/* Allocate scratchpad buffers */
+	for (i = 0; i < hiberbufs; i++) {
+		dwc->scratchpad[i] = dma_alloc_coherent(NULL, 4096, &dma_adr,
+							GFP_KERNEL);
+		if (!dwc->scratchpad[i]) {
+			while (--i >= 0) {
+				dma_adr = (dma_addr_t)
+					dwc->scratchpad_array->dma_adr[i];
+				dma_free_coherent(NULL, 4096,
+					dwc->scratchpad[i], dma_adr);
+				dwc->scratchpad[i] = NULL;
+			}
+
+			goto err_free;
+		}
+
+		dwc->scratchpad_array->dma_adr[i] = cpu_to_le64(dma_adr);
+	}
+
+	return 0;
+
+err_free:
+	dma_free_coherent(NULL, sizeof(*dwc->scratchpad_array),
+			dwc->scratchpad_array, dwc->scratchpad_array_dma);
+	dwc->scratchpad_array = NULL;
+err:
+	return -ENOMEM;
+}
+
+void dwc3_free_scratchpad_buffers(struct dwc3 *dwc)
+{
+	dma_addr_t	dma_adr;
+	int		hiberbufs, i;
+
+	if (!dwc3_hiber_enabled(dwc))
+		return;
+
+	hiberbufs = DWC3_GHWPARAMS4_HIBER_SCRATCHBUFS(dwc->hwparams.hwparams4);
+	for (i = 0; i < hiberbufs; i++) {
+		if (dwc->scratchpad[i] != NULL) {
+			dma_adr = (dma_addr_t)
+				dwc->scratchpad_array->dma_adr[i];
+			dma_free_coherent(NULL, 4096, dwc->scratchpad[i],
+					dma_adr);
+			dwc->scratchpad[i] = NULL;
+		}
+	}
+
+	if (dwc->scratchpad_array) {
+		dma_free_coherent(NULL, sizeof(*dwc->scratchpad_array),
+			dwc->scratchpad_array, dwc->scratchpad_array_dma);
+		dwc->scratchpad_array = NULL;
+	}
+}
+
+static void dwc3_set_scratchpad_buf_array(struct dwc3 *dwc)
+{
+	unsigned	cmd;
+	u32		param;
+	int		ret;
+
+	cmd = DWC3_DGCMD_SET_SCRATCHPAD_ADDR_LO;
+	param = lower_32_bits(dwc->scratchpad_array_dma);
+	ret = dwc3_send_gadget_dev_cmd(dwc, cmd, param);
+	WARN_ON_ONCE(ret);
+
+	cmd = DWC3_DGCMD_SET_SCRATCHPAD_ADDR_HI;
+	param = upper_32_bits(dwc->scratchpad_array_dma);
+	ret = dwc3_send_gadget_dev_cmd(dwc, cmd, param);
+	WARN_ON_ONCE(ret);
+}
+
+static void dwc3_save_ep_state(struct dwc3 *dwc, struct dwc3_ep *dep)
+{
+	struct dwc3_gadget_ep_cmd_params	params;
+	u32					cmd;
+	int					ret;
+
+	memset(&params, 0, sizeof(params));
+	cmd = DWC3_DEPCMD_GETEPSTATE;
+	ret = dwc3_send_gadget_ep_cmd(dwc, dep->number, cmd, &params);
+	if (ret)
+		dev_err(dwc->dev, "failed to get EP state on %s\n", dep->name);
+	else
+		/* State is returned in DEPCMDPAR2 */
+		dep->saved_state = dwc3_readl(dwc->regs,
+					DWC3_DEPCMDPAR2(dep->number));
+}
+
+/*
+ * Read the D* registers (DCTL, DCFG, DEVTEN) and G* registers
+ * (GSBUSCFG0/1, GCTL, GTXTHRCFG, GRXTHRCFG, GTXFIFOSIZn,
+ * GRXFIFOSIZ0, GUSB3PIPECTL0, GUSB2PHYCFG0) and save their
+ * state. Any of these registers whose runtime state will be
+ * restored by the normal initialization sequence do not need
+ * to be saved.
+ */
+static void dwc3_save_reg_state(struct dwc3 *dwc)
+{
+	struct dwc3_ep	*dep;
+	u32		reg;
+	int		epnum;
+
+	dev_vdbg(dwc->dev, "%s()\n", __func__);
+
+	dwc->dcfg_save = dwc3_readl(dwc->regs, DWC3_DCFG);
+	dev_vdbg(dwc->dev, "DCFG=%08x\n", dwc->dcfg_save);
+	dwc->dctl_save = dwc3_readl(dwc->regs, DWC3_DCTL);
+	dwc->gctl_save = dwc3_readl(dwc->regs, DWC3_GCTL);
+
+	for (epnum = 0; epnum < DWC3_ENDPOINTS_NUM; epnum++) {
+		dep = dwc->eps[epnum];
+		if (!(epnum & 1))
+			continue;
+		if (!(dep->flags & DWC3_EP_ENABLED))
+			continue;
+		reg = dwc3_readl(dwc->regs, DWC3_GTXFIFOSIZ(epnum >> 1));
+		dwc->txfifosz_save[epnum] = reg;
+	}
+
+	dwc->rxfifosz_save = dwc3_readl(dwc->regs, DWC3_GRXFIFOSIZ(0));
+}
+
+static void dwc3_restart_xfer(struct dwc3 *dwc, struct dwc3_ep *dep)
+{
+	struct dwc3_gadget_ep_cmd_params	params;
+	struct dwc3_trb_hw			*trb;
+	dma_addr_t				trb_dma;
+	u32					ctrl, size, stat, cmd;
+	int					i, owned, ret;
+
+	dev_vdbg(dwc->dev, "%s()\n", __func__);
+	trb = dep->trb_pool;
+
+	/* Find the first non-hw-owned TRB */
+	for (i = 0; i < DWC3_TRB_NUM; i++, trb++) {
+		ctrl = le32_to_cpu(trb->ctrl);
+		size = le32_to_cpu(trb->size);
+		stat = (size >> 28) & 0xf;
+		if (!(ctrl & 1) && !(stat & DWC3_TRB_STS_XFER_IN_PROG)) {
+			dev_vdbg(dwc->dev, "Found non-hw-owned TRB at %d\n", i);
+			break;
+		}
+	}
+
+	if (i == DWC3_TRB_NUM)
+		trb = dep->trb_pool;
+
+	/* Find the first following hw-owned TRB */
+	for (i = 0, owned = -1; i < DWC3_TRB_NUM; i++) {
+		/*
+		 * If status == 4, this TRB's xfer was in progress prior to
+		 * entering hibernation
+		 */
+		ctrl = le32_to_cpu(trb->ctrl);
+		size = le32_to_cpu(trb->size);
+		stat = (size >> 28) & 0xf;
+		if (stat & DWC3_TRB_STS_XFER_IN_PROG) {
+			dev_vdbg(dwc->dev, "Found in-progress TRB at %d\n", i);
+
+			/* Set HWO back to 1 so the xfer can continue */
+			ctrl |= 1;
+			trb->ctrl = cpu_to_le32(ctrl);
+			owned = trb - dep->trb_pool;
+			break;
+		}
+
+		/* Save the index of the first TRB with the HWO bit set */
+		if (ctrl & 1) {
+			dev_vdbg(dwc->dev, "Found hw-owned TRB at %d\n", i);
+			owned = trb - dep->trb_pool;
+			break;
+		}
+
+		trb++;
+		if (trb == dep->trb_pool + DWC3_TRB_NUM)
+			trb = dep->trb_pool;
+	}
+
+	wmb();
+	dep->hiber_trb_idx = 0;
+
+	if (owned < 0)
+		/* No TRB had HWO bit set, fine */
+		return;
+
+	dev_vdbg(dwc->dev, "idx=%d trb=%p\n", owned, trb);
+
+	/* Restart of Isoc EPs is deferred until the host polls the EP */
+	if (usb_endpoint_type(dep->desc) == USB_ENDPOINT_XFER_ISOC) {
+		dev_vdbg(dwc->dev, "Deferring restart until host polls\n");
+		dep->hiber_trb_idx = owned + 1;
+		return;
+	}
+
+	dev_vdbg(dwc->dev, "%08x %08x %08x %08x\n",
+			*((unsigned *)trb), *((unsigned *)trb + 1),
+			*((unsigned *)trb + 2), *((unsigned *)trb + 3));
+
+	/* Now restart at the first TRB found with HWO set */
+	trb_dma = dep->trb_pool_dma + owned * 16;
+
+	memset(&params, 0, sizeof(params));
+	params.param0 = upper_32_bits(trb_dma);
+	params.param1 = lower_32_bits(trb_dma);
+
+	cmd = DWC3_DEPCMD_STARTTRANSFER;
+
+	ret = dwc3_send_gadget_ep_cmd(dwc, dep->number, cmd, &params);
+	if (ret < 0) {
+		dev_dbg(dwc->dev, "failed to send STARTTRANSFER command\n");
+		/*
+		 * FIXME what to do here?
+		 */
+		dep->res_trans_idx = 0;
+		dep->flags &= ~DWC3_EP_BUSY;
+		return;
+	}
+
+	dep->res_trans_idx = dwc3_gadget_ep_get_transfer_index(dwc,
+			dep->number);
+	WARN_ON_ONCE(!dep->res_trans_idx);
+}
+
+/*
+ * If the reset value of GSBUSCFG0/1 is not correct, write this
+ * register with the desired value.
+ *
+ * Issue a "Set Scratchpad Buffer Array" device generic command
+ * and wait for completion by polling the DGCMD.CmdAct bit.
+ *
+ * Write '1' to DCTL.CRS to start the restore process and wait
+ * for completion by polling the DSTS.RSS bit.
+ *
+ * Restore the remaining D* and G* registers.
+ */
+static void dwc3_restore_state(struct dwc3 *dwc)
+{
+	struct dwc3_ep	*dep;
+	u32		reg;
+	int		epnum;
+
+	dev_vdbg(dwc->dev, "%s()\n", __func__);
+
+	dwc3_set_scratchpad_buf_array(dwc);
+
+	reg = dwc3_readl(dwc->regs, DWC3_DSTS);
+	dev_vdbg(dwc->dev, "DSTS before=%1x\n", reg);
+	reg = dwc3_readl(dwc->regs, DWC3_DCTL);
+	dev_vdbg(dwc->dev, "DCTL before=%1x\n", reg);
+	reg |= DWC3_DCTL_CRS;
+	dwc3_writel(dwc->regs, DWC3_DCTL, reg);
+	reg = dwc3_readl(dwc->regs, DWC3_DCTL);
+	dev_vdbg(dwc->dev, "DCTL after=%1x\n", reg);
+
+	dev_vdbg(dwc->dev, "Set CRS bit, waiting for RSS bit clear\n");
+
+	do {
+		udelay(1);
+		reg = dwc3_readl(dwc->regs, DWC3_DSTS);
+	} while (reg & DWC3_DSTS_RSS);
+
+	dev_vdbg(dwc->dev, "DSTS after=%1x\n", reg);
+
+	dwc3_writel(dwc->regs, DWC3_GCTL, dwc->gctl_save);
+	dwc3_writel(dwc->regs, DWC3_DCFG, dwc->dcfg_save);
+	dev_vdbg(dwc->dev, "DCFG=%08x\n", dwc->dcfg_save);
+	reg = dwc3_readl(dwc->regs, DWC3_DCFG);
+	dev_vdbg(dwc->dev, "DCFG read back %08x\n", reg);
+	dwc3_writel(dwc->regs, DWC3_DCTL, dwc->dctl_save);
+
+	for (epnum = 0; epnum < DWC3_ENDPOINTS_NUM; epnum++) {
+		dep = dwc->eps[epnum];
+		if (!(epnum & 1))
+			continue;
+		if (!(dep->flags & DWC3_EP_ENABLED))
+			continue;
+		reg = dwc->txfifosz_save[epnum];
+		dwc3_writel(dwc->regs, DWC3_GTXFIFOSIZ(epnum >> 1), reg);
+	}
+
+	dwc3_writel(dwc->regs, DWC3_GRXFIFOSIZ(0), dwc->rxfifosz_save);
+}
+
+/*
+ * Configure the core as described in databook Section 9.1.1 "Device
+ * Power-On or Soft Reset," excluding the first step (Soft Reset).
+ */
+static void dwc3_reinit_ctlr(struct dwc3 *dwc, bool restore_state)
+{
+	struct dwc3_ep	*dep;
+	u32		reg;
+	int		ret;
+
+	dev_vdbg(dwc->dev, "%s()\n", __func__);
+
+	dwc3_event_buffers_setup(dwc);
+
+	reg = dwc3_readl(dwc->regs, DWC3_GUSB3PIPECTL(0));
+	reg |= DWC3_GUSB3PIPECTL_SUSPHY;
+	dwc3_writel(dwc->regs, DWC3_GUSB3PIPECTL(0), reg);
+
+	reg = dwc3_readl(dwc->regs, DWC3_GUSB2PHYCFG(0));
+	reg |= DWC3_GUSB2PHYCFG_SUSPHY;
+	dwc3_writel(dwc->regs, DWC3_GUSB2PHYCFG(0), reg);
+
+	/* Enable all but Start and End of Frame IRQs */
+	reg = DWC3_DEVTEN_VNDRDEVTSTRCVEDEN |
+		DWC3_DEVTEN_EVNTOVERFLOWEN |
+		DWC3_DEVTEN_CMDCMPLTEN |
+		DWC3_DEVTEN_ERRTICERREN |
+		DWC3_DEVTEN_HIBERNATIONREQEVTEN |
+		DWC3_DEVTEN_WKUPEVTEN |
+		DWC3_DEVTEN_ULSTCNGEN |
+		DWC3_DEVTEN_CONNECTDONEEN |
+		DWC3_DEVTEN_USBRSTEN |
+		DWC3_DEVTEN_DISCONNEVTEN;
+	dwc3_writel(dwc->regs, DWC3_DEVTEN, reg);
+
+	dep = dwc->eps[0];
+	dep->flags &= ~(DWC3_EP_ENABLED | DWC3_EP_BUSY);
+	dep->res_trans_idx = 0;
+	dep = dwc->eps[1];
+	dep->flags &= ~DWC3_EP_ENABLED;
+
+	ret = __dwc3_gadget_start(dwc, restore_state);
+	WARN_ON_ONCE(ret);
+
+	dwc3_gadget_run_stop(dwc, 1);
+}
+
+/*
+ * This function sends the core into hibernation, saving the core's runtime
+ * state if requested.
+ */
+void dwc3_enter_hibernation(struct dwc3 *dwc, bool save_state)
+{
+	struct dwc3_ep	*dep;
+	unsigned long	flags;
+	u32		reg;
+	int		epnum;
+
+	dev_vdbg(dwc->dev, "%s(%d)\n", __func__, save_state);
+
+	spin_lock_irqsave(&dwc->lock, flags);
+	dwc->hiber_wait_u0 = 0;
+
+	/*
+	 * Issue an "End Transfer" command for all active transfers, with the
+	 * ForceRM field set to 0, including the default control endpoint 0.
+	 */
+
+	for (epnum = 0; epnum < DWC3_ENDPOINTS_NUM; epnum++) {
+		dep = dwc->eps[epnum];
+		if (!(dep->flags & DWC3_EP_ENABLED) || !dep->res_trans_idx)
+			continue;
+		dev_vdbg(dwc->dev, "Stop xfer on phys EP%d\n", epnum);
+		dwc3_stop_active_transfer(dwc, epnum, false);
+	}
+
+	if (save_state) {
+		dev_vdbg(dwc->dev, "Saving EP state\n");
+
+		/*
+		 * Issue a "Get Endpoint State" endpoint command for each active
+		 * endpoint, and save the bits that are returned for use after
+		 * coming out of hibernation.
+		 *
+		 * In addition, software must remember if the endpoint is
+		 * currently in a Halted state. The endpoint is in a Halted
+		 * state if software has issued a "Set STALL" command and has
+		 * not issued a "Clear STALL" command.
+		 */
+
+		for (epnum = 0; epnum < DWC3_ENDPOINTS_NUM; epnum++) {
+			dep = dwc->eps[epnum];
+			if (!dep->flags & DWC3_EP_ENABLED)
+				continue;
+
+			dev_vdbg(dwc->dev, "Save state of phys EP%d\n", epnum);
+			dwc3_save_ep_state(dwc, dep);
+		}
+	}
+
+	/*
+	 * Set DCTL.RunStop to 0, DCTL.KeepConnect to 1 (or 0 if disconnected),
+	 * and wait for DSTS.Halted to be set to 1. Software must service any
+	 * events that are generated while it is waiting for Halted to be set
+	 * to 1.
+	 */
+
+	reg = dwc3_readl(dwc->regs, DWC3_DCTL);
+	reg &= ~DWC3_DCTL_RUN_STOP;
+	if (!save_state)
+		reg &= ~DWC3_DCTL_KEEP_CONNECT;
+	dwc3_writel(dwc->regs, DWC3_DCTL, reg);
+
+	/* We must be able to handle event interrupts while waiting */
+	spin_unlock_irqrestore(&dwc->lock, flags);
+
+	dev_vdbg(dwc->dev, "Cleared Run/Stop bit, waiting for Halted bit\n");
+
+	do {
+		udelay(1);
+		reg = dwc3_readl(dwc->regs, DWC3_DSTS);
+	} while (!(reg & DWC3_DSTS_DEVCTRLHLT));
+
+	spin_lock_irqsave(&dwc->lock, flags);
+	dwc->hibernate = DWC3_HIBER_SLEEPING;
+
+	if (save_state) {
+		dwc3_save_reg_state(dwc);
+
+		dwc3_set_scratchpad_buf_array(dwc);
+
+		/*
+		 * Set the DCTL.CSS bit and wait for the save state process to
+		 * complete by polling for DSTS.SSS to equal 0.
+		 */
+
+		reg = dwc3_readl(dwc->regs, DWC3_DCTL);
+		reg |= DWC3_DCTL_CSS;
+		dwc3_writel(dwc->regs, DWC3_DCTL, reg);
+
+		spin_unlock_irqrestore(&dwc->lock, flags);
+		dev_vdbg(dwc->dev, "Set CSS bit, waiting for SSS bit clear\n");
+
+		do {
+			udelay(1);
+			reg = dwc3_readl(dwc->regs, DWC3_DSTS);
+		} while (reg & DWC3_DSTS_SSS);
+
+		dev_vdbg(dwc->dev, "DSTS after=%08x\n", reg);
+		spin_lock_irqsave(&dwc->lock, flags);
+	}
+
+	/* Set the power state to D3 */
+
+	if (dwc3_power_ctl)
+		dwc3_power_ctl(dwc, 0);
+	dwc->pme_ready = 1;
+
+	spin_unlock_irqrestore(&dwc->lock, flags);
+
+	dev_info(dwc->dev, "In D3\n");
+}
+
+/*
+ * This function finishes exiting from hibernation once the device is connected.
+ */
+void dwc3_exit_hibernation_after_connect(struct dwc3 *dwc, bool connected)
+{
+	struct dwc3_gadget_ep_cmd_params	params;
+	struct dwc3_ep				*dep;
+	u32					reg;
+	int					epnum, ret;
+
+	dev_vdbg(dwc->dev, "%s(%d)\n", __func__, connected);
+
+	if (!dwc3_hiber_enabled(dwc))
+		return;
+
+	if (dwc->hiber_wait_connect)
+		dwc->hiber_wait_connect = 0;
+
+	/*
+	 * Perform the steps in Section 9.1.5 "Initialization on
+	 * SetConfiguration or SetInterface Command" in databook.
+	 *
+	 * While issuing the DEPCFG commands, set each endpoint's sequence
+	 * number and flow control state to the value read during the save.
+	 *
+	 * If the endpoint was in the Halted state prior to entering
+	 * hibernation, software must issue the "Set STALL" endpoint command
+	 * to put the endpoint back into the Halted state.
+	 */
+
+	memset(&params, 0, sizeof(params));
+
+	for (epnum = 2; epnum < DWC3_ENDPOINTS_NUM; epnum++) {
+		dep = dwc->eps[epnum];
+		if (!(dep->flags & DWC3_EP_ENABLED))
+			continue;
+		if (!dep->desc)
+			continue;
+		dev_vdbg(dwc->dev, "Enabling phys EP%d\n", epnum);
+
+		dep->flags &= ~DWC3_EP_ENABLED;
+		ret = __dwc3_gadget_ep_enable(dep, dep->desc, dep->comp_desc,
+						true);
+		if (ret)
+			dev_err(dwc->dev, "failed to enable %s\n", dep->name);
+
+		if (dep->flags & DWC3_EP_STALL) {
+			ret = dwc3_send_gadget_ep_cmd(dwc, epnum,
+						DWC3_DEPCMD_SETSTALL, &params);
+			if (ret)
+				dev_err(dwc->dev, "failed to set STALL on %s\n",
+						dep->name);
+		}
+	}
+
+	/*
+	 * (In this step, software re-configures the existing endpoints and
+	 * starts their transfers).
+	 *
+	 * When software issued the EndXfer command with the ForceRM field set
+	 * to '0' prior to entering hibernation, the core may have written back
+	 * an active TRB for the transfer, setting the HWO bit to '0'. Software
+	 * must ensure that the TRB is valid and set the HWO bit back to '1'
+	 * prior to re-starting the transfer in this step.
+	 */
+	for (epnum = 1; epnum < DWC3_ENDPOINTS_NUM; epnum++) {
+		dep = dwc->eps[epnum];
+		if (!(dep->flags & DWC3_EP_ENABLED))
+			continue;
+		if (!(dep->flags & DWC3_EP_BUSY) || !dep->res_trans_idx)
+			continue;
+		dwc3_restart_xfer(dwc, dep);
+	}
+
+	/*
+	 * If the core is already connected to the host (DSTS.USBLnkSt == 0, 2,
+	 * 3, 14, or 15), set DCTL.ULStChngReq to '8' as described in Table 7-47
+	 * of databook.
+	 *
+	 * If the host initiated resume, this step completes the transition to
+	 * U0. If the host did not initiate resume, this step causes the device
+	 * to initiate resume (remote wakeup).
+	 */
+
+	if (connected) {
+		dev_vdbg(dwc->dev,
+			"Already connected, requesting link state Recovery\n");
+		dwc3_gadget_set_link_state(dwc, DWC3_LINK_STATE_RECOV);
+		dwc->hiber_wait_u0 = 1;
+		reg = dwc3_gadget_get_link_state(dwc);
+		dev_vdbg(dwc->dev, "Link state %d\n", reg);
+	} else {
+		dwc->hiber_wait_u0 = 0;
+	}
+}
+
+/*
+ * This function wakes the core from hibernation.
+ */
+static int dwc3_exit_hibernation(struct dwc3 *dwc, bool restore_state)
+{
+	int		state;
+
+	dev_vdbg(dwc->dev, "%s(%d)\n", __func__, restore_state);
+
+	if (!dwc3_hiber_enabled(dwc))
+		return 0;
+
+	/* Set the power state to D0 */
+	dwc->pme_ready = 0;
+	if (dwc3_power_ctl)
+		dwc3_power_ctl(dwc, 1);
+
+	dev_info(dwc->dev, "In D0\n");
+	dwc->hibernate = DWC3_HIBER_AWAKE;
+
+	if (restore_state)
+		dwc3_restore_state(dwc);
+
+	dwc3_reinit_ctlr(dwc, restore_state);
+
+	/* Read the DSTS register to see the current link state. */
+	state = dwc3_gadget_get_link_state(dwc);
+
+	/*
+	 * If the core is not connected to the host, wait for a Connect Done
+	 * event.
+	 */
+	dwc->hiber_wait_connect = 0;
+	if (state > DWC3_LINK_STATE_U3 && state != DWC3_LINK_STATE_RX_DET &&
+			state != DWC3_LINK_STATE_RESUME) {
+		if (state != DWC3_LINK_STATE_RESET) {
+			dwc->hiber_wait_connect = 1;
+
+			if (state == DWC3_LINK_STATE_SS_DIS &&
+					dwc->speed != USB_SPEED_SUPER) {
+				dwc->hibernate = DWC3_HIBER_SS_DIS_QUIRK;
+				return DWC3_HIBER_SS_DIS_QUIRK;
+			}
+
+			dev_vdbg(dwc->dev, "Link state %d, waiting for connect"
+				" before exiting from hibernation\n", state);
+		}
+
+		/*
+		 * If the DSTS.USBLnkSt equals 14, it means a USB reset was
+		 * received while the core was entering or exiting hibernation.
+		 * Prior to performing the steps in sections 9.1.2 and 9.1.3,
+		 * software must write Resume (8) into the DCTL.ULStChngReq
+		 * field.
+		 */
+		if (state == DWC3_LINK_STATE_RESET) {
+			dev_vdbg(dwc->dev,
+				"USB Reset received during hibernation,"
+				" requesting link state Recovery\n");
+			dwc3_gadget_set_link_state(dwc, DWC3_LINK_STATE_RECOV);
+			dwc->hibernate = DWC3_HIBER_WAIT_LINK_UP;
+			return DWC3_HIBER_WAIT_LINK_UP;
+		}
+	} else {
+		dev_vdbg(dwc->dev, "Link state %d, exiting from hibernation\n",
+				state);
+		dev_vdbg(dwc->dev, "Exiting from hibernation\n");
+
+		/*
+		 * Perform the steps in Section 9.1.3 "Initialization on
+		 * Connect Done" in databook.
+		 */
+		dwc3_gadget_conndone_interrupt(dwc);
+		dwc3_exit_hibernation_after_connect(dwc, 1);
+	}
+
+	return 0;
+}
+
+static void dwc3_wait_for_link_up(struct dwc3 *dwc)
+{
+	unsigned long	flags;
+	u32		state;
+	int		count = 10;
+
+	while (--count >= 0) {
+		msleep(10);
+		spin_lock_irqsave(&dwc->lock, flags);
+		state = dwc3_gadget_get_link_state(dwc);
+		if (state == 0) {
+			dev_vdbg(dwc->dev, "Exiting from hibernation 2\n");
+			dwc->hiber_wait_connect = 0;
+
+			/*
+			 * Perform the steps in Section 9.1.3 "Initialization on
+			 * Connect Done" in databook.
+			 */
+			dwc3_gadget_conndone_interrupt(dwc);
+			dwc3_exit_hibernation_after_connect(dwc, 0);
+			count = 0;
+		}
+
+		spin_unlock_irqrestore(&dwc->lock, flags);
+	}
+}
+
+/*
+ * Kernel thread that monitors the dev->hibernate and dev->usage_cnt variables,
+ * and starts hibernation entry when required. dev->hibernate is set to 1 or 2
+ * from the interrupt handler when the core is requesting to enter hibernation.
+ * This thread checks whether it is safe to do so (dev->usage_cnt == 0) and then
+ * sets dev->hibernate to 3 and puts the core into hibernation. dev->hibernate
+ * >= 3 tells the rest of the driver that it cannot access the hardware.
+ *
+ * After the core exits hibernation, this thread also handles a couple of
+ * special cases; waiting for the link to come back up if it was reset during
+ * hibernation, and putting the core back into hibernation if it should wake
+ * up while the link is disconnected.
+ *
+ * Note that this is probably NOT the way a "real" device would handle
+ * hibernation entry. This code is only for testing hibernation on the Synopsys
+ * HAPS platform.
+ */
+int dwc3_hiber_thread(void *data)
+{
+	struct dwc3	*dwc = (struct dwc3 *)data;
+	unsigned long	flags;
+	u32		state;
+	int		i;
+
+	dev_vdbg(dwc->dev, "%s(%p)\n", __func__, data);
+
+	/*
+	 * Allow the thread to be killed by a signal, but set the signal mask
+	 * to block everything but INT, TERM, KILL, and USR1
+	 */
+	allow_signal(SIGINT);
+	allow_signal(SIGTERM);
+	allow_signal(SIGKILL);
+	allow_signal(SIGUSR1);
+
+	/* Some hibernation actions are very latency sensitive */
+	set_user_nice(current, -10);
+
+	/* Allow the thread to be frozen */
+	set_freezable();
+
+	for (;;) {
+		spin_lock_irqsave(&dwc->lock, flags);
+		state = dwc->hibernate;
+
+		if (dwc->usage_cnt == 0) {
+			if (state == DWC3_HIBER_ENTER_NOSAVE ||
+					state == DWC3_HIBER_ENTER_SAVE) {
+				spin_unlock_irqrestore(&dwc->lock, flags);
+				dwc3_enter_hibernation(dwc,
+						state == DWC3_HIBER_ENTER_SAVE);
+				goto loop;
+			}
+		}
+
+		if (state == DWC3_HIBER_WAIT_LINK_UP) {
+			dwc->hibernate = DWC3_HIBER_AWAKE;
+			spin_unlock_irqrestore(&dwc->lock, flags);
+			dwc3_wait_for_link_up(dwc);
+			goto loop;
+		}
+
+		if (state != DWC3_HIBER_SS_DIS_QUIRK)
+			goto locked_loop;
+
+		for (i = 0; i < 500; i++) {
+			if (dwc->hibernate != DWC3_HIBER_SS_DIS_QUIRK) {
+				dev_info(dwc->dev,
+					"breaking loop after %d ms\n", i);
+				goto locked_loop;
+			}
+
+			spin_unlock_irqrestore(&dwc->lock, flags);
+			msleep(1);
+			spin_lock_irqsave(&dwc->lock, flags);
+		}
+
+		if (dwc->hibernate == DWC3_HIBER_SS_DIS_QUIRK) {
+			if (dwc3_gadget_get_link_state(dwc) ==
+						DWC3_LINK_STATE_SS_DIS) {
+				spin_unlock_irqrestore(&dwc->lock, flags);
+				dwc3_enter_hibernation(dwc, 0);
+				goto loop;
+			} else {
+				dwc->hibernate = DWC3_HIBER_AWAKE;
+				goto locked_loop;
+			}
+
+			goto loop;
+		}
+locked_loop:
+		spin_unlock_irqrestore(&dwc->lock, flags);
+loop:
+		if (kthread_should_stop())
+			break;
+
+		msleep(1);
+	}
+
+	return 0;
+}
+
+/*
+ * If IRQ_NONE is returned the caller should try to handle the interrupt,
+ * and acknowledge it in the hardware.
+ * If IRQ_HANDLED is returned the caller should exit immediately without
+ * touching the hardware.
+ */
+irqreturn_t dwc3_hiber_interrupt_hook(struct dwc3 *dwc)
+{
+	int	state, ret;
+
+	state = dwc->hibernate;
+	if (state < DWC3_HIBER_SLEEPING)
+		return IRQ_NONE;
+
+	if (state == DWC3_HIBER_SS_DIS_QUIRK) {
+		dwc->hibernate = DWC3_HIBER_AWAKE;
+		return IRQ_NONE;
+	}
+
+	if (!dwc->pme_ready) {
+		if (state != DWC3_HIBER_WAIT_LINK_UP)
+			dev_info(dwc->dev,
+				"Intr in hibernate but pme_ready not set\n");
+		return IRQ_HANDLED;
+	}
+
+	/*
+	 * This call is required for the HAPS platform, due to the non-standard
+	 * way that the PME interrupt is implemented. On a normal platform this
+	 * function should be a no-op.
+	 */
+	if (!dwc3_pme_interrupt)
+		return IRQ_HANDLED;
+	ret = dwc3_pme_interrupt(dwc);
+
+	if (ret < 0)
+		return IRQ_HANDLED;
+
+	ret = dwc3_exit_hibernation(dwc, ret);
+	if (ret)
+		dev_vdbg(dwc->dev, "dwc3_exit_hibernation() returned %d\n",
+				ret);
+	return IRQ_HANDLED;
+}
+
+void dwc3_hiber_remote_wake(struct dwc3 *dwc)
+{
+	if (dwc3_hiber_enabled(dwc) && dwc->hiber_wait_u0) {
+		if (dwc3_gadget_get_link_state(dwc) == DWC3_LINK_STATE_U0) {
+			/* TODO: Handle remote wakeup */
+			dwc->hiber_wait_u0 = 0;
+		}
+	}
+}
+
+int dwc3_hibernation_init(struct dwc3 *dwc)
+{
+	if (!dwc3_hiber_enabled(dwc))
+		return 0;
+
+	dwc->hiber_thread = kthread_run(dwc3_hiber_thread, dwc, "hibthr");
+	return 0;
+}
+
+void dwc3_hibernation_exit(struct dwc3 *dwc)
+{
+	if (!dwc3_hiber_enabled(dwc))
+		return;
+
+	if (dwc->hiber_thread) {
+		kthread_stop(dwc->hiber_thread);
+		dwc->hiber_thread = NULL;
+	}
+}
-- 
1.7.4.4

--
To unsubscribe from this list: send the line "unsubscribe linux-usb" in
the body of a message to majordomo@xxxxxxxxxxxxxxx
More majordomo info at  http://vger.kernel.org/majordomo-info.html


[Index of Archives]     [Linux Media]     [Linux Input]     [Linux Audio Users]     [Yosemite News]     [Linux Kernel]     [Linux SCSI]     [Old Linux USB Devel Archive]

  Powered by Linux