linux-arm-msm.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH V3 00/11] Add MSM USB controller driver
@ 2010-12-07 12:23 Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 01/11] USB: Add MSM OTG Controller driver Pavankumar Kondeti
                   ` (11 more replies)
  0 siblings, 12 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:23 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

This patch series adds USB peripheral, host and OTG (role switch based
on Id pin status) support for MSM SoC. The peripheral controller driver patches
include splitting ci13xxx_udc into core and bus glue layers. Peripheral
and Host controller drivers depend on Transceiver driver for clock management
and low power mode. Peripheral and Host devices are made children of OTG
device when devices are registered. Runtime PM functions are used by
Peripheral and Host controller drivers to tell their state to transceiver
driver which actually takes care of putting hardware into low power mode.

Change from V2:
1. Added core_clock in transceiver driver. This clock is introduced from MSM7x30
onwards to remove dependency on AXI bus frequency.
2. Use debugfs instead of sysfs for role switching option.
3. pm_runtime_nocallbacks() is used instead for nop runtime PM methods.
4. Peripheral controller driver makes use of ci13xxx_udc core.

Pavankumar Kondeti (11):
  USB: Add MSM OTG Controller driver
  USB: EHCI: Add MSM Host Controller driver
  USB: EHCI: msm: Add support for power management
  USB: OTG: msm: Add support for power management
  USB: gadget: Separate out PCI bus code from ci13xxx_udc
  USB: gadget: Fix "scheduling while atomic" bugs in ci13xxx_udc
  USB: gadget: Initialize ci13xxx gadget device's coherent DMA mask
  USB: gadget: Introduce ci13xxx_udc_driver struct
  USB: gadget: Add USB controller driver for MSM SoC
  USB: gadget: Implement runtime PM for ci13xxx gadget
  USB: gadget: Implement runtime PM for MSM bus glue driver

 drivers/usb/Kconfig               |    1 +
 drivers/usb/gadget/Kconfig        |   29 +-
 drivers/usb/gadget/Makefile       |    3 +-
 drivers/usb/gadget/ci13xxx_msm.c  |  134 +++++
 drivers/usb/gadget/ci13xxx_pci.c  |  176 ++++++
 drivers/usb/gadget/ci13xxx_udc.c  |  384 ++++++-------
 drivers/usb/gadget/ci13xxx_udc.h  |   19 +
 drivers/usb/gadget/gadget_chips.h |   16 +-
 drivers/usb/host/Kconfig          |   11 +
 drivers/usb/host/ehci-hcd.c       |    5 +
 drivers/usb/host/ehci-msm.c       |  345 ++++++++++++
 drivers/usb/otg/Kconfig           |   11 +
 drivers/usb/otg/Makefile          |    1 +
 drivers/usb/otg/msm72k_otg.c      | 1125 +++++++++++++++++++++++++++++++++++++
 include/linux/usb/msm_hsusb.h     |  112 ++++
 include/linux/usb/msm_hsusb_hw.h  |   59 ++
 16 files changed, 2203 insertions(+), 228 deletions(-)
 create mode 100644 drivers/usb/gadget/ci13xxx_msm.c
 create mode 100644 drivers/usb/gadget/ci13xxx_pci.c
 create mode 100644 drivers/usb/host/ehci-msm.c
 create mode 100644 drivers/usb/otg/msm72k_otg.c
 create mode 100644 include/linux/usb/msm_hsusb.h
 create mode 100644 include/linux/usb/msm_hsusb_hw.h


^ permalink raw reply	[flat|nested] 13+ messages in thread

* [PATCH V3 01/11] USB: Add MSM OTG Controller driver
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
@ 2010-12-07 12:23 ` Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 02/11] USB: EHCI: Add MSM Host " Pavankumar Kondeti
                   ` (10 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:23 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

This driver implements PHY initialization, clock management, ULPI IO ops
and simple OTG state machine to kick host/peripheral based on Id/VBUS
line status.  VBUS/Id lines are tied to a reference voltage on some boards.
Hence provide debugfs interface to select host/peripheral mode.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/otg/Kconfig          |   10 +
 drivers/usb/otg/Makefile         |    1 +
 drivers/usb/otg/msm72k_otg.c     |  850 ++++++++++++++++++++++++++++++++++++++
 include/linux/usb/msm_hsusb.h    |  108 +++++
 include/linux/usb/msm_hsusb_hw.h |   56 +++
 5 files changed, 1025 insertions(+), 0 deletions(-)
 create mode 100644 drivers/usb/otg/msm72k_otg.c
 create mode 100644 include/linux/usb/msm_hsusb.h
 create mode 100644 include/linux/usb/msm_hsusb_hw.h

diff --git a/drivers/usb/otg/Kconfig b/drivers/usb/otg/Kconfig
index 5ce0752..915c729 100644
--- a/drivers/usb/otg/Kconfig
+++ b/drivers/usb/otg/Kconfig
@@ -81,4 +81,14 @@ config USB_LANGWELL_OTG
 	  To compile this driver as a module, choose M here: the
 	  module will be called langwell_otg.
 
+config USB_MSM_OTG_72K
+	tristate "OTG support for Qualcomm on-chip USB controller"
+	depends on (USB || USB_GADGET) && ARCH_MSM
+	select USB_OTG_UTILS
+	help
+	  Enable this to support the USB OTG transceiver on MSM chips. It
+	  handles PHY initialization, clock management, and workarounds
+	  required after resetting the hardware. This driver is required
+	  even for peripheral only or host only mode configuration.
+
 endif # USB || OTG
diff --git a/drivers/usb/otg/Makefile b/drivers/usb/otg/Makefile
index 66f1b83..3b1b096 100644
--- a/drivers/usb/otg/Makefile
+++ b/drivers/usb/otg/Makefile
@@ -15,3 +15,4 @@ obj-$(CONFIG_TWL4030_USB)	+= twl4030-usb.o
 obj-$(CONFIG_USB_LANGWELL_OTG)	+= langwell_otg.o
 obj-$(CONFIG_NOP_USB_XCEIV)	+= nop-usb-xceiv.o
 obj-$(CONFIG_USB_ULPI)		+= ulpi.o
+obj-$(CONFIG_USB_MSM_OTG_72K)	+= msm72k_otg.o
diff --git a/drivers/usb/otg/msm72k_otg.c b/drivers/usb/otg/msm72k_otg.c
new file mode 100644
index 0000000..46f468a
--- /dev/null
+++ b/drivers/usb/otg/msm72k_otg.c
@@ -0,0 +1,850 @@
+/* Copyright (c) 2009-2010, Code Aurora Forum. 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 version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * 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.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA
+ * 02110-1301, USA.
+ *
+ */
+
+#include <linux/module.h>
+#include <linux/device.h>
+#include <linux/platform_device.h>
+#include <linux/clk.h>
+#include <linux/slab.h>
+#include <linux/interrupt.h>
+#include <linux/err.h>
+#include <linux/delay.h>
+#include <linux/io.h>
+#include <linux/ioport.h>
+#include <linux/uaccess.h>
+#include <linux/debugfs.h>
+#include <linux/seq_file.h>
+
+#include <linux/usb.h>
+#include <linux/usb/otg.h>
+#include <linux/usb/ulpi.h>
+#include <linux/usb/gadget.h>
+#include <linux/usb/hcd.h>
+#include <linux/usb/msm_hsusb.h>
+#include <linux/usb/msm_hsusb_hw.h>
+
+#include <mach/clk.h>
+
+#define MSM_USB_BASE	(motg->regs)
+#define DRIVER_NAME	"msm_otg"
+
+#define ULPI_IO_TIMEOUT_USEC	(10 * 1000)
+static int ulpi_read(struct otg_transceiver *otg, u32 reg)
+{
+	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
+	int cnt = 0;
+
+	/* initiate read operation */
+	writel(ULPI_RUN | ULPI_READ | ULPI_ADDR(reg),
+	       USB_ULPI_VIEWPORT);
+
+	/* wait for completion */
+	while (cnt < ULPI_IO_TIMEOUT_USEC) {
+		if (!(readl(USB_ULPI_VIEWPORT) & ULPI_RUN))
+			break;
+		udelay(1);
+		cnt++;
+	}
+
+	if (cnt >= ULPI_IO_TIMEOUT_USEC) {
+		dev_err(otg->dev, "ulpi_read: timeout %08x\n",
+			readl(USB_ULPI_VIEWPORT));
+		return -ETIMEDOUT;
+	}
+	return ULPI_DATA_READ(readl(USB_ULPI_VIEWPORT));
+}
+
+static int ulpi_write(struct otg_transceiver *otg, u32 val, u32 reg)
+{
+	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
+	int cnt = 0;
+
+	/* initiate write operation */
+	writel(ULPI_RUN | ULPI_WRITE |
+	       ULPI_ADDR(reg) | ULPI_DATA(val),
+	       USB_ULPI_VIEWPORT);
+
+	/* wait for completion */
+	while (cnt < ULPI_IO_TIMEOUT_USEC) {
+		if (!(readl(USB_ULPI_VIEWPORT) & ULPI_RUN))
+			break;
+		udelay(1);
+		cnt++;
+	}
+
+	if (cnt >= ULPI_IO_TIMEOUT_USEC) {
+		dev_err(otg->dev, "ulpi_write: timeout\n");
+		return -ETIMEDOUT;
+	}
+	return 0;
+}
+
+static struct otg_io_access_ops msm_otg_io_ops = {
+	.read = ulpi_read,
+	.write = ulpi_write,
+};
+
+static void ulpi_init(struct msm_otg *motg)
+{
+	struct msm_otg_platform_data *pdata = motg->pdata;
+	int *seq = pdata->phy_init_seq;
+
+	if (!seq)
+		return;
+
+	while (seq[0] >= 0) {
+		dev_vdbg(motg->otg.dev, "ulpi: write 0x%02x to 0x%02x\n",
+				seq[0], seq[1]);
+		ulpi_write(&motg->otg, seq[0], seq[1]);
+		seq += 2;
+	}
+}
+
+static int msm_otg_link_clk_reset(struct msm_otg *motg, bool assert)
+{
+	int ret;
+
+	if (assert) {
+		ret = clk_reset(motg->clk, CLK_RESET_ASSERT);
+		if (ret)
+			dev_err(motg->otg.dev, "usb hs_clk assert failed\n");
+	} else {
+		ret = clk_reset(motg->clk, CLK_RESET_DEASSERT);
+		if (ret)
+			dev_err(motg->otg.dev, "usb hs_clk deassert failed\n");
+	}
+	return ret;
+}
+
+static int msm_otg_phy_clk_reset(struct msm_otg *motg)
+{
+	int ret;
+
+	ret = clk_reset(motg->phy_reset_clk, CLK_RESET_ASSERT);
+	if (ret) {
+		dev_err(motg->otg.dev, "usb phy clk assert failed\n");
+		return ret;
+	}
+	usleep_range(10000, 12000);
+	ret = clk_reset(motg->phy_reset_clk, CLK_RESET_DEASSERT);
+	if (ret)
+		dev_err(motg->otg.dev, "usb phy clk deassert failed\n");
+	return ret;
+}
+
+static int msm_otg_phy_reset(struct msm_otg *motg)
+{
+	u32 val;
+	int ret;
+	int retries;
+
+	ret = msm_otg_link_clk_reset(motg, 1);
+	if (ret)
+		return ret;
+	ret = msm_otg_phy_clk_reset(motg);
+	if (ret)
+		return ret;
+	ret = msm_otg_link_clk_reset(motg, 0);
+	if (ret)
+		return ret;
+
+	val = readl(USB_PORTSC) & ~PORTSC_PTS_MASK;
+	writel(val | PORTSC_PTS_ULPI, USB_PORTSC);
+
+	for (retries = 3; retries > 0; retries--) {
+		ret = ulpi_write(&motg->otg, ULPI_FUNC_CTRL_SUSPENDM,
+				ULPI_CLR(ULPI_FUNC_CTRL));
+		if (!ret)
+			break;
+		ret = msm_otg_phy_clk_reset(motg);
+		if (ret)
+			return ret;
+	}
+	if (!retries)
+		return -ETIMEDOUT;
+
+	/* This reset calibrates the phy, if the above write succeeded */
+	ret = msm_otg_phy_clk_reset(motg);
+	if (ret)
+		return ret;
+
+	for (retries = 3; retries > 0; retries--) {
+		ret = ulpi_read(&motg->otg, ULPI_DEBUG);
+		if (ret != -ETIMEDOUT)
+			break;
+		ret = msm_otg_phy_clk_reset(motg);
+		if (ret)
+			return ret;
+	}
+	if (!retries)
+		return -ETIMEDOUT;
+
+	dev_info(motg->otg.dev, "phy_reset: success\n");
+	return 0;
+}
+
+#define LINK_RESET_TIMEOUT_USEC		(250 * 1000)
+static int msm_otg_reset(struct otg_transceiver *otg)
+{
+	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
+	struct msm_otg_platform_data *pdata = motg->pdata;
+	int cnt = 0;
+	int ret;
+	u32 val = 0;
+	u32 ulpi_val = 0;
+
+	ret = msm_otg_phy_reset(motg);
+	if (ret) {
+		dev_err(otg->dev, "phy_reset failed\n");
+		return ret;
+	}
+
+	ulpi_init(motg);
+
+	writel(USBCMD_RESET, USB_USBCMD);
+	while (cnt < LINK_RESET_TIMEOUT_USEC) {
+		if (!(readl(USB_USBCMD) & USBCMD_RESET))
+			break;
+		udelay(1);
+		cnt++;
+	}
+	if (cnt >= LINK_RESET_TIMEOUT_USEC)
+		return -ETIMEDOUT;
+
+	/* select ULPI phy */
+	writel(0x80000000, USB_PORTSC);
+
+	msleep(100);
+
+	writel(0x0, USB_AHBBURST);
+	writel(0x00, USB_AHBMODE);
+
+	if (pdata->otg_control == OTG_PHY_CONTROL) {
+		val = readl(USB_OTGSC);
+		if (pdata->mode == USB_OTG) {
+			ulpi_val = ULPI_INT_IDGRD | ULPI_INT_SESS_VALID;
+			val |= OTGSC_IDIE | OTGSC_BSVIE;
+		} else if (pdata->mode == USB_PERIPHERAL) {
+			ulpi_val = ULPI_INT_SESS_VALID;
+			val |= OTGSC_BSVIE;
+		}
+		writel(val, USB_OTGSC);
+		ulpi_write(otg, ulpi_val, ULPI_USB_INT_EN_RISE);
+		ulpi_write(otg, ulpi_val, ULPI_USB_INT_EN_FALL);
+	}
+
+	return 0;
+}
+
+static void msm_otg_start_host(struct otg_transceiver *otg, int on)
+{
+	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
+	struct msm_otg_platform_data *pdata = motg->pdata;
+	struct usb_hcd *hcd;
+
+	if (!otg->host)
+		return;
+
+	hcd = bus_to_hcd(otg->host);
+
+	if (on) {
+		dev_dbg(otg->dev, "host on\n");
+
+		if (pdata->vbus_power)
+			pdata->vbus_power(1);
+		/*
+		 * Some boards have a switch cotrolled by gpio
+		 * to enable/disable internal HUB. Enable internal
+		 * HUB before kicking the host.
+		 */
+		if (pdata->setup_gpio)
+			pdata->setup_gpio(OTG_STATE_A_HOST);
+#ifdef CONFIG_USB
+		usb_add_hcd(hcd, hcd->irq, IRQF_SHARED);
+#endif
+	} else {
+		dev_dbg(otg->dev, "host off\n");
+
+#ifdef CONFIG_USB
+		usb_remove_hcd(hcd);
+#endif
+		if (pdata->setup_gpio)
+			pdata->setup_gpio(OTG_STATE_UNDEFINED);
+		if (pdata->vbus_power)
+			pdata->vbus_power(0);
+	}
+}
+
+static int msm_otg_set_host(struct otg_transceiver *otg, struct usb_bus *host)
+{
+	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
+	struct usb_hcd *hcd;
+
+	/*
+	 * Fail host registration if this board can support
+	 * only peripheral configuration.
+	 */
+	if (motg->pdata->mode == USB_PERIPHERAL) {
+		dev_info(otg->dev, "Host mode is not supported\n");
+		return -ENODEV;
+	}
+
+	if (!host) {
+		if (otg->state == OTG_STATE_A_HOST) {
+			msm_otg_start_host(otg, 0);
+			otg->host = NULL;
+			otg->state = OTG_STATE_UNDEFINED;
+			schedule_work(&motg->sm_work);
+		} else {
+			otg->host = NULL;
+		}
+
+		return 0;
+	}
+
+	hcd = bus_to_hcd(host);
+	hcd->power_budget = motg->pdata->power_budget;
+
+	otg->host = host;
+	dev_dbg(otg->dev, "host driver registered w/ tranceiver\n");
+
+	/*
+	 * Kick the state machine work, if peripheral is not supported
+	 * or peripheral is already registered with us.
+	 */
+	if (motg->pdata->mode == USB_HOST || otg->gadget)
+		schedule_work(&motg->sm_work);
+
+	return 0;
+}
+
+static void msm_otg_start_peripheral(struct otg_transceiver *otg, int on)
+{
+	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
+	struct msm_otg_platform_data *pdata = motg->pdata;
+
+	if (!otg->gadget)
+		return;
+
+	if (on) {
+		dev_dbg(otg->dev, "gadget on\n");
+		/*
+		 * Some boards have a switch cotrolled by gpio
+		 * to enable/disable internal HUB. Disable internal
+		 * HUB before kicking the gadget.
+		 */
+		if (pdata->setup_gpio)
+			pdata->setup_gpio(OTG_STATE_B_PERIPHERAL);
+		usb_gadget_vbus_connect(otg->gadget);
+	} else {
+		dev_dbg(otg->dev, "gadget off\n");
+		usb_gadget_vbus_disconnect(otg->gadget);
+		if (pdata->setup_gpio)
+			pdata->setup_gpio(OTG_STATE_UNDEFINED);
+	}
+
+}
+
+static int msm_otg_set_peripheral(struct otg_transceiver *otg,
+			struct usb_gadget *gadget)
+{
+	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
+
+	/*
+	 * Fail peripheral registration if this board can support
+	 * only host configuration.
+	 */
+	if (motg->pdata->mode == USB_HOST) {
+		dev_info(otg->dev, "Peripheral mode is not supported\n");
+		return -ENODEV;
+	}
+
+	if (!gadget) {
+		if (otg->state == OTG_STATE_B_PERIPHERAL) {
+			msm_otg_start_peripheral(otg, 0);
+			otg->gadget = NULL;
+			otg->state = OTG_STATE_UNDEFINED;
+			schedule_work(&motg->sm_work);
+		} else {
+			otg->gadget = NULL;
+		}
+
+		return 0;
+	}
+	otg->gadget = gadget;
+	dev_dbg(otg->dev, "peripheral driver registered w/ tranceiver\n");
+
+	/*
+	 * Kick the state machine work, if host is not supported
+	 * or host is already registered with us.
+	 */
+	if (motg->pdata->mode == USB_PERIPHERAL || otg->host)
+		schedule_work(&motg->sm_work);
+
+	return 0;
+}
+
+/*
+ * We support OTG, Peripheral only and Host only configurations. In case
+ * of OTG, mode switch (host-->peripheral/peripheral-->host) can happen
+ * via Id pin status or user request (debugfs). Id/BSV interrupts are not
+ * enabled when switch is controlled by user and default mode is supplied
+ * by board file, which can be changed by userspace later.
+ */
+static void msm_otg_init_sm(struct msm_otg *motg)
+{
+	struct msm_otg_platform_data *pdata = motg->pdata;
+	u32 otgsc = readl(USB_OTGSC);
+
+	switch (pdata->mode) {
+	case USB_OTG:
+		if (pdata->otg_control == OTG_PHY_CONTROL) {
+			if (otgsc & OTGSC_ID)
+				set_bit(ID, &motg->inputs);
+			else
+				clear_bit(ID, &motg->inputs);
+
+			if (otgsc & OTGSC_BSV)
+				set_bit(B_SESS_VLD, &motg->inputs);
+			else
+				clear_bit(B_SESS_VLD, &motg->inputs);
+		} else if (pdata->otg_control == OTG_USER_CONTROL) {
+			if (pdata->default_mode == USB_HOST) {
+				clear_bit(ID, &motg->inputs);
+			} else if (pdata->default_mode == USB_PERIPHERAL) {
+				set_bit(ID, &motg->inputs);
+				set_bit(B_SESS_VLD, &motg->inputs);
+			} else {
+				set_bit(ID, &motg->inputs);
+				clear_bit(B_SESS_VLD, &motg->inputs);
+			}
+		}
+		break;
+	case USB_HOST:
+		clear_bit(ID, &motg->inputs);
+		break;
+	case USB_PERIPHERAL:
+		set_bit(ID, &motg->inputs);
+		if (otgsc & OTGSC_BSV)
+			set_bit(B_SESS_VLD, &motg->inputs);
+		else
+			clear_bit(B_SESS_VLD, &motg->inputs);
+		break;
+	default:
+		break;
+	}
+}
+
+static void msm_otg_sm_work(struct work_struct *w)
+{
+	struct msm_otg *motg = container_of(w, struct msm_otg, sm_work);
+	struct otg_transceiver *otg = &motg->otg;
+
+	switch (otg->state) {
+	case OTG_STATE_UNDEFINED:
+		dev_dbg(otg->dev, "OTG_STATE_UNDEFINED state\n");
+		msm_otg_reset(otg);
+		msm_otg_init_sm(motg);
+		otg->state = OTG_STATE_B_IDLE;
+		/* FALL THROUGH */
+	case OTG_STATE_B_IDLE:
+		dev_dbg(otg->dev, "OTG_STATE_B_IDLE state\n");
+		if (!test_bit(ID, &motg->inputs) && otg->host) {
+			/* disable BSV bit */
+			writel(readl(USB_OTGSC) & ~OTGSC_BSVIE, USB_OTGSC);
+			msm_otg_start_host(otg, 1);
+			otg->state = OTG_STATE_A_HOST;
+		} else if (test_bit(B_SESS_VLD, &motg->inputs) && otg->gadget) {
+			msm_otg_start_peripheral(otg, 1);
+			otg->state = OTG_STATE_B_PERIPHERAL;
+		}
+		break;
+	case OTG_STATE_B_PERIPHERAL:
+		dev_dbg(otg->dev, "OTG_STATE_B_PERIPHERAL state\n");
+		if (!test_bit(B_SESS_VLD, &motg->inputs) ||
+				!test_bit(ID, &motg->inputs)) {
+			msm_otg_start_peripheral(otg, 0);
+			otg->state = OTG_STATE_B_IDLE;
+			msm_otg_reset(otg);
+			schedule_work(w);
+		}
+		break;
+	case OTG_STATE_A_HOST:
+		dev_dbg(otg->dev, "OTG_STATE_A_HOST state\n");
+		if (test_bit(ID, &motg->inputs)) {
+			msm_otg_start_host(otg, 0);
+			otg->state = OTG_STATE_B_IDLE;
+			msm_otg_reset(otg);
+			schedule_work(w);
+		}
+		break;
+	default:
+		break;
+	}
+}
+
+static irqreturn_t msm_otg_irq(int irq, void *data)
+{
+	struct msm_otg *motg = data;
+	struct otg_transceiver *otg = &motg->otg;
+	u32 otgsc = 0;
+
+	otgsc = readl(USB_OTGSC);
+	if (!(otgsc & (OTGSC_IDIS | OTGSC_BSVIS)))
+		return IRQ_NONE;
+
+	if ((otgsc & OTGSC_IDIS) && (otgsc & OTGSC_IDIE)) {
+		if (otgsc & OTGSC_ID)
+			set_bit(ID, &motg->inputs);
+		else
+			clear_bit(ID, &motg->inputs);
+		dev_dbg(otg->dev, "ID set/clear\n");
+	} else if ((otgsc & OTGSC_BSVIS) && (otgsc & OTGSC_BSVIE)) {
+		if (otgsc & OTGSC_BSV)
+			set_bit(B_SESS_VLD, &motg->inputs);
+		else
+			clear_bit(B_SESS_VLD, &motg->inputs);
+		dev_dbg(otg->dev, "BSV set/clear\n");
+	}
+
+	writel(otgsc, USB_OTGSC);
+	schedule_work(&motg->sm_work);
+	return IRQ_HANDLED;
+}
+
+static int msm_otg_mode_show(struct seq_file *s, void *unused)
+{
+	struct msm_otg *motg = s->private;
+	struct otg_transceiver *otg = &motg->otg;
+
+	switch (otg->state) {
+	case OTG_STATE_A_HOST:
+		seq_printf(s, "host\n");
+		break;
+	case OTG_STATE_B_PERIPHERAL:
+		seq_printf(s, "peripheral\n");
+		break;
+	default:
+		seq_printf(s, "none\n");
+		break;
+	}
+
+	return 0;
+}
+
+static int msm_otg_mode_open(struct inode *inode, struct file *file)
+{
+	return single_open(file, msm_otg_mode_show, inode->i_private);
+}
+
+static ssize_t msm_otg_mode_write(struct file *file, const char __user *ubuf,
+				size_t count, loff_t *ppos)
+{
+	struct msm_otg *motg = file->private_data;
+	char buf[16];
+	struct otg_transceiver *otg = &motg->otg;
+	int status = count;
+	enum usb_mode_type req_mode;
+
+	memset(buf, 0x00, sizeof(buf));
+
+	if (copy_from_user(&buf, ubuf, min_t(size_t, sizeof(buf) - 1, count))) {
+		status = -EFAULT;
+		goto out;
+	}
+
+	if (!strncmp(buf, "host", 4)) {
+		req_mode = USB_HOST;
+	} else if (!strncmp(buf, "peripheral", 10)) {
+		req_mode = USB_PERIPHERAL;
+	} else if (!strncmp(buf, "none", 4)) {
+		req_mode = USB_NONE;
+	} else {
+		status = -EINVAL;
+		goto out;
+	}
+
+	switch (req_mode) {
+	case USB_NONE:
+		switch (otg->state) {
+		case OTG_STATE_A_HOST:
+		case OTG_STATE_B_PERIPHERAL:
+			set_bit(ID, &motg->inputs);
+			clear_bit(B_SESS_VLD, &motg->inputs);
+			break;
+		default:
+			goto out;
+		}
+		break;
+	case USB_PERIPHERAL:
+		switch (otg->state) {
+		case OTG_STATE_B_IDLE:
+		case OTG_STATE_A_HOST:
+			set_bit(ID, &motg->inputs);
+			set_bit(B_SESS_VLD, &motg->inputs);
+			break;
+		default:
+			goto out;
+		}
+		break;
+	case USB_HOST:
+		switch (otg->state) {
+		case OTG_STATE_B_IDLE:
+		case OTG_STATE_B_PERIPHERAL:
+			clear_bit(ID, &motg->inputs);
+			break;
+		default:
+			goto out;
+		}
+		break;
+	default:
+		goto out;
+	}
+
+	schedule_work(&motg->sm_work);
+out:
+	return status;
+}
+
+const struct file_operations msm_otg_mode_fops = {
+	.open = msm_otg_mode_open,
+	.read = seq_read,
+	.write = msm_otg_mode_write,
+	.llseek = seq_lseek,
+	.release = single_release,
+};
+
+static struct dentry *msm_otg_dbg_root;
+static struct dentry *msm_otg_dbg_mode;
+
+static int msm_otg_debugfs_init(struct msm_otg *motg)
+{
+	msm_otg_dbg_root = debugfs_create_dir("msm_otg", NULL);
+
+	if (!msm_otg_dbg_root || IS_ERR(msm_otg_dbg_root))
+		return -ENODEV;
+
+	msm_otg_dbg_mode = debugfs_create_file("mode", S_IRUGO | S_IWUSR,
+				msm_otg_dbg_root, motg, &msm_otg_mode_fops);
+	if (!msm_otg_dbg_mode) {
+		debugfs_remove(msm_otg_dbg_root);
+		msm_otg_dbg_root = NULL;
+		return -ENODEV;
+	}
+
+	return 0;
+}
+
+static void msm_otg_debugfs_cleanup(void)
+{
+	debugfs_remove(msm_otg_dbg_mode);
+	debugfs_remove(msm_otg_dbg_root);
+}
+
+static int __init msm_otg_probe(struct platform_device *pdev)
+{
+	int ret = 0;
+	struct resource *res;
+	struct msm_otg *motg;
+	struct otg_transceiver *otg;
+
+	dev_info(&pdev->dev, "msm_otg probe\n");
+	if (!pdev->dev.platform_data) {
+		dev_err(&pdev->dev, "No platform data given. Bailing out\n");
+		return -ENODEV;
+	}
+
+	motg = kzalloc(sizeof(struct msm_otg), GFP_KERNEL);
+	if (!motg) {
+		dev_err(&pdev->dev, "unable to allocate msm_otg\n");
+		return -ENOMEM;
+	}
+
+	motg->pdata = pdev->dev.platform_data;
+	otg = &motg->otg;
+	otg->dev = &pdev->dev;
+
+	motg->phy_reset_clk = clk_get(&pdev->dev, "usb_phy_clk");
+	if (IS_ERR(motg->phy_reset_clk)) {
+		dev_err(&pdev->dev, "failed to get usb_phy_clk\n");
+		ret = PTR_ERR(motg->phy_reset_clk);
+		goto free_motg;
+	}
+
+	motg->clk = clk_get(&pdev->dev, "usb_hs_clk");
+	if (IS_ERR(motg->clk)) {
+		dev_err(&pdev->dev, "failed to get usb_hs_clk\n");
+		ret = PTR_ERR(motg->clk);
+		goto put_phy_reset_clk;
+	}
+
+	motg->pclk = clk_get(&pdev->dev, "usb_hs_pclk");
+	if (IS_ERR(motg->pclk)) {
+		dev_err(&pdev->dev, "failed to get usb_hs_pclk\n");
+		ret = PTR_ERR(motg->pclk);
+		goto put_clk;
+	}
+
+	/*
+	 * USB core clock is not present on all MSM chips. This
+	 * clock is introduced to remove the dependency on AXI
+	 * bus frequency.
+	 */
+	motg->core_clk = clk_get(&pdev->dev, "usb_hs_core_clk");
+	if (IS_ERR(motg->core_clk))
+		motg->core_clk = NULL;
+
+	res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+	if (!res) {
+		dev_err(&pdev->dev, "failed to get platform resource mem\n");
+		ret = -ENODEV;
+		goto put_core_clk;
+	}
+
+	motg->regs = ioremap(res->start, resource_size(res));
+	if (!motg->regs) {
+		dev_err(&pdev->dev, "ioremap failed\n");
+		ret = -ENOMEM;
+		goto put_core_clk;
+	}
+	dev_info(&pdev->dev, "OTG regs = %p\n", motg->regs);
+
+	motg->irq = platform_get_irq(pdev, 0);
+	if (!motg->irq) {
+		dev_err(&pdev->dev, "platform_get_irq failed\n");
+		ret = -ENODEV;
+		goto free_regs;
+	}
+
+	clk_enable(motg->clk);
+	clk_enable(motg->pclk);
+	if (motg->core_clk)
+		clk_enable(motg->core_clk);
+
+	writel(0, USB_USBINTR);
+	writel(0, USB_OTGSC);
+
+	INIT_WORK(&motg->sm_work, msm_otg_sm_work);
+	ret = request_irq(motg->irq, msm_otg_irq, IRQF_SHARED,
+					"msm_otg", motg);
+	if (ret) {
+		dev_err(&pdev->dev, "request irq failed\n");
+		goto disable_clks;
+	}
+
+	otg->init = msm_otg_reset;
+	otg->set_host = msm_otg_set_host;
+	otg->set_peripheral = msm_otg_set_peripheral;
+
+	otg->io_ops = &msm_otg_io_ops;
+
+	ret = otg_set_transceiver(&motg->otg);
+	if (ret) {
+		dev_err(&pdev->dev, "otg_set_transceiver failed\n");
+		goto free_irq;
+	}
+
+	platform_set_drvdata(pdev, motg);
+	device_init_wakeup(&pdev->dev, 1);
+
+	if (motg->pdata->mode == USB_OTG &&
+			motg->pdata->otg_control == OTG_USER_CONTROL) {
+		ret = msm_otg_debugfs_init(motg);
+		if (ret)
+			dev_dbg(&pdev->dev, "mode debugfs file is"
+					"not available\n");
+	}
+
+	return 0;
+
+free_irq:
+	free_irq(motg->irq, motg);
+disable_clks:
+	clk_disable(motg->pclk);
+	clk_disable(motg->clk);
+free_regs:
+	iounmap(motg->regs);
+put_core_clk:
+	if (motg->core_clk)
+		clk_put(motg->core_clk);
+	clk_put(motg->pclk);
+put_clk:
+	clk_put(motg->clk);
+put_phy_reset_clk:
+	clk_put(motg->phy_reset_clk);
+free_motg:
+	kfree(motg);
+	return ret;
+}
+
+static int __devexit msm_otg_remove(struct platform_device *pdev)
+{
+	struct msm_otg *motg = platform_get_drvdata(pdev);
+	struct otg_transceiver *otg = &motg->otg;
+
+	if (otg->host || otg->gadget)
+		return -EBUSY;
+
+	msm_otg_debugfs_cleanup();
+	cancel_work_sync(&motg->sm_work);
+	device_init_wakeup(&pdev->dev, 0);
+	otg_set_transceiver(NULL);
+
+	free_irq(motg->irq, motg);
+
+	clk_disable(motg->pclk);
+	clk_disable(motg->clk);
+	if (motg->core_clk)
+		clk_disable(motg->core_clk);
+
+	iounmap(motg->regs);
+
+	clk_put(motg->phy_reset_clk);
+	clk_put(motg->pclk);
+	clk_put(motg->clk);
+	if (motg->core_clk)
+		clk_put(motg->core_clk);
+
+	kfree(motg);
+
+	return 0;
+}
+
+static struct platform_driver msm_otg_driver = {
+	.remove = __devexit_p(msm_otg_remove),
+	.driver = {
+		.name = DRIVER_NAME,
+		.owner = THIS_MODULE,
+	},
+};
+
+static int __init msm_otg_init(void)
+{
+	return platform_driver_probe(&msm_otg_driver, msm_otg_probe);
+}
+
+static void __exit msm_otg_exit(void)
+{
+	platform_driver_unregister(&msm_otg_driver);
+}
+
+module_init(msm_otg_init);
+module_exit(msm_otg_exit);
+
+MODULE_LICENSE("GPL v2");
+MODULE_DESCRIPTION("MSM USB transceiver driver");
diff --git a/include/linux/usb/msm_hsusb.h b/include/linux/usb/msm_hsusb.h
new file mode 100644
index 0000000..b796df9
--- /dev/null
+++ b/include/linux/usb/msm_hsusb.h
@@ -0,0 +1,108 @@
+/* linux/include/asm-arm/arch-msm/hsusb.h
+ *
+ * Copyright (C) 2008 Google, Inc.
+ * Author: Brian Swetland <swetland@google.com>
+ * Copyright (c) 2009-2010, Code Aurora Forum. All rights reserved.
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * 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 __ASM_ARCH_MSM_HSUSB_H
+#define __ASM_ARCH_MSM_HSUSB_H
+
+#include <linux/types.h>
+#include <linux/usb/otg.h>
+
+/**
+ * Supported USB modes
+ *
+ * USB_PERIPHERAL       Only peripheral mode is supported.
+ * USB_HOST             Only host mode is supported.
+ * USB_OTG              OTG mode is supported.
+ *
+ */
+enum usb_mode_type {
+	USB_NONE = 0,
+	USB_PERIPHERAL,
+	USB_HOST,
+	USB_OTG,
+};
+
+/**
+ * OTG control
+ *
+ * OTG_NO_CONTROL	Id/VBUS notifications not required. Useful in host
+ *                      only configuration.
+ * OTG_PHY_CONTROL	Id/VBUS notifications comes form USB PHY.
+ * OTG_PMIC_CONTROL	Id/VBUS notifications comes from PMIC hardware.
+ * OTG_USER_CONTROL	Id/VBUS notifcations comes from User via sysfs.
+ *
+ */
+enum otg_control_type {
+	OTG_NO_CONTROL = 0,
+	OTG_PHY_CONTROL,
+	OTG_PMIC_CONTROL,
+	OTG_USER_CONTROL,
+};
+
+/**
+ * struct msm_otg_platform_data - platform device data
+ *              for msm72k_otg driver.
+ * @phy_init_seq: PHY configuration sequence. val, reg pairs
+ *              terminated by -1.
+ * @vbus_power: VBUS power on/off routine.
+ * @power_budget: VBUS power budget in mA (0 will be treated as 500mA).
+ * @mode: Supported mode (OTG/peripheral/host).
+ * @otg_control: OTG switch controlled by user/Id pin
+ * @default_mode: Default operational mode. Applicable only if
+ *              OTG switch is controller by user.
+ *
+ */
+struct msm_otg_platform_data {
+	int *phy_init_seq;
+	void (*vbus_power)(bool on);
+	unsigned power_budget;
+	enum usb_mode_type mode;
+	enum otg_control_type otg_control;
+	enum usb_mode_type default_mode;
+	void (*setup_gpio)(enum usb_otg_state state);
+};
+
+/**
+ * struct msm_otg: OTG driver data. Shared by HCD and DCD.
+ * @otg: USB OTG Transceiver structure.
+ * @pdata: otg device platform data.
+ * @irq: IRQ number assigned for HSUSB controller.
+ * @clk: clock struct of usb_hs_clk.
+ * @pclk: clock struct of usb_hs_pclk.
+ * @phy_reset_clk: clock struct of usb_phy_clk.
+ * @core_clk: clock struct of usb_hs_core_clk.
+ * @regs: ioremapped register base address.
+ * @inputs: OTG state machine inputs(Id, SessValid etc).
+ * @sm_work: OTG state machine work.
+ *
+ */
+struct msm_otg {
+	struct otg_transceiver otg;
+	struct msm_otg_platform_data *pdata;
+	int irq;
+	struct clk *clk;
+	struct clk *pclk;
+	struct clk *phy_reset_clk;
+	struct clk *core_clk;
+	void __iomem *regs;
+#define ID		0
+#define B_SESS_VLD	1
+	unsigned long inputs;
+	struct work_struct sm_work;
+};
+
+#endif
diff --git a/include/linux/usb/msm_hsusb_hw.h b/include/linux/usb/msm_hsusb_hw.h
new file mode 100644
index 0000000..b061cff
--- /dev/null
+++ b/include/linux/usb/msm_hsusb_hw.h
@@ -0,0 +1,56 @@
+/*
+ * Copyright (C) 2007 Google, Inc.
+ * Author: Brian Swetland <swetland@google.com>
+ *
+ * This software is licensed under the terms of the GNU General Public
+ * License version 2, as published by the Free Software Foundation, and
+ * may be copied, distributed, and modified under those terms.
+ *
+ * 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 __LINUX_USB_GADGET_MSM72K_UDC_H__
+#define __LINUX_USB_GADGET_MSM72K_UDC_H__
+
+#ifdef CONFIG_ARCH_MSM7X00A
+#define USB_SBUSCFG          (MSM_USB_BASE + 0x0090)
+#else
+#define USB_AHBBURST         (MSM_USB_BASE + 0x0090)
+#define USB_AHBMODE          (MSM_USB_BASE + 0x0098)
+#endif
+#define USB_CAPLENGTH        (MSM_USB_BASE + 0x0100) /* 8 bit */
+
+#define USB_USBCMD           (MSM_USB_BASE + 0x0140)
+#define USB_PORTSC           (MSM_USB_BASE + 0x0184)
+#define USB_OTGSC            (MSM_USB_BASE + 0x01A4)
+#define USB_USBMODE          (MSM_USB_BASE + 0x01A8)
+
+#define USBCMD_RESET   2
+#define USB_USBINTR          (MSM_USB_BASE + 0x0148)
+
+#define PORTSC_PHCD            (1 << 23) /* phy suspend mode */
+#define PORTSC_PTS_MASK         (3 << 30)
+#define PORTSC_PTS_ULPI         (3 << 30)
+
+#define USB_ULPI_VIEWPORT    (MSM_USB_BASE + 0x0170)
+#define ULPI_RUN              (1 << 30)
+#define ULPI_WRITE            (1 << 29)
+#define ULPI_READ             (0 << 29)
+#define ULPI_ADDR(n)          (((n) & 255) << 16)
+#define ULPI_DATA(n)          ((n) & 255)
+#define ULPI_DATA_READ(n)     (((n) >> 8) & 255)
+
+/* OTG definitions */
+#define OTGSC_INTSTS_MASK	(0x7f << 16)
+#define OTGSC_ID		(1 << 8)
+#define OTGSC_BSV		(1 << 11)
+#define OTGSC_IDIS		(1 << 16)
+#define OTGSC_BSVIS		(1 << 19)
+#define OTGSC_IDIE		(1 << 24)
+#define OTGSC_BSVIE		(1 << 27)
+
+#endif /* __LINUX_USB_GADGET_MSM72K_UDC_H__ */
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 02/11] USB: EHCI: Add MSM Host Controller driver
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 01/11] USB: Add MSM OTG Controller driver Pavankumar Kondeti
@ 2010-12-07 12:23 ` Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 03/11] USB: EHCI: msm: Add support for power management Pavankumar Kondeti
                   ` (9 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:23 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

This patch adds support for EHCI compliant HSUSB Host controller found
on MSM chips.  The root hub has a single port and TT is built into it.
This driver depends on OTG driver for PHY initialization, clock
management and powering up VBUS.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/Kconfig         |    1 +
 drivers/usb/host/Kconfig    |   11 ++
 drivers/usb/host/ehci-hcd.c |    5 +
 drivers/usb/host/ehci-msm.c |  290 +++++++++++++++++++++++++++++++++++++++++++
 4 files changed, 307 insertions(+), 0 deletions(-)
 create mode 100644 drivers/usb/host/ehci-msm.c

diff --git a/drivers/usb/Kconfig b/drivers/usb/Kconfig
index 6585f0b..b8e70a9 100644
--- a/drivers/usb/Kconfig
+++ b/drivers/usb/Kconfig
@@ -64,6 +64,7 @@ config USB_ARCH_HAS_EHCI
 	default y if ARCH_OMAP3
 	default y if ARCH_VT8500
 	default y if PLAT_SPEAR
+	default y if ARCH_MSM
 	default PCI
 
 # ARM SA1111 chips have a non-PCI based "OHCI-compatible" USB host interface.
diff --git a/drivers/usb/host/Kconfig b/drivers/usb/host/Kconfig
index 6a7c688..d8665ec 100644
--- a/drivers/usb/host/Kconfig
+++ b/drivers/usb/host/Kconfig
@@ -141,6 +141,17 @@ config USB_EHCI_HCD_OMAP
 	  Enables support for the on-chip EHCI controller on
 	  OMAP3 and later chips.
 
+config USB_EHCI_MSM
+	bool "Support for MSM on-chip EHCI USB controller"
+	depends on USB_EHCI_HCD && ARCH_MSM
+	select USB_EHCI_ROOT_HUB_TT
+	select USB_MSM_OTG_72K
+	---help---
+	  Enables support for the USB Host controller present on the
+	  Qualcomm chipsets. Root Hub has inbuilt TT.
+	  This driver depends on OTG driver for PHY initialization,
+	  clock management, powering up VBUS.
+
 config USB_EHCI_HCD_PPC_OF
 	bool "EHCI support for PPC USB controller on OF platform bus"
 	depends on USB_EHCI_HCD && PPC_OF
diff --git a/drivers/usb/host/ehci-hcd.c b/drivers/usb/host/ehci-hcd.c
index abe8336..cdd3ef8 100644
--- a/drivers/usb/host/ehci-hcd.c
+++ b/drivers/usb/host/ehci-hcd.c
@@ -1231,6 +1231,11 @@ MODULE_LICENSE ("GPL");
 #define PLATFORM_DRIVER		spear_ehci_hcd_driver
 #endif
 
+#ifdef CONFIG_USB_EHCI_MSM
+#include "ehci-msm.c"
+#define PLATFORM_DRIVER		ehci_msm_driver
+#endif
+
 #if !defined(PCI_DRIVER) && !defined(PLATFORM_DRIVER) && \
     !defined(PS3_SYSTEM_BUS_DRIVER) && !defined(OF_PLATFORM_DRIVER) && \
     !defined(XILINX_OF_PLATFORM_DRIVER)
diff --git a/drivers/usb/host/ehci-msm.c b/drivers/usb/host/ehci-msm.c
new file mode 100644
index 0000000..9ed8559
--- /dev/null
+++ b/drivers/usb/host/ehci-msm.c
@@ -0,0 +1,290 @@
+/* ehci-msm.c - HSUSB Host Controller Driver Implementation
+ *
+ * Copyright (c) 2008-2010, Code Aurora Forum. All rights reserved.
+ *
+ * Partly derived from ehci-fsl.c and ehci-hcd.c
+ * Copyright (c) 2000-2004 by David Brownell
+ * Copyright (c) 2005 MontaVista Software
+ *
+ * All source code in this file is licensed under the following license except
+ * where indicated.
+ *
+ * This program is free software; you can redistribute it and/or modify it
+ * under the terms of the GNU General Public License version 2 as published
+ * by the Free Software Foundation.
+ *
+ * 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.
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, you can find it at http://www.fsf.org
+ */
+
+#include <linux/platform_device.h>
+#include <linux/clk.h>
+#include <linux/err.h>
+
+#include <linux/usb/otg.h>
+#include <linux/usb/msm_hsusb_hw.h>
+
+#define MSM_USB_BASE (hcd->regs)
+
+static struct otg_transceiver *otg;
+
+/*
+ * ehci_run defined in drivers/usb/host/ehci-hcd.c reset the controller and
+ * the configuration settings in ehci_msm_reset vanish after controller is
+ * reset. Resetting the controler in ehci_run seems to be un-necessary
+ * provided HCD reset the controller before calling ehci_run. Most of the HCD
+ * do but some are not. So this function is same as ehci_run but we don't
+ * reset the controller here.
+ */
+static int ehci_msm_run(struct usb_hcd *hcd)
+{
+	struct ehci_hcd		*ehci = hcd_to_ehci(hcd);
+	u32			temp;
+	u32			hcc_params;
+
+	hcd->uses_new_polling = 1;
+
+	ehci_writel(ehci, ehci->periodic_dma, &ehci->regs->frame_list);
+	ehci_writel(ehci, (u32)ehci->async->qh_dma, &ehci->regs->async_next);
+
+	/*
+	 * hcc_params controls whether ehci->regs->segment must (!!!)
+	 * be used; it constrains QH/ITD/SITD and QTD locations.
+	 * pci_pool consistent memory always uses segment zero.
+	 * streaming mappings for I/O buffers, like pci_map_single(),
+	 * can return segments above 4GB, if the device allows.
+	 *
+	 * NOTE:  the dma mask is visible through dma_supported(), so
+	 * drivers can pass this info along ... like NETIF_F_HIGHDMA,
+	 * Scsi_Host.highmem_io, and so forth.  It's readonly to all
+	 * host side drivers though.
+	 */
+	hcc_params = ehci_readl(ehci, &ehci->caps->hcc_params);
+	if (HCC_64BIT_ADDR(hcc_params))
+		ehci_writel(ehci, 0, &ehci->regs->segment);
+
+	/*
+	 * Philips, Intel, and maybe others need CMD_RUN before the
+	 * root hub will detect new devices (why?); NEC doesn't
+	 */
+	ehci->command &= ~(CMD_LRESET|CMD_IAAD|CMD_PSE|CMD_ASE|CMD_RESET);
+	ehci->command |= CMD_RUN;
+	ehci_writel(ehci, ehci->command, &ehci->regs->command);
+	dbg_cmd(ehci, "init", ehci->command);
+
+	/*
+	 * Start, enabling full USB 2.0 functionality ... usb 1.1 devices
+	 * are explicitly handed to companion controller(s), so no TT is
+	 * involved with the root hub.  (Except where one is integrated,
+	 * and there's no companion controller unless maybe for USB OTG.)
+	 *
+	 * Turning on the CF flag will transfer ownership of all ports
+	 * from the companions to the EHCI controller.  If any of the
+	 * companions are in the middle of a port reset at the time, it
+	 * could cause trouble.  Write-locking ehci_cf_port_reset_rwsem
+	 * guarantees that no resets are in progress.  After we set CF,
+	 * a short delay lets the hardware catch up; new resets shouldn't
+	 * be started before the port switching actions could complete.
+	 */
+	down_write(&ehci_cf_port_reset_rwsem);
+	hcd->state = HC_STATE_RUNNING;
+	ehci_writel(ehci, FLAG_CF, &ehci->regs->configured_flag);
+	ehci_readl(ehci, &ehci->regs->command);	/* unblock posted writes */
+	usleep_range(5000, 5500);
+	up_write(&ehci_cf_port_reset_rwsem);
+	ehci->last_periodic_enable = ktime_get_real();
+
+	temp = HC_VERSION(ehci_readl(ehci, &ehci->caps->hc_capbase));
+	ehci_info(ehci,
+		"USB %x.%x started, EHCI %x.%02x%s\n",
+		((ehci->sbrn & 0xf0)>>4), (ehci->sbrn & 0x0f),
+		temp >> 8, temp & 0xff,
+		ignore_oc ? ", overcurrent ignored" : "");
+
+	ehci_writel(ehci, INTR_MASK,
+		    &ehci->regs->intr_enable); /* Turn On Interrupts */
+
+	/* GRR this is run-once init(), being done every time the HC starts.
+	 * So long as they're part of class devices, we can't do it init()
+	 * since the class device isn't created that early.
+	 */
+	create_debug_files(ehci);
+	create_companion_file(ehci);
+
+	return 0;
+}
+
+static int ehci_msm_reset(struct usb_hcd *hcd)
+{
+	struct ehci_hcd *ehci = hcd_to_ehci(hcd);
+	int retval;
+
+	ehci->caps = USB_CAPLENGTH;
+	ehci->regs = USB_CAPLENGTH +
+		HC_LENGTH(ehci_readl(ehci, &ehci->caps->hc_capbase));
+
+	/* cache the data to minimize the chip reads*/
+	ehci->hcs_params = ehci_readl(ehci, &ehci->caps->hcs_params);
+
+	hcd->has_tt = 1;
+	ehci->sbrn = HCD_USB2;
+
+	/* data structure init */
+	retval = ehci_init(hcd);
+	if (retval)
+		return retval;
+
+	retval = ehci_reset(ehci);
+	if (retval)
+		return retval;
+
+	/* bursts of unspecified length. */
+	writel(0, USB_AHBBURST);
+	/* Use the AHB transactor */
+	writel(0, USB_AHBMODE);
+	/* Disable streaming mode and select host mode */
+	writel(0x13, USB_USBMODE);
+
+	ehci_port_power(ehci, 1);
+	return 0;
+}
+
+static struct hc_driver msm_hc_driver = {
+	.description		= hcd_name,
+	.product_desc		= "Qualcomm On-Chip EHCI Host Controller",
+	.hcd_priv_size		= sizeof(struct ehci_hcd),
+
+	/*
+	 * generic hardware linkage
+	 */
+	.irq			= ehci_irq,
+	.flags			= HCD_USB2 | HCD_MEMORY,
+
+	.reset			= ehci_msm_reset,
+	.start			= ehci_msm_run,
+
+	.stop			= ehci_stop,
+	.shutdown		= ehci_shutdown,
+
+	/*
+	 * managing i/o requests and associated device resources
+	 */
+	.urb_enqueue		= ehci_urb_enqueue,
+	.urb_dequeue		= ehci_urb_dequeue,
+	.endpoint_disable	= ehci_endpoint_disable,
+	.endpoint_reset		= ehci_endpoint_reset,
+	.clear_tt_buffer_complete = ehci_clear_tt_buffer_complete,
+
+	/*
+	 * scheduling support
+	 */
+	.get_frame_number	= ehci_get_frame,
+
+	/*
+	 * root hub support
+	 */
+	.hub_status_data	= ehci_hub_status_data,
+	.hub_control		= ehci_hub_control,
+	.relinquish_port	= ehci_relinquish_port,
+	.port_handed_over	= ehci_port_handed_over,
+
+	/*
+	 * PM support
+	 */
+	.bus_suspend		= ehci_bus_suspend,
+	.bus_resume		= ehci_bus_resume,
+};
+
+static int ehci_msm_probe(struct platform_device *pdev)
+{
+	struct usb_hcd *hcd;
+	struct resource *res;
+	int ret;
+
+	dev_dbg(&pdev->dev, "ehci_msm proble\n");
+
+	hcd = usb_create_hcd(&msm_hc_driver, &pdev->dev, dev_name(&pdev->dev));
+	if (!hcd) {
+		dev_err(&pdev->dev, "Unable to create HCD\n");
+		return  -ENOMEM;
+	}
+
+	hcd->irq = platform_get_irq(pdev, 0);
+	if (hcd->irq < 0) {
+		dev_err(&pdev->dev, "Unable to get IRQ resource\n");
+		ret = hcd->irq;
+		goto put_hcd;
+	}
+
+	res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+	if (!res) {
+		dev_err(&pdev->dev, "Unable to get memory resource\n");
+		ret = -ENODEV;
+		goto put_hcd;
+	}
+
+	hcd->rsrc_start = res->start;
+	hcd->rsrc_len = resource_size(res);
+	hcd->regs = ioremap(hcd->rsrc_start, hcd->rsrc_len);
+	if (!hcd->regs) {
+		dev_err(&pdev->dev, "ioremap failed\n");
+		ret = -ENOMEM;
+		goto put_hcd;
+	}
+
+	/*
+	 * OTG driver takes care of PHY initialization, clock management,
+	 * powering up VBUS and mapping of registers address space.
+	 */
+	otg = otg_get_transceiver();
+	if (!otg) {
+		dev_err(&pdev->dev, "unable to find transceiver\n");
+		ret = -ENODEV;
+		goto unmap;
+	}
+
+	ret = otg_set_host(otg, &hcd->self);
+	if (ret < 0) {
+		dev_err(&pdev->dev, "unable to register with transceiver\n");
+		goto put_transceiver;
+	}
+
+	device_init_wakeup(&pdev->dev, 1);
+	return 0;
+
+put_transceiver:
+	otg_put_transceiver(otg);
+unmap:
+	iounmap(hcd->regs);
+put_hcd:
+	usb_put_hcd(hcd);
+
+	return ret;
+}
+
+static int __devexit ehci_msm_remove(struct platform_device *pdev)
+{
+	struct usb_hcd *hcd = platform_get_drvdata(pdev);
+
+	device_init_wakeup(&pdev->dev, 0);
+
+	otg_set_host(otg, NULL);
+	otg_put_transceiver(otg);
+
+	usb_put_hcd(hcd);
+
+	return 0;
+}
+
+static struct platform_driver ehci_msm_driver = {
+	.probe	= ehci_msm_probe,
+	.remove	= __devexit_p(ehci_msm_remove),
+	.driver = {
+		   .name = "msm_hsusb_host",
+	},
+};
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 03/11] USB: EHCI: msm: Add support for power management
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 01/11] USB: Add MSM OTG Controller driver Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 02/11] USB: EHCI: Add MSM Host " Pavankumar Kondeti
@ 2010-12-07 12:23 ` Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 04/11] USB: OTG: " Pavankumar Kondeti
                   ` (8 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:23 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

Enable runtime PM and mark no_callbacks flag.  OTG device, parent of
HCD takes care of putting hardware into low power mode.  Adjust port
power wakeup flags during system suspend and resume.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/host/Kconfig    |    2 +-
 drivers/usb/host/ehci-msm.c |   57 ++++++++++++++++++++++++++++++++++++++++++-
 2 files changed, 57 insertions(+), 2 deletions(-)

diff --git a/drivers/usb/host/Kconfig b/drivers/usb/host/Kconfig
index d8665ec..b9cc311 100644
--- a/drivers/usb/host/Kconfig
+++ b/drivers/usb/host/Kconfig
@@ -150,7 +150,7 @@ config USB_EHCI_MSM
 	  Enables support for the USB Host controller present on the
 	  Qualcomm chipsets. Root Hub has inbuilt TT.
 	  This driver depends on OTG driver for PHY initialization,
-	  clock management, powering up VBUS.
+	  clock management, powering up VBUS, and power management.
 
 config USB_EHCI_HCD_PPC_OF
 	bool "EHCI support for PPC USB controller on OF platform bus"
diff --git a/drivers/usb/host/ehci-msm.c b/drivers/usb/host/ehci-msm.c
index 9ed8559..413f4de 100644
--- a/drivers/usb/host/ehci-msm.c
+++ b/drivers/usb/host/ehci-msm.c
@@ -25,6 +25,7 @@
 #include <linux/platform_device.h>
 #include <linux/clk.h>
 #include <linux/err.h>
+#include <linux/pm_runtime.h>
 
 #include <linux/usb/otg.h>
 #include <linux/usb/msm_hsusb_hw.h>
@@ -239,7 +240,8 @@ static int ehci_msm_probe(struct platform_device *pdev)
 
 	/*
 	 * OTG driver takes care of PHY initialization, clock management,
-	 * powering up VBUS and mapping of registers address space.
+	 * powering up VBUS, mapping of registers address space and power
+	 * management.
 	 */
 	otg = otg_get_transceiver();
 	if (!otg) {
@@ -255,6 +257,13 @@ static int ehci_msm_probe(struct platform_device *pdev)
 	}
 
 	device_init_wakeup(&pdev->dev, 1);
+	/*
+	 * OTG device parent of HCD takes care of putting
+	 * hardware into low power mode.
+	 */
+	pm_runtime_no_callbacks(&pdev->dev);
+	pm_runtime_enable(&pdev->dev);
+
 	return 0;
 
 put_transceiver:
@@ -272,6 +281,8 @@ static int __devexit ehci_msm_remove(struct platform_device *pdev)
 	struct usb_hcd *hcd = platform_get_drvdata(pdev);
 
 	device_init_wakeup(&pdev->dev, 0);
+	pm_runtime_disable(&pdev->dev);
+	pm_runtime_set_suspended(&pdev->dev);
 
 	otg_set_host(otg, NULL);
 	otg_put_transceiver(otg);
@@ -281,10 +292,54 @@ static int __devexit ehci_msm_remove(struct platform_device *pdev)
 	return 0;
 }
 
+#ifdef CONFIG_PM
+static int ehci_msm_pm_suspend(struct device *dev)
+{
+	struct usb_hcd *hcd = dev_get_drvdata(dev);
+	bool wakeup = device_may_wakeup(dev);
+
+	dev_dbg(dev, "ehci-msm PM suspend\n");
+
+	/*
+	 * EHCI helper function has also the same check before manipulating
+	 * port wakeup flags.  We do check here the same condition before
+	 * calling the same helper function to avoid bringing hardware
+	 * from Low power mode when there is no need for adjusting port
+	 * wakeup flags.
+	 */
+	if (hcd->self.root_hub->do_remote_wakeup && !wakeup) {
+		pm_runtime_resume(dev);
+		ehci_prepare_ports_for_controller_suspend(hcd_to_ehci(hcd),
+				wakeup);
+	}
+
+	return 0;
+}
+
+static int ehci_msm_pm_resume(struct device *dev)
+{
+	struct usb_hcd *hcd = dev_get_drvdata(dev);
+
+	dev_dbg(dev, "ehci-msm PM resume\n");
+	ehci_prepare_ports_for_controller_resume(hcd_to_ehci(hcd));
+
+	return 0;
+}
+#else
+#define ehci_msm_pm_suspend	NULL
+#define ehci_msm_pm_resume	NULL
+#endif
+
+static const struct dev_pm_ops ehci_msm_dev_pm_ops = {
+	.suspend         = ehci_msm_pm_suspend,
+	.resume          = ehci_msm_pm_resume,
+};
+
 static struct platform_driver ehci_msm_driver = {
 	.probe	= ehci_msm_probe,
 	.remove	= __devexit_p(ehci_msm_remove),
 	.driver = {
 		   .name = "msm_hsusb_host",
+		   .pm = &ehci_msm_dev_pm_ops,
 	},
 };
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 04/11] USB: OTG: msm: Add support for power management
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (2 preceding siblings ...)
  2010-12-07 12:23 ` [PATCH V3 03/11] USB: EHCI: msm: Add support for power management Pavankumar Kondeti
@ 2010-12-07 12:23 ` Pavankumar Kondeti
  2010-12-07 12:23 ` [PATCH V3 05/11] USB: gadget: Separate out PCI bus code from ci13xxx_udc Pavankumar Kondeti
                   ` (7 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:23 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

Implement runtime and system pm ops to put hardware into low power
mode (LPM). As part of LPM, USB clocks are turned off, PHY is put
into suspend state and PHY comparators are turned off if VBUS/Id
notifications are not required from PHY.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/otg/Kconfig          |    5 +-
 drivers/usb/otg/msm72k_otg.c     |  283 +++++++++++++++++++++++++++++++++++++-
 include/linux/usb/msm_hsusb.h    |    4 +
 include/linux/usb/msm_hsusb_hw.h |    3 +
 4 files changed, 289 insertions(+), 6 deletions(-)

diff --git a/drivers/usb/otg/Kconfig b/drivers/usb/otg/Kconfig
index 915c729..2810c2a 100644
--- a/drivers/usb/otg/Kconfig
+++ b/drivers/usb/otg/Kconfig
@@ -88,7 +88,8 @@ config USB_MSM_OTG_72K
 	help
 	  Enable this to support the USB OTG transceiver on MSM chips. It
 	  handles PHY initialization, clock management, and workarounds
-	  required after resetting the hardware. This driver is required
-	  even for peripheral only or host only mode configuration.
+	  required after resetting the hardware and power management.
+	  This driver is required even for peripheral only or host only
+	  mode configurations.
 
 endif # USB || OTG
diff --git a/drivers/usb/otg/msm72k_otg.c b/drivers/usb/otg/msm72k_otg.c
index 46f468a..1cd52ed 100644
--- a/drivers/usb/otg/msm72k_otg.c
+++ b/drivers/usb/otg/msm72k_otg.c
@@ -29,6 +29,7 @@
 #include <linux/uaccess.h>
 #include <linux/debugfs.h>
 #include <linux/seq_file.h>
+#include <linux/pm_runtime.h>
 
 #include <linux/usb.h>
 #include <linux/usb/otg.h>
@@ -251,6 +252,154 @@ static int msm_otg_reset(struct otg_transceiver *otg)
 	return 0;
 }
 
+#define PHY_SUSPEND_TIMEOUT_USEC	(500 * 1000)
+static int msm_otg_suspend(struct msm_otg *motg)
+{
+	struct otg_transceiver *otg = &motg->otg;
+	struct usb_bus *bus = otg->host;
+	struct msm_otg_platform_data *pdata = motg->pdata;
+	int cnt = 0;
+
+	if (atomic_read(&motg->in_lpm))
+		return 0;
+
+	disable_irq(motg->irq);
+	/*
+	 * Interrupt Latch Register auto-clear feature is not present
+	 * in all PHY versions. Latch register is clear on read type.
+	 * Clear latch register to avoid spurious wakeup from
+	 * low power mode (LPM).
+	 */
+	ulpi_read(otg, 0x14);
+
+	/*
+	 * PHY comparators are disabled when PHY enters into low power
+	 * mode (LPM). Keep PHY comparators ON in LPM only when we expect
+	 * VBUS/Id notifications from USB PHY. Otherwise turn off USB
+	 * PHY comparators. This save significant amount of power.
+	 */
+	if (pdata->otg_control == OTG_PHY_CONTROL)
+		ulpi_write(otg, 0x01, 0x30);
+
+	/*
+	 * PLL is not turned off when PHY enters into low power mode (LPM).
+	 * Disable PLL for maximum power savings.
+	 */
+	ulpi_write(otg, 0x08, 0x09);
+
+	/*
+	 * PHY may take some time or even fail to enter into low power
+	 * mode (LPM). Hence poll for 500 msec and reset the PHY and link
+	 * in failure case.
+	 */
+	writel(readl(USB_PORTSC) | PORTSC_PHCD, USB_PORTSC);
+	while (cnt < PHY_SUSPEND_TIMEOUT_USEC) {
+		if (readl(USB_PORTSC) & PORTSC_PHCD)
+			break;
+		udelay(1);
+		cnt++;
+	}
+
+	if (cnt >= PHY_SUSPEND_TIMEOUT_USEC) {
+		dev_err(otg->dev, "Unable to suspend PHY\n");
+		msm_otg_reset(otg);
+		enable_irq(motg->irq);
+		return -ETIMEDOUT;
+	}
+
+	/*
+	 * PHY has capability to generate interrupt asynchronously in low
+	 * power mode (LPM). This interrupt is level triggered. So USB IRQ
+	 * line must be disabled till async interrupt enable bit is cleared
+	 * in USBCMD register. Assert STP (ULPI interface STOP signal) to
+	 * block data communication from PHY.
+	 */
+	writel(readl(USB_USBCMD) | ASYNC_INTR_CTRL | ULPI_STP_CTRL, USB_USBCMD);
+
+	clk_disable(motg->pclk);
+	clk_disable(motg->clk);
+	if (motg->core_clk)
+		clk_disable(motg->core_clk);
+
+	if (device_may_wakeup(otg->dev))
+		enable_irq_wake(motg->irq);
+	if (bus)
+		clear_bit(HCD_FLAG_HW_ACCESSIBLE, &(bus_to_hcd(bus))->flags);
+
+	atomic_set(&motg->in_lpm, 1);
+	enable_irq(motg->irq);
+
+	dev_info(otg->dev, "USB in low power mode\n");
+
+	return 0;
+}
+
+#define PHY_RESUME_TIMEOUT_USEC	(100 * 1000)
+static int msm_otg_resume(struct msm_otg *motg)
+{
+	struct otg_transceiver *otg = &motg->otg;
+	struct usb_bus *bus = otg->host;
+	int cnt = 0;
+	unsigned temp;
+
+	if (!atomic_read(&motg->in_lpm))
+		return 0;
+
+	clk_enable(motg->pclk);
+	clk_enable(motg->clk);
+	if (motg->core_clk)
+		clk_enable(motg->core_clk);
+
+	temp = readl(USB_USBCMD);
+	temp &= ~ASYNC_INTR_CTRL;
+	temp &= ~ULPI_STP_CTRL;
+	writel(temp, USB_USBCMD);
+
+	/*
+	 * PHY comes out of low power mode (LPM) in case of wakeup
+	 * from asynchronous interrupt.
+	 */
+	if (!(readl(USB_PORTSC) & PORTSC_PHCD))
+		goto skip_phy_resume;
+
+	writel(readl(USB_PORTSC) & ~PORTSC_PHCD, USB_PORTSC);
+	while (cnt < PHY_RESUME_TIMEOUT_USEC) {
+		if (!(readl(USB_PORTSC) & PORTSC_PHCD))
+			break;
+		udelay(1);
+		cnt++;
+	}
+
+	if (cnt >= PHY_RESUME_TIMEOUT_USEC) {
+		/*
+		 * This is a fatal error. Reset the link and
+		 * PHY. USB state can not be restored. Re-insertion
+		 * of USB cable is the only way to get USB working.
+		 */
+		dev_err(otg->dev, "Unable to resume USB."
+				"Re-plugin the cable\n");
+		msm_otg_reset(otg);
+	}
+
+skip_phy_resume:
+	if (device_may_wakeup(otg->dev))
+		disable_irq_wake(motg->irq);
+	if (bus)
+		set_bit(HCD_FLAG_HW_ACCESSIBLE, &(bus_to_hcd(bus))->flags);
+
+	if (motg->async_int) {
+		motg->async_int = 0;
+		pm_runtime_put(otg->dev);
+		enable_irq(motg->irq);
+	}
+
+	atomic_set(&motg->in_lpm, 0);
+
+	dev_info(otg->dev, "USB exited from low power mode\n");
+
+	return 0;
+}
+
 static void msm_otg_start_host(struct otg_transceiver *otg, int on)
 {
 	struct msm_otg *motg = container_of(otg, struct msm_otg, otg);
@@ -306,6 +455,7 @@ static int msm_otg_set_host(struct otg_transceiver *otg, struct usb_bus *host)
 
 	if (!host) {
 		if (otg->state == OTG_STATE_A_HOST) {
+			pm_runtime_get_sync(otg->dev);
 			msm_otg_start_host(otg, 0);
 			otg->host = NULL;
 			otg->state = OTG_STATE_UNDEFINED;
@@ -327,8 +477,10 @@ static int msm_otg_set_host(struct otg_transceiver *otg, struct usb_bus *host)
 	 * Kick the state machine work, if peripheral is not supported
 	 * or peripheral is already registered with us.
 	 */
-	if (motg->pdata->mode == USB_HOST || otg->gadget)
+	if (motg->pdata->mode == USB_HOST || otg->gadget) {
+		pm_runtime_get_sync(otg->dev);
 		schedule_work(&motg->sm_work);
+	}
 
 	return 0;
 }
@@ -376,6 +528,7 @@ static int msm_otg_set_peripheral(struct otg_transceiver *otg,
 
 	if (!gadget) {
 		if (otg->state == OTG_STATE_B_PERIPHERAL) {
+			pm_runtime_get_sync(otg->dev);
 			msm_otg_start_peripheral(otg, 0);
 			otg->gadget = NULL;
 			otg->state = OTG_STATE_UNDEFINED;
@@ -393,8 +546,10 @@ static int msm_otg_set_peripheral(struct otg_transceiver *otg,
 	 * Kick the state machine work, if host is not supported
 	 * or host is already registered with us.
 	 */
-	if (motg->pdata->mode == USB_PERIPHERAL || otg->host)
+	if (motg->pdata->mode == USB_PERIPHERAL || otg->host) {
+		pm_runtime_get_sync(otg->dev);
 		schedule_work(&motg->sm_work);
+	}
 
 	return 0;
 }
@@ -473,6 +628,7 @@ static void msm_otg_sm_work(struct work_struct *w)
 			msm_otg_start_peripheral(otg, 1);
 			otg->state = OTG_STATE_B_PERIPHERAL;
 		}
+		pm_runtime_put_sync(otg->dev);
 		break;
 	case OTG_STATE_B_PERIPHERAL:
 		dev_dbg(otg->dev, "OTG_STATE_B_PERIPHERAL state\n");
@@ -504,6 +660,13 @@ static irqreturn_t msm_otg_irq(int irq, void *data)
 	struct otg_transceiver *otg = &motg->otg;
 	u32 otgsc = 0;
 
+	if (atomic_read(&motg->in_lpm)) {
+		disable_irq_nosync(irq);
+		motg->async_int = 1;
+		pm_runtime_get(otg->dev);
+		return IRQ_HANDLED;
+	}
+
 	otgsc = readl(USB_OTGSC);
 	if (!(otgsc & (OTGSC_IDIS | OTGSC_BSVIS)))
 		return IRQ_NONE;
@@ -514,12 +677,14 @@ static irqreturn_t msm_otg_irq(int irq, void *data)
 		else
 			clear_bit(ID, &motg->inputs);
 		dev_dbg(otg->dev, "ID set/clear\n");
+		pm_runtime_get_noresume(otg->dev);
 	} else if ((otgsc & OTGSC_BSVIS) && (otgsc & OTGSC_BSVIE)) {
 		if (otgsc & OTGSC_BSV)
 			set_bit(B_SESS_VLD, &motg->inputs);
 		else
 			clear_bit(B_SESS_VLD, &motg->inputs);
 		dev_dbg(otg->dev, "BSV set/clear\n");
+		pm_runtime_get_noresume(otg->dev);
 	}
 
 	writel(otgsc, USB_OTGSC);
@@ -616,6 +781,7 @@ static ssize_t msm_otg_mode_write(struct file *file, const char __user *ubuf,
 		goto out;
 	}
 
+	pm_runtime_get_sync(otg->dev);
 	schedule_work(&motg->sm_work);
 out:
 	return status;
@@ -770,8 +936,10 @@ static int __init msm_otg_probe(struct platform_device *pdev)
 					"not available\n");
 	}
 
-	return 0;
+	pm_runtime_set_active(&pdev->dev);
+	pm_runtime_enable(&pdev->dev);
 
+	return 0;
 free_irq:
 	free_irq(motg->irq, motg);
 disable_clks:
@@ -796,23 +964,45 @@ static int __devexit msm_otg_remove(struct platform_device *pdev)
 {
 	struct msm_otg *motg = platform_get_drvdata(pdev);
 	struct otg_transceiver *otg = &motg->otg;
+	int cnt = 0;
 
 	if (otg->host || otg->gadget)
 		return -EBUSY;
 
 	msm_otg_debugfs_cleanup();
 	cancel_work_sync(&motg->sm_work);
+
+	msm_otg_resume(motg);
+
 	device_init_wakeup(&pdev->dev, 0);
-	otg_set_transceiver(NULL);
+	pm_runtime_disable(&pdev->dev);
 
+	otg_set_transceiver(NULL);
 	free_irq(motg->irq, motg);
 
+	/*
+	 * Put PHY in low power mode.
+	 */
+	ulpi_read(otg, 0x14);
+	ulpi_write(otg, 0x08, 0x09);
+
+	writel(readl(USB_PORTSC) | PORTSC_PHCD, USB_PORTSC);
+	while (cnt < PHY_SUSPEND_TIMEOUT_USEC) {
+		if (readl(USB_PORTSC) & PORTSC_PHCD)
+			break;
+		udelay(1);
+		cnt++;
+	}
+	if (cnt >= PHY_SUSPEND_TIMEOUT_USEC)
+		dev_err(otg->dev, "Unable to suspend PHY\n");
+
 	clk_disable(motg->pclk);
 	clk_disable(motg->clk);
 	if (motg->core_clk)
 		clk_disable(motg->core_clk);
 
 	iounmap(motg->regs);
+	pm_runtime_set_suspended(&pdev->dev);
 
 	clk_put(motg->phy_reset_clk);
 	clk_put(motg->pclk);
@@ -825,11 +1015,96 @@ static int __devexit msm_otg_remove(struct platform_device *pdev)
 	return 0;
 }
 
+#ifdef CONFIG_PM_RUNTIME
+static int msm_otg_runtime_idle(struct device *dev)
+{
+	struct msm_otg *motg = dev_get_drvdata(dev);
+	struct otg_transceiver *otg = &motg->otg;
+
+	dev_dbg(dev, "OTG runtime idle\n");
+
+	/*
+	 * It is observed some times that a spurious interrupt
+	 * comes when PHY is put into LPM immediately after PHY reset.
+	 * This 1 sec delay also prevents entering into LPM immediately
+	 * after asynchronous interrupt.
+	 */
+	if (otg->state != OTG_STATE_UNDEFINED)
+		pm_schedule_suspend(dev, 1000);
+
+	return -EAGAIN;
+}
+
+static int msm_otg_runtime_suspend(struct device *dev)
+{
+	struct msm_otg *motg = dev_get_drvdata(dev);
+
+	dev_dbg(dev, "OTG runtime suspend\n");
+	return msm_otg_suspend(motg);
+}
+
+static int msm_otg_runtime_resume(struct device *dev)
+{
+	struct msm_otg *motg = dev_get_drvdata(dev);
+
+	dev_dbg(dev, "OTG runtime resume\n");
+	return msm_otg_resume(motg);
+}
+#else
+#define msm_otg_runtime_idle	NULL
+#define msm_otg_runtime_suspend	NULL
+#define msm_otg_runtime_resume	NULL
+#endif
+
+#ifdef CONFIG_PM
+static int msm_otg_pm_suspend(struct device *dev)
+{
+	struct msm_otg *motg = dev_get_drvdata(dev);
+
+	dev_dbg(dev, "OTG PM suspend\n");
+	return msm_otg_suspend(motg);
+}
+
+static int msm_otg_pm_resume(struct device *dev)
+{
+	struct msm_otg *motg = dev_get_drvdata(dev);
+	int ret;
+
+	dev_dbg(dev, "OTG PM resume\n");
+
+	ret = msm_otg_resume(motg);
+	if (ret)
+		return ret;
+
+	/*
+	 * Runtime PM Documentation recommends bringing the
+	 * device to full powered state upon resume.
+	 */
+	pm_runtime_disable(dev);
+	pm_runtime_set_active(dev);
+	pm_runtime_enable(dev);
+
+	return 0;
+}
+#else
+#define msm_otg_pm_suspend	NULL
+#define msm_otg_pm_resume	NULL
+#endif
+
+static const struct dev_pm_ops msm_otg_dev_pm_ops = {
+	.runtime_suspend = msm_otg_runtime_suspend,
+	.runtime_resume  = msm_otg_runtime_resume,
+	.runtime_idle    = msm_otg_runtime_idle,
+	.suspend         = msm_otg_pm_suspend,
+	.resume          = msm_otg_pm_resume,
+};
+
 static struct platform_driver msm_otg_driver = {
 	.remove = __devexit_p(msm_otg_remove),
 	.driver = {
 		.name = DRIVER_NAME,
 		.owner = THIS_MODULE,
+		.pm = &msm_otg_dev_pm_ops,
 	},
 };
 
diff --git a/include/linux/usb/msm_hsusb.h b/include/linux/usb/msm_hsusb.h
index b796df9..3675e03 100644
--- a/include/linux/usb/msm_hsusb.h
+++ b/include/linux/usb/msm_hsusb.h
@@ -88,6 +88,8 @@ struct msm_otg_platform_data {
  * @regs: ioremapped register base address.
  * @inputs: OTG state machine inputs(Id, SessValid etc).
  * @sm_work: OTG state machine work.
+ * @in_lpm: indicates low power mode (LPM) state.
+ * @async_int: Async interrupt arrived.
  *
  */
 struct msm_otg {
@@ -103,6 +105,8 @@ struct msm_otg {
 #define B_SESS_VLD	1
 	unsigned long inputs;
 	struct work_struct sm_work;
+	atomic_t in_lpm;
+	int async_int;
 };
 
 #endif
diff --git a/include/linux/usb/msm_hsusb_hw.h b/include/linux/usb/msm_hsusb_hw.h
index b061cff..b92e173 100644
--- a/include/linux/usb/msm_hsusb_hw.h
+++ b/include/linux/usb/msm_hsusb_hw.h
@@ -44,6 +44,9 @@
 #define ULPI_DATA(n)          ((n) & 255)
 #define ULPI_DATA_READ(n)     (((n) >> 8) & 255)
 
+#define ASYNC_INTR_CTRL         (1 << 29) /* Enable async interrupt */
+#define ULPI_STP_CTRL           (1 << 30) /* Block communication with PHY */
+
 /* OTG definitions */
 #define OTGSC_INTSTS_MASK	(0x7f << 16)
 #define OTGSC_ID		(1 << 8)
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 05/11] USB: gadget: Separate out PCI bus code from ci13xxx_udc
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (3 preceding siblings ...)
  2010-12-07 12:23 ` [PATCH V3 04/11] USB: OTG: " Pavankumar Kondeti
@ 2010-12-07 12:23 ` Pavankumar Kondeti
  2010-12-07 12:24 ` [PATCH V3 06/11] USB: gadget: Fix "scheduling while atomic" bugs in ci13xxx_udc Pavankumar Kondeti
                   ` (6 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:23 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

Move PCI bus code from ci13xxx_udc to a new file ci13xxx_pci.  SoC's
which has MIPS USB core can include the ci13xxx_udc and keep bus glue
code in their respective gadget controller drivers.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/gadget/Kconfig        |    8 +-
 drivers/usb/gadget/Makefile       |    2 +-
 drivers/usb/gadget/ci13xxx_pci.c  |  172 +++++++++++++++++++++++++++++++++++++
 drivers/usb/gadget/ci13xxx_udc.c  |  159 ----------------------------------
 drivers/usb/gadget/gadget_chips.h |    8 +-
 5 files changed, 181 insertions(+), 168 deletions(-)
 create mode 100644 drivers/usb/gadget/ci13xxx_pci.c

diff --git a/drivers/usb/gadget/Kconfig b/drivers/usb/gadget/Kconfig
index 23fac38..6bcbcb0 100644
--- a/drivers/usb/gadget/Kconfig
+++ b/drivers/usb/gadget/Kconfig
@@ -427,8 +427,8 @@ config USB_FSL_QE
 	default USB_GADGET
 	select USB_GADGET_SELECTED
 
-config USB_GADGET_CI13XXX
-	boolean "MIPS USB CI13xxx"
+config USB_GADGET_CI13XXX_PCI
+	boolean "MIPS USB CI13xxx PCI UDC"
 	depends on PCI
 	select USB_GADGET_DUALSPEED
 	help
@@ -439,9 +439,9 @@ config USB_GADGET_CI13XXX
 	  dynamically linked module called "ci13xxx_udc" and force all
 	  gadget drivers to also be dynamically linked.
 
-config USB_CI13XXX
+config USB_CI13XXX_PCI
 	tristate
-	depends on USB_GADGET_CI13XXX
+	depends on USB_GADGET_CI13XXX_PCI
 	default USB_GADGET
 	select USB_GADGET_SELECTED
 
diff --git a/drivers/usb/gadget/Makefile b/drivers/usb/gadget/Makefile
index a3e6b90..f53fda7 100644
--- a/drivers/usb/gadget/Makefile
+++ b/drivers/usb/gadget/Makefile
@@ -21,7 +21,7 @@ fsl_usb2_udc-$(CONFIG_ARCH_MXC)	+= fsl_mxc_udc.o
 obj-$(CONFIG_USB_M66592)	+= m66592-udc.o
 obj-$(CONFIG_USB_R8A66597)	+= r8a66597-udc.o
 obj-$(CONFIG_USB_FSL_QE)	+= fsl_qe_udc.o
-obj-$(CONFIG_USB_CI13XXX)	+= ci13xxx_udc.o
+obj-$(CONFIG_USB_CI13XXX_PCI)	+= ci13xxx_pci.o
 obj-$(CONFIG_USB_S3C_HSOTG)	+= s3c-hsotg.o
 obj-$(CONFIG_USB_LANGWELL)	+= langwell_udc.o
 obj-$(CONFIG_USB_EG20T)		+= pch_udc.o
diff --git a/drivers/usb/gadget/ci13xxx_pci.c b/drivers/usb/gadget/ci13xxx_pci.c
new file mode 100644
index 0000000..7a0f153
--- /dev/null
+++ b/drivers/usb/gadget/ci13xxx_pci.c
@@ -0,0 +1,172 @@
+/*
+ * ci13xxx_pci.c - MIPS USB IP core family device controller
+ *
+ * Copyright (C) 2008 Chipidea - MIPS Technologies, Inc. All rights reserved.
+ *
+ * Author: David Lopo
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 as
+ * published by the Free Software Foundation.
+ */
+
+#include <linux/module.h>
+#include <linux/pci.h>
+
+#include "ci13xxx_udc.c"
+
+/* driver name */
+#define UDC_DRIVER_NAME   "ci13xxx_pci"
+
+/******************************************************************************
+ * PCI block
+ *****************************************************************************/
+/**
+ * ci13xxx_pci_irq: interrut handler
+ * @irq:  irq number
+ * @pdev: USB Device Controller interrupt source
+ *
+ * This function returns IRQ_HANDLED if the IRQ has been handled
+ * This is an ISR don't trace, use attribute interface instead
+ */
+static irqreturn_t ci13xxx_pci_irq(int irq, void *pdev)
+{
+	if (irq == 0) {
+		dev_err(&((struct pci_dev *)pdev)->dev, "Invalid IRQ0 usage!");
+		return IRQ_HANDLED;
+	}
+	return udc_irq();
+}
+
+/**
+ * ci13xxx_pci_probe: PCI probe
+ * @pdev: USB device controller being probed
+ * @id:   PCI hotplug ID connecting controller to UDC framework
+ *
+ * This function returns an error code
+ * Allocates basic PCI resources for this USB device controller, and then
+ * invokes the udc_probe() method to start the UDC associated with it
+ */
+static int __devinit ci13xxx_pci_probe(struct pci_dev *pdev,
+				       const struct pci_device_id *id)
+{
+	void __iomem *regs = NULL;
+	int retval = 0;
+
+	if (id == NULL)
+		return -EINVAL;
+
+	retval = pci_enable_device(pdev);
+	if (retval)
+		goto done;
+
+	if (!pdev->irq) {
+		dev_err(&pdev->dev, "No IRQ, check BIOS/PCI setup!");
+		retval = -ENODEV;
+		goto disable_device;
+	}
+
+	retval = pci_request_regions(pdev, UDC_DRIVER_NAME);
+	if (retval)
+		goto disable_device;
+
+	/* BAR 0 holds all the registers */
+	regs = pci_iomap(pdev, 0, 0);
+	if (!regs) {
+		dev_err(&pdev->dev, "Error mapping memory!");
+		retval = -EFAULT;
+		goto release_regions;
+	}
+	pci_set_drvdata(pdev, (__force void *)regs);
+
+	pci_set_master(pdev);
+	pci_try_set_mwi(pdev);
+
+	retval = udc_probe(&pdev->dev, regs, UDC_DRIVER_NAME);
+	if (retval)
+		goto iounmap;
+
+	/* our device does not have MSI capability */
+
+	retval = request_irq(pdev->irq, ci13xxx_pci_irq, IRQF_SHARED,
+			     UDC_DRIVER_NAME, pdev);
+	if (retval)
+		goto gadget_remove;
+
+	return 0;
+
+ gadget_remove:
+	udc_remove();
+ iounmap:
+	pci_iounmap(pdev, regs);
+ release_regions:
+	pci_release_regions(pdev);
+ disable_device:
+	pci_disable_device(pdev);
+ done:
+	return retval;
+}
+
+/**
+ * ci13xxx_pci_remove: PCI remove
+ * @pdev: USB Device Controller being removed
+ *
+ * Reverses the effect of ci13xxx_pci_probe(),
+ * first invoking the udc_remove() and then releases
+ * all PCI resources allocated for this USB device controller
+ */
+static void __devexit ci13xxx_pci_remove(struct pci_dev *pdev)
+{
+	free_irq(pdev->irq, pdev);
+	udc_remove();
+	pci_iounmap(pdev, (__force void __iomem *)pci_get_drvdata(pdev));
+	pci_release_regions(pdev);
+	pci_disable_device(pdev);
+}
+
+/**
+ * PCI device table
+ * PCI device structure
+ *
+ * Check "pci.h" for details
+ */
+static DEFINE_PCI_DEVICE_TABLE(ci13xxx_pci_id_table) = {
+	{ PCI_DEVICE(0x153F, 0x1004) },
+	{ PCI_DEVICE(0x153F, 0x1006) },
+	{ 0, 0, 0, 0, 0, 0, 0 /* end: all zeroes */ }
+};
+MODULE_DEVICE_TABLE(pci, ci13xxx_pci_id_table);
+
+static struct pci_driver ci13xxx_pci_driver = {
+	.name         =	UDC_DRIVER_NAME,
+	.id_table     =	ci13xxx_pci_id_table,
+	.probe        =	ci13xxx_pci_probe,
+	.remove       =	__devexit_p(ci13xxx_pci_remove),
+};
+
+/**
+ * ci13xxx_pci_init: module init
+ *
+ * Driver load
+ */
+static int __init ci13xxx_pci_init(void)
+{
+	return pci_register_driver(&ci13xxx_pci_driver);
+}
+module_init(ci13xxx_pci_init);
+
+/**
+ * ci13xxx_pci_exit: module exit
+ *
+ * Driver unload
+ */
+static void __exit ci13xxx_pci_exit(void)
+{
+	pci_unregister_driver(&ci13xxx_pci_driver);
+}
+module_exit(ci13xxx_pci_exit);
+
+MODULE_AUTHOR("MIPS - David Lopo <dlopo@chipidea.mips.com>");
+MODULE_DESCRIPTION("MIPS CI13XXX USB Peripheral Controller");
+MODULE_LICENSE("GPL");
+MODULE_VERSION("June 2008");
diff --git a/drivers/usb/gadget/ci13xxx_udc.c b/drivers/usb/gadget/ci13xxx_udc.c
index 98b36fc..4e9ec7d 100644
--- a/drivers/usb/gadget/ci13xxx_udc.c
+++ b/drivers/usb/gadget/ci13xxx_udc.c
@@ -22,7 +22,6 @@
  * - ENDPT:  endpoint operations (Gadget API)
  * - GADGET: gadget operations (Gadget API)
  * - BUS:    bus glue code, bus abstraction layer
- * - PCI:    PCI core interface and PCI resources (interrupts, memory...)
  *
  * Compile Options
  * - CONFIG_USB_GADGET_DEBUG_FILES: enable debug facilities
@@ -60,8 +59,6 @@
 #include <linux/io.h>
 #include <linux/irq.h>
 #include <linux/kernel.h>
-#include <linux/module.h>
-#include <linux/pci.h>
 #include <linux/slab.h>
 #include <linux/usb/ch9.h>
 #include <linux/usb/gadget.h>
@@ -75,9 +72,6 @@
 /* ctrl register bank access */
 static DEFINE_SPINLOCK(udc_lock);
 
-/* driver name */
-#define UDC_DRIVER_NAME   "ci13xxx_udc"
-
 /* control endpoint description */
 static const struct usb_endpoint_descriptor
 ctrl_endpt_desc = {
@@ -2680,156 +2674,3 @@ static void udc_remove(void)
 	kfree(udc);
 	_udc = NULL;
 }
-
-/******************************************************************************
- * PCI block
- *****************************************************************************/
-/**
- * ci13xxx_pci_irq: interrut handler
- * @irq:  irq number
- * @pdev: USB Device Controller interrupt source
- *
- * This function returns IRQ_HANDLED if the IRQ has been handled
- * This is an ISR don't trace, use attribute interface instead
- */
-static irqreturn_t ci13xxx_pci_irq(int irq, void *pdev)
-{
-	if (irq == 0) {
-		dev_err(&((struct pci_dev *)pdev)->dev, "Invalid IRQ0 usage!");
-		return IRQ_HANDLED;
-	}
-	return udc_irq();
-}
-
-/**
- * ci13xxx_pci_probe: PCI probe
- * @pdev: USB device controller being probed
- * @id:   PCI hotplug ID connecting controller to UDC framework
- *
- * This function returns an error code
- * Allocates basic PCI resources for this USB device controller, and then
- * invokes the udc_probe() method to start the UDC associated with it
- */
-static int __devinit ci13xxx_pci_probe(struct pci_dev *pdev,
-				       const struct pci_device_id *id)
-{
-	void __iomem *regs = NULL;
-	int retval = 0;
-
-	if (id == NULL)
-		return -EINVAL;
-
-	retval = pci_enable_device(pdev);
-	if (retval)
-		goto done;
-
-	if (!pdev->irq) {
-		dev_err(&pdev->dev, "No IRQ, check BIOS/PCI setup!");
-		retval = -ENODEV;
-		goto disable_device;
-	}
-
-	retval = pci_request_regions(pdev, UDC_DRIVER_NAME);
-	if (retval)
-		goto disable_device;
-
-	/* BAR 0 holds all the registers */
-	regs = pci_iomap(pdev, 0, 0);
-	if (!regs) {
-		dev_err(&pdev->dev, "Error mapping memory!");
-		retval = -EFAULT;
-		goto release_regions;
-	}
-	pci_set_drvdata(pdev, (__force void *)regs);
-
-	pci_set_master(pdev);
-	pci_try_set_mwi(pdev);
-
-	retval = udc_probe(&pdev->dev, regs, UDC_DRIVER_NAME);
-	if (retval)
-		goto iounmap;
-
-	/* our device does not have MSI capability */
-
-	retval = request_irq(pdev->irq, ci13xxx_pci_irq, IRQF_SHARED,
-			     UDC_DRIVER_NAME, pdev);
-	if (retval)
-		goto gadget_remove;
-
-	return 0;
-
- gadget_remove:
-	udc_remove();
- iounmap:
-	pci_iounmap(pdev, regs);
- release_regions:
-	pci_release_regions(pdev);
- disable_device:
-	pci_disable_device(pdev);
- done:
-	return retval;
-}
-
-/**
- * ci13xxx_pci_remove: PCI remove
- * @pdev: USB Device Controller being removed
- *
- * Reverses the effect of ci13xxx_pci_probe(),
- * first invoking the udc_remove() and then releases
- * all PCI resources allocated for this USB device controller
- */
-static void __devexit ci13xxx_pci_remove(struct pci_dev *pdev)
-{
-	free_irq(pdev->irq, pdev);
-	udc_remove();
-	pci_iounmap(pdev, (__force void __iomem *)pci_get_drvdata(pdev));
-	pci_release_regions(pdev);
-	pci_disable_device(pdev);
-}
-
-/**
- * PCI device table
- * PCI device structure
- *
- * Check "pci.h" for details
- */
-static DEFINE_PCI_DEVICE_TABLE(ci13xxx_pci_id_table) = {
-	{ PCI_DEVICE(0x153F, 0x1004) },
-	{ PCI_DEVICE(0x153F, 0x1006) },
-	{ 0, 0, 0, 0, 0, 0, 0 /* end: all zeroes */ }
-};
-MODULE_DEVICE_TABLE(pci, ci13xxx_pci_id_table);
-
-static struct pci_driver ci13xxx_pci_driver = {
-	.name         =	UDC_DRIVER_NAME,
-	.id_table     =	ci13xxx_pci_id_table,
-	.probe        =	ci13xxx_pci_probe,
-	.remove       =	__devexit_p(ci13xxx_pci_remove),
-};
-
-/**
- * ci13xxx_pci_init: module init
- *
- * Driver load
- */
-static int __init ci13xxx_pci_init(void)
-{
-	return pci_register_driver(&ci13xxx_pci_driver);
-}
-module_init(ci13xxx_pci_init);
-
-/**
- * ci13xxx_pci_exit: module exit
- *
- * Driver unload
- */
-static void __exit ci13xxx_pci_exit(void)
-{
-	pci_unregister_driver(&ci13xxx_pci_driver);
-}
-module_exit(ci13xxx_pci_exit);
-
-MODULE_AUTHOR("MIPS - David Lopo <dlopo@chipidea.mips.com>");
-MODULE_DESCRIPTION("MIPS CI13XXX USB Peripheral Controller");
-MODULE_LICENSE("GPL");
-MODULE_VERSION("June 2008");
diff --git a/drivers/usb/gadget/gadget_chips.h b/drivers/usb/gadget/gadget_chips.h
index d7b3bbe..3093ebb 100644
--- a/drivers/usb/gadget/gadget_chips.h
+++ b/drivers/usb/gadget/gadget_chips.h
@@ -120,10 +120,10 @@
 #define gadget_is_fsl_qe(g)	0
 #endif
 
-#ifdef CONFIG_USB_GADGET_CI13XXX
-#define gadget_is_ci13xxx(g)	(!strcmp("ci13xxx_udc", (g)->name))
+#ifdef CONFIG_USB_GADGET_CI13XXX_PCI
+#define gadget_is_ci13xxx_pci(g)	(!strcmp("ci13xxx_pci", (g)->name))
 #else
-#define gadget_is_ci13xxx(g)	0
+#define gadget_is_ci13xxx_pci(g)	0
 #endif
 
 // CONFIG_USB_GADGET_SX2
@@ -197,7 +197,7 @@ static inline int usb_gadget_controller_number(struct usb_gadget *gadget)
 		return 0x21;
 	else if (gadget_is_fsl_qe(gadget))
 		return 0x22;
-	else if (gadget_is_ci13xxx(gadget))
+	else if (gadget_is_ci13xxx_pci(gadget))
 		return 0x23;
 	else if (gadget_is_langwell(gadget))
 		return 0x24;
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 06/11] USB: gadget: Fix "scheduling while atomic" bugs in ci13xxx_udc
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (4 preceding siblings ...)
  2010-12-07 12:23 ` [PATCH V3 05/11] USB: gadget: Separate out PCI bus code from ci13xxx_udc Pavankumar Kondeti
@ 2010-12-07 12:24 ` Pavankumar Kondeti
  2010-12-07 12:24 ` [PATCH V3 07/11] USB: gadget: Initialize ci13xxx gadget device's coherent DMA mask Pavankumar Kondeti
                   ` (5 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:24 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

dma_pool_alloc() require sleeping context when called with GFP_KERNEL
argument.  Hence release the spin lock before calling dma_pool_alloc().

usb_ep_alloc_request can also be called with non-atomic GFP flags.  Hence
get rid off spin lock while allocation request memory.

Use GFP_ATOMIC flag for allocating request for ep0 in interrupt handler.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/gadget/ci13xxx_udc.c |    9 +++------
 1 files changed, 3 insertions(+), 6 deletions(-)

diff --git a/drivers/usb/gadget/ci13xxx_udc.c b/drivers/usb/gadget/ci13xxx_udc.c
index 4e9ec7d..d19537a 100644
--- a/drivers/usb/gadget/ci13xxx_udc.c
+++ b/drivers/usb/gadget/ci13xxx_udc.c
@@ -1626,7 +1626,7 @@ __acquires(udc->lock)
 	spin_unlock(udc->lock);
 	retval = usb_ep_enable(&mEp->ep, &ctrl_endpt_desc);
 	if (!retval) {
-		mEp->status = usb_ep_alloc_request(&mEp->ep, GFP_KERNEL);
+		mEp->status = usb_ep_alloc_request(&mEp->ep, GFP_ATOMIC);
 		if (mEp->status == NULL) {
 			usb_ep_disable(&mEp->ep);
 			retval = -ENOMEM;
@@ -2055,7 +2055,6 @@ static struct usb_request *ep_alloc_request(struct usb_ep *ep, gfp_t gfp_flags)
 {
 	struct ci13xxx_ep  *mEp  = container_of(ep, struct ci13xxx_ep, ep);
 	struct ci13xxx_req *mReq = NULL;
-	unsigned long flags;
 
 	trace("%p, %i", ep, gfp_flags);
 
@@ -2064,8 +2063,6 @@ static struct usb_request *ep_alloc_request(struct usb_ep *ep, gfp_t gfp_flags)
 		return NULL;
 	}
 
-	spin_lock_irqsave(mEp->lock, flags);
-
 	mReq = kzalloc(sizeof(struct ci13xxx_req), gfp_flags);
 	if (mReq != NULL) {
 		INIT_LIST_HEAD(&mReq->queue);
@@ -2080,8 +2077,6 @@ static struct usb_request *ep_alloc_request(struct usb_ep *ep, gfp_t gfp_flags)
 
 	dbg_event(_usb_addr(mEp), "ALLOC", mReq == NULL);
 
-	spin_unlock_irqrestore(mEp->lock, flags);
-
 	return (mReq == NULL) ? NULL : &mReq->req;
 }
 
@@ -2404,9 +2399,11 @@ int usb_gadget_probe_driver(struct usb_gadget_driver *driver,
 		/* this allocation cannot be random */
 		for (k = RX; k <= TX; k++) {
 			INIT_LIST_HEAD(&mEp->qh[k].queue);
+			spin_unlock_irqrestore(udc->lock, flags);
 			mEp->qh[k].ptr = dma_pool_alloc(udc->qh_pool,
 							GFP_KERNEL,
 							&mEp->qh[k].dma);
+			spin_lock_irqsave(udc->lock, flags);
 			if (mEp->qh[k].ptr == NULL)
 				retval = -ENOMEM;
 			else
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 07/11] USB: gadget: Initialize ci13xxx gadget device's coherent DMA mask
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (5 preceding siblings ...)
  2010-12-07 12:24 ` [PATCH V3 06/11] USB: gadget: Fix "scheduling while atomic" bugs in ci13xxx_udc Pavankumar Kondeti
@ 2010-12-07 12:24 ` Pavankumar Kondeti
  2010-12-07 12:24 ` [PATCH V3 08/11] USB: gadget: Introduce ci13xxx_udc_driver struct Pavankumar Kondeti
                   ` (4 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:24 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

dma_alloc_coherent() which is internally called by dma_pool_alloc()
flags a warning if device's coherent DMA mask.  Hence initialize
gadget device's coherent DMA mask to it's parent mask.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/gadget/ci13xxx_udc.c |    1 +
 1 files changed, 1 insertions(+), 0 deletions(-)

diff --git a/drivers/usb/gadget/ci13xxx_udc.c b/drivers/usb/gadget/ci13xxx_udc.c
index d19537a..956fa64 100644
--- a/drivers/usb/gadget/ci13xxx_udc.c
+++ b/drivers/usb/gadget/ci13xxx_udc.c
@@ -2624,6 +2624,7 @@ static int udc_probe(struct device *dev, void __iomem *regs, const char *name)
 
 	dev_set_name(&udc->gadget.dev, "gadget");
 	udc->gadget.dev.dma_mask = dev->dma_mask;
+	udc->gadget.dev.coherent_dma_mask = dev->coherent_dma_mask;
 	udc->gadget.dev.parent   = dev;
 	udc->gadget.dev.release  = udc_release;
 
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 08/11] USB: gadget: Introduce ci13xxx_udc_driver struct
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (6 preceding siblings ...)
  2010-12-07 12:24 ` [PATCH V3 07/11] USB: gadget: Initialize ci13xxx gadget device's coherent DMA mask Pavankumar Kondeti
@ 2010-12-07 12:24 ` Pavankumar Kondeti
  2010-12-07 12:24 ` [PATCH V3 09/11] USB: gadget: Add USB controller driver for MSM SoC Pavankumar Kondeti
                   ` (3 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:24 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

Introduces ci13xxx_udc_driver struct for bus glue drivers to hint
ci13xxx_udc core about their special requirements.  The flags include
avoiding hardware register access when controller is not in peripheral
mode, enabling pull-up upon VBUS, disabling streaming mode and dependency
on transceiver driver.

Initialize gadget_ops in udc_probe so that transceiver can notify VBUS
presence even when no gadget driver is bounded.

A notify_event callback is embedded in the same struct. This patch implements
two events called CONTROLLER_RESET_EVENT and CONTROLLER_STOPPED_EVENT to
notify the bus glue driver after resetting and stopping the controller for
performing SoC specific quirks.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/gadget/ci13xxx_pci.c |    6 +-
 drivers/usb/gadget/ci13xxx_udc.c |  205 ++++++++++++++++++++++++++++----------
 drivers/usb/gadget/ci13xxx_udc.h |   19 ++++
 3 files changed, 175 insertions(+), 55 deletions(-)

diff --git a/drivers/usb/gadget/ci13xxx_pci.c b/drivers/usb/gadget/ci13xxx_pci.c
index 7a0f153..883ab5e 100644
--- a/drivers/usb/gadget/ci13xxx_pci.c
+++ b/drivers/usb/gadget/ci13xxx_pci.c
@@ -38,6 +38,10 @@ static irqreturn_t ci13xxx_pci_irq(int irq, void *pdev)
 	return udc_irq();
 }
 
+static struct ci13xxx_udc_driver ci13xxx_pci_udc_driver = {
+	.name		= UDC_DRIVER_NAME,
+};
+
 /**
  * ci13xxx_pci_probe: PCI probe
  * @pdev: USB device controller being probed
@@ -82,7 +86,7 @@ static int __devinit ci13xxx_pci_probe(struct pci_dev *pdev,
 	pci_set_master(pdev);
 	pci_try_set_mwi(pdev);
 
-	retval = udc_probe(&pdev->dev, regs, UDC_DRIVER_NAME);
+	retval = udc_probe(&ci13xxx_pci_udc_driver, &pdev->dev, regs);
 	if (retval)
 		goto iounmap;
 
diff --git a/drivers/usb/gadget/ci13xxx_udc.c b/drivers/usb/gadget/ci13xxx_udc.c
index 956fa64..c10d1ae 100644
--- a/drivers/usb/gadget/ci13xxx_udc.c
+++ b/drivers/usb/gadget/ci13xxx_udc.c
@@ -62,6 +62,7 @@
 #include <linux/slab.h>
 #include <linux/usb/ch9.h>
 #include <linux/usb/gadget.h>
+#include <linux/usb/otg.h>
 
 #include "ci13xxx_udc.h"
 
@@ -126,6 +127,9 @@ static struct {
 	size_t        size;   /* bank size */
 } hw_bank;
 
+/* MSM specific */
+#define ABS_AHBBURST        (0x0090UL)
+#define ABS_AHBMODE         (0x0098UL)
 /* UDC register map */
 #define ABS_CAPLENGTH       (0x100UL)
 #define ABS_HCCPARAMS       (0x108UL)
@@ -242,13 +246,7 @@ static u32 hw_ctest_and_write(u32 addr, u32 mask, u32 data)
 	return (reg & mask) >> ffs_nr(mask);
 }
 
-/**
- * hw_device_reset: resets chip (execute without interruption)
- * @base: register base address
- *
- * This function returns an error code
- */
-static int hw_device_reset(void __iomem *base)
+static int hw_device_init(void __iomem *base)
 {
 	u32 reg;
 
@@ -265,6 +263,28 @@ static int hw_device_reset(void __iomem *base)
 	hw_bank.size += CAP_LAST;
 	hw_bank.size /= sizeof(u32);
 
+	reg = hw_aread(ABS_DCCPARAMS, DCCPARAMS_DEN) >> ffs_nr(DCCPARAMS_DEN);
+	if (reg == 0 || reg > ENDPT_MAX)
+		return -ENODEV;
+
+	hw_ep_max = reg;   /* cache hw ENDPT_MAX */
+
+	/* setup lock mode ? */
+
+	/* ENDPTSETUPSTAT is '0' by default */
+
+	/* HCSPARAMS.bf.ppc SHOULD BE zero for device */
+
+	return 0;
+}
+/**
+ * hw_device_reset: resets chip (execute without interruption)
+ * @base: register base address
+ *
+ * This function returns an error code
+ */
+static int hw_device_reset(struct ci13xxx *udc)
+{
 	/* should flush & stop before reset */
 	hw_cwrite(CAP_ENDPTFLUSH, ~0, ~0);
 	hw_cwrite(CAP_USBCMD, USBCMD_RS, 0);
@@ -273,6 +293,14 @@ static int hw_device_reset(void __iomem *base)
 	while (hw_cread(CAP_USBCMD, USBCMD_RST))
 		udelay(10);             /* not RTOS friendly */
 
+
+	if (udc->udc_driver->notify_event)
+		udc->udc_driver->notify_event(udc,
+			CI13XXX_CONTROLLER_RESET_EVENT);
+
+	if (udc->udc_driver->flags && CI13XXX_DISABLE_STREAMING)
+		hw_cwrite(CAP_USBMODE, USBMODE_SDIS, USBMODE_SDIS);
+
 	/* USBMODE should be configured step by step */
 	hw_cwrite(CAP_USBMODE, USBMODE_CM, USBMODE_CM_IDLE);
 	hw_cwrite(CAP_USBMODE, USBMODE_CM, USBMODE_CM_DEVICE);
@@ -284,18 +312,6 @@ static int hw_device_reset(void __iomem *base)
 		return -ENODEV;
 	}
 
-	reg = hw_aread(ABS_DCCPARAMS, DCCPARAMS_DEN) >> ffs_nr(DCCPARAMS_DEN);
-	if (reg == 0 || reg > ENDPT_MAX)
-		return -ENODEV;
-
-	hw_ep_max = reg;   /* cache hw ENDPT_MAX */
-
-	/* setup lock mode ? */
-
-	/* ENDPTSETUPSTAT is '0' by default */
-
-	/* HCSPARAMS.bf.ppc SHOULD BE zero for device */
-
 	return 0;
 }
 
@@ -1551,8 +1567,6 @@ __acquires(mEp->lock)
  * Caller must hold lock
  */
 static int _gadget_stop_activity(struct usb_gadget *gadget)
-__releases(udc->lock)
-__acquires(udc->lock)
 {
 	struct usb_ep *ep;
 	struct ci13xxx    *udc = container_of(gadget, struct ci13xxx, gadget);
@@ -1564,8 +1578,6 @@ __acquires(udc->lock)
 	if (gadget == NULL)
 		return -EINVAL;
 
-	spin_unlock(udc->lock);
-
 	/* flush all endpoints */
 	gadget_for_each_ep(ep, gadget) {
 		usb_ep_fifo_flush(ep);
@@ -1585,8 +1597,6 @@ __acquires(udc->lock)
 		mEp->status = NULL;
 	}
 
-	spin_lock(udc->lock);
-
 	return 0;
 }
 
@@ -1615,6 +1625,7 @@ __acquires(udc->lock)
 
 	dbg_event(0xFF, "BUS RST", 0);
 
+	spin_unlock(udc->lock);
 	retval = _gadget_stop_activity(&udc->gadget);
 	if (retval)
 		goto done;
@@ -1623,7 +1634,6 @@ __acquires(udc->lock)
 	if (retval)
 		goto done;
 
-	spin_unlock(udc->lock);
 	retval = usb_ep_enable(&mEp->ep, &ctrl_endpt_desc);
 	if (!retval) {
 		mEp->status = usb_ep_alloc_request(&mEp->ep, GFP_ATOMIC);
@@ -2321,12 +2331,45 @@ static const struct usb_ep_ops usb_ep_ops = {
 /******************************************************************************
  * GADGET block
  *****************************************************************************/
+static int ci13xxx_vbus_session(struct usb_gadget *_gadget, int is_active)
+{
+	struct ci13xxx *udc = container_of(_gadget, struct ci13xxx, gadget);
+	unsigned long flags;
+	int gadget_ready = 0;
+
+	if (!(udc->udc_driver->flags & CI13XXX_PULLUP_ON_VBUS))
+		return -EOPNOTSUPP;
+
+	spin_lock_irqsave(udc->lock, flags);
+	udc->vbus_active = is_active;
+	if (udc->driver)
+		gadget_ready = 1;
+	spin_unlock_irqrestore(udc->lock, flags);
+
+	if (gadget_ready) {
+		if (is_active) {
+			hw_device_reset(udc);
+			hw_device_state(udc->ci13xxx_ep[0].qh[RX].dma);
+		} else {
+			hw_device_state(0);
+			if (udc->udc_driver->notify_event)
+				udc->udc_driver->notify_event(udc,
+				CI13XXX_CONTROLLER_STOPPED_EVENT);
+			_gadget_stop_activity(&udc->gadget);
+		}
+	}
+
+	return 0;
+}
+
 /**
  * Device operations part of the API to the USB controller hardware,
  * which don't involve endpoints (or i/o)
  * Check  "usb_gadget.h" for details
  */
-static const struct usb_gadget_ops usb_gadget_ops;
+static const struct usb_gadget_ops usb_gadget_ops = {
+	.vbus_session	= ci13xxx_vbus_session,
+};
 
 /**
  * usb_gadget_probe_driver: register a gadget driver
@@ -2379,7 +2422,6 @@ int usb_gadget_probe_driver(struct usb_gadget_driver *driver,
 	info("hw_ep_max = %d", hw_ep_max);
 
 	udc->driver = driver;
-	udc->gadget.ops        = NULL;
 	udc->gadget.dev.driver = NULL;
 
 	retval = 0;
@@ -2420,7 +2462,6 @@ int usb_gadget_probe_driver(struct usb_gadget_driver *driver,
 
 	/* bind gadget */
 	driver->driver.bus     = NULL;
-	udc->gadget.ops        = &usb_gadget_ops;
 	udc->gadget.dev.driver = &driver->driver;
 
 	spin_unlock_irqrestore(udc->lock, flags);
@@ -2428,11 +2469,19 @@ int usb_gadget_probe_driver(struct usb_gadget_driver *driver,
 	spin_lock_irqsave(udc->lock, flags);
 
 	if (retval) {
-		udc->gadget.ops        = NULL;
 		udc->gadget.dev.driver = NULL;
 		goto done;
 	}
 
+	if (udc->udc_driver->flags & CI13XXX_PULLUP_ON_VBUS) {
+		if (udc->vbus_active) {
+			if (udc->udc_driver->flags & CI13XXX_REGS_SHARED)
+				hw_device_reset(udc);
+		} else {
+			goto done;
+		}
+	}
+
 	retval = hw_device_state(udc->ci13xxx_ep[0].qh[RX].dma);
 
  done:
@@ -2466,19 +2515,21 @@ int usb_gadget_unregister_driver(struct usb_gadget_driver *driver)
 
 	spin_lock_irqsave(udc->lock, flags);
 
-	hw_device_state(0);
-
-	/* unbind gadget */
-	if (udc->gadget.ops != NULL) {
+	if (!(udc->udc_driver->flags & CI13XXX_PULLUP_ON_VBUS) ||
+			udc->vbus_active) {
+		hw_device_state(0);
+		if (udc->udc_driver->notify_event)
+			udc->udc_driver->notify_event(udc,
+			CI13XXX_CONTROLLER_STOPPED_EVENT);
 		_gadget_stop_activity(&udc->gadget);
+	}
 
-		spin_unlock_irqrestore(udc->lock, flags);
-		driver->unbind(&udc->gadget);               /* MAY SLEEP */
-		spin_lock_irqsave(udc->lock, flags);
+	/* unbind gadget */
+	spin_unlock_irqrestore(udc->lock, flags);
+	driver->unbind(&udc->gadget);               /* MAY SLEEP */
+	spin_lock_irqsave(udc->lock, flags);
 
-		udc->gadget.ops        = NULL;
-		udc->gadget.dev.driver = NULL;
-	}
+	udc->gadget.dev.driver = NULL;
 
 	/* free resources */
 	for (i = 0; i < hw_ep_max; i++) {
@@ -2535,6 +2586,14 @@ static irqreturn_t udc_irq(void)
 	}
 
 	spin_lock(udc->lock);
+
+	if (udc->udc_driver->flags & CI13XXX_REGS_SHARED) {
+		if (hw_cread(CAP_USBMODE, USBMODE_CM) !=
+				USBMODE_CM_DEVICE) {
+			spin_unlock(udc->lock);
+			return IRQ_NONE;
+		}
+	}
 	intr = hw_test_and_clear_intr_active();
 	if (intr) {
 		isr_statistics.hndl.buf[isr_statistics.hndl.idx++] = intr;
@@ -2593,14 +2652,16 @@ static void udc_release(struct device *dev)
  * No interrupts active, the IRQ has not been requested yet
  * Kernel assumes 32-bit DMA operations by default, no need to dma_set_mask
  */
-static int udc_probe(struct device *dev, void __iomem *regs, const char *name)
+static int udc_probe(struct ci13xxx_udc_driver *driver, struct device *dev,
+		void __iomem *regs)
 {
 	struct ci13xxx *udc;
 	int retval = 0;
 
 	trace("%p, %p, %p", dev, regs, name);
 
-	if (dev == NULL || regs == NULL || name == NULL)
+	if (dev == NULL || regs == NULL || driver == NULL ||
+			driver->name == NULL)
 		return -EINVAL;
 
 	udc = kzalloc(sizeof(struct ci13xxx), GFP_KERNEL);
@@ -2608,16 +2669,14 @@ static int udc_probe(struct device *dev, void __iomem *regs, const char *name)
 		return -ENOMEM;
 
 	udc->lock = &udc_lock;
+	udc->regs = regs;
+	udc->udc_driver = driver;
 
-	retval = hw_device_reset(regs);
-	if (retval)
-		goto done;
-
-	udc->gadget.ops          = NULL;
+	udc->gadget.ops          = &usb_gadget_ops;
 	udc->gadget.speed        = USB_SPEED_UNKNOWN;
 	udc->gadget.is_dualspeed = 1;
 	udc->gadget.is_otg       = 0;
-	udc->gadget.name         = name;
+	udc->gadget.name         = driver->name;
 
 	INIT_LIST_HEAD(&udc->gadget.ep_list);
 	udc->gadget.ep0 = NULL;
@@ -2628,23 +2687,57 @@ static int udc_probe(struct device *dev, void __iomem *regs, const char *name)
 	udc->gadget.dev.parent   = dev;
 	udc->gadget.dev.release  = udc_release;
 
+	retval = hw_device_init(regs);
+	if (retval < 0)
+		goto free_udc;
+
+	udc->transceiver = otg_get_transceiver();
+
+	if (udc->udc_driver->flags & CI13XXX_REQUIRE_TRANSCEIVER) {
+		if (udc->transceiver == NULL) {
+			retval = -ENODEV;
+			goto free_udc;
+		}
+	}
+
+	if (!(udc->udc_driver->flags & CI13XXX_REGS_SHARED)) {
+		retval = hw_device_reset(udc);
+		if (retval)
+			goto put_transceiver;
+	}
+
 	retval = device_register(&udc->gadget.dev);
-	if (retval)
-		goto done;
+	if (retval) {
+		put_device(&udc->gadget.dev);
+		goto put_transceiver;
+	}
 
 #ifdef CONFIG_USB_GADGET_DEBUG_FILES
 	retval = dbg_create_files(&udc->gadget.dev);
 #endif
-	if (retval) {
-		device_unregister(&udc->gadget.dev);
-		goto done;
+	if (retval)
+		goto unreg_device;
+
+	if (udc->transceiver) {
+		retval = otg_set_peripheral(udc->transceiver, &udc->gadget);
+		if (retval)
+			goto remove_dbg;
 	}
 
 	_udc = udc;
 	return retval;
 
- done:
 	err("error = %i", retval);
+remove_dbg:
+#ifdef CONFIG_USB_GADGET_DEBUG_FILES
+	dbg_remove_files(&udc->gadget.dev);
+#endif
+unreg_device:
+	device_unregister(&udc->gadget.dev);
+put_transceiver:
+	if (udc->transceiver)
+		otg_put_transceiver(udc->transceiver);
+free_udc:
 	kfree(udc);
 	_udc = NULL;
 	return retval;
@@ -2664,6 +2757,10 @@ static void udc_remove(void)
 		return;
 	}
 
+	if (udc->transceiver) {
+		otg_set_peripheral(udc->transceiver, &udc->gadget);
+		otg_put_transceiver(udc->transceiver);
+	}
 #ifdef CONFIG_USB_GADGET_DEBUG_FILES
 	dbg_remove_files(&udc->gadget.dev);
 #endif
diff --git a/drivers/usb/gadget/ci13xxx_udc.h b/drivers/usb/gadget/ci13xxx_udc.h
index 4026e9c..4fd1931 100644
--- a/drivers/usb/gadget/ci13xxx_udc.h
+++ b/drivers/usb/gadget/ci13xxx_udc.h
@@ -97,9 +97,24 @@ struct ci13xxx_ep {
 	struct dma_pool                       *td_pool;
 };
 
+struct ci13xxx;
+struct ci13xxx_udc_driver {
+	const char	*name;
+	unsigned long	 flags;
+#define CI13XXX_REGS_SHARED		BIT(0)
+#define CI13XXX_REQUIRE_TRANSCEIVER	BIT(1)
+#define CI13XXX_PULLUP_ON_VBUS		BIT(2)
+#define CI13XXX_DISABLE_STREAMING	BIT(3)
+
+#define CI13XXX_CONTROLLER_RESET_EVENT		0
+#define CI13XXX_CONTROLLER_STOPPED_EVENT	1
+	void	(*notify_event) (struct ci13xxx *udc, unsigned event);
+};
+
 /* CI13XXX UDC descriptor & global resources */
 struct ci13xxx {
 	spinlock_t		  *lock;      /* ctrl register bank access */
+	void __iomem              *regs;      /* registers address space */
 
 	struct dma_pool           *qh_pool;   /* DMA pool for queue heads */
 	struct dma_pool           *td_pool;   /* DMA pool for transfer descs */
@@ -108,6 +123,9 @@ struct ci13xxx {
 	struct ci13xxx_ep          ci13xxx_ep[ENDPT_MAX]; /* extended endpts */
 
 	struct usb_gadget_driver  *driver;     /* 3rd party gadget driver */
+	struct ci13xxx_udc_driver *udc_driver; /* device controller driver */
+	int                        vbus_active; /* is VBUS active */
+	struct otg_transceiver    *transceiver; /* Transceiver struct */
 };
 
 /******************************************************************************
@@ -157,6 +175,7 @@ struct ci13xxx {
 #define    USBMODE_CM_DEVICE  (0x02UL <<  0)
 #define    USBMODE_CM_HOST    (0x03UL <<  0)
 #define USBMODE_SLOM          BIT(3)
+#define USBMODE_SDIS          BIT(4)
 
 /* ENDPTCTRL */
 #define ENDPTCTRL_RXS         BIT(0)
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 09/11] USB: gadget: Add USB controller driver for MSM SoC
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (7 preceding siblings ...)
  2010-12-07 12:24 ` [PATCH V3 08/11] USB: gadget: Introduce ci13xxx_udc_driver struct Pavankumar Kondeti
@ 2010-12-07 12:24 ` Pavankumar Kondeti
  2010-12-07 12:24 ` [PATCH V3 10/11] USB: gadget: Implement runtime PM for ci13xxx gadget Pavankumar Kondeti
                   ` (2 subsequent siblings)
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:24 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

MSM SoC has chipidea USB controller. So use ci13xxx_udc core.
This driver depends on transceiver driver for clock control,
PHY initialization, VBUS detection.  Register for notify_event
callback to perform MSM specific quirks after controller is reset
and stopped.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/gadget/Kconfig        |   21 ++++++
 drivers/usb/gadget/Makefile       |    1 +
 drivers/usb/gadget/ci13xxx_msm.c  |  130 +++++++++++++++++++++++++++++++++++++
 drivers/usb/gadget/gadget_chips.h |    8 ++
 4 files changed, 160 insertions(+), 0 deletions(-)
 create mode 100644 drivers/usb/gadget/ci13xxx_msm.c

diff --git a/drivers/usb/gadget/Kconfig b/drivers/usb/gadget/Kconfig
index 6bcbcb0..7201b4e 100644
--- a/drivers/usb/gadget/Kconfig
+++ b/drivers/usb/gadget/Kconfig
@@ -531,6 +531,27 @@ config USB_EG20T
 	default USB_GADGET
 	select USB_GADGET_SELECTED
 
+config USB_GADGET_CI13XXX_MSM
+	boolean "MIPS USB CI13xxx for MSM"
+	depends on ARCH_MSM
+	select USB_GADGET_DUALSPEED
+	select USB_MSM_OTG_72K
+	help
+	  MSM SoC has chipidea USB controller.  This driver uses
+	  ci13xxx_udc core.
+	  This driver depends on OTG driver for PHY initialization,
+	  clock management, powering up VBUS, and power management.
+
+	  Say "y" to link the driver statically, or "m" to build a
+	  dynamically linked module called "ci13xxx_msm" and force all
+	  gadget drivers to also be dynamically linked.
+
+config USB_CI13XXX_MSM
+	tristate
+	depends on USB_GADGET_CI13XXX_MSM
+	default USB_GADGET
+	select USB_GADGET_SELECTED
+
 #
 # LAST -- dummy/emulated controller
 #
diff --git a/drivers/usb/gadget/Makefile b/drivers/usb/gadget/Makefile
index f53fda7..fbf5db4 100644
--- a/drivers/usb/gadget/Makefile
+++ b/drivers/usb/gadget/Makefile
@@ -27,6 +27,7 @@ obj-$(CONFIG_USB_LANGWELL)	+= langwell_udc.o
 obj-$(CONFIG_USB_EG20T)		+= pch_udc.o
 obj-$(CONFIG_USB_PXA_U2O)	+= mv_udc.o
 mv_udc-y			:= mv_udc_core.o mv_udc_phy.o
+obj-$(CONFIG_USB_CI13XXX_MSM)	+= ci13xxx_msm.o
 
 #
 # USB gadget drivers
diff --git a/drivers/usb/gadget/ci13xxx_msm.c b/drivers/usb/gadget/ci13xxx_msm.c
new file mode 100644
index 0000000..c497337
--- /dev/null
+++ b/drivers/usb/gadget/ci13xxx_msm.c
@@ -0,0 +1,130 @@
+/* Copyright (c) 2010, Code Aurora Forum. 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 version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * 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.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA
+ * 02110-1301, USA.
+ *
+ */
+
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/usb/msm_hsusb_hw.h>
+#include <linux/usb/ulpi.h>
+
+#include "ci13xxx_udc.c"
+
+#define MSM_USB_BASE	(udc->regs)
+
+static irqreturn_t msm_udc_irq(int irq, void *data)
+{
+	return udc_irq();
+}
+
+static void ci13xxx_msm_notify_event(struct ci13xxx *udc, unsigned event)
+{
+	struct device *dev = udc->gadget.dev.parent;
+	int val;
+
+	switch (event) {
+	case CI13XXX_CONTROLLER_RESET_EVENT:
+		dev_dbg(dev, "CI13XXX_CONTROLLER_RESET_EVENT received\n");
+		writel(0, USB_AHBBURST);
+		writel(0, USB_AHBMODE);
+		break;
+	case CI13XXX_CONTROLLER_STOPPED_EVENT:
+		dev_dbg(dev, "CI13XXX_CONTROLLER_STOPPED_EVENT received\n");
+		/*
+		 * Put the transceiver in non-driving mode. Otherwise host
+		 * may not detect soft-disconnection.
+		 */
+		val = otg_io_read(udc->transceiver, ULPI_FUNC_CTRL);
+		val &= ~ULPI_FUNC_CTRL_OPMODE_MASK;
+		val |= ULPI_FUNC_CTRL_OPMODE_NONDRIVING;
+		otg_io_write(udc->transceiver, val, ULPI_FUNC_CTRL);
+		break;
+	default:
+		dev_dbg(dev, "unknown ci13xxx_udc event\n");
+		break;
+	}
+}
+
+static struct ci13xxx_udc_driver ci13xxx_msm_udc_driver = {
+	.name			= "ci13xxx_msm",
+	.flags			= CI13XXX_REGS_SHARED |
+				  CI13XXX_REQUIRE_TRANSCEIVER |
+				  CI13XXX_PULLUP_ON_VBUS |
+				  CI13XXX_DISABLE_STREAMING,
+
+	.notify_event		= ci13xxx_msm_notify_event,
+};
+
+static int ci13xxx_msm_probe(struct platform_device *pdev)
+{
+	struct resource *res;
+	void __iomem *regs;
+	int irq;
+	int ret;
+
+	dev_dbg(&pdev->dev, "ci13xxx_msm_probe\n");
+
+	res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+	if (!res) {
+		dev_err(&pdev->dev, "failed to get platform resource mem\n");
+		return -ENXIO;
+	}
+
+	regs = ioremap(res->start, resource_size(res));
+	if (!regs) {
+		dev_err(&pdev->dev, "ioremap failed\n");
+		return -ENOMEM;
+	}
+
+	ret = udc_probe(&ci13xxx_msm_udc_driver, &pdev->dev, regs);
+	if (ret < 0) {
+		dev_err(&pdev->dev, "udc_probe failed\n");
+		goto iounmap;
+	}
+
+	irq = platform_get_irq(pdev, 0);
+	if (irq < 0) {
+		dev_err(&pdev->dev, "IRQ not found\n");
+		ret = -ENXIO;
+		goto udc_remove;
+	}
+
+	ret = request_irq(irq, msm_udc_irq, IRQF_SHARED, pdev->name, pdev);
+	if (ret < 0) {
+		dev_err(&pdev->dev, "request_irq failed\n");
+		goto udc_remove;
+	}
+
+	return 0;
+
+udc_remove:
+	udc_remove();
+iounmap:
+	iounmap(regs);
+
+	return ret;
+}
+
+static struct platform_driver ci13xxx_msm_driver = {
+	.probe = ci13xxx_msm_probe,
+	.driver = { .name = "msm_hsusb", },
+};
+
+static int __init ci13xxx_msm_init(void)
+{
+	return platform_driver_register(&ci13xxx_msm_driver);
+}
+module_init(ci13xxx_msm_init);
diff --git a/drivers/usb/gadget/gadget_chips.h b/drivers/usb/gadget/gadget_chips.h
index 3093ebb..ad2114e 100644
--- a/drivers/usb/gadget/gadget_chips.h
+++ b/drivers/usb/gadget/gadget_chips.h
@@ -148,6 +148,12 @@
 #define	gadget_is_pch(g)	0
 #endif
 
+#ifdef CONFIG_USB_GADGET_CI13XXX_MSM
+#define gadget_is_ci13xxx_msm(g)	(!strcmp("ci13xxx_msm", (g)->name))
+#else
+#define gadget_is_ci13xxx_msm(g)	0
+#endif
+
 /**
  * usb_gadget_controller_number - support bcdDevice id convention
  * @gadget: the controller being driven
@@ -207,6 +213,8 @@ static inline int usb_gadget_controller_number(struct usb_gadget *gadget)
 		return 0x26;
 	else if (gadget_is_pch(gadget))
 		return 0x27;
+	else if (gadget_is_ci13xxx_msm(gadget))
+		return 0x28;
 	return -ENOENT;
 }
 
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 10/11] USB: gadget: Implement runtime PM for ci13xxx gadget
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (8 preceding siblings ...)
  2010-12-07 12:24 ` [PATCH V3 09/11] USB: gadget: Add USB controller driver for MSM SoC Pavankumar Kondeti
@ 2010-12-07 12:24 ` Pavankumar Kondeti
  2010-12-07 12:24 ` [PATCH V3 11/11] USB: gadget: Implement runtime PM for MSM bus glue driver Pavankumar Kondeti
  2010-12-09  7:07 ` [PATCH V3 00/11] Add MSM USB controller driver Pavan Kondeti
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:24 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

The actual suspend/resume work is delegated to bus glue driver, which
is responsible for putting hardware in low power mode.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/gadget/ci13xxx_udc.c |   10 ++++++++++
 1 files changed, 10 insertions(+), 0 deletions(-)

diff --git a/drivers/usb/gadget/ci13xxx_udc.c b/drivers/usb/gadget/ci13xxx_udc.c
index c10d1ae..f200e47 100644
--- a/drivers/usb/gadget/ci13xxx_udc.c
+++ b/drivers/usb/gadget/ci13xxx_udc.c
@@ -60,6 +60,7 @@
 #include <linux/irq.h>
 #include <linux/kernel.h>
 #include <linux/slab.h>
+#include <linux/pm_runtime.h>
 #include <linux/usb/ch9.h>
 #include <linux/usb/gadget.h>
 #include <linux/usb/otg.h>
@@ -2348,6 +2349,7 @@ static int ci13xxx_vbus_session(struct usb_gadget *_gadget, int is_active)
 
 	if (gadget_ready) {
 		if (is_active) {
+			pm_runtime_get_sync(&_gadget->dev);
 			hw_device_reset(udc);
 			hw_device_state(udc->ci13xxx_ep[0].qh[RX].dma);
 		} else {
@@ -2356,6 +2358,7 @@ static int ci13xxx_vbus_session(struct usb_gadget *_gadget, int is_active)
 				udc->udc_driver->notify_event(udc,
 				CI13XXX_CONTROLLER_STOPPED_EVENT);
 			_gadget_stop_activity(&udc->gadget);
+			pm_runtime_put_sync(&_gadget->dev);
 		}
 	}
 
@@ -2473,16 +2476,20 @@ int usb_gadget_probe_driver(struct usb_gadget_driver *driver,
 		goto done;
 	}
 
+	pm_runtime_get_sync(&udc->gadget.dev);
 	if (udc->udc_driver->flags & CI13XXX_PULLUP_ON_VBUS) {
 		if (udc->vbus_active) {
 			if (udc->udc_driver->flags & CI13XXX_REGS_SHARED)
 				hw_device_reset(udc);
 		} else {
+			pm_runtime_put_sync(&udc->gadget.dev);
 			goto done;
 		}
 	}
 
 	retval = hw_device_state(udc->ci13xxx_ep[0].qh[RX].dma);
+	if (retval)
+		pm_runtime_put_sync(&udc->gadget.dev);
 
  done:
 	spin_unlock_irqrestore(udc->lock, flags);
@@ -2522,6 +2529,7 @@ int usb_gadget_unregister_driver(struct usb_gadget_driver *driver)
 			udc->udc_driver->notify_event(udc,
 			CI13XXX_CONTROLLER_STOPPED_EVENT);
 		_gadget_stop_activity(&udc->gadget);
+		pm_runtime_put(&udc->gadget.dev);
 	}
 
 	/* unbind gadget */
@@ -2723,6 +2731,8 @@ static int udc_probe(struct ci13xxx_udc_driver *driver, struct device *dev,
 		if (retval)
 			goto remove_dbg;
 	}
+	pm_runtime_no_callbacks(&udc->gadget.dev);
+	pm_runtime_enable(&udc->gadget.dev);
 
 	_udc = udc;
 	return retval;
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* [PATCH V3 11/11] USB: gadget: Implement runtime PM for MSM bus glue driver
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (9 preceding siblings ...)
  2010-12-07 12:24 ` [PATCH V3 10/11] USB: gadget: Implement runtime PM for ci13xxx gadget Pavankumar Kondeti
@ 2010-12-07 12:24 ` Pavankumar Kondeti
  2010-12-09  7:07 ` [PATCH V3 00/11] Add MSM USB controller driver Pavan Kondeti
  11 siblings, 0 replies; 13+ messages in thread
From: Pavankumar Kondeti @ 2010-12-07 12:24 UTC (permalink / raw)
  To: linux-usb, greg
  Cc: linux-arm-msm, swetland, arve, benoitgoby, lockwood, dima,
	Pavankumar Kondeti

OTG driver takes care of putting hardware in low power mode.  Hence
not registered for any runtime PM callbacks.

Signed-off-by: Pavankumar Kondeti <pkondeti@codeaurora.org>
---
 drivers/usb/gadget/ci13xxx_msm.c |    4 ++++
 1 files changed, 4 insertions(+), 0 deletions(-)

diff --git a/drivers/usb/gadget/ci13xxx_msm.c b/drivers/usb/gadget/ci13xxx_msm.c
index c497337..139ac94 100644
--- a/drivers/usb/gadget/ci13xxx_msm.c
+++ b/drivers/usb/gadget/ci13xxx_msm.c
@@ -18,6 +18,7 @@
 
 #include <linux/module.h>
 #include <linux/platform_device.h>
+#include <linux/pm_runtime.h>
 #include <linux/usb/msm_hsusb_hw.h>
 #include <linux/usb/ulpi.h>
 
@@ -108,6 +109,9 @@ static int ci13xxx_msm_probe(struct platform_device *pdev)
 		goto udc_remove;
 	}
 
+	pm_runtime_no_callbacks(&pdev->dev);
+	pm_runtime_enable(&pdev->dev);
+
 	return 0;
 
 udc_remove:
-- 
1.7.1
--
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.


^ permalink raw reply related	[flat|nested] 13+ messages in thread

* Re: [PATCH V3 00/11] Add MSM USB controller driver
  2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
                   ` (10 preceding siblings ...)
  2010-12-07 12:24 ` [PATCH V3 11/11] USB: gadget: Implement runtime PM for MSM bus glue driver Pavankumar Kondeti
@ 2010-12-09  7:07 ` Pavan Kondeti
  11 siblings, 0 replies; 13+ messages in thread
From: Pavan Kondeti @ 2010-12-09  7:07 UTC (permalink / raw)
  To: Pavankumar Kondeti
  Cc: linux-usb, greg, linux-arm-msm, swetland, arve, benoitgoby,
	lockwood, dima

Hi All,

On 12/7/2010 5:53 PM, Pavankumar Kondeti wrote:
> This patch series adds USB peripheral, host and OTG (role switch based
> on Id pin status) support for MSM SoC. The peripheral controller driver patches
> include splitting ci13xxx_udc into core and bus glue layers. Peripheral
> and Host controller drivers depend on Transceiver driver for clock management
> and low power mode. Peripheral and Host devices are made children of OTG
> device when devices are registered. Runtime PM functions are used by
> Peripheral and Host controller drivers to tell their state to transceiver
> driver which actually takes care of putting hardware into low power mode.
> 
> Change from V2:
> 1. Added core_clock in transceiver driver. This clock is introduced from MSM7x30
> onwards to remove dependency on AXI bus frequency.
> 2. Use debugfs instead of sysfs for role switching option.
> 3. pm_runtime_nocallbacks() is used instead for nop runtime PM methods.
> 4. Peripheral controller driver makes use of ci13xxx_udc core.
> 
> Pavankumar Kondeti (11):
>   USB: Add MSM OTG Controller driver
>   USB: EHCI: Add MSM Host Controller driver
>   USB: EHCI: msm: Add support for power management
>   USB: OTG: msm: Add support for power management
>   USB: gadget: Separate out PCI bus code from ci13xxx_udc
>   USB: gadget: Fix "scheduling while atomic" bugs in ci13xxx_udc
>   USB: gadget: Initialize ci13xxx gadget device's coherent DMA mask
>   USB: gadget: Introduce ci13xxx_udc_driver struct
>   USB: gadget: Add USB controller driver for MSM SoC
>   USB: gadget: Implement runtime PM for ci13xxx gadget
>   USB: gadget: Implement runtime PM for MSM bus glue driver
> 

I have received feedback to re-use the ci13xxx_udc driver when I
submitted a new device controller driver (msm72k_udc.c) for MSM SoC.
http://www.mail-archive.com/linux-arm-msm@vger.kernel.org/msg01111.html

I have split ci13xxx_udc into generic ci13xxx_udc core and PCI bus glue
driver. I have added a new bus glue driver for MSM. We need this bus
glue driver to perform MSM specific quirks after controller is reset and
stopped (i.e after disabling pull-up in device mode). I have verified
ci13xxx_udc driver on MSM SoC. I don't have PCI ci13xxx hardware to test
ci13xxx on PCI. I have not made any changes in PCI driver. So in theory,
these patches should not break PCI driver. It would be really nice if
any one can test 5-11 patches of this series
on PCI ci13xxx hardware.

Thanks in advance,
Pavan

-- 
Sent by a consultant of the Qualcomm Innovation Center, Inc.
The Qualcomm Innovation Center, Inc. is a member of the Code Aurora Forum.

^ permalink raw reply	[flat|nested] 13+ messages in thread

end of thread, other threads:[~2010-12-09  7:07 UTC | newest]

Thread overview: 13+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2010-12-07 12:23 [PATCH V3 00/11] Add MSM USB controller driver Pavankumar Kondeti
2010-12-07 12:23 ` [PATCH V3 01/11] USB: Add MSM OTG Controller driver Pavankumar Kondeti
2010-12-07 12:23 ` [PATCH V3 02/11] USB: EHCI: Add MSM Host " Pavankumar Kondeti
2010-12-07 12:23 ` [PATCH V3 03/11] USB: EHCI: msm: Add support for power management Pavankumar Kondeti
2010-12-07 12:23 ` [PATCH V3 04/11] USB: OTG: " Pavankumar Kondeti
2010-12-07 12:23 ` [PATCH V3 05/11] USB: gadget: Separate out PCI bus code from ci13xxx_udc Pavankumar Kondeti
2010-12-07 12:24 ` [PATCH V3 06/11] USB: gadget: Fix "scheduling while atomic" bugs in ci13xxx_udc Pavankumar Kondeti
2010-12-07 12:24 ` [PATCH V3 07/11] USB: gadget: Initialize ci13xxx gadget device's coherent DMA mask Pavankumar Kondeti
2010-12-07 12:24 ` [PATCH V3 08/11] USB: gadget: Introduce ci13xxx_udc_driver struct Pavankumar Kondeti
2010-12-07 12:24 ` [PATCH V3 09/11] USB: gadget: Add USB controller driver for MSM SoC Pavankumar Kondeti
2010-12-07 12:24 ` [PATCH V3 10/11] USB: gadget: Implement runtime PM for ci13xxx gadget Pavankumar Kondeti
2010-12-07 12:24 ` [PATCH V3 11/11] USB: gadget: Implement runtime PM for MSM bus glue driver Pavankumar Kondeti
2010-12-09  7:07 ` [PATCH V3 00/11] Add MSM USB controller driver Pavan Kondeti

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).