summaryrefslogtreecommitdiffstats
path: root/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'drivers')
-rw-r--r--drivers/Kconfig1
-rw-r--r--drivers/Makefile1
-rw-r--r--drivers/base/driver.c22
-rw-r--r--drivers/bus/mvebu-mbus.c6
-rw-r--r--drivers/firmware/Kconfig14
-rw-r--r--drivers/firmware/Makefile2
-rw-r--r--drivers/firmware/altera_serial.c315
-rw-r--r--drivers/firmware/socfpga.c440
-rw-r--r--drivers/i2c/busses/i2c-at91.c98
-rw-r--r--drivers/i2c/busses/i2c-omap.c20
-rw-r--r--drivers/input/imx_keypad.c2
-rw-r--r--drivers/mci/atmel_mci.c1
-rw-r--r--drivers/mtd/devices/Kconfig5
-rw-r--r--drivers/mtd/devices/Makefile1
-rw-r--r--drivers/mtd/devices/mtdram.c122
-rw-r--r--drivers/mtd/nand/Kconfig2
-rw-r--r--drivers/mtd/nand/atmel_nand.c121
-rw-r--r--drivers/mtd/nor/cfi_flash.c4
-rw-r--r--drivers/net/ethoc.c6
-rw-r--r--drivers/net/macb.c6
-rw-r--r--drivers/net/phy/marvell.c17
-rw-r--r--drivers/net/phy/micrel.c4
-rw-r--r--drivers/net/phy/phy.c142
-rw-r--r--drivers/net/usb/asix.c123
-rw-r--r--drivers/of/Kconfig2
-rw-r--r--drivers/of/base.c77
-rw-r--r--drivers/of/fdt.c2
-rw-r--r--drivers/pinctrl/Kconfig24
-rw-r--r--drivers/pinctrl/mvebu/Kconfig8
-rw-r--r--drivers/pinctrl/pinctrl-rockchip.c3
-rw-r--r--drivers/pinctrl/pinctrl.c6
-rw-r--r--drivers/usb/Kconfig2
-rw-r--r--drivers/usb/Makefile1
-rw-r--r--drivers/usb/core/of.c1
-rw-r--r--drivers/usb/gadget/Kconfig12
-rw-r--r--drivers/usb/gadget/at91_udc.c23
-rw-r--r--drivers/usb/gadget/dfu.c1
-rw-r--r--drivers/usb/gadget/f_fastboot.c1
-rw-r--r--drivers/usb/gadget/fsl_udc.c44
-rw-r--r--drivers/usb/gadget/pxa27x_udc.c27
-rw-r--r--drivers/usb/gadget/udc-core.c34
-rw-r--r--drivers/usb/imx/chipidea-imx.c1
-rw-r--r--drivers/usb/musb/Kconfig29
-rw-r--r--drivers/usb/musb/Makefile11
-rw-r--r--drivers/usb/musb/am35x-phy-control.h21
-rw-r--r--drivers/usb/musb/musb_am335x.c29
-rw-r--r--drivers/usb/musb/musb_barebox.c146
-rw-r--r--drivers/usb/musb/musb_core.c1156
-rw-r--r--drivers/usb/musb/musb_core.h585
-rw-r--r--drivers/usb/musb/musb_dma.h194
-rw-r--r--drivers/usb/musb/musb_dsps.c464
-rw-r--r--drivers/usb/musb/musb_gadget.c1308
-rw-r--r--drivers/usb/musb/musb_gadget.h147
-rw-r--r--drivers/usb/musb/musb_gadget_ep0.c1079
-rw-r--r--drivers/usb/musb/musb_host.c1749
-rw-r--r--drivers/usb/musb/musb_host.h258
-rw-r--r--drivers/usb/musb/musb_io.h122
-rw-r--r--drivers/usb/musb/musb_regs.h652
-rw-r--r--drivers/usb/musb/phy-am335x-control.c168
-rw-r--r--drivers/usb/musb/phy-am335x.c86
-rw-r--r--drivers/usb/musb/phy-am335x.h6
61 files changed, 9673 insertions, 281 deletions
diff --git a/drivers/Kconfig b/drivers/Kconfig
index d38032c0e6..e126f62c8f 100644
--- a/drivers/Kconfig
+++ b/drivers/Kconfig
@@ -29,5 +29,6 @@ source "drivers/regulator/Kconfig"
source "drivers/reset/Kconfig"
source "drivers/pci/Kconfig"
source "drivers/rtc/Kconfig"
+source "drivers/firmware/Kconfig"
endmenu
diff --git a/drivers/Makefile b/drivers/Makefile
index 4591f9a408..cf42190b7b 100644
--- a/drivers/Makefile
+++ b/drivers/Makefile
@@ -28,3 +28,4 @@ obj-$(CONFIG_REGULATOR) += regulator/
obj-$(CONFIG_RESET_CONTROLLER) += reset/
obj-$(CONFIG_PCI) += pci/
obj-y += rtc/
+obj-$(CONFIG_FIRMWARE) += firmware/
diff --git a/drivers/base/driver.c b/drivers/base/driver.c
index e024024616..e0125a1b92 100644
--- a/drivers/base/driver.c
+++ b/drivers/base/driver.c
@@ -383,28 +383,6 @@ const char *dev_id(const struct device_d *dev)
return buf;
}
-int dev_printf(int level, const struct device_d *dev, const char *format, ...)
-{
- va_list args;
- int ret = 0;
-
- if (level > barebox_loglevel)
- return 0;
-
- if (dev->driver && dev->driver->name)
- ret += printf("%s ", dev->driver->name);
-
- ret += printf("%s: ", dev_name(dev));
-
- va_start(args, format);
-
- ret += vprintf(format, args);
-
- va_end(args);
-
- return ret;
-}
-
void devices_shutdown(void)
{
struct device_d *dev;
diff --git a/drivers/bus/mvebu-mbus.c b/drivers/bus/mvebu-mbus.c
index b7f78367d4..9dc43011b9 100644
--- a/drivers/bus/mvebu-mbus.c
+++ b/drivers/bus/mvebu-mbus.c
@@ -744,6 +744,7 @@ static int mvebu_mbus_init(void)
postcore_initcall(mvebu_mbus_init);
struct mbus_range {
+ const char *compatible;
u32 mbusid;
u32 remap;
struct list_head list;
@@ -752,10 +753,11 @@ struct mbus_range {
#define MBUS_ID(t,a) (((t) << 24) | ((attr) << 16))
static LIST_HEAD(mbus_ranges);
-void mvebu_mbus_add_range(u8 target, u8 attr, u32 remap)
+void mvebu_mbus_add_range(const char *compatible, u8 target, u8 attr, u32 remap)
{
struct mbus_range *r = xzalloc(sizeof(*r));
+ r->compatible = strdup(compatible);
r->mbusid = MBUS_ID(target, attr);
r->remap = remap;
list_add_tail(&r->list, &mbus_ranges);
@@ -811,6 +813,8 @@ static int mvebu_mbus_of_fixup(struct device_node *root, void *context)
continue;
list_for_each_entry(r, &mbus_ranges, list) {
+ if (!of_machine_is_compatible(r->compatible))
+ continue;
if (r->mbusid == mbusid)
ranges[n + na + pa - 1] = r->remap;
}
diff --git a/drivers/firmware/Kconfig b/drivers/firmware/Kconfig
new file mode 100644
index 0000000000..5866063251
--- /dev/null
+++ b/drivers/firmware/Kconfig
@@ -0,0 +1,14 @@
+menu "Firmware Drivers"
+
+config FIRMWARE_ALTERA_SERIAL
+ bool "Altera SPI programming"
+ depends on OFDEVICE
+ select FIRMWARE
+ help
+ Programming an Altera FPGA via a few GPIOs for the control lines and
+ MOSI, MISO and clock from an SPI interface for the data lines
+
+config FIRMWARE_ALTERA_SOCFPGA
+ bool "Altera SoCFPGA fpga loader"
+
+endmenu
diff --git a/drivers/firmware/Makefile b/drivers/firmware/Makefile
new file mode 100644
index 0000000000..c3a3c34004
--- /dev/null
+++ b/drivers/firmware/Makefile
@@ -0,0 +1,2 @@
+obj-$(CONFIG_FIRMWARE_ALTERA_SERIAL) += altera_serial.o
+obj-$(CONFIG_FIRMWARE_ALTERA_SOCFPGA) += socfpga.o
diff --git a/drivers/firmware/altera_serial.c b/drivers/firmware/altera_serial.c
new file mode 100644
index 0000000000..23ba3b00a4
--- /dev/null
+++ b/drivers/firmware/altera_serial.c
@@ -0,0 +1,315 @@
+/*
+ * Copyright (c) 2013 Juergen Beisert <kernel@pengutronix.de>, Pengutronix
+ *
+ * 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.
+ */
+
+#include <common.h>
+#include <init.h>
+#include <driver.h>
+#include <firmware.h>
+#include <of_gpio.h>
+#include <xfuncs.h>
+#include <malloc.h>
+#include <gpio.h>
+#include <clock.h>
+#include <spi/spi.h>
+
+#include <fcntl.h>
+#include <fs.h>
+
+/*
+ * Physical requirements:
+ * - three free GPIOs for the signals nCONFIG, CONFIGURE_DONE, nSTATUS
+ * - 32 bit per word, LSB first capable SPI master (MOSI + clock)
+ *
+ * Example how to configure this driver via device tree
+ *
+ * fpga@0 {
+ * compatible = "altr,fpga-passive-serial";
+ * nstat-gpio = <&gpio4 18 0>;
+ * confd-gpio = <&gpio4 19 0>;
+ * nconfig-gpio = <&gpio4 20 0>;
+ * spi-max-frequency = <10000000>;
+ * reg = <0>;
+ * };
+ */
+
+struct fpga_spi {
+ struct firmware_handler fh;
+ int nstat_gpio; /* input GPIO to read the status line */
+ int confd_gpio; /* input GPIO to read the config done line */
+ int nconfig_gpio; /* output GPIO to start the FPGA's config */
+ struct device_d *dev;
+ struct spi_device *spi;
+ bool padding_done;
+};
+
+static int altera_spi_open(struct firmware_handler *fh)
+{
+ struct fpga_spi *this = container_of(fh, struct fpga_spi, fh);
+ struct device_d *dev = this->dev;
+ int ret;
+
+ dev_dbg(dev, "Initiating programming\n");
+
+ /* initiate an FPGA programming */
+ gpio_set_value(this->nconfig_gpio, 0);
+
+ /*
+ * after about 2 µs the FPGA must acknowledge with
+ * STATUS and CONFIG DONE lines at low level
+ */
+ ret = wait_on_timeout(2 * USECOND,
+ (gpio_get_value(this->nstat_gpio) == 0) &&
+ (gpio_get_value(this->confd_gpio) == 0));
+
+ if (ret != 0) {
+ dev_err(dev, "FPGA does not acknowledge the programming initiation\n");
+ if (gpio_get_value(this->nstat_gpio))
+ dev_err(dev, "STATUS is still high!\n");
+ if (gpio_get_value(this->confd_gpio))
+ dev_err(dev, "CONFIG DONE is still high!\n");
+ return ret;
+ }
+
+ /* arm the FPGA to await its new firmware */
+ ret = gpio_set_value(this->nconfig_gpio, 1);
+ if (ret)
+ return ret;
+
+ /* once again, we might need padding the data */
+ this->padding_done = false;
+
+ /*
+ * after about 1506 µs the FPGA must acknowledge this step
+ * with the STATUS line at high level
+ */
+ ret = wait_on_timeout(1600 * USECOND,
+ gpio_get_value(this->nstat_gpio) == 1);
+ if (ret != 0) {
+ dev_err(dev, "FPGA does not acknowledge the programming start\n");
+ return ret;
+ }
+
+ dev_dbg(dev, "Initiating passed\n");
+ /* at the end, wait at least 2 µs prior beginning writing data */
+ udelay(2);
+
+ return 0;
+}
+
+static int altera_spi_write(struct firmware_handler *fh, const void *buf, size_t sz)
+{
+ struct fpga_spi *this = container_of(fh, struct fpga_spi, fh);
+ struct device_d *dev = this->dev;
+ struct spi_transfer t[2];
+ struct spi_message m;
+ u32 dummy;
+ int ret;
+
+ dev_dbg(dev, "Start writing %d bytes.\n", __func__, sz);
+
+ spi_message_init(&m);
+
+ if (sz < sizeof(u32)) {
+ /* simple padding */
+ dummy = 0;
+ memcpy(&dummy, buf, sz);
+ buf = &dummy;
+ sz = sizeof(u32);
+ this->padding_done = true;
+ }
+
+ t[0].tx_buf = buf;
+ t[0].rx_buf = NULL;
+ t[0].len = sz;
+ spi_message_add_tail(&t[0], &m);
+
+ if (sz & 0x3) { /* padding required? */
+ u32 *word_buf = (u32 *)buf;
+ dummy = 0;
+ memcpy(&dummy, &word_buf[sz >> 2], sz & 0x3);
+ t[0].len &= ~0x03;
+ t[1].tx_buf = &dummy;
+ t[1].rx_buf = NULL;
+ t[1].len = sizeof(u32);
+ spi_message_add_tail(&t[1], &m);
+ this->padding_done = true;
+ }
+
+ ret = spi_sync(this->spi, &m);
+ if (ret != 0)
+ dev_err(dev, "programming failure\n");
+
+ return ret;
+}
+
+static int altera_spi_close(struct firmware_handler *fh)
+{
+ struct fpga_spi *this = container_of(fh, struct fpga_spi, fh);
+ struct device_d *dev = this->dev;
+ struct spi_transfer t;
+ struct spi_message m;
+ u32 dummy = 0;
+ int ret;
+
+ dev_dbg(dev, "Finalize programming\n");
+
+ if (this->padding_done == false) {
+ spi_message_init(&m);
+ t.tx_buf = &dummy;
+ t.rx_buf = NULL;
+ t.len = sizeof(dummy);
+ spi_message_add_tail(&t, &m);
+
+ ret = spi_sync(this->spi, &m);
+ if (ret != 0)
+ dev_err(dev, "programming failure\n");
+ }
+
+ /*
+ * when programming was successful,
+ * both status lines should be at high level
+ */
+ ret = wait_on_timeout(10 * USECOND,
+ (gpio_get_value(this->nstat_gpio) == 1) &&
+ (gpio_get_value(this->confd_gpio) == 1));
+ if (ret == 0) {
+ dev_dbg(dev, "Programming successful\n");
+ return ret;
+ }
+
+ dev_err(dev, "Programming failed due to time out\n");
+ if (gpio_get_value(this->nstat_gpio) == 0)
+ dev_err(dev, "STATUS is still low!\n");
+ if (gpio_get_value(this->confd_gpio) == 0)
+ dev_err(dev, "CONFIG DONE is still low!\n");
+
+ return -EIO;
+}
+
+static int altera_spi_of(struct device_d *dev, struct fpga_spi *this)
+{
+ struct device_node *n = dev->device_node;
+ const char *name;
+ int ret;
+
+ name = "nstat-gpio";
+ this->nstat_gpio = of_get_named_gpio(n, name, 0);
+ if (this->nstat_gpio < 0) {
+ ret = this->nstat_gpio;
+ goto out;
+ }
+
+ name = "confd-gpio";
+ this->confd_gpio = of_get_named_gpio(n, name, 0);
+ if (this->confd_gpio < 0) {
+ ret = this->confd_gpio;
+ goto out;
+ }
+
+ name = "nconfig-gpio";
+ this->nconfig_gpio = of_get_named_gpio(n, name, 0);
+ if (this->nconfig_gpio < 0) {
+ ret = this->nconfig_gpio;
+ goto out;
+ }
+
+ /* init to passive and sane values */
+ ret = gpio_direction_output(this->nconfig_gpio, 1);
+ if (ret)
+ return ret;
+ ret = gpio_direction_input(this->nstat_gpio);
+ if (ret)
+ return ret;
+ ret = gpio_direction_input(this->confd_gpio);
+ if (ret)
+ return ret;
+
+ return 0;
+
+out:
+ dev_err(dev, "Cannot request \"%s\" gpio: %s\n", name, strerror(-ret));
+
+ return ret;
+}
+
+static void altera_spi_init_mode(struct spi_device *spi)
+{
+ spi->bits_per_word = 32;
+ /*
+ * CPHA = CPOL = 0
+ * the FPGA expects its firmware data with LSB first
+ */
+ spi->mode = SPI_MODE_0 | SPI_LSB_FIRST;
+}
+
+static int altera_spi_probe(struct device_d *dev)
+{
+ int rc;
+ struct fpga_spi *this;
+ struct firmware_handler *fh;
+ const char *alias = of_alias_get(dev->device_node);
+ const char *model = NULL;
+
+ dev_dbg(dev, "Probing FPGA firmware programmer\n");
+
+ this = xzalloc(sizeof(*this));
+ fh = &this->fh;
+
+ rc = altera_spi_of(dev, this);
+ if (rc != 0)
+ goto out;
+
+ if (alias)
+ fh->id = xstrdup(alias);
+ else
+ fh->id = xstrdup("altera-fpga");
+
+ fh->open = altera_spi_open;
+ fh->write = altera_spi_write;
+ fh->close = altera_spi_close;
+ of_property_read_string(dev->device_node, "compatible", &model);
+ if (model)
+ fh->model = xstrdup(model);
+ fh->dev = dev;
+
+ this->spi = (struct spi_device *)dev->type_data;
+ altera_spi_init_mode(this->spi);
+ this->dev = dev;
+
+ dev_dbg(dev, "Registering FPGA firmware programmer\n");
+ rc = firmwaremgr_register(fh);
+ if (rc != 0) {
+ free(this);
+ goto out;
+ }
+
+ return 0;
+out:
+ free(fh->id);
+ free(this);
+
+ return rc;
+}
+
+static struct of_device_id altera_spi_id_table[] = {
+ {
+ .compatible = "altr,passive-serial",
+ },
+};
+
+static struct driver_d altera_spi_driver = {
+ .name = "altera-fpga",
+ .of_compatible = DRV_OF_COMPAT(altera_spi_id_table),
+ .probe = altera_spi_probe,
+};
+device_spi_driver(altera_spi_driver);
diff --git a/drivers/firmware/socfpga.c b/drivers/firmware/socfpga.c
new file mode 100644
index 0000000000..a5dc6072aa
--- /dev/null
+++ b/drivers/firmware/socfpga.c
@@ -0,0 +1,440 @@
+/*
+ *
+ * Copyright (C) 2012 Altera Corporation <www.altera.com>
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions are met:
+ * - Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * - Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in the
+ * documentation and/or other materials provided with the distribution.
+ * - Neither the name of the Altera Corporation nor the
+ * names of its contributors may be used to endorse or promote products
+ * derived from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
+ * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED. IN NO EVENT SHALL ALTERA CORPORATION BE LIABLE FOR ANY
+ * DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+ * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ * ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#include <firmware.h>
+#include <command.h>
+#include <common.h>
+#include <malloc.h>
+#include <clock.h>
+#include <fcntl.h>
+#include <init.h>
+#include <io.h>
+#include <mach/system-manager.h>
+#include <mach/reset-manager.h>
+#include <mach/socfpga-regs.h>
+#include <mach/sdram.h>
+
+#define FPGAMGRREGS_STAT 0x0
+#define FPGAMGRREGS_CTRL 0x4
+#define FPGAMGRREGS_DCLKCNT 0x8
+#define FPGAMGRREGS_DCLKSTAT 0xc
+
+#define FPGAMGRREGS_MON_GPIO_PORTA_EOI_ADDRESS 0x84c
+#define FPGAMGRREGS_MON_GPIO_EXT_PORTA_ADDRESS 0x850
+
+#define FPGAMGRREGS_CTRL_CFGWDTH_MASK 0x200
+#define FPGAMGRREGS_CTRL_AXICFGEN_MASK 0x100
+#define FPGAMGRREGS_CTRL_NCONFIGPULL_MASK 0x4
+#define FPGAMGRREGS_CTRL_NCE_MASK 0x2
+#define FPGAMGRREGS_CTRL_EN_MASK 0x1
+#define FPGAMGRREGS_CTRL_CDRATIO_LSB 6
+
+#define FPGAMGRREGS_STAT_MODE_MASK 0x7
+#define FPGAMGRREGS_STAT_MSEL_MASK 0xf8
+#define FPGAMGRREGS_STAT_MSEL_LSB 3
+
+#define FPGAMGRREGS_MON_GPIO_EXT_PORTA_CRC_MASK 0x8
+#define FPGAMGRREGS_MON_GPIO_EXT_PORTA_ID_MASK 0x4
+#define FPGAMGRREGS_MON_GPIO_EXT_PORTA_CD_MASK 0x2
+#define FPGAMGRREGS_MON_GPIO_EXT_PORTA_NS_MASK 0x1
+
+/* FPGA Mode */
+#define FPGAMGRREGS_MODE_FPGAOFF 0x0
+#define FPGAMGRREGS_MODE_RESETPHASE 0x1
+#define FPGAMGRREGS_MODE_CFGPHASE 0x2
+#define FPGAMGRREGS_MODE_INITPHASE 0x3
+#define FPGAMGRREGS_MODE_USERMODE 0x4
+#define FPGAMGRREGS_MODE_UNKNOWN 0x5
+
+/* FPGA CD Ratio Value */
+#define CDRATIO_x1 0x0
+#define CDRATIO_x2 0x1
+#define CDRATIO_x4 0x2
+#define CDRATIO_x8 0x3
+
+struct fpgamgr {
+ struct firmware_handler fh;
+ struct device_d *dev;
+ void __iomem *regs;
+ void __iomem *regs_data;
+};
+
+/* Get the FPGA mode */
+static uint32_t fpgamgr_get_mode(struct fpgamgr *mgr)
+{
+ return readl(mgr->regs + FPGAMGRREGS_STAT) & FPGAMGRREGS_STAT_MODE_MASK;
+}
+
+static int fpgamgr_dclkcnt_set(struct fpgamgr *mgr, unsigned long cnt)
+{
+ uint64_t start;
+
+ /* clear any existing done status */
+ if (readl(mgr->regs + FPGAMGRREGS_DCLKSTAT))
+ writel(0x1, mgr->regs + FPGAMGRREGS_DCLKSTAT);
+
+ writel(cnt, mgr->regs + FPGAMGRREGS_DCLKCNT);
+
+ /* wait till the dclkcnt done */
+ start = get_time_ns();
+ while (1) {
+ if (readl(mgr->regs + FPGAMGRREGS_DCLKSTAT)) {
+ writel(0x1, mgr->regs + FPGAMGRREGS_DCLKSTAT);
+ return 0;
+ }
+
+ if (is_timeout(start, 100 * MSECOND))
+ return -ETIMEDOUT;
+ }
+}
+
+/* Start the FPGA programming by initialize the FPGA Manager */
+static int fpgamgr_program_init(struct fpgamgr *mgr)
+{
+ unsigned long reg;
+ uint32_t ctrl = 0, ratio;
+ uint64_t start;
+
+ /* get the MSEL value */
+ reg = readl(mgr->regs + FPGAMGRREGS_STAT);
+ reg = ((reg & FPGAMGRREGS_STAT_MSEL_MASK) >> FPGAMGRREGS_STAT_MSEL_LSB);
+
+ if (reg & 0x8)
+ ctrl |= FPGAMGRREGS_CTRL_CFGWDTH_MASK;
+ else
+ ctrl &= ~FPGAMGRREGS_CTRL_CFGWDTH_MASK;
+
+ switch (reg & 0xb) {
+ case 0xa:
+ ratio = CDRATIO_x8;
+ break;
+ case 0x2:
+ case 0x9:
+ ratio = CDRATIO_x4;
+ break;
+ case 0x1:
+ ratio = CDRATIO_x2;
+ break;
+ case 0x8:
+ case 0xb:
+ default:
+ ratio = CDRATIO_x1;
+ break;
+ }
+
+ ctrl |= ratio << FPGAMGRREGS_CTRL_CDRATIO_LSB;
+
+ /* clear nce bit to allow HPS configuration */
+ ctrl &= ~FPGAMGRREGS_CTRL_NCE_MASK;
+
+ /* to enable FPGA Manager drive over configuration line */
+ ctrl |= FPGAMGRREGS_CTRL_EN_MASK;
+
+ /* put FPGA into reset phase */
+ ctrl |= FPGAMGRREGS_CTRL_NCONFIGPULL_MASK;
+
+ writel(ctrl, mgr->regs + FPGAMGRREGS_CTRL);
+
+ /* (1) wait until FPGA enter reset phase */
+ start = get_time_ns();
+ while (1) {
+ if (fpgamgr_get_mode(mgr) == FPGAMGRREGS_MODE_RESETPHASE)
+ break;
+ if (is_timeout(start, 100 * MSECOND))
+ return -ETIMEDOUT;
+ }
+
+ /* release FPGA from reset phase */
+ ctrl = readl(mgr->regs + FPGAMGRREGS_CTRL);
+ ctrl &= ~FPGAMGRREGS_CTRL_NCONFIGPULL_MASK;
+ writel(ctrl, mgr->regs + FPGAMGRREGS_CTRL);
+
+ /* (2) wait until FPGA enter configuration phase */
+ start = get_time_ns();
+ while (1) {
+ if (fpgamgr_get_mode(mgr) == FPGAMGRREGS_MODE_CFGPHASE)
+ break;
+ if (is_timeout(start, 100 * MSECOND))
+ return -ETIMEDOUT;
+ }
+
+ /* clear all interrupt in CB Monitor */
+ writel(0xFFF, (mgr->regs + FPGAMGRREGS_MON_GPIO_PORTA_EOI_ADDRESS));
+
+ /* enable AXI configuration */
+ ctrl = readl(mgr->regs + FPGAMGRREGS_CTRL);
+ ctrl |= FPGAMGRREGS_CTRL_AXICFGEN_MASK;
+ writel(ctrl, mgr->regs + FPGAMGRREGS_CTRL);
+
+ return 0;
+}
+
+/* Ensure the FPGA entering config done */
+static int fpgamgr_program_poll_cd(struct fpgamgr *mgr)
+{
+ unsigned long reg;
+ uint32_t val;
+ uint64_t start;
+
+ /* (3) wait until full config done */
+ start = get_time_ns();
+ while (1) {
+ reg = readl(mgr->regs + FPGAMGRREGS_MON_GPIO_EXT_PORTA_ADDRESS);
+
+ /* config error */
+ if (!(reg & FPGAMGRREGS_MON_GPIO_EXT_PORTA_NS_MASK) &&
+ !(reg & FPGAMGRREGS_MON_GPIO_EXT_PORTA_CD_MASK))
+ return -EIO;
+
+ /* config done without error */
+ if ((reg & FPGAMGRREGS_MON_GPIO_EXT_PORTA_NS_MASK) &&
+ (reg & FPGAMGRREGS_MON_GPIO_EXT_PORTA_CD_MASK))
+ break;
+
+ if (is_timeout(start, 100 * MSECOND))
+ return -ETIMEDOUT;
+ }
+
+ /* disable AXI configuration */
+ val = readl(mgr->regs + FPGAMGRREGS_CTRL);
+ val &= ~FPGAMGRREGS_CTRL_AXICFGEN_MASK;
+ writel(val, mgr->regs + FPGAMGRREGS_CTRL);
+
+ return 0;
+}
+
+/* Ensure the FPGA entering init phase */
+static int fpgamgr_program_poll_initphase(struct fpgamgr *mgr)
+{
+ uint64_t start;
+
+ /* additional clocks for the CB to enter initialization phase */
+ if (fpgamgr_dclkcnt_set(mgr, 0x4) != 0)
+ return -5;
+
+ /* (4) wait until FPGA enter init phase or user mode */
+ start = get_time_ns();
+ while (1) {
+ int mode = fpgamgr_get_mode(mgr);
+
+ if (mode == FPGAMGRREGS_MODE_INITPHASE ||
+ mode == FPGAMGRREGS_MODE_USERMODE)
+ break;
+
+ if (is_timeout(start, 100 * MSECOND))
+ return -ETIMEDOUT;
+ }
+
+ return 0;
+}
+
+/* Ensure the FPGA entering user mode */
+static int fpgamgr_program_poll_usermode(struct fpgamgr *mgr)
+{
+ uint32_t val;
+ uint64_t start;
+
+ /* additional clocks for the CB to exit initialization phase */
+ if (fpgamgr_dclkcnt_set(mgr, 0x5000) != 0)
+ return -7;
+
+ /* (5) wait until FPGA enter user mode */
+ start = get_time_ns();
+ while (1) {
+ if (fpgamgr_get_mode(mgr) == FPGAMGRREGS_MODE_USERMODE)
+ break;
+ if (is_timeout(start, 100 * MSECOND))
+ return -ETIMEDOUT;
+ }
+
+ /* to release FPGA Manager drive over configuration line */
+ val = readl(mgr->regs + FPGAMGRREGS_CTRL);
+ val &= ~FPGAMGRREGS_CTRL_EN_MASK;
+ writel(val, mgr->regs + FPGAMGRREGS_CTRL);
+
+ return 0;
+}
+
+/*
+ * Using FPGA Manager to program the FPGA
+ * Return 0 for sucess
+ */
+static int fpgamgr_program_start(struct firmware_handler *fh)
+{
+ struct fpgamgr *mgr = container_of(fh, struct fpgamgr, fh);
+ int status;
+
+ /* prior programming the FPGA, all bridges need to be shut off */
+
+ /* disable all signals from hps peripheral controller to fpga */
+ writel(0, SYSMGR_FPGAINTF_MODULE);
+
+ /* disable all signals from fpga to hps sdram */
+ writel(0, (CYCLONE5_SDR_ADDRESS + SDR_CTRLGRP_FPGAPORTRST_ADDRESS));
+
+ /* disable all axi bridge (hps2fpga, lwhps2fpga & fpga2hps) */
+ writel(~0, CYCLONE5_RSTMGR_ADDRESS + RESET_MGR_BRG_MOD_RESET_OFS);
+
+ /* unmap the bridges from NIC-301 */
+ writel(0x1, CYCLONE5_L3REGS_ADDRESS);
+
+ dev_dbg(mgr->dev, "start programming...\n");
+
+ /* initialize the FPGA Manager */
+ status = fpgamgr_program_init(mgr);
+ if (status) {
+ dev_err(mgr->dev, "program init failed with: %s\n",
+ strerror(-status));
+ return status;
+ }
+
+ return 0;
+}
+
+/* Write the RBF data to FPGA Manager */
+static int fpgamgr_program_write_buf(struct firmware_handler *fh, const void *buf,
+ size_t size)
+{
+ struct fpgamgr *mgr = container_of(fh, struct fpgamgr, fh);
+ const uint32_t *buf32 = buf;
+
+ /* write to FPGA Manager AXI data */
+ while (size) {
+ writel(*buf32, mgr->regs_data);
+ readl(mgr->regs + FPGAMGRREGS_MON_GPIO_EXT_PORTA_ADDRESS);
+ buf32++;
+ size -= sizeof(uint32_t);
+ }
+
+ return 0;
+}
+
+static int fpgamgr_program_finish(struct firmware_handler *fh)
+{
+ struct fpgamgr *mgr = container_of(fh, struct fpgamgr, fh);
+ int status;
+
+ /* Ensure the FPGA entering config done */
+ status = fpgamgr_program_poll_cd(mgr);
+ if (status) {
+ dev_err(mgr->dev, "poll for config done failed with: %s\n",
+ strerror(-status));
+ return status;
+ }
+
+ dev_dbg(mgr->dev, "waiting for init phase...\n");
+
+ /* Ensure the FPGA entering init phase */
+ status = fpgamgr_program_poll_initphase(mgr);
+ if (status) {
+ dev_err(mgr->dev, "poll for init phase failed with: %s\n",
+ strerror(-status));
+ return status;
+ }
+
+ dev_dbg(mgr->dev, "waiting for user mode...\n");
+
+ /* Ensure the FPGA entering user mode */
+ status = fpgamgr_program_poll_usermode(mgr);
+ if (status) {
+ dev_err(mgr->dev, "poll for user mode with: %s\n",
+ strerror(-status));
+ return status;
+ }
+
+ return 0;
+}
+
+static int fpgamgr_probe(struct device_d *dev)
+{
+ struct fpgamgr *mgr;
+ struct firmware_handler *fh;
+ const char *alias = of_alias_get(dev->device_node);
+ const char *model = NULL;
+ int ret;
+
+ dev_dbg(dev, "Probing FPGA firmware programmer\n");
+
+ mgr = xzalloc(sizeof(*mgr));
+ fh = &mgr->fh;
+
+ mgr->regs = dev_request_mem_region(dev, 0);
+ if (!mgr->regs) {
+ ret = -EBUSY;
+ goto out;
+ }
+
+ mgr->regs_data = dev_request_mem_region(dev, 1);
+ if (!mgr->regs_data) {
+ ret = -EBUSY;
+ goto out;
+ }
+
+ if (alias)
+ fh->id = xstrdup(alias);
+ else
+ fh->id = xstrdup("socfpga-fpga");
+
+ fh->open = fpgamgr_program_start;
+ fh->write = fpgamgr_program_write_buf;
+ fh->close = fpgamgr_program_finish;
+ of_property_read_string(dev->device_node, "compatible", &model);
+ if (model)
+ fh->model = xstrdup(model);
+ fh->dev = dev;
+
+ mgr->dev = dev;
+
+ dev_dbg(dev, "Registering FPGA firmware programmer\n");
+
+ ret = firmwaremgr_register(fh);
+ if (ret != 0) {
+ free(mgr);
+ goto out;
+ }
+
+ return 0;
+out:
+ free(fh->id);
+ free(mgr);
+
+ return ret;
+}
+
+static struct of_device_id fpgamgr_id_table[] = {
+ {
+ .compatible = "altr,socfpga-fpga-mgr",
+ },
+};
+
+static struct driver_d fpgamgr_driver = {
+ .name = "socfpa-fpgamgr",
+ .of_compatible = DRV_OF_COMPAT(fpgamgr_id_table),
+ .probe = fpgamgr_probe,
+};
+device_platform_driver(fpgamgr_driver);
diff --git a/drivers/i2c/busses/i2c-at91.c b/drivers/i2c/busses/i2c-at91.c
index 399f6a94be..deb4ea4f3b 100644
--- a/drivers/i2c/busses/i2c-at91.c
+++ b/drivers/i2c/busses/i2c-at91.c
@@ -174,24 +174,32 @@ static void at91_twi_read_next_byte(struct at91_twi_dev *dev)
static int at91_twi_wait_completion(struct at91_twi_dev *dev)
{
uint64_t start = get_time_ns();
- unsigned int status = at91_twi_read(dev, AT91_TWI_SR);
- unsigned int irqstatus = at91_twi_read(dev, AT91_TWI_IMR);
+ unsigned int status;
+ unsigned int irqstatus;
+
+ do {
+ status = at91_twi_read(dev, AT91_TWI_SR);
+ irqstatus = at91_twi_read(dev, AT91_TWI_IMR);
+
+ if (!(status & irqstatus)) {
+ if (is_timeout(start, AT91_I2C_TIMEOUT)) {
+ dev_warn(&dev->adapter.dev, "timeout waiting for bus ready\n");
+ return -ETIMEDOUT;
+ } else {
+ continue;
+ }
+ }
- if (irqstatus & AT91_TWI_RXRDY)
- at91_twi_read_next_byte(dev);
- else if (irqstatus & AT91_TWI_TXRDY)
- at91_twi_write_next_byte(dev);
- else
- dev_warn(&dev->adapter.dev, "neither rx and tx are ready\n");
+ if (irqstatus & AT91_TWI_RXRDY)
+ at91_twi_read_next_byte(dev);
+ else if (irqstatus & AT91_TWI_TXRDY)
+ at91_twi_write_next_byte(dev);
+ else
+ dev_warn(&dev->adapter.dev, "neither rx and tx are ready\n");
- dev->transfer_status |= status;
+ dev->transfer_status |= status;
- while(!(at91_twi_read(dev, AT91_TWI_SR) & AT91_TWI_TXCOMP)) {
- if(is_timeout(start, AT91_I2C_TIMEOUT)) {
- dev_warn(&dev->adapter.dev, "timeout waiting for bus ready\n");
- return -ETIMEDOUT;
- }
- }
+ } while (!(at91_twi_read(dev, AT91_TWI_SR) & AT91_TWI_TXCOMP));
at91_disable_twi_interrupts(dev);
@@ -346,23 +354,56 @@ static struct at91_twi_pdata at91sam9g10_config = {
.has_unre_flag = false,
};
+static struct at91_twi_pdata at91sam9x5_config = {
+ .clk_max_div = 7,
+ .clk_offset = 4,
+ .has_unre_flag = false,
+};
+
static struct platform_device_id at91_twi_devtypes[] = {
{
- .name = "i2c-at91rm9200",
+ .name = "at91rm9200-i2c",
.driver_data = (unsigned long) &at91rm9200_config,
}, {
- .name = "i2c-at91sam9261",
+ .name = "at91sam9261-i2c",
.driver_data = (unsigned long) &at91sam9261_config,
}, {
- .name = "i2c-at91sam9260",
+ .name = "at91sam9260-i2c",
.driver_data = (unsigned long) &at91sam9260_config,
}, {
- .name = "i2c-at91sam9g20",
+ .name = "at91sam9g20-i2c",
.driver_data = (unsigned long) &at91sam9g20_config,
}, {
- .name = "i2c-at91sam9g10",
+ .name = "at91sam9g10-i2c",
.driver_data = (unsigned long) &at91sam9g10_config,
}, {
+ .name = "at91sam9x5-i2c",
+ .driver_data = (unsigned long) &at91sam9x5_config,
+ }, {
+ /* sentinel */
+ }
+};
+
+static struct of_device_id at91_twi_dt_ids[] = {
+ {
+ .compatible = "atmel,at91rm9200-i2c",
+ .data = (unsigned long) &at91rm9200_config,
+ } , {
+ .compatible = "atmel,at91sam9260-i2c",
+ .data = (unsigned long) &at91sam9260_config,
+ } , {
+ .compatible = "atmel,at91sam9261-i2c",
+ .data = (unsigned long) &at91sam9261_config,
+ } , {
+ .compatible = "atmel,at91sam9g20-i2c",
+ .data = (unsigned long) &at91sam9g20_config,
+ } , {
+ .compatible = "atmel,at91sam9g10-i2c",
+ .data = (unsigned long) &at91sam9g10_config,
+ }, {
+ .compatible = "atmel,at91sam9x5-i2c",
+ .data = (unsigned long) &at91sam9x5_config,
+ }, {
/* sentinel */
}
};
@@ -371,14 +412,16 @@ static int at91_twi_probe(struct device_d *dev)
{
struct at91_twi_dev *i2c_at91;
struct at91_twi_pdata *i2c_data;
- int rc;
+ int rc = 0;
u32 bus_clk_rate;
i2c_at91 = xzalloc(sizeof(struct at91_twi_dev));
rc = dev_get_drvdata(dev, (unsigned long *)&i2c_data);
- if (rc)
+ if (rc < 0) {
+ dev_err(dev, "failed to retrieve driver data\n");
goto out_free;
+ }
i2c_at91->pdata = i2c_data;
@@ -389,7 +432,7 @@ static int at91_twi_probe(struct device_d *dev)
goto out_free;
}
- i2c_at91->clk = clk_get(dev, "twi_clk");
+ i2c_at91->clk = clk_get(dev, NULL);
if (IS_ERR(i2c_at91->clk)) {
dev_err(dev, "no clock defined\n");
rc = -ENODEV;
@@ -418,17 +461,18 @@ static int at91_twi_probe(struct device_d *dev)
return 0;
out_adap_fail:
- clk_disable(i2c_at91->clk);
- clk_put(i2c_at91->clk);
+ clk_disable(i2c_at91->clk);
+ clk_put(i2c_at91->clk);
out_free:
- kfree(i2c_at91);
- return rc;
+ kfree(i2c_at91);
+ return rc;
}
static struct driver_d at91_twi_driver = {
.name = "at91-twi",
.probe = at91_twi_probe,
.id_table = at91_twi_devtypes,
+ .of_compatible = DRV_OF_COMPAT(at91_twi_dt_ids),
};
device_platform_driver(at91_twi_driver);
diff --git a/drivers/i2c/busses/i2c-omap.c b/drivers/i2c/busses/i2c-omap.c
index 0d714cc940..094f5916cf 100644
--- a/drivers/i2c/busses/i2c-omap.c
+++ b/drivers/i2c/busses/i2c-omap.c
@@ -151,7 +151,6 @@ struct omap_i2c_struct {
u8 reg_shift;
struct omap_i2c_driver_data *data;
struct resource *ioarea;
- u32 fclk_rate;
u32 speed; /* Speed of bus in Khz */
u16 scheme;
u16 cmd_err;
@@ -421,7 +420,7 @@ static int omap_i2c_init(struct omap_i2c_struct *i2c_omap)
internal_clk = 4000;
/* Compute prescaler divisor */
- psc = i2c_omap->fclk_rate / internal_clk;
+ psc = i2c_data->fclk_rate / internal_clk;
psc = psc - 1;
/* If configured for High Speed */
@@ -1016,9 +1015,16 @@ i2c_omap_probe(struct device_d *pdev)
i2c_omap->reg_shift = (i2c_data->flags >>
OMAP_I2C_FLAG_BUS_SHIFT__SHIFT) & 3;
- if (pdev->platform_data != NULL)
+ if (pdev->platform_data != NULL) {
speed = *(u32 *)pdev->platform_data;
- else
+ } else {
+ of_property_read_u32(pdev->device_node, "clock-frequency",
+ &speed);
+ /* convert DT freq value in Hz into kHz for speed */
+ speed /= 1000;
+ }
+
+ if (!speed)
speed = 100; /* Default speed */
i2c_omap->speed = speed;
@@ -1082,12 +1088,6 @@ i2c_omap_probe(struct device_d *pdev)
i2c_omap->b_hw = 1; /* Enable hardware fixes */
}
- i2c_omap->fclk_rate = i2c_data->fclk_rate;
-
- if (!i2c_omap->fclk_rate)
- of_property_read_u32(pdev->device_node, "clock-frequency",
- &i2c_omap->fclk_rate);
-
/* reset ASAP, clearing any IRQs */
omap_i2c_init(i2c_omap);
diff --git a/drivers/input/imx_keypad.c b/drivers/input/imx_keypad.c
index c67deb8d49..331eadd75f 100644
--- a/drivers/input/imx_keypad.c
+++ b/drivers/input/imx_keypad.c
@@ -391,7 +391,7 @@ static int __init imx_keypad_probe(struct device_d *dev)
struct imx_keypad *keypad;
const struct matrix_keymap_data *keymap_data = dev->platform_data;
struct console_device *cdev;
- int error, i;
+ int i;
if (!keymap_data) {
pr_err("no keymap defined\n");
diff --git a/drivers/mci/atmel_mci.c b/drivers/mci/atmel_mci.c
index 63d2475da7..10e769ea13 100644
--- a/drivers/mci/atmel_mci.c
+++ b/drivers/mci/atmel_mci.c
@@ -511,6 +511,7 @@ static void atmci_get_cap(struct atmel_mci *host)
host->caps.need_reset_after_xfer = 1;
switch (version & 0xf00) {
+ case 0x600:
case 0x500:
host->caps.has_odd_clk_div = 1;
case 0x400:
diff --git a/drivers/mtd/devices/Kconfig b/drivers/mtd/devices/Kconfig
index 61278a235d..7f9c306258 100644
--- a/drivers/mtd/devices/Kconfig
+++ b/drivers/mtd/devices/Kconfig
@@ -58,4 +58,9 @@ config MTD_DOCG3
M-Systems and now Sandisk. The support is very experimental,
and doesn't give access to any write operations.
+config MTD_MTDRAM
+ tristate "Support for NVRAM devices (FRAM, MRAM, ...)"
+ help
+ This enables non volatile RAM to used as MTD devices.
+
endmenu
diff --git a/drivers/mtd/devices/Makefile b/drivers/mtd/devices/Makefile
index bf1f8a9f15..bc1960e1b2 100644
--- a/drivers/mtd/devices/Makefile
+++ b/drivers/mtd/devices/Makefile
@@ -5,3 +5,4 @@
obj-$(CONFIG_MTD_DATAFLASH) += mtd_dataflash.o
obj-$(CONFIG_MTD_DOCG3) += docg3.o
obj-$(CONFIG_MTD_M25P80) += m25p80.o
+obj-$(CONFIG_MTD_MTDRAM) += mtdram.o
diff --git a/drivers/mtd/devices/mtdram.c b/drivers/mtd/devices/mtdram.c
new file mode 100644
index 0000000000..d1eaafdab5
--- /dev/null
+++ b/drivers/mtd/devices/mtdram.c
@@ -0,0 +1,122 @@
+/*
+ * Author: Sebastian Block <basti@linux-source.de>
+ * Copyright (c) 2014
+ *
+ * Some parts are based on mtdram.c found in Linux kernel
+ * by Alexander Larsson <alex@cendio.se>
+ * and Joern Engel <joern@wh.fh-wedel.de>.
+ *
+ * This code 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 <common.h>
+#include <environment.h>
+#include <errno.h>
+#include <init.h>
+#include <io.h>
+#include <linux/mtd/mtd.h>
+#include <malloc.h>
+#include <of.h>
+
+struct mtdram_priv_data {
+ struct mtd_info mtd;
+ void *base;
+};
+
+static int ram_erase(struct mtd_info *mtd, struct erase_info *instr)
+{
+ memset((char *)mtd->priv + instr->addr, 0xff, instr->len);
+ instr->state = MTD_ERASE_DONE;
+ mtd_erase_callback(instr);
+ return 0;
+}
+
+static int ram_write(struct mtd_info *mtd, loff_t to, size_t len, size_t *retlen, const u_char *buf)
+{
+ memcpy((char*)mtd->priv + to, buf, len);
+ *retlen = len;
+ return 0;
+}
+
+static int ram_read(struct mtd_info *mtd, loff_t from, size_t len, size_t *retlen, u_char *buf)
+{
+ memcpy(buf, mtd->priv + from, len);
+ *retlen = len;
+ return 0;
+}
+
+static int mtdram_probe(struct device_d *dev)
+{
+ void __iomem *base;
+ int device_id;
+ struct mtd_info *mtd;
+ struct resource *res;
+ loff_t size;
+ int ret = 0;
+
+ mtd = xzalloc(sizeof(struct mtd_info));
+
+ device_id = DEVICE_ID_SINGLE;
+ if (dev->device_node) {
+ const char *alias = of_alias_get(dev->device_node);
+ if (alias)
+ mtd->name = xstrdup(alias);
+ }
+
+ if (!mtd->name) {
+ device_id = DEVICE_ID_DYNAMIC;
+ mtd->name = "mtdram";
+ }
+
+ base = dev_request_mem_region(dev, 0);
+ if (!base) {
+ ret = -EBUSY;
+ goto nobase;
+ }
+
+ res = dev_get_resource(dev, IORESOURCE_MEM, 0);
+ size = (unsigned long) resource_size(res);
+ mtd->priv = base;
+
+ mtd->type = MTD_RAM;
+ mtd->writesize = 1;
+ mtd->writebufsize = 64;
+ mtd->flags = MTD_CAP_RAM;
+ mtd->size = size;
+
+ mtd->read = ram_read;
+ mtd->write = ram_write;
+ mtd->erase = ram_erase;
+ mtd->erasesize = 1;
+
+ mtd->parent = dev;
+
+ ret = add_mtd_device(mtd, mtd->name, device_id);
+ return ret;
+
+nobase:
+ kfree(mtd);
+
+ return ret;
+}
+
+static __maybe_unused struct of_device_id mtdram_dt_ids[] = {
+ {
+ .compatible = "mtd-ram",
+ }, {
+ /* sentinel */
+ }
+};
+
+static struct driver_d mtdram_driver = {
+ .name = "mtdram",
+ .probe = mtdram_probe,
+ .of_compatible = DRV_OF_COMPAT(mtdram_dt_ids),
+};
+device_platform_driver(mtdram_driver);
+
+MODULE_LICENSE("GPL");
+MODULE_AUTHOR("Sebastian Block");
+MODULE_DESCRIPTION("MTD RAM driver for NVRAMs");
diff --git a/drivers/mtd/nand/Kconfig b/drivers/mtd/nand/Kconfig
index ccf1f9c110..c345847d8f 100644
--- a/drivers/mtd/nand/Kconfig
+++ b/drivers/mtd/nand/Kconfig
@@ -93,7 +93,7 @@ config NAND_OMAP_GPMC
config NAND_ORION
bool
prompt "Orion NAND driver"
- depends on ARCH_MVEBU
+ depends on ARCH_KIRKWOOD
help
Support for the Orion NAND controller, present in Kirkwood SoCs.
diff --git a/drivers/mtd/nand/atmel_nand.c b/drivers/mtd/nand/atmel_nand.c
index 524606a407..4ddabda572 100644
--- a/drivers/mtd/nand/atmel_nand.c
+++ b/drivers/mtd/nand/atmel_nand.c
@@ -767,12 +767,105 @@ static void atmel_pmecc_core_init(struct mtd_info *mtd)
pmecc_writel(host->ecc, CTRL, PMECC_CTRL_ENABLE);
}
+static uint16_t *pmecc_galois_table;
+static int pmecc_build_galois_table(unsigned int mm, int16_t *index_of,
+ int16_t *alpha_to)
+{
+ unsigned int i, mask, nn;
+ unsigned int p[15];
+
+ nn = (1 << mm) - 1;
+ /* set default value */
+ for (i = 1; i < mm; i++)
+ p[i] = 0;
+
+ /* 1 + X^mm */
+ p[0] = 1;
+ p[mm] = 1;
+
+ /* others */
+ switch (mm) {
+ case 3:
+ case 4:
+ case 6:
+ case 15:
+ p[1] = 1;
+ break;
+ case 5:
+ case 11:
+ p[2] = 1;
+ break;
+ case 7:
+ case 10:
+ p[3] = 1;
+ break;
+ case 8:
+ p[2] = p[3] = p[4] = 1;
+ break;
+ case 9:
+ p[4] = 1;
+ break;
+ case 12:
+ p[1] = p[4] = p[6] = 1;
+ break;
+ case 13:
+ p[1] = p[3] = p[4] = 1;
+ break;
+ case 14:
+ p[1] = p[6] = p[10] = 1;
+ break;
+ default:
+ /* Error */
+ return -EINVAL;
+ }
+
+ /* Build alpha ^ mm it will help to generate the field (primitiv) */
+ alpha_to[mm] = 0;
+ for (i = 0; i < mm; i++)
+ if (p[i])
+ alpha_to[mm] |= 1 << i;
+
+ /*
+ * Then build elements from 0 to mm - 1. As degree is less than mm
+ * so it is just a logical shift.
+ */
+ mask = 1;
+ for (i = 0; i < mm; i++) {
+ alpha_to[i] = mask;
+ index_of[alpha_to[i]] = i;
+ mask <<= 1;
+ }
+
+ index_of[alpha_to[mm]] = mm;
+
+ /* use a mask to select the MSB bit of the LFSR */
+ mask >>= 1;
+
+ /* then finish the building */
+ for (i = mm + 1; i <= nn; i++) {
+ /* check if the msb bit of the lfsr is set */
+ if (alpha_to[i - 1] & mask)
+ alpha_to[i] = alpha_to[mm] ^
+ ((alpha_to[i - 1] ^ mask) << 1);
+ else
+ alpha_to[i] = alpha_to[i - 1] << 1;
+
+ index_of[alpha_to[i]] = i % nn;
+ }
+
+ /* index of 0 is undefined in a multiplicative field */
+ index_of[0] = -1;
+
+ return 0;
+}
+
static int __init atmel_pmecc_nand_init_params(struct device_d *dev,
struct atmel_nand_host *host)
{
struct mtd_info *mtd = &host->mtd;
struct nand_chip *nand_chip = &host->nand_chip;
int cap, sector_size, err_no;
+ int ret;
cap = host->board->pmecc_corr_cap;
sector_size = host->board->pmecc_sector_size;
@@ -786,14 +879,34 @@ static int __init atmel_pmecc_nand_init_params(struct device_d *dev,
}
host->pmerrloc_base = dev_request_mem_region(dev, 2);
- host->pmecc_rom_base = dev_request_mem_region(dev, 3);
-
- if (!host->pmerrloc_base || !host->pmecc_rom_base) {
+ if (!host->pmerrloc_base) {
dev_err(host->dev,
- "Can not get I/O resource for PMECC ERRLOC controller or ROM!\n");
+ "Can not get I/O resource for PMECC ERRLOC controller!\n");
return -EIO;
}
+ host->pmecc_rom_base = dev_request_mem_region(dev, 3);
+ if (!host->pmecc_rom_base) {
+ /* Set pmecc_rom_base as the begin of gf table */
+ int size = sector_size == 512 ? 0x2000 : 0x4000;
+ pmecc_galois_table = xzalloc(2 * size * sizeof(uint16_t));
+ if (!pmecc_galois_table)
+ return -ENOMEM;
+ host->pmecc_rom_base = pmecc_galois_table;
+ ret = pmecc_build_galois_table((sector_size == 512) ?
+ PMECC_GF_DIMENSION_13 :
+ PMECC_GF_DIMENSION_14,
+ host->pmecc_rom_base,
+ host->pmecc_rom_base + (size * sizeof(int16_t)));
+ if (ret) {
+ dev_err(host->dev,
+ "Can not get I/O resource for ROM!\n");
+ return -EIO;
+ }
+
+ host->board->pmecc_lookup_table_offset = 0;
+ }
+
/* ECC is calculated for the whole page (1 step) */
nand_chip->ecc.size = mtd->writesize;
diff --git a/drivers/mtd/nor/cfi_flash.c b/drivers/mtd/nor/cfi_flash.c
index a494063922..0fa41bf67b 100644
--- a/drivers/mtd/nor/cfi_flash.c
+++ b/drivers/mtd/nor/cfi_flash.c
@@ -1000,8 +1000,8 @@ static int cfi_probe (struct device_d *dev)
return -ENODEV;
}
- dev_info(dev, "found cfi flash at %p, size %ld\n",
- info->base, info->size);
+ dev_info(dev, "found cfi flash at 0x%p, size %s\n",
+ info->base, size_human_readable(info->size));
dev->info = cfi_info;
diff --git a/drivers/net/ethoc.c b/drivers/net/ethoc.c
index 59e8f01e0b..7c52a09eaa 100644
--- a/drivers/net/ethoc.c
+++ b/drivers/net/ethoc.c
@@ -568,8 +568,14 @@ static int ethoc_probe(struct device_d *dev)
return 0;
}
+static struct of_device_id ethoc_dt_ids[] = {
+ { .compatible = "opencores,ethoc", },
+ { }
+};
+
static struct driver_d ethoc_driver = {
.name = "ethoc",
.probe = ethoc_probe,
+ .of_compatible = DRV_OF_COMPAT(ethoc_dt_ids),
};
device_platform_driver(ethoc_driver);
diff --git a/drivers/net/macb.c b/drivers/net/macb.c
index 03558af8f1..8e67aecc84 100644
--- a/drivers/net/macb.c
+++ b/drivers/net/macb.c
@@ -304,7 +304,6 @@ static void macb_configure_dma(struct macb_device *bp)
if (macb_is_gem(bp)) {
dmacfg = gem_readl(bp, DMACFG) & ~GEM_BF(RXBS, -1L);
dmacfg |= GEM_BF(RXBS, bp->rx_buffer_size / RX_BUFFER_MULTIPLE);
- dmacfg |= GEM_BF(FBLDO, 16);
dmacfg |= GEM_BIT(TXPBMS) | GEM_BF(RXBMS, -1L);
dmacfg |= GEM_BIT(DDRP);
dmacfg &= ~GEM_BIT(ENDIA);
@@ -352,7 +351,10 @@ static void macb_init(struct macb_device *macb)
break;
case PHY_INTERFACE_MODE_RMII:
if (IS_ENABLED(CONFIG_ARCH_AT91))
- val = MACB_BIT(RMII) | MACB_BIT(CLKEN);
+ if (macb_is_gem(macb))
+ val = GEM_BIT(RGMII);
+ else
+ val = MACB_BIT(RMII) | MACB_BIT(CLKEN);
else
val = 0;
break;
diff --git a/drivers/net/phy/marvell.c b/drivers/net/phy/marvell.c
index 34f852e065..f2bc64925d 100644
--- a/drivers/net/phy/marvell.c
+++ b/drivers/net/phy/marvell.c
@@ -10,22 +10,7 @@
#include <linux/ethtool.h>
#include <linux/phy.h>
#include <linux/smscphy.h>
-
-/* Known PHY IDs */
-#define MARVELL_PHY_ID_88E1101 0x01410c60
-#define MARVELL_PHY_ID_88E1112 0x01410c90
-#define MARVELL_PHY_ID_88E1111 0x01410cc0
-#define MARVELL_PHY_ID_88E1118 0x01410e10
-#define MARVELL_PHY_ID_88E1121R 0x01410cb0
-#define MARVELL_PHY_ID_88E1145 0x01410cd0
-#define MARVELL_PHY_ID_88E1149R 0x01410e50
-#define MARVELL_PHY_ID_88E1240 0x01410e30
-#define MARVELL_PHY_ID_88E1318S 0x01410e90
-#define MARVELL_PHY_ID_88E1116R 0x01410e40
-#define MARVELL_PHY_ID_88E1510 0x01410dd0
-
-/* Mask used for ID comparisons */
-#define MARVELL_PHY_ID_MASK 0xfffffff0
+#include <linux/marvell_phy.h>
/* Marvell Register Page register */
#define MII_MARVELL_PHY_PAGE 22
diff --git a/drivers/net/phy/micrel.c b/drivers/net/phy/micrel.c
index 8aea6534b8..88c64e59a0 100644
--- a/drivers/net/phy/micrel.c
+++ b/drivers/net/phy/micrel.c
@@ -254,11 +254,11 @@ static struct phy_driver ksphy_driver[] = {
.config_aneg = genphy_config_aneg,
.read_status = genphy_read_status,
}, {
+ /* I saw the same issue like PHY_ID_KSZ9021 for Asym_Pause */
.phy_id = PHY_ID_KSZ9031,
.phy_id_mask = 0x00fffff0,
.drv.name = "Micrel KSZ9031 Gigabit PHY",
- .features = (PHY_GBIT_FEATURES | SUPPORTED_Pause
- | SUPPORTED_Asym_Pause),
+ .features = (PHY_GBIT_FEATURES | SUPPORTED_Pause),
.config_init = kszphy_config_init,
.config_aneg = genphy_config_aneg,
.read_status = genphy_read_status,
diff --git a/drivers/net/phy/phy.c b/drivers/net/phy/phy.c
index cad4cf5475..f3dffca46e 100644
--- a/drivers/net/phy/phy.c
+++ b/drivers/net/phy/phy.c
@@ -31,26 +31,41 @@
static struct phy_driver genphy_driver;
static int genphy_config_init(struct phy_device *phydev);
-int phy_update_status(struct phy_device *dev)
+/**
+ * phy_aneg_done - return auto-negotiation status
+ * @phydev: target phy_device struct
+ *
+ * Description: Return the auto-negotiation status from this @phydev
+ * Returns > 0 on success or < 0 on error. 0 means that auto-negotiation
+ * is still pending.
+ */
+static int phy_aneg_done(struct phy_device *phydev)
+{
+ struct phy_driver *drv = to_phy_driver(phydev->dev.driver);
+
+ return drv->aneg_done(phydev);
+}
+
+int phy_update_status(struct phy_device *phydev)
{
- struct phy_driver *drv = to_phy_driver(dev->dev.driver);
- struct eth_device *edev = dev->attached_dev;
+ struct phy_driver *drv = to_phy_driver(phydev->dev.driver);
+ struct eth_device *edev = phydev->attached_dev;
int ret;
- int oldspeed = dev->speed, oldduplex = dev->duplex;
+ int oldspeed = phydev->speed, oldduplex = phydev->duplex;
- ret = drv->read_status(dev);
+ ret = drv->read_status(phydev);
if (ret)
return ret;
- if (dev->speed == oldspeed && dev->duplex == oldduplex)
+ if (phydev->speed == oldspeed && phydev->duplex == oldduplex)
return 0;
- if (dev->adjust_link)
- dev->adjust_link(edev);
+ if (phydev->adjust_link)
+ phydev->adjust_link(edev);
- if (dev->link)
- dev_info(&edev->dev, "%dMbps %s duplex link detected\n", dev->speed,
- dev->duplex ? "full" : "half");
+ if (phydev->link)
+ dev_info(&edev->dev, "%dMbps %s duplex link detected\n",
+ phydev->speed, phydev->duplex ? "full" : "half");
return 0;
}
@@ -71,9 +86,7 @@ int phy_register_fixup(const char *bus_id, u32 phy_uid, u32 phy_uid_mask,
{
struct phy_fixup *fixup;
- fixup = kzalloc(sizeof(struct phy_fixup), GFP_KERNEL);
- if (!fixup)
- return -ENOMEM;
+ fixup = xzalloc(sizeof(struct phy_fixup));
strlcpy(fixup->bus_id, bus_id, sizeof(fixup->bus_id));
fixup->phy_uid = phy_uid;
@@ -138,31 +151,28 @@ int phy_scan_fixups(struct phy_device *phydev)
static struct phy_device *phy_device_create(struct mii_bus *bus, int addr, int phy_id)
{
- struct phy_device *dev;
+ struct phy_device *phydev;
/* We allocate the device, and initialize the
* default values */
- dev = kzalloc(sizeof(*dev), GFP_KERNEL);
-
- if (NULL == dev)
- return (struct phy_device*) PTR_ERR((void*)-ENOMEM);
+ phydev = xzalloc(sizeof(*phydev));
- dev->speed = 0;
- dev->duplex = -1;
- dev->pause = dev->asym_pause = 0;
- dev->link = 1;
- dev->autoneg = AUTONEG_ENABLE;
+ phydev->speed = 0;
+ phydev->duplex = -1;
+ phydev->pause = phydev->asym_pause = 0;
+ phydev->link = 1;
+ phydev->autoneg = AUTONEG_ENABLE;
- dev->addr = addr;
- dev->phy_id = phy_id;
+ phydev->addr = addr;
+ phydev->phy_id = phy_id;
- dev->bus = bus;
- dev->dev.bus = &mdio_bus_type;
+ phydev->bus = bus;
+ phydev->dev.bus = &mdio_bus_type;
- strcpy(dev->dev.name, "phy");
- dev->dev.id = DEVICE_ID_DYNAMIC;
+ strcpy(phydev->dev.name, "phy");
+ phydev->dev.id = DEVICE_ID_DYNAMIC;
- return dev;
+ return phydev;
}
/**
* get_phy_id - reads the specified addr for its ID.
@@ -207,7 +217,7 @@ int get_phy_id(struct mii_bus *bus, int addr, u32 *phy_id)
*/
struct phy_device *get_phy_device(struct mii_bus *bus, int addr)
{
- struct phy_device *dev = NULL;
+ struct phy_device *phydev = NULL;
u32 phy_id = 0;
int r;
@@ -219,9 +229,9 @@ struct phy_device *get_phy_device(struct mii_bus *bus, int addr)
if ((phy_id & 0x1fffffff) == 0x1fffffff)
return ERR_PTR(-ENODEV);
- dev = phy_device_create(bus, addr, phy_id);
+ phydev = phy_device_create(bus, addr, phy_id);
- return dev;
+ return phydev;
}
static void phy_config_aneg(struct phy_device *phydev)
@@ -232,31 +242,31 @@ static void phy_config_aneg(struct phy_device *phydev)
drv->config_aneg(phydev);
}
-int phy_register_device(struct phy_device* dev)
+int phy_register_device(struct phy_device *phydev)
{
int ret;
- if (dev->registered)
+ if (phydev->registered)
return -EBUSY;
- dev->dev.parent = &dev->bus->dev;
+ phydev->dev.parent = &phydev->bus->dev;
- ret = register_device(&dev->dev);
+ ret = register_device(&phydev->dev);
if (ret)
return ret;
- dev->bus->phy_map[dev->addr] = dev;
+ phydev->bus->phy_map[phydev->addr] = phydev;
- dev->registered = 1;
+ phydev->registered = 1;
- if (dev->dev.driver)
+ if (phydev->dev.driver)
return 0;
- dev->dev.driver = &genphy_driver.drv;
- ret = device_probe(&dev->dev);
+ phydev->dev.driver = &genphy_driver.drv;
+ ret = device_probe(&phydev->dev);
if (ret) {
- unregister_device(&dev->dev);
- dev->registered = 0;
+ unregister_device(&phydev->dev);
+ phydev->registered = 0;
}
return ret;
@@ -477,25 +487,15 @@ int genphy_setup_forced(struct phy_device *phydev)
int phy_wait_aneg_done(struct phy_device *phydev)
{
uint64_t start = get_time_ns();
- int ctl;
if (phydev->autoneg == AUTONEG_DISABLE)
return 0;
while (!is_timeout(start, PHY_AN_TIMEOUT * SECOND)) {
- ctl = phy_read(phydev, MII_BMSR);
- if (ctl & BMSR_ANEGCOMPLETE) {
+ if (phy_aneg_done(phydev) > 0) {
phydev->link = 1;
return 0;
}
-
- /* Restart auto-negotiation if remote fault */
- if (ctl & BMSR_RFAULT) {
- puts("PHY remote fault detected\n"
- "PHY restarting auto-negotiation\n");
- phy_write(phydev, MII_BMCR,
- BMCR_ANENABLE | BMCR_ANRESTART);
- }
}
phydev->link = 0;
@@ -572,6 +572,33 @@ int genphy_config_aneg(struct phy_device *phydev)
}
/**
+ * genphy_aneg_done - return auto-negotiation status
+ * @phydev: target phy_device struct
+ *
+ * Description: Reads the status register and returns 0 either if
+ * auto-negotiation is incomplete, or if there was an error.
+ * Returns BMSR_ANEGCOMPLETE if auto-negotiation is done.
+ */
+int genphy_aneg_done(struct phy_device *phydev)
+{
+ int bmsr = phy_read(phydev, MII_BMSR);
+
+ if (bmsr < 0)
+ return bmsr;
+
+ /* Restart auto-negotiation if remote fault */
+ if (bmsr & BMSR_RFAULT) {
+ puts("PHY remote fault detected\n"
+ "PHY restarting auto-negotiation\n");
+ phy_write(phydev, MII_BMCR,
+ BMCR_ANENABLE | BMCR_ANRESTART);
+ }
+
+ return bmsr & BMSR_ANEGCOMPLETE;
+}
+EXPORT_SYMBOL(genphy_aneg_done);
+
+/**
* genphy_update_link - update link status in @phydev
* @phydev: target phy_device struct
*
@@ -825,6 +852,9 @@ int phy_driver_register(struct phy_driver *phydrv)
if (!phydrv->config_aneg)
phydrv->config_aneg = genphy_config_aneg;
+ if (!phydrv->aneg_done)
+ phydrv->aneg_done = genphy_aneg_done;
+
if (!phydrv->read_status)
phydrv->read_status = genphy_read_status;
diff --git a/drivers/net/usb/asix.c b/drivers/net/usb/asix.c
index d6ac322b7b..14a8c765f1 100644
--- a/drivers/net/usb/asix.c
+++ b/drivers/net/usb/asix.c
@@ -7,6 +7,7 @@
#include <errno.h>
#include <malloc.h>
#include <asm/byteorder.h>
+#include <asm/unaligned.h>
/* ASIX AX8817X based USB 2.0 Ethernet Devices */
@@ -134,6 +135,8 @@
#define FLAG_EEPROM_MAC (1UL << 0) /* init device MAC from eeprom */
+#define RX_FIXUP_SIZE 1514
+
/* This structure cannot exceed sizeof(unsigned long [5]) AKA 20 bytes */
struct asix_data {
u8 multi_filter[AX_MCAST_FILTER_SIZE];
@@ -150,6 +153,18 @@ struct ax88172_int_data {
__le16 res3;
} __attribute__ ((packed));
+struct asix_rx_fixup_info {
+ u32 header;
+ u16 size;
+ u16 offset;
+ bool split_head;
+ unsigned char ax_skb[RX_FIXUP_SIZE];
+};
+
+struct asix_common_private {
+ struct asix_rx_fixup_info rx_fixup_info;
+};
+
static int asix_read_cmd(struct usbnet *dev, u8 cmd, u16 value, u16 index,
u16 size, void *data)
{
@@ -409,49 +424,87 @@ static int ax88172_get_ethaddr(struct eth_device *edev, unsigned char *adr)
return 0;
}
-static int asix_rx_fixup(struct usbnet *dev, void *buf, int len)
+int asix_rx_fixup_internal(struct usbnet *dev, void *buf, int len,
+ struct asix_rx_fixup_info *rx)
{
- unsigned int header;
- unsigned short size;
-
- memcpy(&header, (void*) buf, sizeof(header));
- le32_to_cpus(&header);
- buf += 4;
- len -= 4;
-
- while (len > 0) {
- if ((header & 0x07ff) != ((~header >> 16) & 0x07ff))
- dev_err(&dev->edev.dev, "asix_rx_fixup() Bad Header Length\n");
-
- /* get the packet length */
- size = (unsigned short) (header & 0x07ff);
-
- if (size > 1514) {
- dev_err(&dev->edev.dev, "asix_rx_fixup() Bad RX Length %d\n", size);
- return 0;
+ int offset = 0;
+
+ while (offset + sizeof(u16) < len) {
+ u16 remaining = 0;
+
+ if (!rx->size) {
+ if ((len - offset == sizeof(u16)) ||
+ rx->split_head) {
+ if (!rx->split_head) {
+ rx->header = get_unaligned_le16(
+ buf + offset);
+ rx->split_head = true;
+ offset += sizeof(u16);
+ break;
+ } else {
+ rx->header |= (get_unaligned_le16(
+ buf + offset)
+ << 16);
+ rx->split_head = false;
+ offset += sizeof(u16);
+ }
+ } else {
+ rx->header = get_unaligned_le32(buf +
+ offset);
+ offset += sizeof(u32);
+ }
+ rx->offset = 0U;
+
+ /* get the packet length */
+ rx->size = (u16) (rx->header & 0x7ff);
+ if (rx->size != ((~rx->header >> 16) & 0x7ff)) {
+ dev_err(&dev->edev.dev, "asix_rx_fixup() Bad Header Length 0x%x, offset %d\n",
+ rx->header, offset);
+ rx->size = 0;
+ return -1;
+ }
}
+ if (rx->size > RX_FIXUP_SIZE) {
+ dev_err(&dev->edev.dev, "asix_rx_fixup() Bad RX Length %d\n",
+ rx->size);
+ rx->offset = 0U;
+ rx->size = 0U;
- net_receive(&dev->edev, buf, size);
+ return -1;
+ }
- buf += ((size + 1) & 0xfffe);
- len -= ((size + 1) & 0xfffe);
+ if (rx->size > (len - offset)) {
+ remaining = rx->size - (len - offset);
+ rx->size = len - offset;
+ }
- if (len == 0)
- break;
+ memcpy(rx->ax_skb + rx->offset, buf + offset, rx->size);
+ rx->offset += rx->size;
+ if (!remaining)
+ net_receive(&dev->edev, rx->ax_skb,
+ (u16) (rx->header & 0x7ff));
- memcpy(&header, (void*) buf, sizeof(header));
- le32_to_cpus(&header);
- buf += 4;
- len -= 4;
+ offset += ((rx->size + 1) & 0xfffe);
+ rx->size = remaining;
}
- if (len < 0) {
- dev_err(&dev->edev.dev,"asix_rx_fixup() Bad SKB Length %d\n", len);
+ if (len != offset) {
+ dev_err(&dev->edev.dev, "asix_rx_fixup() Bad SKB Length %d, %d\n",
+ len, offset);
return -1;
}
+
return 0;
}
+static int asix_rx_fixup_common(struct usbnet *dev, void *buf, int len)
+{
+ struct asix_common_private *dp = dev->driver_priv;
+ struct asix_rx_fixup_info *rx = &dp->rx_fixup_info;
+
+ return asix_rx_fixup_internal(dev, buf, len, rx);
+}
+
static int asix_tx_fixup(struct usbnet *dev,
void *buf, int len,
void *nbuf, int *nlen)
@@ -632,6 +685,11 @@ static int ax88772_bind(struct usbnet *dev)
dev->rx_urb_size = 2048;
}
+ dev->driver_priv = kzalloc(sizeof(struct asix_common_private),
+ GFP_KERNEL);
+ if (!dev->driver_priv)
+ return -ENOMEM;
+
return 0;
out:
@@ -641,6 +699,7 @@ out:
static void asix_unbind(struct usbnet *dev)
{
mdiobus_unregister(&dev->miibus);
+ kfree(dev->driver_priv);
}
static struct driver_info ax8817x_info = {
@@ -688,7 +747,7 @@ static struct driver_info ax88772_info = {
.bind = ax88772_bind,
.unbind = asix_unbind,
.flags = FLAG_ETHER | FLAG_FRAMING_AX,
- .rx_fixup = asix_rx_fixup,
+ .rx_fixup = asix_rx_fixup_common,
.tx_fixup = asix_tx_fixup,
};
@@ -697,7 +756,7 @@ static struct driver_info ax88772b_info = {
.bind = ax88772_bind,
.unbind = asix_unbind,
.flags = FLAG_ETHER | FLAG_FRAMING_AX,
- .rx_fixup = asix_rx_fixup,
+ .rx_fixup = asix_rx_fixup_common,
.tx_fixup = asix_tx_fixup,
.data = FLAG_EEPROM_MAC,
};
diff --git a/drivers/of/Kconfig b/drivers/of/Kconfig
index 81955063d7..97a1d933ec 100644
--- a/drivers/of/Kconfig
+++ b/drivers/of/Kconfig
@@ -4,7 +4,7 @@ config OFTREE
config OFTREE_MEM_GENERIC
depends on OFTREE
- depends on PPC || ARM || ARCH_EFI
+ depends on PPC || ARM || ARCH_EFI || OPENRISC
def_bool y
config DTC
diff --git a/drivers/of/base.c b/drivers/of/base.c
index c440a69e6c..e9f0883f47 100644
--- a/drivers/of/base.c
+++ b/drivers/of/base.c
@@ -265,19 +265,39 @@ struct device_node *of_find_node_by_alias(struct device_node *root, const char *
EXPORT_SYMBOL_GPL(of_find_node_by_alias);
/*
- * of_find_node_by_phandle - Find a node given a phandle
- * @handle: phandle of the node to find
+ * of_find_node_by_phandle_from - Find a node given a phandle from given
+ * root node.
+ * @handle: phandle of the node to find
+ * @root: root node of the tree to search in. If NULL use the
+ * internal tree.
*/
-struct device_node *of_find_node_by_phandle(phandle phandle)
+struct device_node *of_find_node_by_phandle_from(phandle phandle,
+ struct device_node *root)
{
struct device_node *node;
- of_tree_for_each_node_from(node, root_node)
+ if (!root)
+ root = root_node;
+
+ if (!root)
+ return 0;
+
+ of_tree_for_each_node_from(node, root)
if (node->phandle == phandle)
return node;
return NULL;
}
+EXPORT_SYMBOL(of_find_node_by_phandle_from);
+
+/*
+ * of_find_node_by_phandle - Find a node given a phandle
+ * @handle: phandle of the node to find
+ */
+struct device_node *of_find_node_by_phandle(phandle phandle)
+{
+ return of_find_node_by_phandle_from(phandle, root_node);
+}
EXPORT_SYMBOL(of_find_node_by_phandle);
/*
@@ -336,6 +356,27 @@ phandle of_node_create_phandle(struct device_node *node)
}
EXPORT_SYMBOL(of_node_create_phandle);
+int of_set_property_to_child_phandle(struct device_node *node, char *prop_name)
+{
+ int ret;
+ phandle p;
+
+ /* Check if property exist */
+ if (!of_get_property(of_get_parent(node), prop_name, NULL))
+ return -EINVAL;
+
+ /* Create or get existing phandle of child node */
+ p = of_node_create_phandle(node);
+ p = cpu_to_be32(p);
+
+ node = of_get_parent(node);
+
+ ret = of_set_property(node, prop_name, &p, sizeof(p), 0);
+
+ return ret;
+}
+EXPORT_SYMBOL(of_set_property_to_child_phandle);
+
/*
* Find a property with a given name for a given node
* and return the value.
@@ -1110,16 +1151,19 @@ int of_property_write_u64_array(struct device_node *np,
}
/**
- * of_parse_phandle - Resolve a phandle property to a device_node pointer
+ * of_parse_phandle_from - Resolve a phandle property to a device_node pointer from
+ * a given root node
* @np: Pointer to device node holding phandle property
+ * @root: root node of the tree to search in. If NULL use the internal tree.
* @phandle_name: Name of property holding a phandle value
* @index: For properties holding a table of phandles, this is the index into
* the table
*
* Returns the device_node pointer found or NULL.
*/
-struct device_node *of_parse_phandle(const struct device_node *np,
- const char *phandle_name, int index)
+struct device_node *of_parse_phandle_from(const struct device_node *np,
+ struct device_node *root,
+ const char *phandle_name, int index)
{
const __be32 *phandle;
int size;
@@ -1128,7 +1172,24 @@ struct device_node *of_parse_phandle(const struct device_node *np,
if ((!phandle) || (size < sizeof(*phandle) * (index + 1)))
return NULL;
- return of_find_node_by_phandle(be32_to_cpup(phandle + index));
+ return of_find_node_by_phandle_from(be32_to_cpup(phandle + index),
+ root);
+}
+EXPORT_SYMBOL(of_parse_phandle_from);
+
+/**
+ * of_parse_phandle - Resolve a phandle property to a device_node pointer
+ * @np: Pointer to device node holding phandle property
+ * @phandle_name: Name of property holding a phandle value
+ * @index: For properties holding a table of phandles, this is the index into
+ * the table
+ *
+ * Returns the device_node pointer found or NULL.
+ */
+struct device_node *of_parse_phandle(const struct device_node *np,
+ const char *phandle_name, int index)
+{
+ return of_parse_phandle_from(np, root_node, phandle_name, index);
}
EXPORT_SYMBOL(of_parse_phandle);
diff --git a/drivers/of/fdt.c b/drivers/of/fdt.c
index 8e4c7756fb..cfe1833509 100644
--- a/drivers/of/fdt.c
+++ b/drivers/of/fdt.c
@@ -1,5 +1,5 @@
/*
- * dtb.c - flat devicetree functions
+ * fdt.c - flat devicetree functions
*
* Copyright (c) 2013 Sascha Hauer <s.hauer@pengutronix.de>, Pengutronix
*
diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig
index 398b931546..770fb2d414 100644
--- a/drivers/pinctrl/Kconfig
+++ b/drivers/pinctrl/Kconfig
@@ -1,20 +1,21 @@
config PINCTRL
bool "Pin controller core support"
- depends on OFDEVICE
+ default y if OFDEVICE
help
Pincontrollers allow to setup the iomux unit of SoCs. The pin
controller core is needed when pin muxing shall be configured
from the devicetree. Legacy drivers here may not need this core
support but instead provide their own SoC specific APIs
+# The following drivers are needed even without PINCTRL because
+# the either have a legacy iomux interface or also register a gpio
+# chip.
config PINCTRL_AT91
- select PINCTRL if OFDEVICE
bool
help
The pinmux controller found on AT91 SoCs.
config PINCTRL_IMX_IOMUX_V1
- select PINCTRL if OFDEVICE
bool
help
This iomux controller is found on i.MX1,21,27.
@@ -25,13 +26,18 @@ config PINCTRL_IMX_IOMUX_V2
This iomux controller is found on i.MX31.
config PINCTRL_IMX_IOMUX_V3
- select PINCTRL if OFDEVICE
bool
help
This iomux controller is found on i.MX25,35,51,53,6.
+if PINCTRL
+
+if !OFDEVICE
+comment "OFDEVICE is not enabled."
+comment "Without device tree support PINCTRL won't do anything"
+endif
+
config PINCTRL_ROCKCHIP
- select PINCTRL
select GPIO_GENERIC
select MFD_SYSCON
bool
@@ -39,19 +45,21 @@ config PINCTRL_ROCKCHIP
The pinmux controller found on Rockchip SoCs.
config PINCTRL_SINGLE
- select PINCTRL
bool "pinctrl single"
config PINCTRL_TEGRA20
- select PINCTRL
bool
+ default y if ARCH_TEGRA_2x_SOC
help
The pinmux controller found on the Tegra 20 line of SoCs.
config PINCTRL_TEGRA30
- select PINCTRL
bool
+ default y if ARCH_TEGRA_3x_SOC
+ default y if ARCH_TEGRA_124_SOC
help
The pinmux controller found on the Tegra 30+ line of SoCs.
source drivers/pinctrl/mvebu/Kconfig
+
+endif
diff --git a/drivers/pinctrl/mvebu/Kconfig b/drivers/pinctrl/mvebu/Kconfig
index be154ed437..af20cad439 100644
--- a/drivers/pinctrl/mvebu/Kconfig
+++ b/drivers/pinctrl/mvebu/Kconfig
@@ -1,15 +1,15 @@
config PINCTRL_ARMADA_370
+ default y if ARCH_ARMADA_370
bool
- select PINCTRL
config PINCTRL_ARMADA_XP
bool
- select PINCTRL
+ default y if ARCH_ARMADA_XP
config PINCTRL_DOVE
bool
- select PINCTRL
+ default y if ARCH_DOVE
config PINCTRL_KIRKWOOD
bool
- select PINCTRL
+ default y if ARCH_KIRKWOOD
diff --git a/drivers/pinctrl/pinctrl-rockchip.c b/drivers/pinctrl/pinctrl-rockchip.c
index a5b52a8bc0..3533aff942 100644
--- a/drivers/pinctrl/pinctrl-rockchip.c
+++ b/drivers/pinctrl/pinctrl-rockchip.c
@@ -443,6 +443,9 @@ static int rockchip_pinctrl_probe(struct device_d *dev)
if (ret)
return ret;
+ if (!IS_ENABLED(CONFIG_PINCTRL))
+ return 0;
+
ret = pinctrl_register(&info->pctl_dev);
if (ret)
return ret;
diff --git a/drivers/pinctrl/pinctrl.c b/drivers/pinctrl/pinctrl.c
index 8963ac75c0..d6479b9cd5 100644
--- a/drivers/pinctrl/pinctrl.c
+++ b/drivers/pinctrl/pinctrl.c
@@ -62,6 +62,9 @@ int of_pinctrl_select_state(struct device_node *np, const char *name)
struct device_node *np_config;
const char *statename;
+ if (!IS_ENABLED(CONFIG_PINCTRL))
+ return -ENOSYS;
+
if (!of_find_property(np, "pinctrl-0", NULL))
return 0;
@@ -146,6 +149,9 @@ int pinctrl_select_state_default(struct device_d *dev)
int pinctrl_register(struct pinctrl_device *pdev)
{
+ if (!IS_ENABLED(CONFIG_PINCTRL))
+ return -ENOSYS;
+
BUG_ON(!pdev->dev->device_node);
list_add_tail(&pdev->list, &pinctrl_list);
diff --git a/drivers/usb/Kconfig b/drivers/usb/Kconfig
index eedd20e311..8520a2fd9b 100644
--- a/drivers/usb/Kconfig
+++ b/drivers/usb/Kconfig
@@ -19,3 +19,5 @@ endif
source drivers/usb/gadget/Kconfig
+source drivers/usb/musb/Kconfig
+
diff --git a/drivers/usb/Makefile b/drivers/usb/Makefile
index 3cefab7131..047f184800 100644
--- a/drivers/usb/Makefile
+++ b/drivers/usb/Makefile
@@ -1,5 +1,6 @@
obj-$(CONFIG_USB) += core/
obj-$(CONFIG_USB_IMX_CHIPIDEA) += imx/
+obj-$(CONFIG_USB_MUSB) += musb/
obj-$(CONFIG_USB_GADGET) += gadget/
obj-$(CONFIG_USB_STORAGE) += storage/
obj-y += host/
diff --git a/drivers/usb/core/of.c b/drivers/usb/core/of.c
index 1ddbdaab0f..fd20368424 100644
--- a/drivers/usb/core/of.c
+++ b/drivers/usb/core/of.c
@@ -16,6 +16,7 @@
#include <common.h>
#include <usb/usb.h>
+#include <usb/phy.h>
#include <of.h>
static const char *usb_dr_modes[] = {
diff --git a/drivers/usb/gadget/Kconfig b/drivers/usb/gadget/Kconfig
index 883a19f35b..65315e6f31 100644
--- a/drivers/usb/gadget/Kconfig
+++ b/drivers/usb/gadget/Kconfig
@@ -1,9 +1,4 @@
-config USB_HAVE_GADGET_DRIVER
- bool
- default y if ARCH_IMX || ARCH_MXS || ARCH_AT91 || ARCH_PXA
-
menuconfig USB_GADGET
- depends on USB_HAVE_GADGET_DRIVER
select USB
bool "USB gadget support"
@@ -12,13 +7,11 @@ if USB_GADGET
config USB_GADGET_DUALSPEED
bool
-choice
- prompt "USB Peripheral Controller"
-
config USB_GADGET_DRIVER_ARC
bool
prompt "Arc OTG device core"
depends on ARCH_IMX || ARCH_MXS
+ default y
select USB_GADGET_DUALSPEED
select POLLER
@@ -26,6 +19,7 @@ config USB_GADGET_DRIVER_AT91
bool
prompt "at91 gadget driver"
depends on ARCH_AT91
+ default y
select USB_GADGET_DUALSPEED
select POLLER
@@ -33,9 +27,9 @@ config USB_GADGET_DRIVER_PXA27X
bool
prompt "PXA27x gadget driver"
depends on ARCH_PXA
+ default y
select USB_GADGET_DUALSPEED
select POLLER
-endchoice
comment "USB Gadget drivers"
diff --git a/drivers/usb/gadget/at91_udc.c b/drivers/usb/gadget/at91_udc.c
index 2f0d5ed6fa..60e1ff79d3 100644
--- a/drivers/usb/gadget/at91_udc.c
+++ b/drivers/usb/gadget/at91_udc.c
@@ -21,7 +21,6 @@
#include <clock.h>
#include <usb/ch9.h>
#include <usb/gadget.h>
-#include <poller.h>
#include <gpio.h>
#include <linux/list.h>
@@ -1257,6 +1256,8 @@ static int at91_udc_stop(struct usb_gadget *gadget, struct usb_gadget_driver *dr
return 0;
}
+static void at91_udc_gadget_poll(struct usb_gadget *gadget);
+
static const struct usb_gadget_ops at91_udc_ops = {
.get_frame = at91_get_frame,
.wakeup = at91_wakeup,
@@ -1271,6 +1272,7 @@ static const struct usb_gadget_ops at91_udc_ops = {
/* .vbus_power = at91_vbus_power, */
.udc_start = at91_udc_start,
.udc_stop = at91_udc_stop,
+ .udc_poll = at91_udc_gadget_poll,
};
/*-------------------------------------------------------------------------*/
@@ -1350,13 +1352,13 @@ static int at91_udc_vbus_set(struct param_d *p, void *priv)
return -EROFS;
}
-int usb_gadget_poll(void)
+static void at91_udc_gadget_poll(struct usb_gadget *gadget)
{
struct at91_udc *udc = &controller;
u32 value;
if (!udc->udp_baseaddr)
- return -ENODEV;
+ return;
if (gpio_is_valid(udc->board.vbus_pin)) {
value = gpio_get_value(udc->board.vbus_pin);
@@ -1365,27 +1367,16 @@ int usb_gadget_poll(void)
udc->gpio_vbus_val = value;
if (!value)
- return 0;
+ return;
}
value = at91_udp_read(udc, AT91_UDP_ISR) & (~(AT91_UDP_SOFINT));
if (value)
at91_udc_irq(udc);
-
- return value;
}
/*-------------------------------------------------------------------------*/
-static void at91_udc_poller(struct poller_struct *poller)
-{
- usb_gadget_poll();
-}
-
-static struct poller_struct poller = {
- .func = at91_udc_poller
-};
-
static int __init at91udc_probe(struct device_d *dev)
{
struct at91_udc *udc = &controller;
@@ -1480,8 +1471,6 @@ static int __init at91udc_probe(struct device_d *dev)
udc->vbus = 1;
}
- poller_register(&poller);
-
retval = usb_add_gadget_udc_release(dev, &udc->gadget, NULL);
if (retval)
goto fail0a;
diff --git a/drivers/usb/gadget/dfu.c b/drivers/usb/gadget/dfu.c
index ddd765a343..67a0703ca9 100644
--- a/drivers/usb/gadget/dfu.c
+++ b/drivers/usb/gadget/dfu.c
@@ -722,6 +722,7 @@ static struct usb_composite_driver dfu_driver = {
.name = "g_dfu",
.dev = &dfu_dev_descriptor,
.strings = dev_strings,
+ .max_speed = USB_SPEED_HIGH,
.bind = dfu_driver_bind,
.unbind = dfu_driver_unbind,
};
diff --git a/drivers/usb/gadget/f_fastboot.c b/drivers/usb/gadget/f_fastboot.c
index 9aec6b198a..92a1a218c6 100644
--- a/drivers/usb/gadget/f_fastboot.c
+++ b/drivers/usb/gadget/f_fastboot.c
@@ -26,6 +26,7 @@
#include <boot.h>
#include <dma.h>
#include <fs.h>
+#include <libfile.h>
#include <file-list.h>
#include <progress.h>
#include <environment.h>
diff --git a/drivers/usb/gadget/fsl_udc.c b/drivers/usb/gadget/fsl_udc.c
index 877d2dfec4..d067f03a40 100644
--- a/drivers/usb/gadget/fsl_udc.c
+++ b/drivers/usb/gadget/fsl_udc.c
@@ -7,7 +7,6 @@
#include <usb/gadget.h>
#include <usb/fsl_usb2.h>
#include <io.h>
-#include <poller.h>
#include <asm/byteorder.h>
#include <linux/err.h>
@@ -1938,18 +1937,17 @@ static void dtd_complete_irq(struct fsl_udc *udc)
/*
* USB device controller interrupt handler
*/
-int usb_gadget_poll(void)
+static void fsl_udc_gadget_poll(struct usb_gadget *gadget)
{
struct fsl_udc *udc = udc_controller;
u32 irq_src;
- int status = 0;
if (!udc)
- return -ENODEV;
+ return;
/* Disable ISR for OTG host mode */
if (udc->stopped)
- return -EIO;
+ return;
irq_src = readl(&dr_regs->usbsts) & readl(&dr_regs->usbintr);
/* Clear notification bits */
@@ -1962,43 +1960,27 @@ int usb_gadget_poll(void)
tripwire_handler(udc, 0,
(u8 *) (&udc->local_setup_buff));
setup_received_irq(udc, &udc->local_setup_buff);
- status = 1;
}
/* completion of dtd */
- if (readl(&dr_regs->endptcomplete)) {
+ if (readl(&dr_regs->endptcomplete))
dtd_complete_irq(udc);
- status = 1;
- }
- }
-
- /* SOF (for ISO transfer) */
- if (irq_src & USB_STS_SOF) {
- status = 1;
}
/* Port Change */
- if (irq_src & USB_STS_PORT_CHANGE) {
+ if (irq_src & USB_STS_PORT_CHANGE)
port_change_irq(udc);
- status = 1;
- }
/* Reset Received */
- if (irq_src & USB_STS_RESET) {
+ if (irq_src & USB_STS_RESET)
reset_irq(udc);
- status = 1;
- }
/* Sleep Enable (Suspend) */
- if (irq_src & USB_STS_SUSPEND) {
+ if (irq_src & USB_STS_SUSPEND)
udc->driver->disconnect(&udc_controller->gadget);
- status = 1;
- }
if (irq_src & (USB_STS_ERR | USB_STS_SYS_ERR))
printf("Error IRQ %x\n", irq_src);
-
- return status;
}
/*----------------------------------------------------------------*
@@ -2197,6 +2179,7 @@ static struct usb_gadget_ops fsl_gadget_ops = {
.pullup = fsl_pullup,
.udc_start = fsl_udc_start,
.udc_stop = fsl_udc_stop,
+ .udc_poll = fsl_udc_gadget_poll,
};
/*----------------------------------------------------------------
@@ -2234,15 +2217,6 @@ static int __init struct_ep_setup(struct fsl_udc *udc, unsigned char index,
return 0;
}
-static void fsl_udc_poller(struct poller_struct *poller)
-{
- usb_gadget_poll();
-}
-
-static struct poller_struct poller = {
- .func = fsl_udc_poller
-};
-
int ci_udc_register(struct device_d *dev, void __iomem *regs)
{
int ret, i;
@@ -2305,8 +2279,6 @@ int ci_udc_register(struct device_d *dev, void __iomem *regs)
struct_ep_setup(udc_controller, i * 2 + 1, name, 1);
}
- poller_register(&poller);
-
ret = usb_add_gadget_udc_release(dev, &udc_controller->gadget,
NULL);
if (ret)
diff --git a/drivers/usb/gadget/pxa27x_udc.c b/drivers/usb/gadget/pxa27x_udc.c
index 6cc4dd7bda..3db3480cad 100644
--- a/drivers/usb/gadget/pxa27x_udc.c
+++ b/drivers/usb/gadget/pxa27x_udc.c
@@ -23,7 +23,6 @@
#include <io.h>
#include <gpio.h>
#include <init.h>
-#include <poller.h>
#include <usb/ch9.h>
#include <usb/gadget.h>
@@ -884,6 +883,7 @@ static int pxa_udc_vbus_session(struct usb_gadget *_gadget, int is_active)
static int pxa_udc_start(struct usb_gadget *gadget, struct usb_gadget_driver *driver);
static int pxa_udc_stop(struct usb_gadget *gadget, struct usb_gadget_driver *driver);
+static void pxa_udc_gadget_poll(struct usb_gadget *gadget);
static const struct usb_gadget_ops pxa_udc_ops = {
.get_frame = pxa_udc_get_frame,
@@ -892,6 +892,7 @@ static const struct usb_gadget_ops pxa_udc_ops = {
.vbus_session = pxa_udc_vbus_session,
.udc_start = pxa_udc_start,
.udc_stop = pxa_udc_stop,
+ .udc_poll = pxa_udc_gadget_poll,
};
static void clk_enable(void)
@@ -1366,14 +1367,13 @@ static void irq_udc_reset(struct pxa_udc *udc)
ep0_idle(udc);
}
-int usb_gadget_poll(void)
+static void pxa_udc_gadget_poll(struct usb_gadget *gadget)
{
- struct pxa_udc *udc = the_controller;
+ struct pxa_udc *udc = to_gadget_udc(gadget);
u32 udcisr0 = udc_readl(udc, UDCISR0);
u32 udcisr1 = udc_readl(udc, UDCISR1);
u32 udccr = udc_readl(udc, UDCCR);
u32 udcisr1_spec;
- int ret = 0;
udc->vbus_sensed = udc->mach->udc_is_connected();
if (should_enable_udc(udc))
@@ -1384,7 +1384,7 @@ int usb_gadget_poll(void)
}
if (!udc->enabled)
- return -EIO;
+ return;
dev_dbg(udc->dev, "Interrupt, UDCISR0:0x%08x, UDCISR1:0x%08x, "
"UDCCR:0x%08x\n", udcisr0, udcisr1, udccr);
@@ -1398,15 +1398,9 @@ int usb_gadget_poll(void)
irq_udc_reconfig(udc);
if (unlikely(udcisr1_spec & UDCISR1_IRRS))
irq_udc_reset(udc);
- if (udcisr1_spec)
- ret = 1;
- if ((udcisr0 & UDCCISR0_EP_MASK) | (udcisr1 & UDCCISR1_EP_MASK)) {
+ if ((udcisr0 & UDCCISR0_EP_MASK) | (udcisr1 & UDCCISR1_EP_MASK))
irq_handle_data(udc);
- ret = 1;
- }
-
- return ret;
}
static struct pxa_udc memory = {
@@ -1453,14 +1447,6 @@ static struct pxa_udc memory = {
}
};
-static void pxa27x_udc_poller(struct poller_struct *poller)
-{
- usb_gadget_poll();
-}
-static struct poller_struct poller = {
- .func = pxa27x_udc_poller
-};
-
static int __init pxa_udc_probe(struct device_d *dev)
{
struct pxa_udc *udc = &memory;
@@ -1484,7 +1470,6 @@ static int __init pxa_udc_probe(struct device_d *dev)
the_controller = udc;
udc_init_data(udc);
pxa_eps_setup(udc);
- poller_register(&poller);
ret = usb_add_gadget_udc_release(dev, &udc->gadget, NULL);
if (ret)
diff --git a/drivers/usb/gadget/udc-core.c b/drivers/usb/gadget/udc-core.c
index 2f62177cac..4f001e102f 100644
--- a/drivers/usb/gadget/udc-core.c
+++ b/drivers/usb/gadget/udc-core.c
@@ -20,6 +20,7 @@
#include <common.h>
#include <driver.h>
#include <init.h>
+#include <poller.h>
#include <usb/ch9.h>
#include <usb/gadget.h>
@@ -38,6 +39,7 @@ struct usb_udc {
struct usb_gadget *gadget;
struct device_d dev;
struct list_head list;
+ struct poller_struct poller;
};
static LIST_HEAD(udc_list);
@@ -146,6 +148,18 @@ static inline void usb_gadget_udc_stop(struct usb_gadget *gadget,
gadget->ops->udc_stop(gadget, driver);
}
+int usb_gadget_poll(void)
+{
+ struct usb_udc *udc;
+
+ list_for_each_entry(udc, &udc_list, list) {
+ if (udc->gadget->ops->udc_poll)
+ udc->gadget->ops->udc_poll(udc->gadget);
+ }
+
+ return 0;
+}
+
/**
* usb_add_gadget_udc_release - adds a new gadget to the udc class driver list
* @parent: the parent device to this udc. Usually the controller driver's
@@ -223,6 +237,9 @@ static void usb_gadget_remove_driver(struct usb_udc *udc)
dev_dbg(&udc->dev, "unregistering UDC driver [%s]\n",
udc->gadget->name);
+ if (udc->gadget->ops->udc_poll)
+ poller_unregister(&udc->poller);
+
usb_gadget_disconnect(udc->gadget);
udc->driver->disconnect(udc->gadget);
udc->driver->unbind(udc->gadget);
@@ -267,6 +284,13 @@ EXPORT_SYMBOL_GPL(usb_del_gadget_udc);
/* ------------------------------------------------------------------------- */
+static void udc_poll_driver(struct poller_struct *poller)
+{
+ struct usb_udc *udc = container_of(poller, struct usb_udc, poller);
+
+ udc->gadget->ops->udc_poll(udc->gadget);
+}
+
static int udc_bind_to_driver(struct usb_udc *udc, struct usb_gadget_driver *driver)
{
int ret;
@@ -278,6 +302,13 @@ static int udc_bind_to_driver(struct usb_udc *udc, struct usb_gadget_driver *dri
udc->dev.driver = &driver->driver;
udc->gadget->dev.driver = &driver->driver;
+ if (udc->gadget->ops->udc_poll) {
+ udc->poller.func = udc_poll_driver;
+ ret = poller_register(&udc->poller);
+ if (ret)
+ return ret;
+ }
+
ret = driver->bind(udc->gadget, driver);
if (ret)
goto err1;
@@ -291,6 +322,9 @@ static int udc_bind_to_driver(struct usb_udc *udc, struct usb_gadget_driver *dri
return 0;
err1:
+ if (udc->gadget->ops->udc_poll)
+ poller_unregister(&udc->poller);
+
if (ret != -EISNAM)
dev_err(&udc->dev, "failed to start %s: %d\n",
udc->driver->function, ret);
diff --git a/drivers/usb/imx/chipidea-imx.c b/drivers/usb/imx/chipidea-imx.c
index ffa46dac6e..1dca6bfe1d 100644
--- a/drivers/usb/imx/chipidea-imx.c
+++ b/drivers/usb/imx/chipidea-imx.c
@@ -22,6 +22,7 @@
#include <usb/ehci.h>
#include <regulator.h>
#include <usb/chipidea-imx.h>
+#include <usb/phy.h>
#include <usb/ulpi.h>
#include <usb/fsl_usb2.h>
#include <linux/err.h>
diff --git a/drivers/usb/musb/Kconfig b/drivers/usb/musb/Kconfig
new file mode 100644
index 0000000000..e0a1139bc0
--- /dev/null
+++ b/drivers/usb/musb/Kconfig
@@ -0,0 +1,29 @@
+config USB_MUSB
+ bool "MUSB support"
+
+if USB_MUSB
+
+config USB_MUSB_DSPS
+ tristate
+
+config USB_MUSB_AM335X
+ tristate "AM335x USB support"
+ depends on ARCH_AM33XX
+ select USB_MUSB_DSPS
+ help
+ This driver provides the necessary bit to enable USB support
+ on the TI AM335x SoC.
+
+config USB_MUSB_HOST
+ bool "MUSB Host mode support"
+ depends on USB_HOST
+ help
+ Select this when you want to use MUSB in host mode.
+
+config USB_MUSB_GADGET
+ bool "MUSB Gadget mode support"
+ depends on USB_GADGET
+ help
+ Select this when you want to use MUSB in gadget mode.
+
+endif
diff --git a/drivers/usb/musb/Makefile b/drivers/usb/musb/Makefile
new file mode 100644
index 0000000000..364a43fecb
--- /dev/null
+++ b/drivers/usb/musb/Makefile
@@ -0,0 +1,11 @@
+#
+# for USB OTG silicon based on Mentor Graphics INVENTRA designs
+#
+
+obj-y += musb_core.o musb_barebox.o
+
+obj-$(CONFIG_USB_MUSB_HOST) += musb_host.o
+obj-$(CONFIG_USB_MUSB_GADGET) += musb_gadget.o musb_gadget_ep0.o
+
+obj-$(CONFIG_USB_MUSB_DSPS) += musb_dsps.o
+obj-$(CONFIG_USB_MUSB_AM335X) += phy-am335x-control.o musb_am335x.o phy-am335x.o
diff --git a/drivers/usb/musb/am35x-phy-control.h b/drivers/usb/musb/am35x-phy-control.h
new file mode 100644
index 0000000000..c492d421dc
--- /dev/null
+++ b/drivers/usb/musb/am35x-phy-control.h
@@ -0,0 +1,21 @@
+#ifndef _AM335x_PHY_CONTROL_H_
+#define _AM335x_PHY_CONTROL_H_
+
+struct phy_control {
+ void (*phy_power)(struct phy_control *phy_ctrl, u32 id, bool on);
+ void (*phy_wkup)(struct phy_control *phy_ctrl, u32 id, bool on);
+};
+
+static inline void phy_ctrl_power(struct phy_control *phy_ctrl, u32 id, bool on)
+{
+ phy_ctrl->phy_power(phy_ctrl, id, on);
+}
+
+static inline void phy_ctrl_wkup(struct phy_control *phy_ctrl, u32 id, bool on)
+{
+ phy_ctrl->phy_wkup(phy_ctrl, id, on);
+}
+
+struct phy_control *am335x_get_phy_control(struct device_d *dev);
+
+#endif
diff --git a/drivers/usb/musb/musb_am335x.c b/drivers/usb/musb/musb_am335x.c
new file mode 100644
index 0000000000..2a9167a245
--- /dev/null
+++ b/drivers/usb/musb/musb_am335x.c
@@ -0,0 +1,29 @@
+#include <common.h>
+#include <init.h>
+#include <linux/clk.h>
+
+static int am335x_child_probe(struct device_d *dev)
+{
+ int ret;
+
+ ret = of_platform_populate(dev->device_node, NULL, dev);
+ if (ret)
+ return ret;
+
+ return 0;
+}
+
+static __maybe_unused struct of_device_id am335x_child_dt_ids[] = {
+ {
+ .compatible = "ti,am33xx-usb",
+ }, {
+ /* sentinel */
+ },
+};
+
+static struct driver_d am335x_child_driver = {
+ .name = "am335x_child_probe",
+ .probe = am335x_child_probe,
+ .of_compatible = DRV_OF_COMPAT(am335x_child_dt_ids),
+};
+device_platform_driver(am335x_child_driver);
diff --git a/drivers/usb/musb/musb_barebox.c b/drivers/usb/musb/musb_barebox.c
new file mode 100644
index 0000000000..6bc232b570
--- /dev/null
+++ b/drivers/usb/musb/musb_barebox.c
@@ -0,0 +1,146 @@
+#include <common.h>
+#include <init.h>
+#include <clock.h>
+#include <usb/musb.h>
+#include <usb/usb.h>
+#include <linux/types.h>
+#include <linux/err.h>
+#include <linux/barebox-wrapper.h>
+
+#include "musb_core.h"
+#include "musb_gadget.h"
+
+static struct usb_host_endpoint hep;
+static struct urb urb;
+
+static void musb_host_complete_urb(struct urb *urb)
+{
+ urb->dev->status &= ~USB_ST_NOT_PROC;
+ urb->dev->act_len = urb->actual_length;
+}
+
+static struct urb *construct_urb(struct usb_device *dev, int endpoint_type,
+ unsigned long pipe, void *buffer, int len,
+ struct devrequest *setup, int interval)
+{
+ int epnum = usb_pipeendpoint(pipe);
+ int is_in = usb_pipein(pipe);
+
+ memset(&urb, 0, sizeof(struct urb));
+ memset(&hep, 0, sizeof(struct usb_host_endpoint));
+ INIT_LIST_HEAD(&hep.urb_list);
+ INIT_LIST_HEAD(&urb.urb_list);
+ urb.ep = &hep;
+ urb.complete = musb_host_complete_urb;
+ urb.status = -EINPROGRESS;
+ urb.dev = dev;
+ urb.pipe = pipe;
+ urb.transfer_buffer = buffer;
+ urb.transfer_dma = (unsigned long)buffer;
+ urb.transfer_buffer_length = len;
+ urb.setup_packet = (unsigned char *)setup;
+
+ urb.ep->desc.wMaxPacketSize =
+ __cpu_to_le16(is_in ? dev->epmaxpacketin[epnum] :
+ dev->epmaxpacketout[epnum]);
+ urb.ep->desc.bmAttributes = endpoint_type;
+ urb.ep->desc.bEndpointAddress =
+ (is_in ? USB_DIR_IN : USB_DIR_OUT) | epnum;
+ urb.ep->desc.bInterval = interval;
+
+ return &urb;
+}
+
+#define MUSB_HOST_TIMEOUT 0x5fffff
+
+static int submit_urb(struct usb_device *dev, struct urb *urb, int timeout_ms)
+{
+ struct usb_host *host = dev->host;
+ struct musb *musb = to_musb(host);
+ int ret;
+ uint64_t start;
+ uint64_t timeout = timeout_ms;
+
+ ret = musb_urb_enqueue(musb->hcd, urb, 0);
+ if (ret < 0) {
+ printf("Failed to enqueue URB to controller\n");
+ return ret;
+ }
+
+ start = get_time_ns();
+
+ do {
+ musb->isr(musb);
+
+ if (!urb->status)
+ return 0;
+
+ } while (!is_timeout(start, timeout * MSECOND));
+
+ if (urb->dev->status & USB_ST_NOT_PROC)
+ ret = -ETIMEDOUT;
+ else
+ ret = urb->status;
+
+ musb_urb_dequeue(musb->hcd, urb, -ECONNRESET);
+
+ return ret;
+}
+
+static int
+submit_bulk_msg(struct usb_device *dev, unsigned long pipe, void *buffer,
+ int length, int timeout)
+{
+ struct urb *urb = construct_urb(dev, USB_ENDPOINT_XFER_BULK, pipe,
+ buffer, length, NULL, 0);
+ return submit_urb(dev, urb, timeout);
+}
+
+static int
+submit_control_msg(struct usb_device *dev, unsigned long pipe, void *buffer,
+ int length, struct devrequest *setup, int timeout)
+{
+ struct usb_host *host = dev->host;
+ struct musb *musb = to_musb(host);
+ struct urb *urb = construct_urb(dev, USB_ENDPOINT_XFER_CONTROL, pipe,
+ buffer, length, setup, 0);
+
+ /* Fix speed for non hub-attached devices */
+ if (!dev->parent)
+ dev->speed = musb->host_speed;
+
+ return submit_urb(dev, urb, timeout);
+}
+
+static int
+submit_int_msg(struct usb_device *dev, unsigned long pipe, void *buffer,
+ int length, int interval)
+{
+ struct urb *urb = construct_urb(dev, USB_ENDPOINT_XFER_INT, pipe,
+ buffer, length, NULL, interval);
+ return submit_urb(dev, urb, 100);
+}
+
+static int musb_detect(struct device_d *dev)
+{
+ struct musb *musb = dev->priv;
+
+ return usb_host_detect(&musb->host);
+}
+
+int musb_register(struct musb *musb)
+{
+ struct usb_host *host;
+
+ host = &musb->host;
+ host->hw_dev = musb->controller;
+ host->init = musb_init;
+ host->submit_int_msg = submit_int_msg;
+ host->submit_control_msg = submit_control_msg;
+ host->submit_bulk_msg = submit_bulk_msg;
+
+ musb->controller->detect = musb_detect;
+ usb_register_host(host);
+
+ return 0;
+}
diff --git a/drivers/usb/musb/musb_core.c b/drivers/usb/musb/musb_core.c
new file mode 100644
index 0000000000..ccb702980f
--- /dev/null
+++ b/drivers/usb/musb/musb_core.c
@@ -0,0 +1,1156 @@
+/*
+ * MUSB OTG driver core code
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+/*
+ * Inventra (Multipoint) Dual-Role Controller Driver for Linux.
+ *
+ * This consists of a Host Controller Driver (HCD) and a peripheral
+ * controller driver implementing the "Gadget" API; OTG support is
+ * in the works. These are normal Linux-USB controller drivers which
+ * use IRQs and have no dedicated thread.
+ *
+ * This version of the driver has only been used with products from
+ * Texas Instruments. Those products integrate the Inventra logic
+ * with other DMA, IRQ, and bus modules, as well as other logic that
+ * needs to be reflected in this driver.
+ *
+ *
+ * NOTE: the original Mentor code here was pretty much a collection
+ * of mechanisms that don't seem to have been fully integrated/working
+ * for *any* Linux kernel version. This version aims at Linux 2.6.now,
+ * Key open issues include:
+ *
+ * - Lack of host-side transaction scheduling, for all transfer types.
+ * The hardware doesn't do it; instead, software must.
+ *
+ * This is not an issue for OTG devices that don't support external
+ * hubs, but for more "normal" USB hosts it's a user issue that the
+ * "multipoint" support doesn't scale in the expected ways. That
+ * includes DaVinci EVM in a common non-OTG mode.
+ *
+ * * Control and bulk use dedicated endpoints, and there's as
+ * yet no mechanism to either (a) reclaim the hardware when
+ * peripherals are NAKing, which gets complicated with bulk
+ * endpoints, or (b) use more than a single bulk endpoint in
+ * each direction.
+ *
+ * RESULT: one device may be perceived as blocking another one.
+ *
+ * * Interrupt and isochronous will dynamically allocate endpoint
+ * hardware, but (a) there's no record keeping for bandwidth;
+ * (b) in the common case that few endpoints are available, there
+ * is no mechanism to reuse endpoints to talk to multiple devices.
+ *
+ * RESULT: At one extreme, bandwidth can be overcommitted in
+ * some hardware configurations, no faults will be reported.
+ * At the other extreme, the bandwidth capabilities which do
+ * exist tend to be severely undercommitted. You can't yet hook
+ * up both a keyboard and a mouse to an external USB hub.
+ */
+
+/*
+ * This gets many kinds of configuration information:
+ * - Kconfig for everything user-configurable
+ * - platform_device for addressing, irq, and platform_data
+ * - platform_data is mostly for board-specific information
+ * (plus recentrly, SOC or family details)
+ *
+ * Most of the conditional compilation will (someday) vanish.
+ */
+
+#include <common.h>
+#include <init.h>
+#include <clock.h>
+#include <usb/musb.h>
+#include <usb/usb.h>
+#include <linux/types.h>
+#include <linux/err.h>
+#include <linux/barebox-wrapper.h>
+
+#include "musb_core.h"
+#include "musb_gadget.h"
+
+#define TA_WAIT_BCON(m) max_t(int, (m)->a_wait_bcon, OTG_TIME_A_WAIT_BCON)
+
+
+#define DRIVER_AUTHOR "Mentor Graphics, Texas Instruments, Nokia"
+#define DRIVER_DESC "Inventra Dual-Role USB Controller Driver"
+
+#define MUSB_VERSION "6.0"
+
+#define DRIVER_INFO DRIVER_DESC ", v" MUSB_VERSION
+
+#define MUSB_DRIVER_NAME "musb-hdrc"
+const char musb_driver_name[] = MUSB_DRIVER_NAME;
+
+MODULE_DESCRIPTION(DRIVER_INFO);
+MODULE_AUTHOR(DRIVER_AUTHOR);
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:" MUSB_DRIVER_NAME);
+
+#define MUSB_HOST_TIMEOUT 0x5fffff
+
+/*-------------------------------------------------------------------------*/
+
+#ifndef CONFIG_BLACKFIN
+static int musb_ulpi_read(struct usb_phy *phy, u32 offset)
+{
+ void __iomem *addr = phy->io_priv;
+ int i = 0;
+ u8 r;
+ u8 power;
+ int ret;
+
+ /* Make sure the transceiver is not in low power mode */
+ power = musb_readb(addr, MUSB_POWER);
+ power &= ~MUSB_POWER_SUSPENDM;
+ musb_writeb(addr, MUSB_POWER, power);
+
+ /* REVISIT: musbhdrc_ulpi_an.pdf recommends setting the
+ * ULPICarKitControlDisableUTMI after clearing POWER_SUSPENDM.
+ */
+
+ musb_writeb(addr, MUSB_ULPI_REG_ADDR, (u8)offset);
+ musb_writeb(addr, MUSB_ULPI_REG_CONTROL,
+ MUSB_ULPI_REG_REQ | MUSB_ULPI_RDN_WR);
+
+ while (!(musb_readb(addr, MUSB_ULPI_REG_CONTROL)
+ & MUSB_ULPI_REG_CMPLT)) {
+ i++;
+ if (i == 10000) {
+ ret = -ETIMEDOUT;
+ goto out;
+ }
+
+ }
+ r = musb_readb(addr, MUSB_ULPI_REG_CONTROL);
+ r &= ~MUSB_ULPI_REG_CMPLT;
+ musb_writeb(addr, MUSB_ULPI_REG_CONTROL, r);
+
+ ret = musb_readb(addr, MUSB_ULPI_REG_DATA);
+
+out:
+ return ret;
+}
+
+static int musb_ulpi_write(struct usb_phy *phy, u32 offset, u32 data)
+{
+ void __iomem *addr = phy->io_priv;
+ int i = 0;
+ u8 r = 0;
+ u8 power;
+ int ret = 0;
+
+ /* Make sure the transceiver is not in low power mode */
+ power = musb_readb(addr, MUSB_POWER);
+ power &= ~MUSB_POWER_SUSPENDM;
+ musb_writeb(addr, MUSB_POWER, power);
+
+ musb_writeb(addr, MUSB_ULPI_REG_ADDR, (u8)offset);
+ musb_writeb(addr, MUSB_ULPI_REG_DATA, (u8)data);
+ musb_writeb(addr, MUSB_ULPI_REG_CONTROL, MUSB_ULPI_REG_REQ);
+
+ while (!(musb_readb(addr, MUSB_ULPI_REG_CONTROL)
+ & MUSB_ULPI_REG_CMPLT)) {
+ i++;
+ if (i == 10000) {
+ ret = -ETIMEDOUT;
+ goto out;
+ }
+ }
+
+ r = musb_readb(addr, MUSB_ULPI_REG_CONTROL);
+ r &= ~MUSB_ULPI_REG_CMPLT;
+ musb_writeb(addr, MUSB_ULPI_REG_CONTROL, r);
+
+out:
+ return ret;
+}
+#else
+#define musb_ulpi_read NULL
+#define musb_ulpi_write NULL
+#endif
+
+struct usb_phy_io_ops musb_ulpi_access = {
+ .read = musb_ulpi_read,
+ .write = musb_ulpi_write,
+};
+
+/*-------------------------------------------------------------------------*/
+
+#if !defined(CONFIG_USB_MUSB_TUSB6010) && !defined(CONFIG_USB_MUSB_BLACKFIN)
+
+/*
+ * Load an endpoint's FIFO
+ */
+void musb_write_fifo(struct musb_hw_ep *hw_ep, u16 len, const u8 *src)
+{
+ struct musb *musb = hw_ep->musb;
+ void __iomem *fifo = hw_ep->fifo;
+
+ if (unlikely(len == 0))
+ return;
+
+ prefetch((u8 *)src);
+
+ dev_dbg(musb->controller, "%cX ep%d fifo %p count %d buf %p\n",
+ 'T', hw_ep->epnum, fifo, len, src);
+
+ /* we can't assume unaligned reads work */
+ if (likely((0x01 & (unsigned long) src) == 0)) {
+ u16 index = 0;
+
+ /* best case is 32bit-aligned source address */
+ if ((0x02 & (unsigned long) src) == 0) {
+ if (len >= 4) {
+ writesl(fifo, src + index, len >> 2);
+ index += len & ~0x03;
+ }
+ if (len & 0x02) {
+ musb_writew(fifo, 0, *(u16 *)&src[index]);
+ index += 2;
+ }
+ } else {
+ if (len >= 2) {
+ writesw(fifo, src + index, len >> 1);
+ index += len & ~0x01;
+ }
+ }
+ if (len & 0x01)
+ musb_writeb(fifo, 0, src[index]);
+ } else {
+ /* byte aligned */
+ writesb(fifo, src, len);
+ }
+}
+
+#if !defined(CONFIG_USB_MUSB_AM35X)
+/*
+ * Unload an endpoint's FIFO
+ */
+void musb_read_fifo(struct musb_hw_ep *hw_ep, u16 len, u8 *dst)
+{
+ struct musb *musb = hw_ep->musb;
+ void __iomem *fifo = hw_ep->fifo;
+
+ if (unlikely(len == 0))
+ return;
+
+ dev_dbg(musb->controller, "%cX ep%d fifo %p count %d buf %p\n",
+ 'R', hw_ep->epnum, fifo, len, dst);
+
+ /* we can't assume unaligned writes work */
+ if (likely((0x01 & (unsigned long) dst) == 0)) {
+ u16 index = 0;
+
+ /* best case is 32bit-aligned destination address */
+ if ((0x02 & (unsigned long) dst) == 0) {
+ if (len >= 4) {
+ readsl(fifo, dst, len >> 2);
+ index = len & ~0x03;
+ }
+ if (len & 0x02) {
+ *(u16 *)&dst[index] = musb_readw(fifo, 0);
+ index += 2;
+ }
+ } else {
+ if (len >= 2) {
+ readsw(fifo, dst, len >> 1);
+ index = len & ~0x01;
+ }
+ }
+ if (len & 0x01)
+ dst[index] = musb_readb(fifo, 0);
+ } else {
+ /* byte aligned */
+ readsb(fifo, dst, len);
+ }
+}
+#endif
+
+#endif /* normal PIO */
+
+/*-------------------------------------------------------------------------*/
+
+
+/* for high speed test mode; see USB 2.0 spec 7.1.20 */
+static const u8 musb_test_packet[53] = {
+ /* implicit SYNC then DATA0 to start */
+
+ /* JKJKJKJK x9 */
+ 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00,
+ /* JJKKJJKK x8 */
+ 0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa, 0xaa,
+ /* JJJJKKKK x8 */
+ 0xee, 0xee, 0xee, 0xee, 0xee, 0xee, 0xee, 0xee,
+ /* JJJJJJJKKKKKKK x8 */
+ 0xfe, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff, 0xff,
+ /* JJJJJJJK x8 */
+ 0x7f, 0xbf, 0xdf, 0xef, 0xf7, 0xfb, 0xfd,
+ /* JKKKKKKK x10, JK */
+ 0xfc, 0x7e, 0xbf, 0xdf, 0xef, 0xf7, 0xfb, 0xfd, 0x7e
+
+ /* implicit CRC16 then EOP to end */
+};
+
+void musb_load_testpacket(struct musb *musb)
+{
+ void __iomem *regs = musb->endpoints[0].regs;
+
+ musb_ep_select(musb->mregs, 0);
+ musb_write_fifo(musb->control_ep,
+ sizeof(musb_test_packet), musb_test_packet);
+ musb_writew(regs, MUSB_CSR0, MUSB_CSR0_TXPKTRDY);
+}
+
+/*-------------------------------------------------------------------------*/
+
+static void musb_generic_disable(struct musb *musb)
+{
+ void __iomem *mbase = musb->mregs;
+ u16 temp;
+
+ /* disable interrupts */
+ musb_writeb(mbase, MUSB_INTRUSBE, 0);
+ musb->intrtxe = 0;
+ musb_writew(mbase, MUSB_INTRTXE, 0);
+ musb->intrrxe = 0;
+ musb_writew(mbase, MUSB_INTRRXE, 0);
+
+ /* off */
+ musb_writeb(mbase, MUSB_DEVCTL, 0);
+
+ /* flush pending interrupts */
+ temp = musb_readb(mbase, MUSB_INTRUSB);
+ temp = musb_readw(mbase, MUSB_INTRTX);
+ temp = musb_readw(mbase, MUSB_INTRRX);
+
+}
+
+/*
+ * Program the HDRC to start (enable interrupts, dma, etc.).
+ */
+void musb_start(struct musb *musb)
+{
+ void __iomem *regs = musb->mregs;
+ u8 devctl = musb_readb(regs, MUSB_DEVCTL);
+
+ dev_dbg(musb->controller, "<== devctl %02x\n", devctl);
+
+ /* Set INT enable registers, enable interrupts */
+ musb->intrtxe = musb->epmask;
+ musb_writew(regs, MUSB_INTRTXE, musb->intrtxe);
+ musb->intrrxe = musb->epmask & 0xfffe;
+ musb_writew(regs, MUSB_INTRRXE, musb->intrrxe);
+ musb_writeb(regs, MUSB_INTRUSBE, 0xf7);
+
+ musb_writeb(regs, MUSB_TESTMODE, 0);
+
+ /* put into basic highspeed mode and start session */
+ musb_writeb(regs, MUSB_POWER, MUSB_POWER_ISOUPDATE
+ | MUSB_POWER_HSENAB
+ /* ENSUSPEND wedges tusb */
+ /* | MUSB_POWER_ENSUSPEND */
+ );
+
+ musb->is_active = 0;
+ devctl = musb_readb(regs, MUSB_DEVCTL);
+ devctl &= ~MUSB_DEVCTL_SESSION;
+
+ /* session started after:
+ * (a) ID-grounded irq, host mode;
+ * (b) vbus present/connect IRQ, peripheral mode;
+ * (c) peripheral initiates, using SRP
+ */
+ if (musb->port_mode != MUSB_PORT_MODE_HOST &&
+ (devctl & MUSB_DEVCTL_VBUS) == MUSB_DEVCTL_VBUS) {
+ musb->is_active = 1;
+ } else {
+ devctl |= MUSB_DEVCTL_SESSION;
+ }
+
+ musb_platform_enable(musb);
+ musb_writeb(regs, MUSB_DEVCTL, devctl);
+}
+
+/*
+ * Make the HDRC stop (disable interrupts, etc.);
+ * reversible by musb_start
+ * called on gadget driver unregister
+ * with controller locked, irqs blocked
+ * acts as a NOP unless some role activated the hardware
+ */
+void musb_stop(struct musb *musb)
+{
+ /* stop IRQs, timers, ... */
+ musb_platform_disable(musb);
+ musb_generic_disable(musb);
+ dev_dbg(musb->controller, "HDRC disabled\n");
+
+ /* FIXME
+ * - mark host and/or peripheral drivers unusable/inactive
+ * - disable DMA (and enable it in HdrcStart)
+ * - make sure we can musb_start() after musb_stop(); with
+ * OTG mode, gadget driver module rmmod/modprobe cycles that
+ * - ...
+ */
+ musb_platform_try_idle(musb, 0);
+}
+
+/*-------------------------------------------------------------------------*/
+
+/*
+ * The silicon either has hard-wired endpoint configurations, or else
+ * "dynamic fifo" sizing. The driver has support for both, though at this
+ * writing only the dynamic sizing is very well tested. Since we switched
+ * away from compile-time hardware parameters, we can no longer rely on
+ * dead code elimination to leave only the relevant one in the object file.
+ *
+ * We don't currently use dynamic fifo setup capability to do anything
+ * more than selecting one of a bunch of predefined configurations.
+ */
+#if defined(CONFIG_USB_MUSB_TUSB6010) \
+ || defined(CONFIG_USB_MUSB_TUSB6010_MODULE) \
+ || defined(CONFIG_USB_MUSB_OMAP2PLUS) \
+ || defined(CONFIG_USB_MUSB_OMAP2PLUS_MODULE) \
+ || defined(CONFIG_USB_MUSB_AM35X) \
+ || defined(CONFIG_USB_MUSB_AM35X_MODULE) \
+ || defined(CONFIG_USB_MUSB_DSPS) \
+ || defined(CONFIG_USB_MUSB_DSPS_MODULE)
+static ushort fifo_mode = 4;
+#elif defined(CONFIG_USB_MUSB_UX500) \
+ || defined(CONFIG_USB_MUSB_UX500_MODULE)
+static ushort fifo_mode = 5;
+#else
+static ushort fifo_mode = 2;
+#endif
+
+/*
+ * tables defining fifo_mode values. define more if you like.
+ * for host side, make sure both halves of ep1 are set up.
+ */
+
+/* mode 0 - fits in 2KB */
+static struct musb_fifo_cfg mode_0_cfg[] = {
+{ .hw_ep_num = 1, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 1, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_RXTX, .maxpacket = 512, },
+{ .hw_ep_num = 3, .style = FIFO_RXTX, .maxpacket = 256, },
+{ .hw_ep_num = 4, .style = FIFO_RXTX, .maxpacket = 256, },
+};
+
+/* mode 1 - fits in 4KB */
+static struct musb_fifo_cfg mode_1_cfg[] = {
+{ .hw_ep_num = 1, .style = FIFO_TX, .maxpacket = 512, .mode = BUF_DOUBLE, },
+{ .hw_ep_num = 1, .style = FIFO_RX, .maxpacket = 512, .mode = BUF_DOUBLE, },
+{ .hw_ep_num = 2, .style = FIFO_RXTX, .maxpacket = 512, .mode = BUF_DOUBLE, },
+{ .hw_ep_num = 3, .style = FIFO_RXTX, .maxpacket = 256, },
+{ .hw_ep_num = 4, .style = FIFO_RXTX, .maxpacket = 256, },
+};
+
+/* mode 2 - fits in 4KB */
+static struct musb_fifo_cfg mode_2_cfg[] = {
+{ .hw_ep_num = 1, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 1, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 3, .style = FIFO_RXTX, .maxpacket = 256, },
+{ .hw_ep_num = 4, .style = FIFO_RXTX, .maxpacket = 256, },
+};
+
+/* mode 3 - fits in 4KB */
+static struct musb_fifo_cfg mode_3_cfg[] = {
+{ .hw_ep_num = 1, .style = FIFO_TX, .maxpacket = 512, .mode = BUF_DOUBLE, },
+{ .hw_ep_num = 1, .style = FIFO_RX, .maxpacket = 512, .mode = BUF_DOUBLE, },
+{ .hw_ep_num = 2, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 3, .style = FIFO_RXTX, .maxpacket = 256, },
+{ .hw_ep_num = 4, .style = FIFO_RXTX, .maxpacket = 256, },
+};
+
+/* mode 4 - fits in 16KB */
+static struct musb_fifo_cfg mode_4_cfg[] = {
+{ .hw_ep_num = 1, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 1, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 3, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 3, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 4, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 4, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 5, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 5, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 6, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 6, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 7, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 7, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 8, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 8, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 9, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 9, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 10, .style = FIFO_TX, .maxpacket = 256, },
+{ .hw_ep_num = 10, .style = FIFO_RX, .maxpacket = 64, },
+{ .hw_ep_num = 11, .style = FIFO_TX, .maxpacket = 256, },
+{ .hw_ep_num = 11, .style = FIFO_RX, .maxpacket = 64, },
+{ .hw_ep_num = 12, .style = FIFO_TX, .maxpacket = 256, },
+{ .hw_ep_num = 12, .style = FIFO_RX, .maxpacket = 64, },
+{ .hw_ep_num = 13, .style = FIFO_RXTX, .maxpacket = 4096, },
+{ .hw_ep_num = 14, .style = FIFO_RXTX, .maxpacket = 1024, },
+{ .hw_ep_num = 15, .style = FIFO_RXTX, .maxpacket = 1024, },
+};
+
+/* mode 5 - fits in 8KB */
+static struct musb_fifo_cfg mode_5_cfg[] = {
+{ .hw_ep_num = 1, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 1, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 2, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 3, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 3, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 4, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 4, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 5, .style = FIFO_TX, .maxpacket = 512, },
+{ .hw_ep_num = 5, .style = FIFO_RX, .maxpacket = 512, },
+{ .hw_ep_num = 6, .style = FIFO_TX, .maxpacket = 32, },
+{ .hw_ep_num = 6, .style = FIFO_RX, .maxpacket = 32, },
+{ .hw_ep_num = 7, .style = FIFO_TX, .maxpacket = 32, },
+{ .hw_ep_num = 7, .style = FIFO_RX, .maxpacket = 32, },
+{ .hw_ep_num = 8, .style = FIFO_TX, .maxpacket = 32, },
+{ .hw_ep_num = 8, .style = FIFO_RX, .maxpacket = 32, },
+{ .hw_ep_num = 9, .style = FIFO_TX, .maxpacket = 32, },
+{ .hw_ep_num = 9, .style = FIFO_RX, .maxpacket = 32, },
+{ .hw_ep_num = 10, .style = FIFO_TX, .maxpacket = 32, },
+{ .hw_ep_num = 10, .style = FIFO_RX, .maxpacket = 32, },
+{ .hw_ep_num = 11, .style = FIFO_TX, .maxpacket = 32, },
+{ .hw_ep_num = 11, .style = FIFO_RX, .maxpacket = 32, },
+{ .hw_ep_num = 12, .style = FIFO_TX, .maxpacket = 32, },
+{ .hw_ep_num = 12, .style = FIFO_RX, .maxpacket = 32, },
+{ .hw_ep_num = 13, .style = FIFO_RXTX, .maxpacket = 512, },
+{ .hw_ep_num = 14, .style = FIFO_RXTX, .maxpacket = 1024, },
+{ .hw_ep_num = 15, .style = FIFO_RXTX, .maxpacket = 1024, },
+};
+
+/*
+ * configure a fifo; for non-shared endpoints, this may be called
+ * once for a tx fifo and once for an rx fifo.
+ *
+ * returns negative errno or offset for next fifo.
+ */
+static int
+fifo_setup(struct musb *musb, struct musb_hw_ep *hw_ep,
+ const struct musb_fifo_cfg *cfg, u16 offset)
+{
+ void __iomem *mbase = musb->mregs;
+ int size = 0;
+ u16 maxpacket = cfg->maxpacket;
+ u16 c_off = offset >> 3;
+ u8 c_size;
+
+ /* expect hw_ep has already been zero-initialized */
+
+ size = ffs(max(maxpacket, (u16) 8)) - 1;
+ maxpacket = 1 << size;
+
+ c_size = size - 3;
+ if (cfg->mode == BUF_DOUBLE) {
+ if ((offset + (maxpacket << 1)) >
+ (1 << (musb->config->ram_bits + 2)))
+ return -EMSGSIZE;
+ c_size |= MUSB_FIFOSZ_DPB;
+ } else {
+ if ((offset + maxpacket) > (1 << (musb->config->ram_bits + 2)))
+ return -EMSGSIZE;
+ }
+
+ /* configure the FIFO */
+ musb_writeb(mbase, MUSB_INDEX, hw_ep->epnum);
+
+ /* EP0 reserved endpoint for control, bidirectional;
+ * EP1 reserved for bulk, two unidirectional halves.
+ */
+ if (hw_ep->epnum == 1)
+ musb->bulk_ep = hw_ep;
+ /* REVISIT error check: be sure ep0 can both rx and tx ... */
+ switch (cfg->style) {
+ case FIFO_TX:
+ musb_write_txfifosz(mbase, c_size);
+ musb_write_txfifoadd(mbase, c_off);
+ hw_ep->tx_double_buffered = !!(c_size & MUSB_FIFOSZ_DPB);
+ hw_ep->max_packet_sz_tx = maxpacket;
+ break;
+ case FIFO_RX:
+ musb_write_rxfifosz(mbase, c_size);
+ musb_write_rxfifoadd(mbase, c_off);
+ hw_ep->rx_double_buffered = !!(c_size & MUSB_FIFOSZ_DPB);
+ hw_ep->max_packet_sz_rx = maxpacket;
+ break;
+ case FIFO_RXTX:
+ musb_write_txfifosz(mbase, c_size);
+ musb_write_txfifoadd(mbase, c_off);
+ hw_ep->rx_double_buffered = !!(c_size & MUSB_FIFOSZ_DPB);
+ hw_ep->max_packet_sz_rx = maxpacket;
+
+ musb_write_rxfifosz(mbase, c_size);
+ musb_write_rxfifoadd(mbase, c_off);
+ hw_ep->tx_double_buffered = hw_ep->rx_double_buffered;
+ hw_ep->max_packet_sz_tx = maxpacket;
+
+ hw_ep->is_shared_fifo = true;
+ break;
+ }
+
+ /* NOTE rx and tx endpoint irqs aren't managed separately,
+ * which happens to be ok
+ */
+ musb->epmask |= (1 << hw_ep->epnum);
+
+ return offset + (maxpacket << ((c_size & MUSB_FIFOSZ_DPB) ? 1 : 0));
+}
+
+static struct musb_fifo_cfg ep0_cfg = {
+ .style = FIFO_RXTX, .maxpacket = 64,
+};
+
+static int ep_config_from_table(struct musb *musb)
+{
+ const struct musb_fifo_cfg *cfg;
+ unsigned i, n;
+ int offset;
+ struct musb_hw_ep *hw_ep = musb->endpoints;
+
+ if (musb->config->fifo_cfg) {
+ cfg = musb->config->fifo_cfg;
+ n = musb->config->fifo_cfg_size;
+ goto done;
+ }
+
+ switch (fifo_mode) {
+ default:
+ fifo_mode = 0;
+ /* FALLTHROUGH */
+ case 0:
+ cfg = mode_0_cfg;
+ n = ARRAY_SIZE(mode_0_cfg);
+ break;
+ case 1:
+ cfg = mode_1_cfg;
+ n = ARRAY_SIZE(mode_1_cfg);
+ break;
+ case 2:
+ cfg = mode_2_cfg;
+ n = ARRAY_SIZE(mode_2_cfg);
+ break;
+ case 3:
+ cfg = mode_3_cfg;
+ n = ARRAY_SIZE(mode_3_cfg);
+ break;
+ case 4:
+ cfg = mode_4_cfg;
+ n = ARRAY_SIZE(mode_4_cfg);
+ break;
+ case 5:
+ cfg = mode_5_cfg;
+ n = ARRAY_SIZE(mode_5_cfg);
+ break;
+ }
+
+ printk(KERN_DEBUG "%s: setup fifo_mode %d\n",
+ musb_driver_name, fifo_mode);
+
+
+done:
+ offset = fifo_setup(musb, hw_ep, &ep0_cfg, 0);
+ /* assert(offset > 0) */
+
+ /* NOTE: for RTL versions >= 1.400 EPINFO and RAMINFO would
+ * be better than static musb->config->num_eps and DYN_FIFO_SIZE...
+ */
+
+ for (i = 0; i < n; i++) {
+ u8 epn = cfg->hw_ep_num;
+
+ if (epn >= musb->config->num_eps) {
+ pr_debug("%s: invalid ep %d\n",
+ musb_driver_name, epn);
+ return -EINVAL;
+ }
+ offset = fifo_setup(musb, hw_ep + epn, cfg++, offset);
+ if (offset < 0) {
+ pr_debug("%s: mem overrun, ep %d\n",
+ musb_driver_name, epn);
+ return offset;
+ }
+ epn++;
+ musb->nr_endpoints = max(epn, musb->nr_endpoints);
+ }
+
+ printk(KERN_DEBUG "%s: %d/%d max ep, %d/%d memory\n",
+ musb_driver_name,
+ n + 1, musb->config->num_eps * 2 - 1,
+ offset, (1 << (musb->config->ram_bits + 2)));
+
+ if (!musb->bulk_ep) {
+ pr_debug("%s: missing bulk\n", musb_driver_name);
+ return -EINVAL;
+ }
+
+ return 0;
+}
+
+
+/*
+ * ep_config_from_hw - when MUSB_C_DYNFIFO_DEF is false
+ * @param musb the controller
+ */
+static int ep_config_from_hw(struct musb *musb)
+{
+ u8 epnum = 0;
+ struct musb_hw_ep *hw_ep;
+ void __iomem *mbase = musb->mregs;
+ int ret = 0;
+
+ dev_dbg(musb->controller, "<== static silicon ep config\n");
+
+ /* FIXME pick up ep0 maxpacket size */
+
+ for (epnum = 1; epnum < musb->config->num_eps; epnum++) {
+ musb_ep_select(mbase, epnum);
+ hw_ep = musb->endpoints + epnum;
+
+ ret = musb_read_fifosize(musb, hw_ep, epnum);
+ if (ret < 0)
+ break;
+
+ /* FIXME set up hw_ep->{rx,tx}_double_buffered */
+
+ /* pick an RX/TX endpoint for bulk */
+ if (hw_ep->max_packet_sz_tx < 512
+ || hw_ep->max_packet_sz_rx < 512)
+ continue;
+
+ /* REVISIT: this algorithm is lazy, we should at least
+ * try to pick a double buffered endpoint.
+ */
+ if (musb->bulk_ep)
+ continue;
+ musb->bulk_ep = hw_ep;
+ }
+
+ if (!musb->bulk_ep) {
+ pr_debug("%s: missing bulk\n", musb_driver_name);
+ return -EINVAL;
+ }
+
+ return 0;
+}
+
+enum { MUSB_CONTROLLER_MHDRC, MUSB_CONTROLLER_HDRC, };
+
+/* Initialize MUSB (M)HDRC part of the USB hardware subsystem;
+ * configure endpoints, or take their config from silicon
+ */
+static int musb_core_init(u16 musb_type, struct musb *musb)
+{
+ u8 reg;
+ char *type;
+ char aInfo[90], aRevision[32], aDate[12];
+ void __iomem *mbase = musb->mregs;
+ int status = 0;
+ int i;
+
+ /* log core options (read using indexed model) */
+ reg = musb_read_configdata(mbase);
+
+ strcpy(aInfo, (reg & MUSB_CONFIGDATA_UTMIDW) ? "UTMI-16" : "UTMI-8");
+ if (reg & MUSB_CONFIGDATA_DYNFIFO) {
+ strcat(aInfo, ", dyn FIFOs");
+ musb->dyn_fifo = true;
+ }
+ if (reg & MUSB_CONFIGDATA_MPRXE) {
+ strcat(aInfo, ", bulk combine");
+ musb->bulk_combine = true;
+ }
+ if (reg & MUSB_CONFIGDATA_MPTXE) {
+ strcat(aInfo, ", bulk split");
+ musb->bulk_split = true;
+ }
+ if (reg & MUSB_CONFIGDATA_HBRXE) {
+ strcat(aInfo, ", HB-ISO Rx");
+ musb->hb_iso_rx = true;
+ }
+ if (reg & MUSB_CONFIGDATA_HBTXE) {
+ strcat(aInfo, ", HB-ISO Tx");
+ musb->hb_iso_tx = true;
+ }
+ if (reg & MUSB_CONFIGDATA_SOFTCONE)
+ strcat(aInfo, ", SoftConn");
+
+ printk(KERN_DEBUG "%s: ConfigData=0x%02x (%s)\n",
+ musb_driver_name, reg, aInfo);
+
+ aDate[0] = 0;
+ if (MUSB_CONTROLLER_MHDRC == musb_type) {
+ musb->is_multipoint = 1;
+ type = "M";
+ } else {
+ musb->is_multipoint = 0;
+ type = "";
+#ifndef CONFIG_USB_OTG_BLACKLIST_HUB
+ printk(KERN_ERR
+ "%s: kernel must blacklist external hubs\n",
+ musb_driver_name);
+#endif
+ }
+
+ /* log release info */
+ musb->hwvers = musb_read_hwvers(mbase);
+ snprintf(aRevision, 32, "%d.%d%s", MUSB_HWVERS_MAJOR(musb->hwvers),
+ MUSB_HWVERS_MINOR(musb->hwvers),
+ (musb->hwvers & MUSB_HWVERS_RC) ? "RC" : "");
+ printk(KERN_DEBUG "%s: %sHDRC RTL version %s %s\n",
+ musb_driver_name, type, aRevision, aDate);
+
+ /* configure ep0 */
+ musb_configure_ep0(musb);
+
+ /* discover endpoint configuration */
+ musb->nr_endpoints = 1;
+ musb->epmask = 1;
+
+ if (musb->dyn_fifo)
+ status = ep_config_from_table(musb);
+ else
+ status = ep_config_from_hw(musb);
+
+ if (status < 0)
+ return status;
+
+ /* finish init, and print endpoint config */
+ for (i = 0; i < musb->nr_endpoints; i++) {
+ struct musb_hw_ep *hw_ep = musb->endpoints + i;
+
+ hw_ep->fifo = MUSB_FIFO_OFFSET(i) + mbase;
+#if defined(CONFIG_USB_MUSB_TUSB6010) || defined (CONFIG_USB_MUSB_TUSB6010_MODULE)
+ hw_ep->fifo_async = musb->async + 0x400 + MUSB_FIFO_OFFSET(i);
+ hw_ep->fifo_sync = musb->sync + 0x400 + MUSB_FIFO_OFFSET(i);
+ hw_ep->fifo_sync_va =
+ musb->sync_va + 0x400 + MUSB_FIFO_OFFSET(i);
+
+ if (i == 0)
+ hw_ep->conf = mbase - 0x400 + TUSB_EP0_CONF;
+ else
+ hw_ep->conf = mbase + 0x400 + (((i - 1) & 0xf) << 2);
+#endif
+
+ hw_ep->regs = MUSB_EP_OFFSET(i, 0) + mbase;
+ hw_ep->target_regs = musb_read_target_reg_base(i, mbase);
+ hw_ep->rx_reinit = 1;
+ hw_ep->tx_reinit = 1;
+
+ if (hw_ep->max_packet_sz_tx) {
+ dev_dbg(musb->controller,
+ "%s: hw_ep %d%s, %smax %d\n",
+ musb_driver_name, i,
+ hw_ep->is_shared_fifo ? "shared" : "tx",
+ hw_ep->tx_double_buffered
+ ? "doublebuffer, " : "",
+ hw_ep->max_packet_sz_tx);
+ }
+ if (hw_ep->max_packet_sz_rx && !hw_ep->is_shared_fifo) {
+ dev_dbg(musb->controller,
+ "%s: hw_ep %d%s, %smax %d\n",
+ musb_driver_name, i,
+ "rx",
+ hw_ep->rx_double_buffered
+ ? "doublebuffer, " : "",
+ hw_ep->max_packet_sz_rx);
+ }
+ if (!(hw_ep->max_packet_sz_tx || hw_ep->max_packet_sz_rx))
+ dev_dbg(musb->controller, "hw_ep %d not configured\n", i);
+ }
+
+ return 0;
+}
+
+/*-------------------------------------------------------------------------*/
+
+/*
+ * handle all the irqs defined by the HDRC core. for now we expect: other
+ * irq sources (phy, dma, etc) will be handled first, musb->int_* values
+ * will be assigned, and the irq will already have been acked.
+ *
+ * called in irq context with spinlock held, irqs blocked
+ */
+irqreturn_t musb_interrupt(struct musb *musb)
+{
+ irqreturn_t retval = IRQ_NONE;
+ u8 devctl;
+ int ep_num;
+ u32 reg;
+
+ devctl = musb_readb(musb->mregs, MUSB_DEVCTL);
+
+ dev_dbg(musb->controller, "** IRQ %s usb%04x tx%04x rx%04x\n",
+ is_host_active(musb) ? "host" : "peripheral",
+ musb->int_usb, musb->int_tx, musb->int_rx);
+
+ /* "stage 1" is handling endpoint irqs */
+
+ /* handle endpoint 0 first */
+ if (musb->int_tx & 1) {
+ if (is_host_active(musb))
+ retval |= musb_h_ep0_irq(musb);
+ else
+ retval |= musb_g_ep0_irq(musb);
+ }
+
+ /* RX on endpoints 1-15 */
+ reg = musb->int_rx >> 1;
+ ep_num = 1;
+ while (reg) {
+ if (reg & 1) {
+ /* musb_ep_select(musb->mregs, ep_num); */
+ /* REVISIT just retval = ep->rx_irq(...) */
+ retval = IRQ_HANDLED;
+ if (is_host_active(musb))
+ musb_host_rx(musb, ep_num);
+ else
+ musb_g_rx(musb, ep_num);
+ }
+
+ reg >>= 1;
+ ep_num++;
+ }
+
+ /* TX on endpoints 1-15 */
+ reg = musb->int_tx >> 1;
+ ep_num = 1;
+ while (reg) {
+ if (reg & 1) {
+ /* musb_ep_select(musb->mregs, ep_num); */
+ /* REVISIT just retval |= ep->tx_irq(...) */
+ retval = IRQ_HANDLED;
+ if (is_host_active(musb))
+ musb_host_tx(musb, ep_num);
+ else
+ musb_g_tx(musb, ep_num);
+ }
+ reg >>= 1;
+ ep_num++;
+ }
+
+ return retval;
+}
+EXPORT_SYMBOL_GPL(musb_interrupt);
+
+/* --------------------------------------------------------------------------
+ * Init support
+ */
+
+static struct musb *musb_init_instance(struct musb *musb,
+ struct musb_hdrc_config *config)
+{
+ struct musb_hw_ep *ep;
+ int epnum;
+ int ret;
+
+ INIT_LIST_HEAD(&musb->control);
+ INIT_LIST_HEAD(&musb->in_bulk);
+ INIT_LIST_HEAD(&musb->out_bulk);
+
+ musb->vbuserr_retry = VBUSERR_RETRY_COUNT;
+ musb->a_wait_bcon = OTG_TIME_A_WAIT_BCON;
+ musb->nIrq = -ENODEV;
+ musb->config = config;
+ BUG_ON(musb->config->num_eps > MUSB_C_NUM_EPS);
+ for (epnum = 0, ep = musb->endpoints;
+ epnum < musb->config->num_eps;
+ epnum++, ep++) {
+ ep->musb = musb;
+ ep->epnum = epnum;
+ }
+
+ ret = musb_host_alloc(musb);
+ if (ret < 0)
+ goto err_free;
+
+ return musb;
+
+err_free:
+ return NULL;
+}
+
+static void musb_free(struct musb *musb)
+{
+ /* this has multiple entry modes. it handles fault cleanup after
+ * probe(), where things may be partially set up, as well as rmmod
+ * cleanup after everything's been de-activated.
+ */
+
+ musb_host_free(musb);
+}
+
+int musb_init(struct usb_host *host)
+{
+ struct musb *musb = to_musb(host);
+ void *mbase;
+ int timeout = MUSB_HOST_TIMEOUT;
+ u8 power;
+
+ musb_start(musb);
+ mbase = musb->mregs;
+ do {
+ if (musb_readb(mbase, MUSB_DEVCTL) & MUSB_DEVCTL_HM)
+ break;
+ } while (--timeout);
+ if (!timeout)
+ return -ENODEV;
+
+ power = musb_readb(mbase, MUSB_POWER);
+ musb_writeb(mbase, MUSB_POWER, MUSB_POWER_RESET | power);
+ udelay(30000);
+ power = musb_readb(mbase, MUSB_POWER);
+ musb_writeb(mbase, MUSB_POWER, ~MUSB_POWER_RESET & power);
+
+ musb->isr(musb);
+ udelay(30000); /* necessary for proper hub detection */
+ musb->host_speed = (musb_readb(mbase, MUSB_POWER) & MUSB_POWER_HSMODE) ?
+ USB_SPEED_HIGH :
+ (musb_readb(mbase, MUSB_DEVCTL) & MUSB_DEVCTL_FSDEV) ?
+ USB_SPEED_FULL : USB_SPEED_LOW;
+ musb->is_active = 1;
+
+ return 0;
+}
+
+/*
+ * Perform generic per-controller initialization.
+ *
+ * @dev: the controller (already clocked, etc)
+ * @nIrq: IRQ number
+ * @ctrl: virtual address of controller registers,
+ * not yet corrected for platform-specific offsets
+ */
+int
+musb_init_controller(struct musb *musb, struct musb_hdrc_platform_data *plat)
+{
+ int status;
+
+ /* allocate */
+ musb = musb_init_instance(musb, plat->config);
+ if (!musb) {
+ status = -ENOMEM;
+ goto fail0;
+ }
+
+ musb->board_set_power = plat->set_power;
+ musb->min_power = plat->min_power;
+ musb->ops = plat->platform_ops;
+ musb->port_mode = plat->mode;
+
+ /* The musb_platform_init() call:
+ * - adjusts musb->mregs
+ * - sets the musb->isr
+ * - may initialize an integrated transceiver
+ * - initializes musb->xceiv, usually by otg_get_phy()
+ * - stops powering VBUS
+ *
+ * There are various transceiver configurations. Blackfin,
+ * DaVinci, TUSB60x0, and others integrate them. OMAP3 uses
+ * external/discrete ones in various flavors (twl4030 family,
+ * isp1504, non-OTG, etc) mostly hooking up through ULPI.
+ */
+ status = musb_platform_init(musb);
+ if (status < 0)
+ goto fail1;
+
+ if (!musb->isr) {
+ status = -ENODEV;
+ goto fail2;
+ }
+
+ /* be sure interrupts are disabled before connecting ISR */
+ musb_platform_disable(musb);
+ musb_generic_disable(musb);
+
+ /* setup musb parts of the core (especially endpoints) */
+ status = musb_core_init(plat->config->multipoint
+ ? MUSB_CONTROLLER_MHDRC
+ : MUSB_CONTROLLER_HDRC, musb);
+ if (status < 0)
+ goto fail3;
+
+ switch (musb->port_mode) {
+ case MUSB_PORT_MODE_HOST:
+ status = musb_host_setup(musb, plat->power);
+ break;
+ case MUSB_PORT_MODE_GADGET:
+ status = musb_gadget_setup(musb);
+ break;
+ case MUSB_PORT_MODE_DUAL_ROLE:
+ status = musb_host_setup(musb, plat->power);
+ if (status < 0)
+ goto fail3;
+ status = musb_gadget_setup(musb);
+ if (status < 0)
+ goto fail3;
+ break;
+ default:
+ dev_err(musb->controller, "unsupported port mode %d\n", musb->port_mode);
+ break;
+ }
+
+ if (status < 0)
+ goto fail3;
+
+ if (IS_ENABLED(CONFIG_USB_MUSB_HOST) && plat->mode == USB_DR_MODE_HOST)
+ musb_register(musb);
+
+ return 0;
+
+fail3:
+fail2:
+ musb_platform_exit(musb);
+
+fail1:
+ dev_err(musb->controller,
+ "musb_init_controller failed with status %d\n", status);
+
+ musb_free(musb);
+
+fail0:
+
+ return status;
+
+}
diff --git a/drivers/usb/musb/musb_core.h b/drivers/usb/musb/musb_core.h
new file mode 100644
index 0000000000..46265d6190
--- /dev/null
+++ b/drivers/usb/musb/musb_core.h
@@ -0,0 +1,585 @@
+/*
+ * MUSB OTG driver defines
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#ifndef __MUSB_CORE_H__
+#define __MUSB_CORE_H__
+
+#include <poller.h>
+#include <notifier.h>
+#include <usb/usb.h>
+#include <usb/phy.h>
+
+struct musb;
+struct musb_hw_ep;
+struct musb_ep;
+
+/* Helper defines for struct musb->hwvers */
+#define MUSB_HWVERS_MAJOR(x) ((x >> 10) & 0x1f)
+#define MUSB_HWVERS_MINOR(x) (x & 0x3ff)
+#define MUSB_HWVERS_RC 0x8000
+#define MUSB_HWVERS_1300 0x52C
+#define MUSB_HWVERS_1400 0x590
+#define MUSB_HWVERS_1800 0x720
+#define MUSB_HWVERS_1900 0x784
+#define MUSB_HWVERS_2000 0x800
+
+#include "musb_dma.h"
+
+#include "musb_io.h"
+#include "musb_regs.h"
+
+#include "musb_gadget.h"
+#include "musb_host.h"
+
+/* NOTE: otg and peripheral-only state machines start at B_IDLE.
+ * OTG or host-only go to A_IDLE when ID is sensed.
+ */
+#define is_peripheral_active(m) (!(m)->is_host)
+#define is_host_active(m) ((m)->is_host)
+
+enum {
+ MUSB_PORT_MODE_HOST = 1,
+ MUSB_PORT_MODE_GADGET,
+ MUSB_PORT_MODE_DUAL_ROLE,
+};
+
+/****************************** CONSTANTS ********************************/
+
+#ifndef MUSB_C_NUM_EPS
+#define MUSB_C_NUM_EPS ((u8)16)
+#endif
+
+#ifndef MUSB_MAX_END0_PACKET
+#define MUSB_MAX_END0_PACKET ((u16)MUSB_EP0_FIFOSIZE)
+#endif
+
+/* host side ep0 states */
+enum musb_h_ep0_state {
+ MUSB_EP0_IDLE,
+ MUSB_EP0_START, /* expect ack of setup */
+ MUSB_EP0_IN, /* expect IN DATA */
+ MUSB_EP0_OUT, /* expect ack of OUT DATA */
+ MUSB_EP0_STATUS, /* expect ack of STATUS */
+} __attribute__ ((packed));
+
+/* peripheral side ep0 states */
+enum musb_g_ep0_state {
+ MUSB_EP0_STAGE_IDLE, /* idle, waiting for SETUP */
+ MUSB_EP0_STAGE_SETUP, /* received SETUP */
+ MUSB_EP0_STAGE_TX, /* IN data */
+ MUSB_EP0_STAGE_RX, /* OUT data */
+ MUSB_EP0_STAGE_STATUSIN, /* (after OUT data) */
+ MUSB_EP0_STAGE_STATUSOUT, /* (after IN data) */
+ MUSB_EP0_STAGE_ACKWAIT, /* after zlp, before statusin */
+} __attribute__ ((packed));
+
+/*
+ * OTG protocol constants. See USB OTG 1.3 spec,
+ * sections 5.5 "Device Timings" and 6.6.5 "Timers".
+ */
+#define OTG_TIME_A_WAIT_VRISE 100 /* msec (max) */
+#define OTG_TIME_A_WAIT_BCON 1100 /* min 1 second */
+#define OTG_TIME_A_AIDL_BDIS 200 /* min 200 msec */
+#define OTG_TIME_B_ASE0_BRST 100 /* min 3.125 ms */
+
+
+/*************************** REGISTER ACCESS ********************************/
+
+/* Endpoint registers (other than dynfifo setup) can be accessed either
+ * directly with the "flat" model, or after setting up an index register.
+ */
+
+#if defined(CONFIG_ARCH_DAVINCI) || defined(CONFIG_SOC_OMAP2430) \
+ || defined(CONFIG_SOC_OMAP3430) || defined(CONFIG_BLACKFIN) \
+ || defined(CONFIG_ARCH_OMAP4)
+/* REVISIT indexed access seemed to
+ * misbehave (on DaVinci) for at least peripheral IN ...
+ */
+#define MUSB_FLAT_REG
+#endif
+
+/* TUSB mapping: "flat" plus ep0 special cases */
+#if defined(CONFIG_USB_MUSB_TUSB6010) || \
+ defined(CONFIG_USB_MUSB_TUSB6010_MODULE)
+#define musb_ep_select(_mbase, _epnum) \
+ musb_writeb((_mbase), MUSB_INDEX, (_epnum))
+#define MUSB_EP_OFFSET MUSB_TUSB_OFFSET
+
+/* "flat" mapping: each endpoint has its own i/o address */
+#elif defined(MUSB_FLAT_REG)
+#define musb_ep_select(_mbase, _epnum) (((void)(_mbase)), ((void)(_epnum)))
+#define MUSB_EP_OFFSET MUSB_FLAT_OFFSET
+
+/* "indexed" mapping: INDEX register controls register bank select */
+#else
+#define musb_ep_select(_mbase, _epnum) \
+ musb_writeb((_mbase), MUSB_INDEX, (_epnum))
+#define MUSB_EP_OFFSET MUSB_INDEXED_OFFSET
+#endif
+
+/****************************** FUNCTIONS ********************************/
+
+#define MUSB_HST_MODE(_musb)\
+ { (_musb)->is_host = true; }
+#define MUSB_DEV_MODE(_musb) \
+ { (_musb)->is_host = false; }
+
+#define test_devctl_hst_mode(_x) \
+ (musb_readb((_x)->mregs, MUSB_DEVCTL)&MUSB_DEVCTL_HM)
+
+#define MUSB_MODE(musb) ((musb)->is_host ? "Host" : "Peripheral")
+
+/******************************** TYPES *************************************/
+
+/**
+ * struct musb_platform_ops - Operations passed to musb_core by HW glue layer
+ * @init: turns on clocks, sets up platform-specific registers, etc
+ * @exit: undoes @init
+ * @set_mode: forcefully changes operating mode
+ * @try_ilde: tries to idle the IP
+ * @vbus_status: returns vbus status if possible
+ * @set_vbus: forces vbus status
+ * @adjust_channel_params: pre check for standard dma channel_program func
+ */
+struct musb_platform_ops {
+ int (*init)(struct musb *musb);
+ int (*exit)(struct musb *musb);
+
+ void (*enable)(struct musb *musb);
+ void (*disable)(struct musb *musb);
+
+ int (*set_mode)(struct musb *musb, u8 mode);
+ void (*try_idle)(struct musb *musb, uint64_t timeout);
+ int (*reset)(struct musb *musb);
+
+ int (*vbus_status)(struct musb *musb);
+ void (*set_vbus)(struct musb *musb, int on);
+
+ int (*adjust_channel_params)(/*struct dma_channel *channel,*/
+ u16 packet_sz, u8 *mode,
+ dma_addr_t *dma_addr, u32 *len);
+};
+
+/*
+ * struct musb_hw_ep - endpoint hardware (bidirectional)
+ *
+ * Ordered slightly for better cacheline locality.
+ */
+struct musb_hw_ep {
+ struct musb *musb;
+ void __iomem *fifo;
+ void __iomem *regs;
+
+#if defined(CONFIG_USB_MUSB_TUSB6010) || \
+ defined(CONFIG_USB_MUSB_TUSB6010_MODULE)
+ void __iomem *conf;
+#endif
+
+ /* index in musb->endpoints[] */
+ u8 epnum;
+
+ /* hardware configuration, possibly dynamic */
+ bool is_shared_fifo;
+ bool tx_double_buffered;
+ bool rx_double_buffered;
+ u16 max_packet_sz_tx;
+ u16 max_packet_sz_rx;
+
+ struct dma_channel *tx_channel;
+ struct dma_channel *rx_channel;
+
+#if defined(CONFIG_USB_MUSB_TUSB6010) || \
+ defined(CONFIG_USB_MUSB_TUSB6010_MODULE)
+ /* TUSB has "asynchronous" and "synchronous" dma modes */
+ dma_addr_t fifo_async;
+ dma_addr_t fifo_sync;
+ void __iomem *fifo_sync_va;
+#endif
+
+ void __iomem *target_regs;
+
+ /* currently scheduled peripheral endpoint */
+ struct musb_qh *in_qh;
+ struct musb_qh *out_qh;
+
+ u8 rx_reinit;
+ u8 tx_reinit;
+
+ /* peripheral side */
+ struct musb_ep ep_in; /* TX */
+ struct musb_ep ep_out; /* RX */
+};
+
+static inline struct musb_request *next_in_request(struct musb_hw_ep *hw_ep)
+{
+ return next_request(&hw_ep->ep_in);
+}
+
+static inline struct musb_request *next_out_request(struct musb_hw_ep *hw_ep)
+{
+ return next_request(&hw_ep->ep_out);
+}
+
+struct musb_csr_regs {
+ /* FIFO registers */
+ u16 txmaxp, txcsr, rxmaxp, rxcsr;
+ u16 rxfifoadd, txfifoadd;
+ u8 txtype, txinterval, rxtype, rxinterval;
+ u8 rxfifosz, txfifosz;
+ u8 txfunaddr, txhubaddr, txhubport;
+ u8 rxfunaddr, rxhubaddr, rxhubport;
+};
+
+struct musb_context_registers {
+
+ u8 power;
+ u8 intrusbe;
+ u16 frame;
+ u8 index, testmode;
+
+ u8 devctl, busctl, misc;
+ u32 otg_interfsel;
+
+ struct musb_csr_regs index_regs[MUSB_C_NUM_EPS];
+};
+
+struct usb_phy;
+struct usb_otg;
+
+/*
+ * Allocated per bus (tree of devices) we have:
+ */
+struct usb_bus {
+ u8 otg_port; /* 0, or number of OTG/HNP port */
+ unsigned is_b_host:1; /* true during some HNP roleswitches */
+ unsigned b_hnp_enable:1; /* OTG: did A-Host enable HNP? */
+};
+
+struct usb_hcd {
+ struct usb_bus self;
+ void *hcd_priv;
+};
+
+#define to_musb(ptr) container_of(ptr, struct musb, host)
+
+/*
+ * struct musb - Driver instance data.
+ */
+struct musb {
+ /* device lock */
+ spinlock_t lock;
+
+ const struct musb_platform_ops *ops;
+
+ int (*isr)(struct musb *);
+ u16 hwvers;
+
+ u16 intrrxe;
+ u16 intrtxe;
+/* this hub status bit is reserved by USB 2.0 and not seen by usbcore */
+#define MUSB_PORT_STAT_RESUME (1 << 31)
+
+ u32 port1_status;
+
+ uint64_t rh_timer;
+
+ enum musb_h_ep0_state ep0_stage;
+
+ /* bulk traffic normally dedicates endpoint hardware, and each
+ * direction has its own ring of host side endpoints.
+ * we try to progress the transfer at the head of each endpoint's
+ * queue until it completes or NAKs too much; then we try the next
+ * endpoint.
+ */
+ struct musb_hw_ep *bulk_ep;
+
+ struct list_head control; /* of musb_qh */
+ struct list_head in_bulk; /* of musb_qh */
+ struct list_head out_bulk; /* of musb_qh */
+
+ struct poller_async otg_timer;
+
+ struct dma_controller *dma_controller;
+
+ struct device_d *controller;
+ void __iomem *ctrl_base;
+ void __iomem *mregs;
+
+#if defined(CONFIG_USB_MUSB_TUSB6010) || \
+ defined(CONFIG_USB_MUSB_TUSB6010_MODULE)
+ dma_addr_t async;
+ dma_addr_t sync;
+ void __iomem *sync_va;
+#endif
+
+ /* passed down from chip/board specific irq handlers */
+ u8 int_usb;
+ u16 int_rx;
+ u16 int_tx;
+
+ //struct device_d *phydev;
+ struct usb_host host;
+ struct usb_phy *xceiv;
+
+ int nIrq;
+ unsigned irq_wake:1;
+
+ struct musb_hw_ep endpoints[MUSB_C_NUM_EPS];
+#define control_ep endpoints
+
+#define VBUSERR_RETRY_COUNT 3
+ u16 vbuserr_retry;
+ u16 epmask;
+ u8 nr_endpoints;
+
+ int (*board_set_power)(int state);
+
+ u8 min_power; /* vbus for periph, in mA/2 */
+
+ int port_mode; /* MUSB_PORT_MODE_* */
+ bool is_host;
+
+ int a_wait_bcon; /* VBUS timeout in msecs */
+
+ /* active means connected and not suspended */
+ unsigned is_active:1;
+
+ unsigned is_multipoint:1;
+
+ unsigned hb_iso_rx:1; /* high bandwidth iso rx? */
+ unsigned hb_iso_tx:1; /* high bandwidth iso tx? */
+ unsigned dyn_fifo:1; /* dynamic FIFO supported? */
+
+ unsigned bulk_split:1;
+#define can_bulk_split(musb,type) \
+ (((type) == USB_ENDPOINT_XFER_BULK) && (musb)->bulk_split)
+
+ unsigned bulk_combine:1;
+#define can_bulk_combine(musb,type) \
+ (((type) == USB_ENDPOINT_XFER_BULK) && (musb)->bulk_combine)
+
+ /* is_suspended means USB B_PERIPHERAL suspend */
+ unsigned is_suspended:1;
+
+ /* may_wakeup means remote wakeup is enabled */
+ unsigned may_wakeup:1;
+
+ /* is_self_powered is reported in device status and the
+ * config descriptor. is_bus_powered means B_PERIPHERAL
+ * draws some VBUS current; both can be true.
+ */
+ unsigned is_self_powered:1;
+ unsigned is_bus_powered:1;
+
+ unsigned set_address:1;
+ unsigned test_mode:1;
+ unsigned softconnect:1;
+
+ u8 address;
+ u8 test_mode_nr;
+ u16 ackpend; /* ep0 */
+ enum musb_g_ep0_state ep0_state;
+ struct usb_gadget g; /* the gadget */
+ struct usb_gadget_driver *gadget_driver; /* its driver */
+ struct usb_hcd *hcd; /* the usb hcd */
+
+ /*
+ * FIXME: Remove this flag.
+ *
+ * This is only added to allow Blackfin to work
+ * with current driver. For some unknown reason
+ * Blackfin doesn't work with double buffering
+ * and that's enabled by default.
+ *
+ * We added this flag to forcefully disable double
+ * buffering until we get it working.
+ */
+ unsigned double_buffer_not_ok:1;
+
+ struct musb_hdrc_config *config;
+ int host_speed;
+};
+
+static inline struct musb *gadget_to_musb(struct usb_gadget *g)
+{
+ return container_of(g, struct musb, g);
+}
+
+#ifdef CONFIG_BLACKFIN
+static inline int musb_read_fifosize(struct musb *musb,
+ struct musb_hw_ep *hw_ep, u8 epnum)
+{
+ musb->nr_endpoints++;
+ musb->epmask |= (1 << epnum);
+
+ if (epnum < 5) {
+ hw_ep->max_packet_sz_tx = 128;
+ hw_ep->max_packet_sz_rx = 128;
+ } else {
+ hw_ep->max_packet_sz_tx = 1024;
+ hw_ep->max_packet_sz_rx = 1024;
+ }
+ hw_ep->is_shared_fifo = false;
+
+ return 0;
+}
+
+static inline void musb_configure_ep0(struct musb *musb)
+{
+ musb->endpoints[0].max_packet_sz_tx = MUSB_EP0_FIFOSIZE;
+ musb->endpoints[0].max_packet_sz_rx = MUSB_EP0_FIFOSIZE;
+ musb->endpoints[0].is_shared_fifo = true;
+}
+
+#else
+
+static inline int musb_read_fifosize(struct musb *musb,
+ struct musb_hw_ep *hw_ep, u8 epnum)
+{
+ void __iomem *mbase = musb->mregs;
+ u8 reg = 0;
+
+ /* read from core using indexed model */
+ reg = musb_readb(mbase, MUSB_EP_OFFSET(epnum, MUSB_FIFOSIZE));
+ /* 0's returned when no more endpoints */
+ if (!reg)
+ return -ENODEV;
+
+ musb->nr_endpoints++;
+ musb->epmask |= (1 << epnum);
+
+ hw_ep->max_packet_sz_tx = 1 << (reg & 0x0f);
+
+ /* shared TX/RX FIFO? */
+ if ((reg & 0xf0) == 0xf0) {
+ hw_ep->max_packet_sz_rx = hw_ep->max_packet_sz_tx;
+ hw_ep->is_shared_fifo = true;
+ return 0;
+ } else {
+ hw_ep->max_packet_sz_rx = 1 << ((reg & 0xf0) >> 4);
+ hw_ep->is_shared_fifo = false;
+ }
+
+ return 0;
+}
+
+static inline void musb_configure_ep0(struct musb *musb)
+{
+ musb->endpoints[0].max_packet_sz_tx = MUSB_EP0_FIFOSIZE;
+ musb->endpoints[0].max_packet_sz_rx = MUSB_EP0_FIFOSIZE;
+ musb->endpoints[0].is_shared_fifo = true;
+}
+#endif /* CONFIG_BLACKFIN */
+
+
+/***************************** Glue it together *****************************/
+
+extern const char musb_driver_name[];
+
+extern void musb_stop(struct musb *musb);
+extern void musb_start(struct musb *musb);
+
+extern void musb_write_fifo(struct musb_hw_ep *ep, u16 len, const u8 *src);
+extern void musb_read_fifo(struct musb_hw_ep *ep, u16 len, u8 *dst);
+
+extern void musb_load_testpacket(struct musb *);
+
+extern int musb_interrupt(struct musb *);
+
+extern void musb_hnp_stop(struct musb *musb);
+
+static inline void musb_platform_set_vbus(struct musb *musb, int is_on)
+{
+ if (musb->ops->set_vbus)
+ musb->ops->set_vbus(musb, is_on);
+}
+
+static inline void musb_platform_enable(struct musb *musb)
+{
+ if (musb->ops->enable)
+ musb->ops->enable(musb);
+}
+
+static inline void musb_platform_disable(struct musb *musb)
+{
+ if (musb->ops->disable)
+ musb->ops->disable(musb);
+}
+
+static inline void musb_platform_try_idle(struct musb *musb,
+ uint64_t timeout)
+{
+ if (musb->ops->try_idle)
+ musb->ops->try_idle(musb, timeout);
+}
+
+static inline int musb_platform_reset(struct musb *musb)
+{
+ if (!musb->ops->reset)
+ return -EINVAL;
+
+ return musb->ops->reset(musb);
+}
+
+static inline int musb_platform_get_vbus_status(struct musb *musb)
+{
+ if (!musb->ops->vbus_status)
+ return 0;
+
+ return musb->ops->vbus_status(musb);
+}
+
+static inline int musb_platform_init(struct musb *musb)
+{
+ if (!musb->ops->init)
+ return -EINVAL;
+
+ return musb->ops->init(musb);
+}
+
+static inline int musb_platform_exit(struct musb *musb)
+{
+ if (!musb->ops->exit)
+ return -EINVAL;
+
+ return musb->ops->exit(musb);
+}
+
+struct musb_hdrc_platform_data;
+
+int musb_init_controller(struct musb *musb, struct musb_hdrc_platform_data *plat);
+int musb_register(struct musb *data);
+int musb_init(struct usb_host *host);
+
+#endif /* __MUSB_CORE_H__ */
diff --git a/drivers/usb/musb/musb_dma.h b/drivers/usb/musb/musb_dma.h
new file mode 100644
index 0000000000..1345a4ff04
--- /dev/null
+++ b/drivers/usb/musb/musb_dma.h
@@ -0,0 +1,194 @@
+/*
+ * MUSB OTG driver DMA controller abstraction
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#ifndef __MUSB_DMA_H__
+#define __MUSB_DMA_H__
+
+struct musb_hw_ep;
+
+/*
+ * DMA Controller Abstraction
+ *
+ * DMA Controllers are abstracted to allow use of a variety of different
+ * implementations of DMA, as allowed by the Inventra USB cores. On the
+ * host side, usbcore sets up the DMA mappings and flushes caches; on the
+ * peripheral side, the gadget controller driver does. Responsibilities
+ * of a DMA controller driver include:
+ *
+ * - Handling the details of moving multiple USB packets
+ * in cooperation with the Inventra USB core, including especially
+ * the correct RX side treatment of short packets and buffer-full
+ * states (both of which terminate transfers).
+ *
+ * - Knowing the correlation between dma channels and the
+ * Inventra core's local endpoint resources and data direction.
+ *
+ * - Maintaining a list of allocated/available channels.
+ *
+ * - Updating channel status on interrupts,
+ * whether shared with the Inventra core or separate.
+ */
+
+#define DMA_ADDR_INVALID (~(dma_addr_t)0)
+
+#ifdef CONFIG_MUSB_PIO_ONLY
+#define is_dma_capable() (0)
+#else
+#define is_dma_capable() (1)
+#endif
+
+#if defined(CONFIG_USB_TI_CPPI_DMA) || defined(CONFIG_USB_TI_CPPI41_DMA)
+#define is_cppi_enabled() 1
+#else
+#define is_cppi_enabled() 0
+#endif
+
+#ifdef CONFIG_USB_TUSB_OMAP_DMA
+#define tusb_dma_omap() 1
+#else
+#define tusb_dma_omap() 0
+#endif
+
+/* Anomaly 05000456 - USB Receive Interrupt Is Not Generated in DMA Mode 1
+ * Only allow DMA mode 1 to be used when the USB will actually generate the
+ * interrupts we expect.
+ */
+#ifdef CONFIG_BLACKFIN
+# undef USE_MODE1
+# if !ANOMALY_05000456
+# define USE_MODE1
+# endif
+#endif
+
+/*
+ * DMA channel status ... updated by the dma controller driver whenever that
+ * status changes, and protected by the overall controller spinlock.
+ */
+enum dma_channel_status {
+ /* unallocated */
+ MUSB_DMA_STATUS_UNKNOWN,
+ /* allocated ... but not busy, no errors */
+ MUSB_DMA_STATUS_FREE,
+ /* busy ... transactions are active */
+ MUSB_DMA_STATUS_BUSY,
+ /* transaction(s) aborted due to ... dma or memory bus error */
+ MUSB_DMA_STATUS_BUS_ABORT,
+ /* transaction(s) aborted due to ... core error or USB fault */
+ MUSB_DMA_STATUS_CORE_ABORT
+};
+
+struct dma_controller;
+
+/**
+ * struct dma_channel - A DMA channel.
+ * @private_data: channel-private data
+ * @max_len: the maximum number of bytes the channel can move in one
+ * transaction (typically representing many USB maximum-sized packets)
+ * @actual_len: how many bytes have been transferred
+ * @status: current channel status (updated e.g. on interrupt)
+ * @desired_mode: true if mode 1 is desired; false if mode 0 is desired
+ *
+ * channels are associated with an endpoint for the duration of at least
+ * one usb transfer.
+ */
+struct dma_channel {
+ void *private_data;
+ /* FIXME not void* private_data, but a dma_controller * */
+ size_t max_len;
+ size_t actual_len;
+ enum dma_channel_status status;
+ bool desired_mode;
+};
+
+/*
+ * dma_channel_status - return status of dma channel
+ * @c: the channel
+ *
+ * Returns the software's view of the channel status. If that status is BUSY
+ * then it's possible that the hardware has completed (or aborted) a transfer,
+ * so the driver needs to update that status.
+ */
+static inline enum dma_channel_status
+dma_channel_status(struct dma_channel *c)
+{
+ return (is_dma_capable() && c) ? c->status : MUSB_DMA_STATUS_UNKNOWN;
+}
+
+/**
+ * struct dma_controller - A DMA Controller.
+ * @start: call this to start a DMA controller;
+ * return 0 on success, else negative errno
+ * @stop: call this to stop a DMA controller
+ * return 0 on success, else negative errno
+ * @channel_alloc: call this to allocate a DMA channel
+ * @channel_release: call this to release a DMA channel
+ * @channel_abort: call this to abort a pending DMA transaction,
+ * returning it to FREE (but allocated) state
+ *
+ * Controllers manage dma channels.
+ */
+struct dma_controller {
+ struct dma_channel *(*channel_alloc)(struct dma_controller *,
+ struct musb_hw_ep *, u8 is_tx);
+ void (*channel_release)(struct dma_channel *);
+ int (*channel_program)(struct dma_channel *channel,
+ u16 maxpacket, u8 mode,
+ dma_addr_t dma_addr,
+ u32 length);
+ int (*channel_abort)(struct dma_channel *);
+ int (*is_compatible)(struct dma_channel *channel,
+ u16 maxpacket,
+ void *buf, u32 length);
+};
+
+/* called after channel_program(), may indicate a fault */
+extern void musb_dma_completion(struct musb *musb, u8 epnum, u8 transmit);
+
+#ifdef CONFIG_MUSB_PIO_ONLY
+static inline struct dma_controller *dma_controller_create(struct musb *m,
+ void __iomem *io)
+{
+ return NULL;
+}
+
+static inline void dma_controller_destroy(struct dma_controller *d) { }
+
+#else
+
+extern struct dma_controller *dma_controller_create(struct musb *, void __iomem *);
+
+extern void dma_controller_destroy(struct dma_controller *);
+#endif
+
+#endif /* __MUSB_DMA_H__ */
diff --git a/drivers/usb/musb/musb_dsps.c b/drivers/usb/musb/musb_dsps.c
new file mode 100644
index 0000000000..36a316ab37
--- /dev/null
+++ b/drivers/usb/musb/musb_dsps.c
@@ -0,0 +1,464 @@
+/*
+ * Texas Instruments DSPS platforms "glue layer"
+ *
+ * Copyright (C) 2012, by Texas Instruments
+ *
+ * Based on the am35x "glue layer" code.
+ *
+ * This file is part of the Inventra Controller Driver for Linux.
+ *
+ * The Inventra Controller Driver for Linux 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.
+ *
+ * The Inventra Controller Driver for Linux 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 The Inventra Controller Driver for Linux ; if not,
+ * write to the Free Software Foundation, Inc., 59 Temple Place,
+ * Suite 330, Boston, MA 02111-1307 USA
+ *
+ * musb_dsps.c will be a common file for all the TI DSPS platforms
+ * such as dm64x, dm36x, dm35x, da8x, am35x and ti81x.
+ * For now only ti81x is using this and in future davinci.c, am35x.c
+ * da8xx.c would be merged to this file after testing.
+ */
+
+#include <common.h>
+#include <init.h>
+#include <clock.h>
+#include <usb/usb.h>
+#include <usb/musb.h>
+#include <malloc.h>
+#include <linux/err.h>
+#include <linux/barebox-wrapper.h>
+
+#include "musb_core.h"
+#include "phy-am335x.h"
+
+static __maybe_unused struct of_device_id musb_dsps_dt_ids[];
+
+/**
+ * avoid using musb_readx()/musb_writex() as glue layer should not be
+ * dependent on musb core layer symbols.
+ */
+static inline u8 dsps_readb(const void __iomem *addr, unsigned offset)
+{
+ return __raw_readb(addr + offset);
+}
+
+static inline u32 dsps_readl(const void __iomem *addr, unsigned offset)
+{
+ return __raw_readl(addr + offset);
+}
+
+static inline void dsps_writeb(void __iomem *addr, unsigned offset, u8 data)
+{
+ __raw_writeb(data, addr + offset);
+}
+
+static inline void dsps_writel(void __iomem *addr, unsigned offset, u32 data)
+{
+ __raw_writel(data, addr + offset);
+}
+
+/**
+ * DSPS musb wrapper register offset.
+ * FIXME: This should be expanded to have all the wrapper registers from TI DSPS
+ * musb ips.
+ */
+struct dsps_musb_wrapper {
+ u16 revision;
+ u16 control;
+ u16 status;
+ u16 epintr_set;
+ u16 epintr_clear;
+ u16 epintr_status;
+ u16 coreintr_set;
+ u16 coreintr_clear;
+ u16 coreintr_status;
+ u16 phy_utmi;
+ u16 mode;
+
+ /* bit positions for control */
+ unsigned reset:5;
+
+ /* bit positions for interrupt */
+ unsigned usb_shift:5;
+ u32 usb_mask;
+ u32 usb_bitmap;
+ unsigned drvvbus:5;
+
+ unsigned txep_shift:5;
+ u32 txep_mask;
+ u32 txep_bitmap;
+
+ unsigned rxep_shift:5;
+ u32 rxep_mask;
+ u32 rxep_bitmap;
+
+ /* bit positions for phy_utmi */
+ unsigned otg_disable:5;
+
+ /* bit positions for mode */
+ unsigned iddig:5;
+ /* miscellaneous stuff */
+ u8 poll_seconds;
+};
+
+/**
+ * DSPS glue structure.
+ */
+struct dsps_glue {
+ struct device_d *dev;
+ void __iomem *base;
+ unsigned long flags;
+ enum musb_mode mode;
+ struct musb musb;
+ struct musb_hdrc_config config;
+ const struct dsps_musb_wrapper *wrp; /* wrapper register offsets */
+ struct poller_async timer; /* otg_workaround timer */
+ uint64_t last_timer; /* last timer data for each instance */
+ struct device_d otg_dev;
+ uint32_t otgmode;
+ struct musb_hdrc_platform_data pdata;
+};
+
+/**
+ * dsps_musb_enable - enable interrupts
+ */
+static void dsps_musb_enable(struct musb *musb)
+{
+ struct device_d *dev = musb->controller;
+ struct device_d *pdev = dev;
+ struct dsps_glue *glue = pdev->priv;
+ const struct dsps_musb_wrapper *wrp = glue->wrp;
+ void __iomem *reg_base = musb->ctrl_base;
+ u32 epmask, coremask;
+
+ /* Workaround: setup IRQs through both register sets. */
+ epmask = ((musb->epmask & wrp->txep_mask) << wrp->txep_shift) |
+ ((musb->epmask & wrp->rxep_mask) << wrp->rxep_shift);
+ coremask = (wrp->usb_bitmap & ~MUSB_INTR_SOF);
+
+ dsps_writel(reg_base, wrp->epintr_set, epmask);
+ dsps_writel(reg_base, wrp->coreintr_set, coremask);
+ /* Force the DRVVBUS IRQ so we can start polling for ID change. */
+ dsps_writel(reg_base, wrp->coreintr_set,
+ (1 << wrp->drvvbus) << wrp->usb_shift);
+}
+
+/**
+ * dsps_musb_disable - disable HDRC and flush interrupts
+ */
+static void dsps_musb_disable(struct musb *musb)
+{
+ struct device_d *dev = musb->controller;
+ struct device_d *pdev = dev;
+ struct dsps_glue *glue = pdev->priv;
+ const struct dsps_musb_wrapper *wrp = glue->wrp;
+ void __iomem *reg_base = musb->ctrl_base;
+
+ dsps_writel(reg_base, wrp->coreintr_clear, wrp->usb_bitmap);
+ dsps_writel(reg_base, wrp->epintr_clear,
+ wrp->txep_bitmap | wrp->rxep_bitmap);
+ dsps_writeb(musb->mregs, MUSB_DEVCTL, 0);
+}
+
+static irqreturn_t dsps_interrupt(struct musb *musb)
+{
+ void __iomem *reg_base = musb->ctrl_base;
+ struct device_d *dev = musb->controller;
+ struct dsps_glue *glue = dev->priv;
+ const struct dsps_musb_wrapper *wrp = glue->wrp;
+ unsigned long flags;
+ irqreturn_t ret = IRQ_NONE;
+ u32 epintr, usbintr;
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ /* Get endpoint interrupts */
+ epintr = dsps_readl(reg_base, wrp->epintr_status);
+ musb->int_rx = (epintr & wrp->rxep_bitmap) >> wrp->rxep_shift;
+ musb->int_tx = (epintr & wrp->txep_bitmap) >> wrp->txep_shift;
+
+ if (epintr)
+ dsps_writel(reg_base, wrp->epintr_status, epintr);
+
+ /* Get usb core interrupts */
+ usbintr = dsps_readl(reg_base, wrp->coreintr_status);
+ if (!usbintr && !epintr)
+ goto out;
+
+ musb->int_usb = (usbintr & wrp->usb_bitmap) >> wrp->usb_shift;
+ if (usbintr)
+ dsps_writel(reg_base, wrp->coreintr_status, usbintr);
+
+ dev_dbg(musb->controller, "usbintr (%x) epintr(%x)\n",
+ usbintr, epintr);
+
+ if (musb->int_tx || musb->int_rx || musb->int_usb)
+ ret |= musb_interrupt(musb);
+
+out:
+ spin_unlock_irqrestore(&musb->lock, flags);
+
+ return ret;
+}
+
+static int dsps_musb_init(struct musb *musb)
+{
+ struct device_d *dev = musb->controller;
+ struct dsps_glue *glue = dev->priv;
+ const struct dsps_musb_wrapper *wrp = glue->wrp;
+ u32 rev, val, mode;
+
+ musb->xceiv = am335x_get_usb_phy();
+ if (IS_ERR(musb->xceiv))
+ return PTR_ERR(musb->xceiv);
+
+ /* Returns zero if e.g. not clocked */
+ rev = dsps_readl(musb->ctrl_base, wrp->revision);
+ if (!rev)
+ return -ENODEV;
+
+ usb_phy_init(musb->xceiv);
+
+ /* Reset the musb */
+ dsps_writel(musb->ctrl_base, wrp->control, (1 << wrp->reset));
+
+ musb->isr = dsps_interrupt;
+
+ /* reset the otgdisable bit, needed for host mode to work */
+ val = dsps_readl(musb->ctrl_base, wrp->phy_utmi);
+ val &= ~(1 << wrp->otg_disable);
+ dsps_writel(musb->ctrl_base, wrp->phy_utmi, val);
+
+ mode = dsps_readl(musb->ctrl_base, wrp->mode);
+
+ switch (musb->port_mode) {
+ case MUSB_PORT_MODE_HOST:
+ mode &= ~0x100;
+ break;
+ case MUSB_PORT_MODE_GADGET:
+ mode |= 0x100;
+ break;
+ }
+
+ mode |= 0x80;
+ dsps_writel(musb->ctrl_base, wrp->mode, mode); /* IDDIG=0, IDDIG_MUX=1 */
+
+ return 0;
+}
+
+static int dsps_musb_exit(struct musb *musb)
+{
+ usb_phy_shutdown(musb->xceiv);
+ return 0;
+}
+
+static struct musb_platform_ops dsps_ops = {
+ .init = dsps_musb_init,
+ .exit = dsps_musb_exit,
+
+ .enable = dsps_musb_enable,
+ .disable = dsps_musb_disable,
+};
+
+static int get_int_prop(struct device_node *dn, const char *s)
+{
+ int ret;
+ u32 val;
+
+ ret = of_property_read_u32(dn, s, &val);
+ if (ret)
+ return 0;
+ return val;
+}
+
+static int get_musb_port_mode(struct device_d *dev)
+{
+ enum usb_dr_mode mode;
+
+ mode = of_usb_get_dr_mode(dev->device_node, NULL);
+ switch (mode) {
+ case USB_DR_MODE_HOST:
+ return MUSB_PORT_MODE_HOST;
+
+ case USB_DR_MODE_PERIPHERAL:
+ return MUSB_PORT_MODE_GADGET;
+
+ case USB_DR_MODE_UNKNOWN:
+ case USB_DR_MODE_OTG:
+ default:
+ if (!IS_ENABLED(CONFIG_USB_MUSB_HOST))
+ return MUSB_PORT_MODE_GADGET;
+ if (!IS_ENABLED(CONFIG_USB_MUSB_GADGET))
+ return MUSB_PORT_MODE_HOST;
+ return MUSB_PORT_MODE_DUAL_ROLE;
+ }
+}
+
+static int dsps_set_mode(struct param_d *param, void *priv)
+{
+ struct dsps_glue *glue = priv;
+
+ if (glue->pdata.mode != MUSB_PORT_MODE_DUAL_ROLE)
+ return -EBUSY;
+
+ switch (glue->otgmode) {
+ case 0:
+ default:
+ return -EINVAL;
+ case 1:
+ glue->pdata.mode = MUSB_PORT_MODE_HOST;
+ break;
+ case 2:
+ glue->pdata.mode = MUSB_PORT_MODE_GADGET;
+ break;
+ }
+
+ return musb_init_controller(&glue->musb, &glue->pdata);
+}
+
+static const char *dsps_mode_names[] = {
+ "otg", "host", "peripheral"
+};
+
+static int dsps_register_otg_device(struct dsps_glue *glue)
+{
+ int ret;
+
+ strcpy(glue->otg_dev.name, "otg");
+ glue->otg_dev.id = DEVICE_ID_DYNAMIC,
+ glue->otg_dev.parent = glue->dev;
+
+ ret = register_device(&glue->otg_dev);
+ if (ret)
+ return ret;
+
+ dev_add_param_enum(&glue->otg_dev, "mode",
+ dsps_set_mode, NULL, &glue->otgmode,
+ dsps_mode_names, ARRAY_SIZE(dsps_mode_names), glue);
+ return 0;
+}
+
+static int dsps_probe(struct device_d *dev)
+{
+ struct musb_hdrc_platform_data *pdata;
+ struct musb_hdrc_config *config;
+ struct device_node *dn = dev->device_node;
+ const struct dsps_musb_wrapper *wrp;
+ struct dsps_glue *glue;
+ int ret;
+
+ ret = dev_get_drvdata(dev, (unsigned long *)&wrp);
+ if (ret)
+ return ret;
+
+ if (!IS_ENABLED(CONFIG_USB_MUSB_HOST) &&
+ !IS_ENABLED(CONFIG_USB_MUSB_GADGET)) {
+ dev_err(dev, "Both host and device driver disabled.\n");
+ return -ENODEV;
+ }
+
+ /* allocate glue */
+ glue = kzalloc(sizeof(*glue), GFP_KERNEL);
+ if (!glue) {
+ dev_err(dev, "unable to allocate glue memory\n");
+ return -ENOMEM;
+ }
+
+ glue->dev = dev;
+ glue->wrp = wrp;
+
+ dev->priv = glue;
+
+ pdata = &glue->pdata;
+
+ glue->musb.mregs = dev_request_mem_region(dev, 0);
+ if (IS_ERR(glue->musb.mregs))
+ return PTR_ERR(glue->musb.mregs);
+
+ glue->musb.ctrl_base = dev_request_mem_region(dev, 1);
+ if (IS_ERR(glue->musb.ctrl_base))
+ return PTR_ERR(glue->musb.ctrl_base);
+
+ glue->musb.controller = dev;
+
+ config = &glue->config;
+
+ pdata->config = config;
+ pdata->platform_ops = &dsps_ops;
+
+ config->num_eps = get_int_prop(dn, "mentor,num-eps");
+ config->ram_bits = get_int_prop(dn, "mentor,ram-bits");
+
+ pdata->mode = get_musb_port_mode(dev);
+ /* DT keeps this entry in mA, musb expects it as per USB spec */
+ pdata->power = get_int_prop(dn, "mentor,power") / 2;
+ config->multipoint = of_property_read_bool(dn, "mentor,multipoint");
+
+ if (pdata->mode == MUSB_PORT_MODE_DUAL_ROLE) {
+ ret = dsps_register_otg_device(glue);
+ if (ret)
+ return ret;
+ return 0;
+ }
+
+ return musb_init_controller(&glue->musb, pdata);
+}
+
+static const struct dsps_musb_wrapper am33xx_driver_data = {
+ .revision = 0x00,
+ .control = 0x14,
+ .status = 0x18,
+ .epintr_set = 0x38,
+ .epintr_clear = 0x40,
+ .epintr_status = 0x30,
+ .coreintr_set = 0x3c,
+ .coreintr_clear = 0x44,
+ .coreintr_status = 0x34,
+ .phy_utmi = 0xe0,
+ .mode = 0xe8,
+ .reset = 0,
+ .otg_disable = 21,
+ .iddig = 8,
+ .usb_shift = 0,
+ .usb_mask = 0x1ff,
+ .usb_bitmap = (0x1ff << 0),
+ .drvvbus = 8,
+ .txep_shift = 0,
+ .txep_mask = 0xffff,
+ .txep_bitmap = (0xffff << 0),
+ .rxep_shift = 16,
+ .rxep_mask = 0xfffe,
+ .rxep_bitmap = (0xfffe << 16),
+ .poll_seconds = 2,
+};
+
+static __maybe_unused struct of_device_id musb_dsps_dt_ids[] = {
+ {
+ .compatible = "ti,musb-am33xx",
+ .data = (unsigned long) &am33xx_driver_data,
+ }, {
+ /* sentinel */
+ },
+};
+
+static struct driver_d dsps_usbss_driver = {
+ .name = "musb-dsps",
+ .probe = dsps_probe,
+ .of_compatible = DRV_OF_COMPAT(musb_dsps_dt_ids),
+};
+device_platform_driver(dsps_usbss_driver);
+
+MODULE_DESCRIPTION("TI DSPS MUSB Glue Layer");
+MODULE_AUTHOR("Ravi B <ravibabu@ti.com>");
+MODULE_AUTHOR("Ajay Kumar Gupta <ajay.gupta@ti.com>");
+MODULE_LICENSE("GPL v2");
diff --git a/drivers/usb/musb/musb_gadget.c b/drivers/usb/musb/musb_gadget.c
new file mode 100644
index 0000000000..3f0ddd1875
--- /dev/null
+++ b/drivers/usb/musb/musb_gadget.c
@@ -0,0 +1,1308 @@
+/*
+ * MUSB OTG driver peripheral support
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ * Copyright (C) 2009 MontaVista Software, Inc. <source@mvista.com>
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#include <common.h>
+#include <malloc.h>
+#include <clock.h>
+#include "musb_core.h"
+#include "musb_gadget.h"
+
+/*
+ * Immediately complete a request.
+ *
+ * @param request the request to complete
+ * @param status the status to complete the request with
+ * Context: controller locked, IRQs blocked.
+ */
+void musb_g_giveback(
+ struct musb_ep *ep,
+ struct usb_request *request,
+ int status)
+__releases(ep->musb->lock)
+__acquires(ep->musb->lock)
+{
+ struct musb_request *req;
+ struct musb *musb;
+ int busy = ep->busy;
+
+ req = to_musb_request(request);
+
+ list_del(&req->list);
+ if (req->request.status == -EINPROGRESS)
+ req->request.status = status;
+ musb = req->musb;
+
+ ep->busy = 1;
+ spin_unlock(&musb->lock);
+
+ if (request->status == 0)
+ dev_dbg(musb->controller, "%s done request %p, %d/%d\n",
+ ep->end_point.name, request,
+ req->request.actual, req->request.length);
+ else
+ dev_dbg(musb->controller, "%s request %p, %d/%d fault %d\n",
+ ep->end_point.name, request,
+ req->request.actual, req->request.length,
+ request->status);
+ req->request.complete(&req->ep->end_point, &req->request);
+ spin_lock(&musb->lock);
+ ep->busy = busy;
+}
+
+/* ----------------------------------------------------------------------- */
+
+/*
+ * Abort requests queued to an endpoint using the status. Synchronous.
+ * caller locked controller and blocked irqs, and selected this ep.
+ */
+static void nuke(struct musb_ep *ep, const int status)
+{
+ struct musb_request *req = NULL;
+
+ ep->busy = 1;
+
+ while (!list_empty(&ep->req_list)) {
+ req = list_first_entry(&ep->req_list, struct musb_request, list);
+ musb_g_giveback(ep, &req->request, status);
+ }
+}
+
+/* ----------------------------------------------------------------------- */
+
+/* Data transfers - pure PIO, pure DMA, or mixed mode */
+
+/*
+ * This assumes the separate CPPI engine is responding to DMA requests
+ * from the usb core ... sequenced a bit differently from mentor dma.
+ */
+
+static inline int max_ep_writesize(struct musb *musb, struct musb_ep *ep)
+{
+ if (can_bulk_split(musb, ep->type))
+ return ep->hw_ep->max_packet_sz_tx;
+ else
+ return ep->packet_sz;
+}
+
+/*
+ * An endpoint is transmitting data. This can be called either from
+ * the IRQ routine or from ep.queue() to kickstart a request on an
+ * endpoint.
+ *
+ * Context: controller locked, IRQs blocked, endpoint selected
+ */
+static void txstate(struct musb *musb, struct musb_request *req)
+{
+ u8 epnum = req->epnum;
+ struct musb_ep *musb_ep;
+ void __iomem *epio = musb->endpoints[epnum].regs;
+ struct usb_request *request;
+ u16 fifo_count = 0, csr;
+ int use_dma = 0;
+
+ musb_ep = req->ep;
+
+ /* Check if EP is disabled */
+ if (!musb_ep->desc) {
+ dev_dbg(musb->controller, "ep:%s disabled - ignore request\n",
+ musb_ep->end_point.name);
+ return;
+ }
+
+ /* read TXCSR before */
+ csr = musb_readw(epio, MUSB_TXCSR);
+
+ request = &req->request;
+ fifo_count = min(max_ep_writesize(musb, musb_ep),
+ (int)(request->length - request->actual));
+
+ if (csr & MUSB_TXCSR_TXPKTRDY) {
+ dev_dbg(musb->controller, "%s old packet still ready , txcsr %03x\n",
+ musb_ep->end_point.name, csr);
+ return;
+ }
+
+ if (csr & MUSB_TXCSR_P_SENDSTALL) {
+ dev_dbg(musb->controller, "%s stalling, txcsr %03x\n",
+ musb_ep->end_point.name, csr);
+ return;
+ }
+
+ dev_dbg(musb->controller, "hw_ep%d, maxpacket %d, fifo count %d, txcsr %03x\n",
+ epnum, musb_ep->packet_sz, fifo_count,
+ csr);
+
+ if (!use_dma) {
+ musb_write_fifo(musb_ep->hw_ep, fifo_count,
+ (u8 *) (request->buf + request->actual));
+ request->actual += fifo_count;
+ csr |= MUSB_TXCSR_TXPKTRDY;
+ csr &= ~MUSB_TXCSR_P_UNDERRUN;
+ musb_writew(epio, MUSB_TXCSR, csr);
+ }
+
+ /* host may already have the data when this message shows... */
+ dev_dbg(musb->controller, "%s TX/IN %s len %d/%d, txcsr %04x, fifo %d/%d\n",
+ musb_ep->end_point.name, use_dma ? "dma" : "pio",
+ request->actual, request->length,
+ musb_readw(epio, MUSB_TXCSR),
+ fifo_count,
+ musb_readw(epio, MUSB_TXMAXP));
+}
+
+/*
+ * FIFO state update (e.g. data ready).
+ * Called from IRQ, with controller locked.
+ */
+void musb_g_tx(struct musb *musb, u8 epnum)
+{
+ u16 csr;
+ struct musb_request *req;
+ struct usb_request *request;
+ u8 __iomem *mbase = musb->mregs;
+ struct musb_ep *musb_ep = &musb->endpoints[epnum].ep_in;
+ void __iomem *epio = musb->endpoints[epnum].regs;
+
+ musb_ep_select(mbase, epnum);
+ req = next_request(musb_ep);
+ request = &req->request;
+
+ csr = musb_readw(epio, MUSB_TXCSR);
+ dev_dbg(musb->controller, "<== %s, txcsr %04x\n", musb_ep->end_point.name, csr);
+
+ /*
+ * REVISIT: for high bandwidth, MUSB_TXCSR_P_INCOMPTX
+ * probably rates reporting as a host error.
+ */
+ if (csr & MUSB_TXCSR_P_SENTSTALL) {
+ csr |= MUSB_TXCSR_P_WZC_BITS;
+ csr &= ~MUSB_TXCSR_P_SENTSTALL;
+ musb_writew(epio, MUSB_TXCSR, csr);
+ return;
+ }
+
+ if (csr & MUSB_TXCSR_P_UNDERRUN) {
+ /* We NAKed, no big deal... little reason to care. */
+ csr |= MUSB_TXCSR_P_WZC_BITS;
+ csr &= ~(MUSB_TXCSR_P_UNDERRUN | MUSB_TXCSR_TXPKTRDY);
+ musb_writew(epio, MUSB_TXCSR, csr);
+ dev_vdbg(musb->controller, "underrun on ep%d, req %p\n",
+ epnum, request);
+ }
+
+ if (request) {
+ /*
+ * First, maybe a terminating short packet. Some DMA
+ * engines might handle this by themselves.
+ */
+ if ((request->zero && request->length
+ && (request->length % musb_ep->packet_sz == 0)
+ && (request->actual == request->length))
+ ) {
+ /*
+ * On DMA completion, FIFO may not be
+ * available yet...
+ */
+ if (csr & MUSB_TXCSR_TXPKTRDY)
+ return;
+
+ dev_dbg(musb->controller, "sending zero pkt\n");
+ musb_writew(epio, MUSB_TXCSR, MUSB_TXCSR_MODE
+ | MUSB_TXCSR_TXPKTRDY);
+ request->zero = 0;
+ }
+
+ if (request->actual == request->length) {
+ musb_g_giveback(musb_ep, request, 0);
+ /*
+ * In the giveback function the MUSB lock is
+ * released and acquired after sometime. During
+ * this time period the INDEX register could get
+ * changed by the gadget_queue function especially
+ * on SMP systems. Reselect the INDEX to be sure
+ * we are reading/modifying the right registers
+ */
+ musb_ep_select(mbase, epnum);
+ req = musb_ep->desc ? next_request(musb_ep) : NULL;
+ if (!req) {
+ dev_dbg(musb->controller, "%s idle now\n",
+ musb_ep->end_point.name);
+ return;
+ }
+ }
+
+ txstate(musb, req);
+ }
+}
+
+/* ------------------------------------------------------------ */
+
+/*
+ * Context: controller locked, IRQs blocked, endpoint selected
+ */
+static void rxstate(struct musb *musb, struct musb_request *req)
+{
+ const u8 epnum = req->epnum;
+ struct usb_request *request = &req->request;
+ struct musb_ep *musb_ep;
+ void __iomem *epio = musb->endpoints[epnum].regs;
+ unsigned len = 0;
+ u16 fifo_count;
+ u16 csr = musb_readw(epio, MUSB_RXCSR);
+ struct musb_hw_ep *hw_ep = &musb->endpoints[epnum];
+ u8 use_mode_1;
+
+ if (hw_ep->is_shared_fifo)
+ musb_ep = &hw_ep->ep_in;
+ else
+ musb_ep = &hw_ep->ep_out;
+
+ fifo_count = musb_ep->packet_sz;
+
+ /* Check if EP is disabled */
+ if (!musb_ep->desc) {
+ dev_dbg(musb->controller, "ep:%s disabled - ignore request\n",
+ musb_ep->end_point.name);
+ return;
+ }
+
+ if (csr & MUSB_RXCSR_P_SENDSTALL) {
+ dev_dbg(musb->controller, "%s stalling, RXCSR %04x\n",
+ musb_ep->end_point.name, csr);
+ return;
+ }
+
+ if (csr & MUSB_RXCSR_RXPKTRDY) {
+ fifo_count = musb_readw(epio, MUSB_RXCOUNT);
+
+ /*
+ * Enable Mode 1 on RX transfers only when short_not_ok flag
+ * is set. Currently short_not_ok flag is set only from
+ * file_storage and f_mass_storage drivers
+ */
+
+ if (request->short_not_ok && fifo_count == musb_ep->packet_sz)
+ use_mode_1 = 1;
+ else
+ use_mode_1 = 0;
+
+ if (request->actual < request->length) {
+ len = request->length - request->actual;
+ dev_dbg(musb->controller, "%s OUT/RX pio fifo %d/%d, maxpacket %d\n",
+ musb_ep->end_point.name,
+ fifo_count, len,
+ musb_ep->packet_sz);
+
+ fifo_count = min_t(unsigned, len, fifo_count);
+
+ musb_read_fifo(musb_ep->hw_ep, fifo_count, (u8 *)
+ (request->buf + request->actual));
+ request->actual += fifo_count;
+
+ /* REVISIT if we left anything in the fifo, flush
+ * it and report -EOVERFLOW
+ */
+
+ /* ack the read! */
+ csr |= MUSB_RXCSR_P_WZC_BITS;
+ csr &= ~MUSB_RXCSR_RXPKTRDY;
+ musb_writew(epio, MUSB_RXCSR, csr);
+ }
+ }
+
+ /* reach the end or short packet detected */
+ if (request->actual == request->length ||
+ fifo_count < musb_ep->packet_sz)
+ musb_g_giveback(musb_ep, request, 0);
+}
+
+/*
+ * Data ready for a request; called from IRQ
+ */
+void musb_g_rx(struct musb *musb, u8 epnum)
+{
+ u16 csr;
+ struct musb_request *req;
+ struct usb_request *request;
+ void __iomem *mbase = musb->mregs;
+ struct musb_ep *musb_ep;
+ void __iomem *epio = musb->endpoints[epnum].regs;
+ struct musb_hw_ep *hw_ep = &musb->endpoints[epnum];
+
+ if (hw_ep->is_shared_fifo)
+ musb_ep = &hw_ep->ep_in;
+ else
+ musb_ep = &hw_ep->ep_out;
+
+ musb_ep_select(mbase, epnum);
+
+ req = next_request(musb_ep);
+ if (!req)
+ return;
+
+ request = &req->request;
+
+ csr = musb_readw(epio, MUSB_RXCSR);
+
+ dev_dbg(musb->controller, "<== %s, rxcsr %04x%s %p\n", musb_ep->end_point.name,
+ csr, "", request);
+
+ if (csr & MUSB_RXCSR_P_SENTSTALL) {
+ csr |= MUSB_RXCSR_P_WZC_BITS;
+ csr &= ~MUSB_RXCSR_P_SENTSTALL;
+ musb_writew(epio, MUSB_RXCSR, csr);
+ return;
+ }
+
+ if (csr & MUSB_RXCSR_P_OVERRUN) {
+ /* csr |= MUSB_RXCSR_P_WZC_BITS; */
+ csr &= ~MUSB_RXCSR_P_OVERRUN;
+ musb_writew(epio, MUSB_RXCSR, csr);
+
+ dev_dbg(musb->controller, "%s iso overrun on %p\n", musb_ep->name, request);
+ if (request->status == -EINPROGRESS)
+ request->status = -EOVERFLOW;
+ }
+ if (csr & MUSB_RXCSR_INCOMPRX) {
+ /* REVISIT not necessarily an error */
+ dev_dbg(musb->controller, "%s, incomprx\n", musb_ep->end_point.name);
+ }
+
+ /* Analyze request */
+ rxstate(musb, req);
+}
+
+/* ------------------------------------------------------------ */
+
+static int musb_gadget_enable(struct usb_ep *ep,
+ const struct usb_endpoint_descriptor *desc)
+{
+ unsigned long flags;
+ struct musb_ep *musb_ep;
+ struct musb_hw_ep *hw_ep;
+ void __iomem *regs;
+ struct musb *musb;
+ void __iomem *mbase;
+ u8 epnum;
+ u16 csr;
+ unsigned tmp;
+ int status = -EINVAL;
+
+ if (!ep || !desc)
+ return -EINVAL;
+
+ musb_ep = to_musb_ep(ep);
+ hw_ep = musb_ep->hw_ep;
+ regs = hw_ep->regs;
+ musb = musb_ep->musb;
+ mbase = musb->mregs;
+ epnum = musb_ep->current_epnum;
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ if (musb_ep->desc) {
+ status = -EBUSY;
+ goto fail;
+ }
+ musb_ep->type = usb_endpoint_type(desc);
+
+ /* check direction and (later) maxpacket size against endpoint */
+ if (usb_endpoint_num(desc) != epnum)
+ goto fail;
+
+ /* REVISIT this rules out high bandwidth periodic transfers */
+ tmp = usb_endpoint_maxp(desc);
+ if (tmp & ~0x07ff) {
+ int ok;
+
+ if (usb_endpoint_dir_in(desc))
+ ok = musb->hb_iso_tx;
+ else
+ ok = musb->hb_iso_rx;
+
+ if (!ok) {
+ dev_dbg(musb->controller, "no support for high bandwidth ISO\n");
+ goto fail;
+ }
+ musb_ep->hb_mult = (tmp >> 11) & 3;
+ } else {
+ musb_ep->hb_mult = 0;
+ }
+
+ musb_ep->packet_sz = tmp & 0x7ff;
+ tmp = musb_ep->packet_sz * (musb_ep->hb_mult + 1);
+
+ /* enable the interrupts for the endpoint, set the endpoint
+ * packet size (or fail), set the mode, clear the fifo
+ */
+ musb_ep_select(mbase, epnum);
+ if (usb_endpoint_dir_in(desc)) {
+
+ if (hw_ep->is_shared_fifo)
+ musb_ep->is_in = 1;
+ if (!musb_ep->is_in)
+ goto fail;
+
+ if (tmp > hw_ep->max_packet_sz_tx) {
+ dev_dbg(musb->controller, "packet size beyond hardware FIFO size\n");
+ goto fail;
+ }
+
+ musb->intrtxe |= (1 << epnum);
+ musb_writew(mbase, MUSB_INTRTXE, musb->intrtxe);
+
+ /* REVISIT if can_bulk_split(), use by updating "tmp";
+ * likewise high bandwidth periodic tx
+ */
+ /* Set TXMAXP with the FIFO size of the endpoint
+ * to disable double buffering mode.
+ */
+ if (musb->double_buffer_not_ok) {
+ musb_writew(regs, MUSB_TXMAXP, hw_ep->max_packet_sz_tx);
+ } else {
+ if (can_bulk_split(musb, musb_ep->type))
+ musb_ep->hb_mult = (hw_ep->max_packet_sz_tx /
+ musb_ep->packet_sz) - 1;
+ musb_writew(regs, MUSB_TXMAXP, musb_ep->packet_sz
+ | (musb_ep->hb_mult << 11));
+ }
+
+ csr = MUSB_TXCSR_MODE | MUSB_TXCSR_CLRDATATOG;
+ if (musb_readw(regs, MUSB_TXCSR)
+ & MUSB_TXCSR_FIFONOTEMPTY)
+ csr |= MUSB_TXCSR_FLUSHFIFO;
+ if (musb_ep->type == USB_ENDPOINT_XFER_ISOC)
+ csr |= MUSB_TXCSR_P_ISO;
+
+ /* set twice in case of double buffering */
+ musb_writew(regs, MUSB_TXCSR, csr);
+ /* REVISIT may be inappropriate w/o FIFONOTEMPTY ... */
+ musb_writew(regs, MUSB_TXCSR, csr);
+
+ } else {
+
+ if (hw_ep->is_shared_fifo)
+ musb_ep->is_in = 0;
+ if (musb_ep->is_in)
+ goto fail;
+
+ if (tmp > hw_ep->max_packet_sz_rx) {
+ dev_dbg(musb->controller, "packet size beyond hardware FIFO size\n");
+ goto fail;
+ }
+
+ musb->intrrxe |= (1 << epnum);
+ musb_writew(mbase, MUSB_INTRRXE, musb->intrrxe);
+
+ /* REVISIT if can_bulk_combine() use by updating "tmp"
+ * likewise high bandwidth periodic rx
+ */
+ /* Set RXMAXP with the FIFO size of the endpoint
+ * to disable double buffering mode.
+ */
+ if (musb->double_buffer_not_ok)
+ musb_writew(regs, MUSB_RXMAXP, hw_ep->max_packet_sz_tx);
+ else
+ musb_writew(regs, MUSB_RXMAXP, musb_ep->packet_sz
+ | (musb_ep->hb_mult << 11));
+
+ /* force shared fifo to OUT-only mode */
+ if (hw_ep->is_shared_fifo) {
+ csr = musb_readw(regs, MUSB_TXCSR);
+ csr &= ~(MUSB_TXCSR_MODE | MUSB_TXCSR_TXPKTRDY);
+ musb_writew(regs, MUSB_TXCSR, csr);
+ }
+
+ csr = MUSB_RXCSR_FLUSHFIFO | MUSB_RXCSR_CLRDATATOG;
+ if (musb_ep->type == USB_ENDPOINT_XFER_ISOC)
+ csr |= MUSB_RXCSR_P_ISO;
+ else if (musb_ep->type == USB_ENDPOINT_XFER_INT)
+ csr |= MUSB_RXCSR_DISNYET;
+
+ /* set twice in case of double buffering */
+ musb_writew(regs, MUSB_RXCSR, csr);
+ musb_writew(regs, MUSB_RXCSR, csr);
+ }
+
+ musb_ep->desc = desc;
+ musb_ep->busy = 0;
+ musb_ep->wedged = 0;
+ status = 0;
+
+ pr_debug("%s periph: enabled %s for %s %s, %smaxpacket %d\n",
+ musb_driver_name, musb_ep->end_point.name,
+ ({ char *s; switch (musb_ep->type) {
+ case USB_ENDPOINT_XFER_BULK: s = "bulk"; break;
+ case USB_ENDPOINT_XFER_INT: s = "int"; break;
+ default: s = "iso"; break;
+ } s; }),
+ musb_ep->is_in ? "IN" : "OUT",
+ "",
+ musb_ep->packet_sz);
+
+fail:
+ spin_unlock_irqrestore(&musb->lock, flags);
+ return status;
+}
+
+/*
+ * Disable an endpoint flushing all requests queued.
+ */
+static int musb_gadget_disable(struct usb_ep *ep)
+{
+ unsigned long flags;
+ struct musb *musb;
+ u8 epnum;
+ struct musb_ep *musb_ep;
+ void __iomem *epio;
+ int status = 0;
+
+ musb_ep = to_musb_ep(ep);
+ musb = musb_ep->musb;
+ epnum = musb_ep->current_epnum;
+ epio = musb->endpoints[epnum].regs;
+
+ spin_lock_irqsave(&musb->lock, flags);
+ musb_ep_select(musb->mregs, epnum);
+
+ /* zero the endpoint sizes */
+ if (musb_ep->is_in) {
+ musb->intrtxe &= ~(1 << epnum);
+ musb_writew(musb->mregs, MUSB_INTRTXE, musb->intrtxe);
+ musb_writew(epio, MUSB_TXMAXP, 0);
+ } else {
+ musb->intrrxe &= ~(1 << epnum);
+ musb_writew(musb->mregs, MUSB_INTRRXE, musb->intrrxe);
+ musb_writew(epio, MUSB_RXMAXP, 0);
+ }
+
+ musb_ep->desc = NULL;
+ musb_ep->end_point.desc = NULL;
+
+ /* abort all pending DMA and requests */
+ nuke(musb_ep, -ESHUTDOWN);
+
+ spin_unlock_irqrestore(&(musb->lock), flags);
+
+ dev_dbg(musb->controller, "%s\n", musb_ep->end_point.name);
+
+ return status;
+}
+
+/*
+ * Allocate a request for an endpoint.
+ * Reused by ep0 code.
+ */
+struct usb_request *musb_alloc_request(struct usb_ep *ep)
+{
+ struct musb_ep *musb_ep = to_musb_ep(ep);
+ struct musb *musb = musb_ep->musb;
+ struct musb_request *request = NULL;
+
+ request = kzalloc(sizeof *request, gfp_flags);
+ if (!request) {
+ dev_dbg(musb->controller, "not enough memory\n");
+ return NULL;
+ }
+
+ request->request.dma = DMA_ADDR_INVALID;
+ request->epnum = musb_ep->current_epnum;
+ request->ep = musb_ep;
+
+ return &request->request;
+}
+
+/*
+ * Free a request
+ * Reused by ep0 code.
+ */
+void musb_free_request(struct usb_ep *ep, struct usb_request *req)
+{
+ kfree(to_musb_request(req));
+}
+
+static LIST_HEAD(buffers);
+
+struct free_record {
+ struct list_head list;
+ struct device *dev;
+ unsigned bytes;
+ dma_addr_t dma;
+};
+
+/*
+ * Context: controller locked, IRQs blocked.
+ */
+void musb_ep_restart(struct musb *musb, struct musb_request *req)
+{
+ dev_dbg(musb->controller, "<== %s request %p len %u on hw_ep%d\n",
+ req->tx ? "TX/IN" : "RX/OUT",
+ &req->request, req->request.length, req->epnum);
+
+ musb_ep_select(musb->mregs, req->epnum);
+ if (req->tx)
+ txstate(musb, req);
+ else
+ rxstate(musb, req);
+}
+
+static int musb_gadget_queue(struct usb_ep *ep, struct usb_request *req)
+{
+ struct musb_ep *musb_ep;
+ struct musb_request *request;
+ struct musb *musb;
+ int status = 0;
+ unsigned long lockflags;
+
+ if (!ep || !req)
+ return -EINVAL;
+ if (!req->buf)
+ return -ENODATA;
+
+ musb_ep = to_musb_ep(ep);
+ musb = musb_ep->musb;
+
+ request = to_musb_request(req);
+ request->musb = musb;
+
+ if (request->ep != musb_ep)
+ return -EINVAL;
+
+ dev_dbg(musb->controller, "<== to %s request=%p\n", ep->name, req);
+
+ /* request is mine now... */
+ request->request.actual = 0;
+ request->request.status = -EINPROGRESS;
+ request->epnum = musb_ep->current_epnum;
+ request->tx = musb_ep->is_in;
+
+ spin_lock_irqsave(&musb->lock, lockflags);
+
+ /* don't queue if the ep is down */
+ if (!musb_ep->desc) {
+ dev_dbg(musb->controller, "req %p queued to %s while ep %s\n",
+ req, ep->name, "disabled");
+ status = -ESHUTDOWN;
+ goto unlock;
+ }
+
+ /* add request to the list */
+ list_add_tail(&request->list, &musb_ep->req_list);
+
+ /* it this is the head of the queue, start i/o ... */
+ if (!musb_ep->busy && &request->list == musb_ep->req_list.next)
+ musb_ep_restart(musb, request);
+
+unlock:
+ spin_unlock_irqrestore(&musb->lock, lockflags);
+ return status;
+}
+
+static int musb_gadget_dequeue(struct usb_ep *ep, struct usb_request *request)
+{
+ struct musb_ep *musb_ep = to_musb_ep(ep);
+ struct musb_request *req = to_musb_request(request);
+ struct musb_request *r;
+ unsigned long flags;
+ int status = 0;
+ struct musb *musb = musb_ep->musb;
+
+ if (!ep || !request || to_musb_request(request)->ep != musb_ep)
+ return -EINVAL;
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ list_for_each_entry(r, &musb_ep->req_list, list) {
+ if (r == req)
+ break;
+ }
+ if (r != req) {
+ dev_dbg(musb->controller, "request %p not queued to %s\n", request, ep->name);
+ status = -EINVAL;
+ goto done;
+ }
+
+ /* if the hardware doesn't have the request, easy ... */
+ if (musb_ep->req_list.next != &req->list || musb_ep->busy) {
+ musb_g_giveback(musb_ep, request, -ECONNRESET);
+ } else {
+ /* NOTE: by sticking to easily tested hardware/driver states,
+ * we leave counting of in-flight packets imprecise.
+ */
+ musb_g_giveback(musb_ep, request, -ECONNRESET);
+ }
+
+done:
+ spin_unlock_irqrestore(&musb->lock, flags);
+ return status;
+}
+
+/*
+ * Set or clear the halt bit of an endpoint. A halted enpoint won't tx/rx any
+ * data but will queue requests.
+ *
+ * exported to ep0 code
+ */
+static int musb_gadget_set_halt(struct usb_ep *ep, int value)
+{
+ struct musb_ep *musb_ep = to_musb_ep(ep);
+ u8 epnum = musb_ep->current_epnum;
+ struct musb *musb = musb_ep->musb;
+ void __iomem *epio = musb->endpoints[epnum].regs;
+ void __iomem *mbase;
+ unsigned long flags;
+ u16 csr;
+ struct musb_request *request;
+ int status = 0;
+
+ if (!ep)
+ return -EINVAL;
+ mbase = musb->mregs;
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ if ((USB_ENDPOINT_XFER_ISOC == musb_ep->type)) {
+ status = -EINVAL;
+ goto done;
+ }
+
+ musb_ep_select(mbase, epnum);
+
+ request = next_request(musb_ep);
+ if (value) {
+ if (request) {
+ dev_dbg(musb->controller, "request in progress, cannot halt %s\n",
+ ep->name);
+ status = -EAGAIN;
+ goto done;
+ }
+ /* Cannot portably stall with non-empty FIFO */
+ if (musb_ep->is_in) {
+ csr = musb_readw(epio, MUSB_TXCSR);
+ if (csr & MUSB_TXCSR_FIFONOTEMPTY) {
+ dev_dbg(musb->controller, "FIFO busy, cannot halt %s\n", ep->name);
+ status = -EAGAIN;
+ goto done;
+ }
+ }
+ } else
+ musb_ep->wedged = 0;
+
+ /* set/clear the stall and toggle bits */
+ dev_dbg(musb->controller, "%s: %s stall\n", ep->name, value ? "set" : "clear");
+ if (musb_ep->is_in) {
+ csr = musb_readw(epio, MUSB_TXCSR);
+ csr |= MUSB_TXCSR_P_WZC_BITS
+ | MUSB_TXCSR_CLRDATATOG;
+ if (value)
+ csr |= MUSB_TXCSR_P_SENDSTALL;
+ else
+ csr &= ~(MUSB_TXCSR_P_SENDSTALL
+ | MUSB_TXCSR_P_SENTSTALL);
+ csr &= ~MUSB_TXCSR_TXPKTRDY;
+ musb_writew(epio, MUSB_TXCSR, csr);
+ } else {
+ csr = musb_readw(epio, MUSB_RXCSR);
+ csr |= MUSB_RXCSR_P_WZC_BITS
+ | MUSB_RXCSR_FLUSHFIFO
+ | MUSB_RXCSR_CLRDATATOG;
+ if (value)
+ csr |= MUSB_RXCSR_P_SENDSTALL;
+ else
+ csr &= ~(MUSB_RXCSR_P_SENDSTALL
+ | MUSB_RXCSR_P_SENTSTALL);
+ musb_writew(epio, MUSB_RXCSR, csr);
+ }
+
+ /* maybe start the first request in the queue */
+ if (!musb_ep->busy && !value && request) {
+ dev_dbg(musb->controller, "restarting the request\n");
+ musb_ep_restart(musb, request);
+ }
+
+done:
+ spin_unlock_irqrestore(&musb->lock, flags);
+ return status;
+}
+
+/*
+ * Sets the halt feature with the clear requests ignored
+ */
+static int musb_gadget_set_wedge(struct usb_ep *ep)
+{
+ struct musb_ep *musb_ep = to_musb_ep(ep);
+
+ if (!ep)
+ return -EINVAL;
+
+ musb_ep->wedged = 1;
+
+ return usb_ep_set_halt(ep);
+}
+
+static int musb_gadget_fifo_status(struct usb_ep *ep)
+{
+ struct musb_ep *musb_ep = to_musb_ep(ep);
+ void __iomem *epio = musb_ep->hw_ep->regs;
+ int retval = -EINVAL;
+
+ if (musb_ep->desc && !musb_ep->is_in) {
+ struct musb *musb = musb_ep->musb;
+ int epnum = musb_ep->current_epnum;
+ void __iomem *mbase = musb->mregs;
+ unsigned long flags;
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ musb_ep_select(mbase, epnum);
+ /* FIXME return zero unless RXPKTRDY is set */
+ retval = musb_readw(epio, MUSB_RXCOUNT);
+
+ spin_unlock_irqrestore(&musb->lock, flags);
+ }
+ return retval;
+}
+
+static void musb_gadget_fifo_flush(struct usb_ep *ep)
+{
+ struct musb_ep *musb_ep = to_musb_ep(ep);
+ struct musb *musb = musb_ep->musb;
+ u8 epnum = musb_ep->current_epnum;
+ void __iomem *epio = musb->endpoints[epnum].regs;
+ void __iomem *mbase;
+ unsigned long flags;
+ u16 csr;
+
+ mbase = musb->mregs;
+
+ spin_lock_irqsave(&musb->lock, flags);
+ musb_ep_select(mbase, (u8) epnum);
+
+ /* disable interrupts */
+ musb_writew(mbase, MUSB_INTRTXE, musb->intrtxe & ~(1 << epnum));
+
+ if (musb_ep->is_in) {
+ csr = musb_readw(epio, MUSB_TXCSR);
+ if (csr & MUSB_TXCSR_FIFONOTEMPTY) {
+ csr |= MUSB_TXCSR_FLUSHFIFO | MUSB_TXCSR_P_WZC_BITS;
+ /*
+ * Setting both TXPKTRDY and FLUSHFIFO makes controller
+ * to interrupt current FIFO loading, but not flushing
+ * the already loaded ones.
+ */
+ csr &= ~MUSB_TXCSR_TXPKTRDY;
+ musb_writew(epio, MUSB_TXCSR, csr);
+ /* REVISIT may be inappropriate w/o FIFONOTEMPTY ... */
+ musb_writew(epio, MUSB_TXCSR, csr);
+ }
+ } else {
+ csr = musb_readw(epio, MUSB_RXCSR);
+ csr |= MUSB_RXCSR_FLUSHFIFO | MUSB_RXCSR_P_WZC_BITS;
+ musb_writew(epio, MUSB_RXCSR, csr);
+ musb_writew(epio, MUSB_RXCSR, csr);
+ }
+
+ /* re-enable interrupt */
+ musb_writew(mbase, MUSB_INTRTXE, musb->intrtxe);
+ spin_unlock_irqrestore(&musb->lock, flags);
+}
+
+static const struct usb_ep_ops musb_ep_ops = {
+ .enable = musb_gadget_enable,
+ .disable = musb_gadget_disable,
+ .alloc_request = musb_alloc_request,
+ .free_request = musb_free_request,
+ .queue = musb_gadget_queue,
+ .dequeue = musb_gadget_dequeue,
+ .set_halt = musb_gadget_set_halt,
+ .set_wedge = musb_gadget_set_wedge,
+ .fifo_status = musb_gadget_fifo_status,
+ .fifo_flush = musb_gadget_fifo_flush
+};
+
+/* ----------------------------------------------------------------------- */
+
+static int musb_gadget_get_frame(struct usb_gadget *gadget)
+{
+ struct musb *musb = gadget_to_musb(gadget);
+
+ return (int)musb_readw(musb->mregs, MUSB_FRAME);
+}
+
+static int
+musb_gadget_set_self_powered(struct usb_gadget *gadget, int is_selfpowered)
+{
+ struct musb *musb = gadget_to_musb(gadget);
+
+ musb->is_self_powered = !!is_selfpowered;
+ return 0;
+}
+
+static void musb_pullup(struct musb *musb, int is_on)
+{
+ u8 power;
+
+ power = musb_readb(musb->mregs, MUSB_POWER);
+ if (is_on)
+ power |= MUSB_POWER_SOFTCONN;
+ else
+ power &= ~MUSB_POWER_SOFTCONN;
+
+ /* FIXME if on, HdrcStart; if off, HdrcStop */
+
+ dev_dbg(musb->controller, "gadget D+ pullup %s\n",
+ is_on ? "on" : "off");
+ musb_writeb(musb->mregs, MUSB_POWER, power);
+}
+
+static int musb_gadget_vbus_draw(struct usb_gadget *gadget, unsigned mA)
+{
+ struct musb *musb = gadget_to_musb(gadget);
+
+ if (!musb->xceiv->set_power)
+ return -EOPNOTSUPP;
+ return usb_phy_set_power(musb->xceiv, mA);
+}
+
+static int musb_gadget_pullup(struct usb_gadget *gadget, int is_on)
+{
+ struct musb *musb = gadget_to_musb(gadget);
+ unsigned long flags;
+
+ is_on = !!is_on;
+
+ /* NOTE: this assumes we are sensing vbus; we'd rather
+ * not pullup unless the B-session is active.
+ */
+ spin_lock_irqsave(&musb->lock, flags);
+ if (is_on != musb->softconnect) {
+ musb->softconnect = is_on;
+ musb_pullup(musb, is_on);
+ }
+ spin_unlock_irqrestore(&musb->lock, flags);
+
+ return 0;
+}
+
+static void musb_gadget_poll(struct usb_gadget *gadget)
+{
+ struct musb *musb = gadget_to_musb(gadget);
+
+ musb->isr(musb);
+}
+
+static int musb_gadget_start(struct usb_gadget *g,
+ struct usb_gadget_driver *driver);
+static int musb_gadget_stop(struct usb_gadget *g,
+ struct usb_gadget_driver *driver);
+
+static const struct usb_gadget_ops musb_gadget_operations = {
+ .get_frame = musb_gadget_get_frame,
+ .set_selfpowered = musb_gadget_set_self_powered,
+ /* .vbus_session = musb_gadget_vbus_session, */
+ .vbus_draw = musb_gadget_vbus_draw,
+ .pullup = musb_gadget_pullup,
+ .udc_start = musb_gadget_start,
+ .udc_stop = musb_gadget_stop,
+ .udc_poll = musb_gadget_poll,
+};
+
+/* ----------------------------------------------------------------------- */
+
+/* Registration */
+
+/* Only this registration code "knows" the rule (from USB standards)
+ * about there being only one external upstream port. It assumes
+ * all peripheral ports are external...
+ */
+
+static void
+init_peripheral_ep(struct musb *musb, struct musb_ep *ep, u8 epnum, int is_in)
+{
+ struct musb_hw_ep *hw_ep = musb->endpoints + epnum;
+
+ memset(ep, 0, sizeof *ep);
+
+ ep->current_epnum = epnum;
+ ep->musb = musb;
+ ep->hw_ep = hw_ep;
+ ep->is_in = is_in;
+
+ INIT_LIST_HEAD(&ep->req_list);
+
+ sprintf(ep->name, "ep%d%s", epnum,
+ (!epnum || hw_ep->is_shared_fifo) ? "" : (
+ is_in ? "in" : "out"));
+ ep->end_point.name = ep->name;
+ INIT_LIST_HEAD(&ep->end_point.ep_list);
+ if (!epnum) {
+ usb_ep_set_maxpacket_limit(&ep->end_point, 64);
+ ep->end_point.ops = &musb_g_ep0_ops;
+ musb->g.ep0 = &ep->end_point;
+ } else {
+ if (is_in)
+ usb_ep_set_maxpacket_limit(&ep->end_point, hw_ep->max_packet_sz_tx);
+ else
+ usb_ep_set_maxpacket_limit(&ep->end_point, hw_ep->max_packet_sz_rx);
+ ep->end_point.ops = &musb_ep_ops;
+ list_add_tail(&ep->end_point.ep_list, &musb->g.ep_list);
+ }
+}
+
+/*
+ * Initialize the endpoints exposed to peripheral drivers, with backlinks
+ * to the rest of the driver state.
+ */
+static inline void musb_g_init_endpoints(struct musb *musb)
+{
+ u8 epnum;
+ struct musb_hw_ep *hw_ep;
+ unsigned count = 0;
+
+ /* initialize endpoint list just once */
+ INIT_LIST_HEAD(&(musb->g.ep_list));
+
+ for (epnum = 0, hw_ep = musb->endpoints;
+ epnum < musb->nr_endpoints;
+ epnum++, hw_ep++) {
+ if (hw_ep->is_shared_fifo /* || !epnum */) {
+ init_peripheral_ep(musb, &hw_ep->ep_in, epnum, 0);
+ count++;
+ } else {
+ if (hw_ep->max_packet_sz_tx) {
+ init_peripheral_ep(musb, &hw_ep->ep_in,
+ epnum, 1);
+ count++;
+ }
+ if (hw_ep->max_packet_sz_rx) {
+ init_peripheral_ep(musb, &hw_ep->ep_out,
+ epnum, 0);
+ count++;
+ }
+ }
+ }
+}
+
+/* called once during driver setup to initialize and link into
+ * the driver model; memory is zeroed.
+ */
+int musb_gadget_setup(struct musb *musb)
+{
+ int status;
+
+ /* REVISIT minor race: if (erroneously) setting up two
+ * musb peripherals at the same time, only the bus lock
+ * is probably held.
+ */
+
+ musb->g.ops = &musb_gadget_operations;
+ musb->g.max_speed = USB_SPEED_HIGH;
+ musb->g.speed = USB_SPEED_UNKNOWN;
+
+ MUSB_DEV_MODE(musb);
+
+ /* this "gadget" abstracts/virtualizes the controller */
+ musb->g.name = musb_driver_name;
+
+ musb->g.is_otg = 0;
+
+ musb_g_init_endpoints(musb);
+
+ musb->is_active = 0;
+ musb_platform_try_idle(musb, 0);
+
+ status = usb_add_gadget_udc(musb->controller, &musb->g);
+ if (status)
+ goto err;
+
+ return 0;
+err:
+ musb->g.dev.parent = NULL;
+ return status;
+}
+
+void musb_gadget_cleanup(struct musb *musb)
+{
+ if (musb->port_mode == MUSB_PORT_MODE_HOST)
+ return;
+ usb_del_gadget_udc(&musb->g);
+}
+
+/*
+ * Register the gadget driver. Used by gadget drivers when
+ * registering themselves with the controller.
+ *
+ * -EINVAL something went wrong (not driver)
+ * -EBUSY another gadget is already using the controller
+ * -ENOMEM no memory to perform the operation
+ *
+ * @param driver the gadget driver
+ * @return <0 if error, 0 if everything is fine
+ */
+static int musb_gadget_start(struct usb_gadget *g,
+ struct usb_gadget_driver *driver)
+{
+ struct musb *musb = gadget_to_musb(g);
+ unsigned long flags;
+ int retval = 0;
+
+ if (driver->max_speed < USB_SPEED_HIGH) {
+ retval = -EINVAL;
+ goto err;
+ }
+
+ dev_dbg(musb->controller, "registering driver %s\n", driver->function);
+
+ musb->softconnect = 0;
+ musb->gadget_driver = driver;
+
+ spin_lock_irqsave(&musb->lock, flags);
+ musb->is_active = 1;
+
+ spin_unlock_irqrestore(&musb->lock, flags);
+
+ musb_start(musb);
+
+ return 0;
+
+err:
+ return retval;
+}
+
+static void stop_activity(struct musb *musb, struct usb_gadget_driver *driver)
+{
+ int i;
+ struct musb_hw_ep *hw_ep;
+
+ /* don't disconnect if it's not connected */
+ if (musb->g.speed == USB_SPEED_UNKNOWN)
+ driver = NULL;
+ else
+ musb->g.speed = USB_SPEED_UNKNOWN;
+
+ /* deactivate the hardware */
+ if (musb->softconnect) {
+ musb->softconnect = 0;
+ musb_pullup(musb, 0);
+ }
+ musb_stop(musb);
+
+ /* killing any outstanding requests will quiesce the driver;
+ * then report disconnect
+ */
+ if (driver) {
+ for (i = 0, hw_ep = musb->endpoints;
+ i < musb->nr_endpoints;
+ i++, hw_ep++) {
+ musb_ep_select(musb->mregs, i);
+ if (hw_ep->is_shared_fifo /* || !epnum */) {
+ nuke(&hw_ep->ep_in, -ESHUTDOWN);
+ } else {
+ if (hw_ep->max_packet_sz_tx)
+ nuke(&hw_ep->ep_in, -ESHUTDOWN);
+ if (hw_ep->max_packet_sz_rx)
+ nuke(&hw_ep->ep_out, -ESHUTDOWN);
+ }
+ }
+ }
+}
+
+/*
+ * Unregister the gadget driver. Used by gadget drivers when
+ * unregistering themselves from the controller.
+ *
+ * @param driver the gadget driver to unregister
+ */
+static int musb_gadget_stop(struct usb_gadget *g,
+ struct usb_gadget_driver *driver)
+{
+ struct musb *musb = gadget_to_musb(g);
+ unsigned long flags;
+
+ /*
+ * REVISIT always use otg_set_peripheral() here too;
+ * this needs to shut down the OTG engine.
+ */
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ (void) musb_gadget_vbus_draw(&musb->g, 0);
+
+ stop_activity(musb, driver);
+
+ dev_dbg(musb->controller, "unregistering driver %s\n",
+ driver ? driver->function : "(removed)");
+
+ musb->is_active = 0;
+ musb->gadget_driver = NULL;
+ musb_platform_try_idle(musb, 0);
+ spin_unlock_irqrestore(&musb->lock, flags);
+
+ /*
+ * FIXME we need to be able to register another
+ * gadget driver here and have everything work;
+ * that currently misbehaves.
+ */
+
+ return 0;
+}
+
+/* ----------------------------------------------------------------------- */
+
+/* lifecycle operations called through plat_uds.c */
+
+/* called when VBUS drops below session threshold, and in other cases */
+void musb_g_disconnect(struct musb *musb)
+{
+ void __iomem *mregs = musb->mregs;
+ u8 devctl = musb_readb(mregs, MUSB_DEVCTL);
+
+ dev_dbg(musb->controller, "devctl %02x\n", devctl);
+
+ /* clear HR */
+ musb_writeb(mregs, MUSB_DEVCTL, devctl & MUSB_DEVCTL_SESSION);
+
+ /* don't draw vbus until new b-default session */
+ (void) musb_gadget_vbus_draw(&musb->g, 0);
+
+ musb->g.speed = USB_SPEED_UNKNOWN;
+ if (musb->gadget_driver && musb->gadget_driver->disconnect) {
+ spin_unlock(&musb->lock);
+ musb->gadget_driver->disconnect(&musb->g);
+ spin_lock(&musb->lock);
+ }
+
+ musb->is_active = 0;
+}
diff --git a/drivers/usb/musb/musb_gadget.h b/drivers/usb/musb/musb_gadget.h
new file mode 100644
index 0000000000..456c165cc7
--- /dev/null
+++ b/drivers/usb/musb/musb_gadget.h
@@ -0,0 +1,147 @@
+/*
+ * MUSB OTG driver peripheral defines
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#ifndef __MUSB_GADGET_H
+#define __MUSB_GADGET_H
+
+#include <linux/list.h>
+#include <usb/gadget.h>
+
+#if IS_ENABLED(CONFIG_USB_MUSB_GADGET)
+extern int musb_g_ep0_irq(struct musb *);
+extern void musb_g_tx(struct musb *, u8);
+extern void musb_g_rx(struct musb *, u8);
+extern void musb_g_reset(struct musb *);
+extern void musb_g_suspend(struct musb *);
+extern void musb_g_resume(struct musb *);
+extern void musb_g_wakeup(struct musb *);
+extern void musb_g_disconnect(struct musb *);
+extern void musb_gadget_cleanup(struct musb *);
+extern int musb_gadget_setup(struct musb *);
+
+#else
+static inline int musb_g_ep0_irq(struct musb *musb)
+{
+ return 0;
+}
+
+static inline void musb_g_tx(struct musb *musb, u8 epnum) {}
+static inline void musb_g_rx(struct musb *musb, u8 epnum) {}
+static inline void musb_g_reset(struct musb *musb) {}
+static inline void musb_g_suspend(struct musb *musb) {}
+static inline void musb_g_resume(struct musb *musb) {}
+static inline void musb_g_wakeup(struct musb *musb) {}
+static inline void musb_g_disconnect(struct musb *musb) {}
+static inline void musb_gadget_cleanup(struct musb *musb) {}
+static inline int musb_gadget_setup(struct musb *musb)
+{
+ return 0;
+}
+#endif
+
+enum buffer_map_state {
+ UN_MAPPED = 0,
+ PRE_MAPPED,
+ MUSB_MAPPED
+};
+
+struct musb_request {
+ struct usb_request request;
+ struct list_head list;
+ struct musb_ep *ep;
+ struct musb *musb;
+ u8 tx; /* endpoint direction */
+ u8 epnum;
+ enum buffer_map_state map_state;
+};
+
+static inline struct musb_request *to_musb_request(struct usb_request *req)
+{
+ return req ? container_of(req, struct musb_request, request) : NULL;
+}
+
+extern struct usb_request *musb_alloc_request(struct usb_ep *ep);
+extern void musb_free_request(struct usb_ep *ep, struct usb_request *req);
+
+
+/*
+ * struct musb_ep - peripheral side view of endpoint rx or tx side
+ */
+struct musb_ep {
+ /* stuff towards the head is basically write-once. */
+ struct usb_ep end_point;
+ char name[12];
+ struct musb_hw_ep *hw_ep;
+ struct musb *musb;
+ u8 current_epnum;
+
+ /* ... when enabled/disabled ... */
+ u8 type;
+ u8 is_in;
+ u16 packet_sz;
+ const struct usb_endpoint_descriptor *desc;
+ struct dma_channel *dma;
+
+ /* later things are modified based on usage */
+ struct list_head req_list;
+
+ u8 wedged;
+
+ /* true if lock must be dropped but req_list may not be advanced */
+ u8 busy;
+
+ u8 hb_mult;
+};
+
+static inline struct musb_ep *to_musb_ep(struct usb_ep *ep)
+{
+ return ep ? container_of(ep, struct musb_ep, end_point) : NULL;
+}
+
+static inline struct musb_request *next_request(struct musb_ep *ep)
+{
+ struct list_head *queue = &ep->req_list;
+
+ if (list_empty(queue))
+ return NULL;
+ return container_of(queue->next, struct musb_request, list);
+}
+
+extern const struct usb_ep_ops musb_g_ep0_ops;
+
+extern void musb_g_giveback(struct musb_ep *, struct usb_request *, int);
+
+extern void musb_ep_restart(struct musb *, struct musb_request *);
+
+#endif /* __MUSB_GADGET_H */
diff --git a/drivers/usb/musb/musb_gadget_ep0.c b/drivers/usb/musb/musb_gadget_ep0.c
new file mode 100644
index 0000000000..feaa856451
--- /dev/null
+++ b/drivers/usb/musb/musb_gadget_ep0.c
@@ -0,0 +1,1079 @@
+/*
+ * MUSB OTG peripheral driver ep0 handling
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ * Copyright (C) 2008-2009 MontaVista Software, Inc. <source@mvista.com>
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#include <common.h>
+#include <malloc.h>
+#include <clock.h>
+#include "musb_core.h"
+#include "musb_gadget.h"
+
+/* ep0 is always musb->endpoints[0].ep_in */
+#define next_ep0_request(musb) next_in_request(&(musb)->endpoints[0])
+
+/*
+ * locking note: we use only the controller lock, for simpler correctness.
+ * It's always held with IRQs blocked.
+ *
+ * It protects the ep0 request queue as well as ep0_state, not just the
+ * controller and indexed registers. And that lock stays held unless it
+ * needs to be dropped to allow reentering this driver ... like upcalls to
+ * the gadget driver, or adjusting endpoint halt status.
+ */
+
+static char *decode_ep0stage(u8 stage)
+{
+ switch (stage) {
+ case MUSB_EP0_STAGE_IDLE: return "idle";
+ case MUSB_EP0_STAGE_SETUP: return "setup";
+ case MUSB_EP0_STAGE_TX: return "in";
+ case MUSB_EP0_STAGE_RX: return "out";
+ case MUSB_EP0_STAGE_ACKWAIT: return "wait";
+ case MUSB_EP0_STAGE_STATUSIN: return "in/status";
+ case MUSB_EP0_STAGE_STATUSOUT: return "out/status";
+ default: return "?";
+ }
+}
+
+/* handle a standard GET_STATUS request
+ * Context: caller holds controller lock
+ */
+static int service_tx_status_request(
+ struct musb *musb,
+ const struct usb_ctrlrequest *ctrlrequest)
+{
+ void __iomem *mbase = musb->mregs;
+ int handled = 1;
+ u8 result[2], epnum = 0;
+ const u8 recip = ctrlrequest->bRequestType & USB_RECIP_MASK;
+
+ result[1] = 0;
+
+ switch (recip) {
+ case USB_RECIP_DEVICE:
+ result[0] = musb->is_self_powered << USB_DEVICE_SELF_POWERED;
+ result[0] |= musb->may_wakeup << USB_DEVICE_REMOTE_WAKEUP;
+ if (musb->g.is_otg) {
+ result[0] |= musb->g.b_hnp_enable
+ << USB_DEVICE_B_HNP_ENABLE;
+ result[0] |= musb->g.a_alt_hnp_support
+ << USB_DEVICE_A_ALT_HNP_SUPPORT;
+ result[0] |= musb->g.a_hnp_support
+ << USB_DEVICE_A_HNP_SUPPORT;
+ }
+ break;
+
+ case USB_RECIP_INTERFACE:
+ result[0] = 0;
+ break;
+
+ case USB_RECIP_ENDPOINT: {
+ int is_in;
+ struct musb_ep *ep;
+ u16 tmp;
+ void __iomem *regs;
+
+ epnum = (u8) ctrlrequest->wIndex;
+ if (!epnum) {
+ result[0] = 0;
+ break;
+ }
+
+ is_in = epnum & USB_DIR_IN;
+ if (is_in) {
+ epnum &= 0x0f;
+ ep = &musb->endpoints[epnum].ep_in;
+ } else {
+ ep = &musb->endpoints[epnum].ep_out;
+ }
+ regs = musb->endpoints[epnum].regs;
+
+ if (epnum >= MUSB_C_NUM_EPS || !ep->desc) {
+ handled = -EINVAL;
+ break;
+ }
+
+ musb_ep_select(mbase, epnum);
+ if (is_in)
+ tmp = musb_readw(regs, MUSB_TXCSR)
+ & MUSB_TXCSR_P_SENDSTALL;
+ else
+ tmp = musb_readw(regs, MUSB_RXCSR)
+ & MUSB_RXCSR_P_SENDSTALL;
+ musb_ep_select(mbase, 0);
+
+ result[0] = tmp ? 1 : 0;
+ } break;
+
+ default:
+ /* class, vendor, etc ... delegate */
+ handled = 0;
+ break;
+ }
+
+ /* fill up the fifo; caller updates csr0 */
+ if (handled > 0) {
+ u16 len = le16_to_cpu(ctrlrequest->wLength);
+
+ if (len > 2)
+ len = 2;
+ musb_write_fifo(&musb->endpoints[0], len, result);
+ }
+
+ return handled;
+}
+
+/*
+ * handle a control-IN request, the end0 buffer contains the current request
+ * that is supposed to be a standard control request. Assumes the fifo to
+ * be at least 2 bytes long.
+ *
+ * @return 0 if the request was NOT HANDLED,
+ * < 0 when error
+ * > 0 when the request is processed
+ *
+ * Context: caller holds controller lock
+ */
+static int
+service_in_request(struct musb *musb, const struct usb_ctrlrequest *ctrlrequest)
+{
+ int handled = 0; /* not handled */
+
+ if ((ctrlrequest->bRequestType & USB_TYPE_MASK)
+ == USB_TYPE_STANDARD) {
+ switch (ctrlrequest->bRequest) {
+ case USB_REQ_GET_STATUS:
+ handled = service_tx_status_request(musb,
+ ctrlrequest);
+ break;
+
+ /* case USB_REQ_SYNC_FRAME: */
+
+ default:
+ break;
+ }
+ }
+ return handled;
+}
+
+/*
+ * Context: caller holds controller lock
+ */
+static void musb_g_ep0_giveback(struct musb *musb, struct usb_request *req)
+{
+ musb_g_giveback(&musb->endpoints[0].ep_in, req, 0);
+}
+
+/*
+ * Tries to start B-device HNP negotiation if enabled via sysfs
+ */
+static inline void musb_try_b_hnp_enable(struct musb *musb)
+{
+ void __iomem *mbase = musb->mregs;
+ u8 devctl;
+
+ dev_dbg(musb->controller, "HNP: Setting HR\n");
+ devctl = musb_readb(mbase, MUSB_DEVCTL);
+ musb_writeb(mbase, MUSB_DEVCTL, devctl | MUSB_DEVCTL_HR);
+}
+
+/*
+ * Handle all control requests with no DATA stage, including standard
+ * requests such as:
+ * USB_REQ_SET_CONFIGURATION, USB_REQ_SET_INTERFACE, unrecognized
+ * always delegated to the gadget driver
+ * USB_REQ_SET_ADDRESS, USB_REQ_CLEAR_FEATURE, USB_REQ_SET_FEATURE
+ * always handled here, except for class/vendor/... features
+ *
+ * Context: caller holds controller lock
+ */
+static int
+service_zero_data_request(struct musb *musb,
+ struct usb_ctrlrequest *ctrlrequest)
+__releases(musb->lock)
+__acquires(musb->lock)
+{
+ int handled = -EINVAL;
+ void __iomem *mbase = musb->mregs;
+ const u8 recip = ctrlrequest->bRequestType & USB_RECIP_MASK;
+
+ /* the gadget driver handles everything except what we MUST handle */
+ if ((ctrlrequest->bRequestType & USB_TYPE_MASK)
+ == USB_TYPE_STANDARD) {
+ switch (ctrlrequest->bRequest) {
+ case USB_REQ_SET_ADDRESS:
+ /* change it after the status stage */
+ musb->set_address = true;
+ musb->address = (u8) (ctrlrequest->wValue & 0x7f);
+ handled = 1;
+ break;
+
+ case USB_REQ_CLEAR_FEATURE:
+ switch (recip) {
+ case USB_RECIP_DEVICE:
+ if (ctrlrequest->wValue
+ != USB_DEVICE_REMOTE_WAKEUP)
+ break;
+ musb->may_wakeup = 0;
+ handled = 1;
+ break;
+ case USB_RECIP_INTERFACE:
+ break;
+ case USB_RECIP_ENDPOINT:{
+ const u8 epnum =
+ ctrlrequest->wIndex & 0x0f;
+ struct musb_ep *musb_ep;
+ struct musb_hw_ep *ep;
+ struct musb_request *request;
+ void __iomem *regs;
+ int is_in;
+ u16 csr;
+
+ if (epnum == 0 || epnum >= MUSB_C_NUM_EPS ||
+ ctrlrequest->wValue != USB_ENDPOINT_HALT)
+ break;
+
+ ep = musb->endpoints + epnum;
+ regs = ep->regs;
+ is_in = ctrlrequest->wIndex & USB_DIR_IN;
+ if (is_in)
+ musb_ep = &ep->ep_in;
+ else
+ musb_ep = &ep->ep_out;
+ if (!musb_ep->desc)
+ break;
+
+ handled = 1;
+ /* Ignore request if endpoint is wedged */
+ if (musb_ep->wedged)
+ break;
+
+ musb_ep_select(mbase, epnum);
+ if (is_in) {
+ csr = musb_readw(regs, MUSB_TXCSR);
+ csr |= MUSB_TXCSR_CLRDATATOG |
+ MUSB_TXCSR_P_WZC_BITS;
+ csr &= ~(MUSB_TXCSR_P_SENDSTALL |
+ MUSB_TXCSR_P_SENTSTALL |
+ MUSB_TXCSR_TXPKTRDY);
+ musb_writew(regs, MUSB_TXCSR, csr);
+ } else {
+ csr = musb_readw(regs, MUSB_RXCSR);
+ csr |= MUSB_RXCSR_CLRDATATOG |
+ MUSB_RXCSR_P_WZC_BITS;
+ csr &= ~(MUSB_RXCSR_P_SENDSTALL |
+ MUSB_RXCSR_P_SENTSTALL);
+ musb_writew(regs, MUSB_RXCSR, csr);
+ }
+
+ /* Maybe start the first request in the queue */
+ request = next_request(musb_ep);
+ if (!musb_ep->busy && request) {
+ dev_dbg(musb->controller, "restarting the request\n");
+ musb_ep_restart(musb, request);
+ }
+
+ /* select ep0 again */
+ musb_ep_select(mbase, 0);
+ } break;
+ default:
+ /* class, vendor, etc ... delegate */
+ handled = 0;
+ break;
+ }
+ break;
+
+ case USB_REQ_SET_FEATURE:
+ switch (recip) {
+ case USB_RECIP_DEVICE:
+ handled = 1;
+ switch (ctrlrequest->wValue) {
+ case USB_DEVICE_REMOTE_WAKEUP:
+ musb->may_wakeup = 1;
+ break;
+ case USB_DEVICE_TEST_MODE:
+ if (musb->g.speed != USB_SPEED_HIGH)
+ goto stall;
+ if (ctrlrequest->wIndex & 0xff)
+ goto stall;
+
+ switch (ctrlrequest->wIndex >> 8) {
+ case 1:
+ pr_debug("TEST_J\n");
+ /* TEST_J */
+ musb->test_mode_nr =
+ MUSB_TEST_J;
+ break;
+ case 2:
+ /* TEST_K */
+ pr_debug("TEST_K\n");
+ musb->test_mode_nr =
+ MUSB_TEST_K;
+ break;
+ case 3:
+ /* TEST_SE0_NAK */
+ pr_debug("TEST_SE0_NAK\n");
+ musb->test_mode_nr =
+ MUSB_TEST_SE0_NAK;
+ break;
+ case 4:
+ /* TEST_PACKET */
+ pr_debug("TEST_PACKET\n");
+ musb->test_mode_nr =
+ MUSB_TEST_PACKET;
+ break;
+
+ case 0xc0:
+ /* TEST_FORCE_HS */
+ pr_debug("TEST_FORCE_HS\n");
+ musb->test_mode_nr =
+ MUSB_TEST_FORCE_HS;
+ break;
+ case 0xc1:
+ /* TEST_FORCE_FS */
+ pr_debug("TEST_FORCE_FS\n");
+ musb->test_mode_nr =
+ MUSB_TEST_FORCE_FS;
+ break;
+ case 0xc2:
+ /* TEST_FIFO_ACCESS */
+ pr_debug("TEST_FIFO_ACCESS\n");
+ musb->test_mode_nr =
+ MUSB_TEST_FIFO_ACCESS;
+ break;
+ case 0xc3:
+ /* TEST_FORCE_HOST */
+ pr_debug("TEST_FORCE_HOST\n");
+ musb->test_mode_nr =
+ MUSB_TEST_FORCE_HOST;
+ break;
+ default:
+ goto stall;
+ }
+
+ /* enter test mode after irq */
+ if (handled > 0)
+ musb->test_mode = true;
+ break;
+ case USB_DEVICE_B_HNP_ENABLE:
+ if (!musb->g.is_otg)
+ goto stall;
+ musb->g.b_hnp_enable = 1;
+ musb_try_b_hnp_enable(musb);
+ break;
+ case USB_DEVICE_A_HNP_SUPPORT:
+ if (!musb->g.is_otg)
+ goto stall;
+ musb->g.a_hnp_support = 1;
+ break;
+ case USB_DEVICE_A_ALT_HNP_SUPPORT:
+ if (!musb->g.is_otg)
+ goto stall;
+ musb->g.a_alt_hnp_support = 1;
+ break;
+ case USB_DEVICE_DEBUG_MODE:
+ handled = 0;
+ break;
+stall:
+ default:
+ handled = -EINVAL;
+ break;
+ }
+ break;
+
+ case USB_RECIP_INTERFACE:
+ break;
+
+ case USB_RECIP_ENDPOINT:{
+ const u8 epnum =
+ ctrlrequest->wIndex & 0x0f;
+ struct musb_ep *musb_ep;
+ struct musb_hw_ep *ep;
+ void __iomem *regs;
+ int is_in;
+ u16 csr;
+
+ if (epnum == 0 || epnum >= MUSB_C_NUM_EPS ||
+ ctrlrequest->wValue != USB_ENDPOINT_HALT)
+ break;
+
+ ep = musb->endpoints + epnum;
+ regs = ep->regs;
+ is_in = ctrlrequest->wIndex & USB_DIR_IN;
+ if (is_in)
+ musb_ep = &ep->ep_in;
+ else
+ musb_ep = &ep->ep_out;
+ if (!musb_ep->desc)
+ break;
+
+ musb_ep_select(mbase, epnum);
+ if (is_in) {
+ csr = musb_readw(regs, MUSB_TXCSR);
+ if (csr & MUSB_TXCSR_FIFONOTEMPTY)
+ csr |= MUSB_TXCSR_FLUSHFIFO;
+ csr |= MUSB_TXCSR_P_SENDSTALL
+ | MUSB_TXCSR_CLRDATATOG
+ | MUSB_TXCSR_P_WZC_BITS;
+ musb_writew(regs, MUSB_TXCSR, csr);
+ } else {
+ csr = musb_readw(regs, MUSB_RXCSR);
+ csr |= MUSB_RXCSR_P_SENDSTALL
+ | MUSB_RXCSR_FLUSHFIFO
+ | MUSB_RXCSR_CLRDATATOG
+ | MUSB_RXCSR_P_WZC_BITS;
+ musb_writew(regs, MUSB_RXCSR, csr);
+ }
+
+ /* select ep0 again */
+ musb_ep_select(mbase, 0);
+ handled = 1;
+ } break;
+
+ default:
+ /* class, vendor, etc ... delegate */
+ handled = 0;
+ break;
+ }
+ break;
+ default:
+ /* delegate SET_CONFIGURATION, etc */
+ handled = 0;
+ }
+ } else
+ handled = 0;
+ return handled;
+}
+
+/* we have an ep0out data packet
+ * Context: caller holds controller lock
+ */
+static void ep0_rxstate(struct musb *musb)
+{
+ void __iomem *regs = musb->control_ep->regs;
+ struct musb_request *request;
+ struct usb_request *req;
+ u16 count, csr;
+
+ request = next_ep0_request(musb);
+ req = &request->request;
+
+ /* read packet and ack; or stall because of gadget driver bug:
+ * should have provided the rx buffer before setup() returned.
+ */
+ if (req) {
+ void *buf = req->buf + req->actual;
+ unsigned len = req->length - req->actual;
+
+ /* read the buffer */
+ count = musb_readb(regs, MUSB_COUNT0);
+ if (count > len) {
+ req->status = -EOVERFLOW;
+ count = len;
+ }
+ if (count > 0) {
+ musb_read_fifo(&musb->endpoints[0], count, buf);
+ req->actual += count;
+ }
+ csr = MUSB_CSR0_P_SVDRXPKTRDY;
+ if (count < 64 || req->actual == req->length) {
+ musb->ep0_state = MUSB_EP0_STAGE_STATUSIN;
+ csr |= MUSB_CSR0_P_DATAEND;
+ } else
+ req = NULL;
+ } else
+ csr = MUSB_CSR0_P_SVDRXPKTRDY | MUSB_CSR0_P_SENDSTALL;
+
+
+ /* Completion handler may choose to stall, e.g. because the
+ * message just received holds invalid data.
+ */
+ if (req) {
+ musb->ackpend = csr;
+ musb_g_ep0_giveback(musb, req);
+ if (!musb->ackpend)
+ return;
+ musb->ackpend = 0;
+ }
+ musb_ep_select(musb->mregs, 0);
+ musb_writew(regs, MUSB_CSR0, csr);
+}
+
+/*
+ * transmitting to the host (IN), this code might be called from IRQ
+ * and from kernel thread.
+ *
+ * Context: caller holds controller lock
+ */
+static void ep0_txstate(struct musb *musb)
+{
+ void __iomem *regs = musb->control_ep->regs;
+ struct musb_request *req = next_ep0_request(musb);
+ struct usb_request *request;
+ u16 csr = MUSB_CSR0_TXPKTRDY;
+ u8 *fifo_src;
+ u8 fifo_count;
+
+ if (!req) {
+ /* WARN_ON(1); */
+ dev_dbg(musb->controller, "odd; csr0 %04x\n", musb_readw(regs, MUSB_CSR0));
+ return;
+ }
+
+ request = &req->request;
+
+ /* load the data */
+ fifo_src = (u8 *) request->buf + request->actual;
+ fifo_count = min((unsigned) MUSB_EP0_FIFOSIZE,
+ request->length - request->actual);
+ musb_write_fifo(&musb->endpoints[0], fifo_count, fifo_src);
+ request->actual += fifo_count;
+
+ /* update the flags */
+ if (fifo_count < MUSB_MAX_END0_PACKET
+ || (request->actual == request->length
+ && !request->zero)) {
+ musb->ep0_state = MUSB_EP0_STAGE_STATUSOUT;
+ csr |= MUSB_CSR0_P_DATAEND;
+ } else
+ request = NULL;
+
+ /* report completions as soon as the fifo's loaded; there's no
+ * win in waiting till this last packet gets acked. (other than
+ * very precise fault reporting, needed by USB TMC; possible with
+ * this hardware, but not usable from portable gadget drivers.)
+ */
+ if (request) {
+ musb->ackpend = csr;
+ musb_g_ep0_giveback(musb, request);
+ if (!musb->ackpend)
+ return;
+ musb->ackpend = 0;
+ }
+
+ /* send it out, triggering a "txpktrdy cleared" irq */
+ musb_ep_select(musb->mregs, 0);
+ musb_writew(regs, MUSB_CSR0, csr);
+}
+
+/*
+ * Read a SETUP packet (struct usb_ctrlrequest) from the hardware.
+ * Fields are left in USB byte-order.
+ *
+ * Context: caller holds controller lock.
+ */
+static void
+musb_read_setup(struct musb *musb, struct usb_ctrlrequest *req)
+{
+ struct musb_request *r;
+ void __iomem *regs = musb->control_ep->regs;
+
+ musb_read_fifo(&musb->endpoints[0], sizeof *req, (u8 *)req);
+
+ /* NOTE: earlier 2.6 versions changed setup packets to host
+ * order, but now USB packets always stay in USB byte order.
+ */
+ dev_dbg(musb->controller, "SETUP req%02x.%02x v%04x i%04x l%d\n",
+ req->bRequestType,
+ req->bRequest,
+ le16_to_cpu(req->wValue),
+ le16_to_cpu(req->wIndex),
+ le16_to_cpu(req->wLength));
+
+ /* clean up any leftover transfers */
+ r = next_ep0_request(musb);
+ if (r)
+ musb_g_ep0_giveback(musb, &r->request);
+
+ /* For zero-data requests we want to delay the STATUS stage to
+ * avoid SETUPEND errors. If we read data (OUT), delay accepting
+ * packets until there's a buffer to store them in.
+ *
+ * If we write data, the controller acts happier if we enable
+ * the TX FIFO right away, and give the controller a moment
+ * to switch modes...
+ */
+ musb->set_address = false;
+ musb->ackpend = MUSB_CSR0_P_SVDRXPKTRDY;
+ if (req->wLength == 0) {
+ if (req->bRequestType & USB_DIR_IN)
+ musb->ackpend |= MUSB_CSR0_TXPKTRDY;
+ musb->ep0_state = MUSB_EP0_STAGE_ACKWAIT;
+ } else if (req->bRequestType & USB_DIR_IN) {
+ musb->ep0_state = MUSB_EP0_STAGE_TX;
+ musb_writew(regs, MUSB_CSR0, MUSB_CSR0_P_SVDRXPKTRDY);
+ while ((musb_readw(regs, MUSB_CSR0)
+ & MUSB_CSR0_RXPKTRDY) != 0)
+ musb->ackpend = 0;
+ } else
+ musb->ep0_state = MUSB_EP0_STAGE_RX;
+}
+
+static int
+forward_to_driver(struct musb *musb, const struct usb_ctrlrequest *ctrlrequest)
+__releases(musb->lock)
+__acquires(musb->lock)
+{
+ int retval;
+ if (!musb->gadget_driver)
+ return -EOPNOTSUPP;
+ spin_unlock(&musb->lock);
+ retval = musb->gadget_driver->setup(&musb->g, ctrlrequest);
+ spin_lock(&musb->lock);
+ return retval;
+}
+
+/*
+ * Handle peripheral ep0 interrupt
+ *
+ * Context: irq handler; we won't re-enter the driver that way.
+ */
+irqreturn_t musb_g_ep0_irq(struct musb *musb)
+{
+ u16 csr;
+ u16 len;
+ void __iomem *mbase = musb->mregs;
+ void __iomem *regs = musb->endpoints[0].regs;
+ irqreturn_t retval = IRQ_NONE;
+
+ musb_ep_select(mbase, 0); /* select ep0 */
+ csr = musb_readw(regs, MUSB_CSR0);
+ len = musb_readb(regs, MUSB_COUNT0);
+
+ dev_dbg(musb->controller, "csr %04x, count %d, ep0stage %s\n",
+ csr, len, decode_ep0stage(musb->ep0_state));
+
+ if (csr & MUSB_CSR0_P_DATAEND) {
+ /*
+ * If DATAEND is set we should not call the callback,
+ * hence the status stage is not complete.
+ */
+ return IRQ_HANDLED;
+ }
+
+ /* I sent a stall.. need to acknowledge it now.. */
+ if (csr & MUSB_CSR0_P_SENTSTALL) {
+ musb_writew(regs, MUSB_CSR0,
+ csr & ~MUSB_CSR0_P_SENTSTALL);
+ retval = IRQ_HANDLED;
+ musb->ep0_state = MUSB_EP0_STAGE_IDLE;
+ csr = musb_readw(regs, MUSB_CSR0);
+ }
+
+ /* request ended "early" */
+ if (csr & MUSB_CSR0_P_SETUPEND) {
+ musb_writew(regs, MUSB_CSR0, MUSB_CSR0_P_SVDSETUPEND);
+ retval = IRQ_HANDLED;
+ /* Transition into the early status phase */
+ switch (musb->ep0_state) {
+ case MUSB_EP0_STAGE_TX:
+ musb->ep0_state = MUSB_EP0_STAGE_STATUSOUT;
+ break;
+ case MUSB_EP0_STAGE_RX:
+ musb->ep0_state = MUSB_EP0_STAGE_STATUSIN;
+ break;
+ default:
+ dev_err(musb->controller, "SetupEnd came in a wrong ep0stage %s\n",
+ decode_ep0stage(musb->ep0_state));
+ }
+ csr = musb_readw(regs, MUSB_CSR0);
+ /* NOTE: request may need completion */
+ }
+
+ /* docs from Mentor only describe tx, rx, and idle/setup states.
+ * we need to handle nuances around status stages, and also the
+ * case where status and setup stages come back-to-back ...
+ */
+ switch (musb->ep0_state) {
+
+ case MUSB_EP0_STAGE_TX:
+ /* irq on clearing txpktrdy */
+ if ((csr & MUSB_CSR0_TXPKTRDY) == 0) {
+ ep0_txstate(musb);
+ retval = IRQ_HANDLED;
+ }
+ break;
+
+ case MUSB_EP0_STAGE_RX:
+ /* irq on set rxpktrdy */
+ if (csr & MUSB_CSR0_RXPKTRDY) {
+ ep0_rxstate(musb);
+ retval = IRQ_HANDLED;
+ }
+ break;
+
+ case MUSB_EP0_STAGE_STATUSIN:
+ /* end of sequence #2 (OUT/RX state) or #3 (no data) */
+
+ /* update address (if needed) only @ the end of the
+ * status phase per usb spec, which also guarantees
+ * we get 10 msec to receive this irq... until this
+ * is done we won't see the next packet.
+ */
+ if (musb->set_address) {
+ musb->set_address = false;
+ musb_writeb(mbase, MUSB_FADDR, musb->address);
+ }
+
+ /* enter test mode if needed (exit by reset) */
+ else if (musb->test_mode) {
+ dev_dbg(musb->controller, "entering TESTMODE\n");
+
+ if (MUSB_TEST_PACKET == musb->test_mode_nr)
+ musb_load_testpacket(musb);
+
+ musb_writeb(mbase, MUSB_TESTMODE,
+ musb->test_mode_nr);
+ }
+ /* FALLTHROUGH */
+
+ case MUSB_EP0_STAGE_STATUSOUT:
+ /* end of sequence #1: write to host (TX state) */
+ {
+ struct musb_request *req;
+
+ req = next_ep0_request(musb);
+ if (req)
+ musb_g_ep0_giveback(musb, &req->request);
+ }
+
+ /*
+ * In case when several interrupts can get coalesced,
+ * check to see if we've already received a SETUP packet...
+ */
+ if (csr & MUSB_CSR0_RXPKTRDY)
+ goto setup;
+
+ retval = IRQ_HANDLED;
+ musb->ep0_state = MUSB_EP0_STAGE_IDLE;
+ break;
+
+ case MUSB_EP0_STAGE_IDLE:
+ /*
+ * This state is typically (but not always) indiscernible
+ * from the status states since the corresponding interrupts
+ * tend to happen within too little period of time (with only
+ * a zero-length packet in between) and so get coalesced...
+ */
+ retval = IRQ_HANDLED;
+ musb->ep0_state = MUSB_EP0_STAGE_SETUP;
+ /* FALLTHROUGH */
+
+ case MUSB_EP0_STAGE_SETUP:
+setup:
+ if (csr & MUSB_CSR0_RXPKTRDY) {
+ struct usb_ctrlrequest setup;
+ int handled = 0;
+
+ if (len != 8) {
+ dev_err(musb->controller, "SETUP packet len %d != 8 ?\n", len);
+ break;
+ }
+ musb_read_setup(musb, &setup);
+ retval = IRQ_HANDLED;
+
+ /* sometimes the RESET won't be reported */
+ if (unlikely(musb->g.speed == USB_SPEED_UNKNOWN)) {
+ u8 power;
+
+ printk(KERN_NOTICE "%s: peripheral reset "
+ "irq lost!\n",
+ musb_driver_name);
+ power = musb_readb(mbase, MUSB_POWER);
+ musb->g.speed = (power & MUSB_POWER_HSMODE)
+ ? USB_SPEED_HIGH : USB_SPEED_FULL;
+
+ }
+
+ switch (musb->ep0_state) {
+
+ /* sequence #3 (no data stage), includes requests
+ * we can't forward (notably SET_ADDRESS and the
+ * device/endpoint feature set/clear operations)
+ * plus SET_CONFIGURATION and others we must
+ */
+ case MUSB_EP0_STAGE_ACKWAIT:
+ handled = service_zero_data_request(
+ musb, &setup);
+
+ /*
+ * We're expecting no data in any case, so
+ * always set the DATAEND bit -- doing this
+ * here helps avoid SetupEnd interrupt coming
+ * in the idle stage when we're stalling...
+ */
+ musb->ackpend |= MUSB_CSR0_P_DATAEND;
+
+ /* status stage might be immediate */
+ if (handled > 0)
+ musb->ep0_state =
+ MUSB_EP0_STAGE_STATUSIN;
+ break;
+
+ /* sequence #1 (IN to host), includes GET_STATUS
+ * requests that we can't forward, GET_DESCRIPTOR
+ * and others that we must
+ */
+ case MUSB_EP0_STAGE_TX:
+ handled = service_in_request(musb, &setup);
+ if (handled > 0) {
+ musb->ackpend = MUSB_CSR0_TXPKTRDY
+ | MUSB_CSR0_P_DATAEND;
+ musb->ep0_state =
+ MUSB_EP0_STAGE_STATUSOUT;
+ }
+ break;
+
+ /* sequence #2 (OUT from host), always forward */
+ default: /* MUSB_EP0_STAGE_RX */
+ break;
+ }
+
+ dev_dbg(musb->controller, "handled %d, csr %04x, ep0stage %s\n",
+ handled, csr,
+ decode_ep0stage(musb->ep0_state));
+
+ /* unless we need to delegate this to the gadget
+ * driver, we know how to wrap this up: csr0 has
+ * not yet been written.
+ */
+ if (handled < 0)
+ goto stall;
+ else if (handled > 0)
+ goto finish;
+
+ handled = forward_to_driver(musb, &setup);
+ if (handled < 0) {
+ musb_ep_select(mbase, 0);
+stall:
+ dev_dbg(musb->controller, "stall (%d)\n", handled);
+ musb->ackpend |= MUSB_CSR0_P_SENDSTALL;
+ musb->ep0_state = MUSB_EP0_STAGE_IDLE;
+finish:
+ musb_writew(regs, MUSB_CSR0,
+ musb->ackpend);
+ musb->ackpend = 0;
+ }
+ }
+ break;
+
+ case MUSB_EP0_STAGE_ACKWAIT:
+ /* This should not happen. But happens with tusb6010 with
+ * g_file_storage and high speed. Do nothing.
+ */
+ retval = IRQ_HANDLED;
+ break;
+
+ default:
+ /* "can't happen" */
+ WARN_ON(1);
+ musb_writew(regs, MUSB_CSR0, MUSB_CSR0_P_SENDSTALL);
+ musb->ep0_state = MUSB_EP0_STAGE_IDLE;
+ break;
+ }
+
+ return retval;
+}
+
+
+static int
+musb_g_ep0_enable(struct usb_ep *ep, const struct usb_endpoint_descriptor *desc)
+{
+ /* always enabled */
+ return -EINVAL;
+}
+
+static int musb_g_ep0_disable(struct usb_ep *e)
+{
+ /* always enabled */
+ return -EINVAL;
+}
+
+static int
+musb_g_ep0_queue(struct usb_ep *e, struct usb_request *r)
+{
+ struct musb_ep *ep;
+ struct musb_request *req;
+ struct musb *musb;
+ int status;
+ unsigned long lockflags;
+ void __iomem *regs;
+
+ if (!e || !r)
+ return -EINVAL;
+
+ ep = to_musb_ep(e);
+ musb = ep->musb;
+ regs = musb->control_ep->regs;
+
+ req = to_musb_request(r);
+ req->musb = musb;
+ req->request.actual = 0;
+ req->request.status = -EINPROGRESS;
+ req->tx = ep->is_in;
+
+ spin_lock_irqsave(&musb->lock, lockflags);
+
+ if (!list_empty(&ep->req_list)) {
+ status = -EBUSY;
+ goto cleanup;
+ }
+
+ switch (musb->ep0_state) {
+ case MUSB_EP0_STAGE_RX: /* control-OUT data */
+ case MUSB_EP0_STAGE_TX: /* control-IN data */
+ case MUSB_EP0_STAGE_ACKWAIT: /* zero-length data */
+ status = 0;
+ break;
+ default:
+ dev_dbg(musb->controller, "ep0 request queued in state %d\n",
+ musb->ep0_state);
+ status = -EINVAL;
+ goto cleanup;
+ }
+
+ /* add request to the list */
+ list_add_tail(&req->list, &ep->req_list);
+
+ dev_dbg(musb->controller, "queue to %s (%s), length=%d\n",
+ ep->name, ep->is_in ? "IN/TX" : "OUT/RX",
+ req->request.length);
+
+ musb_ep_select(musb->mregs, 0);
+
+ /* sequence #1, IN ... start writing the data */
+ if (musb->ep0_state == MUSB_EP0_STAGE_TX)
+ ep0_txstate(musb);
+
+ /* sequence #3, no-data ... issue IN status */
+ else if (musb->ep0_state == MUSB_EP0_STAGE_ACKWAIT) {
+ if (req->request.length)
+ status = -EINVAL;
+ else {
+ musb->ep0_state = MUSB_EP0_STAGE_STATUSIN;
+ musb_writew(regs, MUSB_CSR0,
+ musb->ackpend | MUSB_CSR0_P_DATAEND);
+ musb->ackpend = 0;
+ musb_g_ep0_giveback(ep->musb, r);
+ }
+
+ /* else for sequence #2 (OUT), caller provides a buffer
+ * before the next packet arrives. deferred responses
+ * (after SETUP is acked) are racey.
+ */
+ } else if (musb->ackpend) {
+ musb_writew(regs, MUSB_CSR0, musb->ackpend);
+ musb->ackpend = 0;
+ }
+
+cleanup:
+ spin_unlock_irqrestore(&musb->lock, lockflags);
+ return status;
+}
+
+static int musb_g_ep0_dequeue(struct usb_ep *ep, struct usb_request *req)
+{
+ /* we just won't support this */
+ return -EINVAL;
+}
+
+static int musb_g_ep0_halt(struct usb_ep *e, int value)
+{
+ struct musb_ep *ep;
+ struct musb *musb;
+ void __iomem *base, *regs;
+ unsigned long flags;
+ int status;
+ u16 csr;
+
+ if (!e || !value)
+ return -EINVAL;
+
+ ep = to_musb_ep(e);
+ musb = ep->musb;
+ base = musb->mregs;
+ regs = musb->control_ep->regs;
+ status = 0;
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ if (!list_empty(&ep->req_list)) {
+ status = -EBUSY;
+ goto cleanup;
+ }
+
+ musb_ep_select(base, 0);
+ csr = musb->ackpend;
+
+ switch (musb->ep0_state) {
+
+ /* Stalls are usually issued after parsing SETUP packet, either
+ * directly in irq context from setup() or else later.
+ */
+ case MUSB_EP0_STAGE_TX: /* control-IN data */
+ case MUSB_EP0_STAGE_ACKWAIT: /* STALL for zero-length data */
+ case MUSB_EP0_STAGE_RX: /* control-OUT data */
+ csr = musb_readw(regs, MUSB_CSR0);
+ /* FALLTHROUGH */
+
+ /* It's also OK to issue stalls during callbacks when a non-empty
+ * DATA stage buffer has been read (or even written).
+ */
+ case MUSB_EP0_STAGE_STATUSIN: /* control-OUT status */
+ case MUSB_EP0_STAGE_STATUSOUT: /* control-IN status */
+
+ csr |= MUSB_CSR0_P_SENDSTALL;
+ musb_writew(regs, MUSB_CSR0, csr);
+ musb->ep0_state = MUSB_EP0_STAGE_IDLE;
+ musb->ackpend = 0;
+ break;
+ default:
+ dev_dbg(musb->controller, "ep0 can't halt in state %d\n", musb->ep0_state);
+ status = -EINVAL;
+ }
+
+cleanup:
+ spin_unlock_irqrestore(&musb->lock, flags);
+ return status;
+}
+
+const struct usb_ep_ops musb_g_ep0_ops = {
+ .enable = musb_g_ep0_enable,
+ .disable = musb_g_ep0_disable,
+ .alloc_request = musb_alloc_request,
+ .free_request = musb_free_request,
+ .queue = musb_g_ep0_queue,
+ .dequeue = musb_g_ep0_dequeue,
+ .set_halt = musb_g_ep0_halt,
+};
diff --git a/drivers/usb/musb/musb_host.c b/drivers/usb/musb/musb_host.c
new file mode 100644
index 0000000000..32a8f06529
--- /dev/null
+++ b/drivers/usb/musb/musb_host.c
@@ -0,0 +1,1749 @@
+/*
+ * MUSB OTG driver host support
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ * Copyright (C) 2008-2009 MontaVista Software, Inc. <source@mvista.com>
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#include <common.h>
+#include <malloc.h>
+#include "musb_core.h"
+#include "musb_host.h"
+
+/* MUSB HOST status 22-mar-2006
+ *
+ * - There's still lots of partial code duplication for fault paths, so
+ * they aren't handled as consistently as they need to be.
+ *
+ * - PIO mostly behaved when last tested.
+ * + including ep0, with all usbtest cases 9, 10
+ * + usbtest 14 (ep0out) doesn't seem to run at all
+ * + double buffered OUT/TX endpoints saw stalls(!) with certain usbtest
+ * configurations, but otherwise double buffering passes basic tests.
+ * + for 2.6.N, for N > ~10, needs API changes for hcd framework.
+ *
+ * - DMA (CPPI) ... partially behaves, not currently recommended
+ * + about 1/15 the speed of typical EHCI implementations (PCI)
+ * + RX, all too often reqpkt seems to misbehave after tx
+ * + TX, no known issues (other than evident silicon issue)
+ *
+ * - DMA (Mentor/OMAP) ...has at least toggle update problems
+ *
+ * - [23-feb-2009] minimal traffic scheduling to avoid bulk RX packet
+ * starvation ... nothing yet for TX, interrupt, or bulk.
+ *
+ * - Not tested with HNP, but some SRP paths seem to behave.
+ *
+ * NOTE 24-August-2006:
+ *
+ * - Bulk traffic finally uses both sides of hardware ep1, freeing up an
+ * extra endpoint for periodic use enabling hub + keybd + mouse. That
+ * mostly works, except that with "usbnet" it's easy to trigger cases
+ * with "ping" where RX loses. (a) ping to davinci, even "ping -f",
+ * fine; but (b) ping _from_ davinci, even "ping -c 1", ICMP RX loses
+ * although ARP RX wins. (That test was done with a full speed link.)
+ */
+
+
+/*
+ * NOTE on endpoint usage:
+ *
+ * CONTROL transfers all go through ep0. BULK ones go through dedicated IN
+ * and OUT endpoints ... hardware is dedicated for those "async" queue(s).
+ * (Yes, bulk _could_ use more of the endpoints than that, and would even
+ * benefit from it.)
+ *
+ * INTERUPPT and ISOCHRONOUS transfers are scheduled to the other endpoints.
+ * So far that scheduling is both dumb and optimistic: the endpoint will be
+ * "claimed" until its software queue is no longer refilled. No multiplexing
+ * of transfers between endpoints, or anything clever.
+ */
+
+struct musb *hcd_to_musb(struct usb_hcd *hcd)
+{
+ return (struct musb *) hcd->hcd_priv;
+}
+
+
+static void musb_ep_program(struct musb *musb, u8 epnum,
+ struct urb *urb, int is_out,
+ u8 *buf, u32 offset, u32 len);
+
+/*
+ * Clear TX fifo. Needed to avoid BABBLE errors.
+ */
+static void musb_h_tx_flush_fifo(struct musb_hw_ep *ep)
+{
+ struct musb *musb = ep->musb;
+ void __iomem *epio = ep->regs;
+ u16 csr;
+ u16 lastcsr = 0;
+ int retries = 1000;
+
+ csr = musb_readw(epio, MUSB_TXCSR);
+ while (csr & MUSB_TXCSR_FIFONOTEMPTY) {
+ if (csr != lastcsr)
+ dev_dbg(musb->controller, "Host TX FIFONOTEMPTY csr: %02x\n", csr);
+ lastcsr = csr;
+ csr |= MUSB_TXCSR_FLUSHFIFO;
+ musb_writew(epio, MUSB_TXCSR, csr);
+ csr = musb_readw(epio, MUSB_TXCSR);
+ if (!retries--) {
+ dev_warn(musb->controller, "Could not flush host TX%d fifo: csr: %04x\n",
+ ep->epnum, csr);
+ return;
+ }
+ mdelay(1);
+ }
+}
+
+static void musb_h_ep0_flush_fifo(struct musb_hw_ep *ep)
+{
+ struct musb *musb = ep->musb;
+ void __iomem *epio = ep->regs;
+ u16 csr;
+ int retries = 5;
+
+ /* scrub any data left in the fifo */
+ do {
+ csr = musb_readw(epio, MUSB_TXCSR);
+ if (!(csr & (MUSB_CSR0_TXPKTRDY | MUSB_CSR0_RXPKTRDY)))
+ break;
+ musb_writew(epio, MUSB_TXCSR, MUSB_CSR0_FLUSHFIFO);
+ csr = musb_readw(epio, MUSB_TXCSR);
+ udelay(10);
+ } while (--retries);
+
+ if (!retries)
+ dev_warn(musb->controller, "Could not flush host TX%d fifo: csr: %04x\n",
+ ep->epnum, csr);
+
+ /* and reset for the next transfer */
+ musb_writew(epio, MUSB_TXCSR, 0);
+}
+
+/*
+ * Start transmit. Caller is responsible for locking shared resources.
+ * musb must be locked.
+ */
+static inline void musb_h_tx_start(struct musb_hw_ep *ep)
+{
+ u16 txcsr;
+
+ /* NOTE: no locks here; caller should lock and select EP */
+ if (ep->epnum) {
+ txcsr = musb_readw(ep->regs, MUSB_TXCSR);
+ txcsr |= MUSB_TXCSR_TXPKTRDY | MUSB_TXCSR_H_WZC_BITS;
+ musb_writew(ep->regs, MUSB_TXCSR, txcsr);
+ } else {
+ txcsr = MUSB_CSR0_H_SETUPPKT | MUSB_CSR0_TXPKTRDY;
+ musb_writew(ep->regs, MUSB_CSR0, txcsr);
+ }
+
+}
+
+static inline void musb_h_tx_dma_start(struct musb_hw_ep *ep)
+{
+ u16 txcsr;
+
+ /* NOTE: no locks here; caller should lock and select EP */
+ txcsr = musb_readw(ep->regs, MUSB_TXCSR);
+ txcsr |= MUSB_TXCSR_DMAENAB | MUSB_TXCSR_H_WZC_BITS;
+ if (is_cppi_enabled())
+ txcsr |= MUSB_TXCSR_DMAMODE;
+ musb_writew(ep->regs, MUSB_TXCSR, txcsr);
+}
+
+static void musb_ep_set_qh(struct musb_hw_ep *ep, int is_in, struct musb_qh *qh)
+{
+ if (is_in != 0 || ep->is_shared_fifo)
+ ep->in_qh = qh;
+ if (is_in == 0 || ep->is_shared_fifo)
+ ep->out_qh = qh;
+}
+
+static struct musb_qh *musb_ep_get_qh(struct musb_hw_ep *ep, int is_in)
+{
+ return is_in ? ep->in_qh : ep->out_qh;
+}
+
+/*
+ * Start the URB at the front of an endpoint's queue
+ * end must be claimed from the caller.
+ *
+ * Context: controller locked, irqs blocked
+ */
+static void
+musb_start_urb(struct musb *musb, int is_in, struct musb_qh *qh)
+{
+ u16 frame;
+ u32 len;
+ void __iomem *mbase = musb->mregs;
+ struct urb *urb = next_urb(qh);
+ void *buf = urb->transfer_buffer;
+ u32 offset = 0;
+ struct musb_hw_ep *hw_ep = qh->hw_ep;
+ unsigned pipe = urb->pipe;
+ u8 address = usb_pipedevice(pipe);
+ int epnum = hw_ep->epnum;
+
+ /* initialize software qh state */
+ qh->offset = 0;
+ qh->segsize = 0;
+
+ /* gather right source of data */
+ switch (qh->type) {
+ case USB_ENDPOINT_XFER_CONTROL:
+ /* control transfers always start with SETUP */
+ is_in = 0;
+ musb->ep0_stage = MUSB_EP0_START;
+ buf = urb->setup_packet;
+ len = 8;
+ break;
+ default: /* bulk, interrupt */
+ /* actual_length may be nonzero on retry paths */
+ buf = urb->transfer_buffer + urb->actual_length;
+ len = urb->transfer_buffer_length - urb->actual_length;
+ }
+
+ dev_dbg(musb->controller, "qh %p urb %p dev%d ep%d%s%s, hw_ep %d, %p/%d\n",
+ qh, urb, address, qh->epnum,
+ is_in ? "in" : "out",
+ ({char *s; switch (qh->type) {
+ case USB_ENDPOINT_XFER_CONTROL: s = ""; break;
+ case USB_ENDPOINT_XFER_BULK: s = "-bulk"; break;
+ default: s = "-intr"; break;
+ } s; }),
+ epnum, buf + offset, len);
+
+ /* Configure endpoint */
+ musb_ep_set_qh(hw_ep, is_in, qh);
+ musb_ep_program(musb, epnum, urb, !is_in, buf, offset, len);
+
+ /* transmit may have more work: start it when it is time */
+ if (is_in)
+ return;
+
+ /* determine if the time is right for a periodic transfer */
+ switch (qh->type) {
+ case USB_ENDPOINT_XFER_INT:
+ dev_dbg(musb->controller, "check whether there's still time for periodic Tx\n");
+ frame = musb_readw(mbase, MUSB_FRAME);
+ /* FIXME this doesn't implement that scheduling policy ...
+ * or handle framecounter wrapping
+ */
+ if (1) { /* Always assume URB_ISO_ASAP */
+ /* REVISIT the SOF irq handler shouldn't duplicate
+ * this code; and we don't init urb->start_frame...
+ */
+ qh->frame = 0;
+ goto start;
+ } else {
+ qh->frame = urb->start_frame;
+ /* enable SOF interrupt so we can count down */
+ dev_dbg(musb->controller, "SOF for %d\n", epnum);
+#if 1 /* ifndef CONFIG_ARCH_DAVINCI */
+ musb_writeb(mbase, MUSB_INTRUSBE, 0xff);
+#endif
+ }
+ break;
+ default:
+start:
+ dev_dbg(musb->controller, "Start TX%d %s\n", epnum,
+ hw_ep->tx_channel ? "dma" : "pio");
+
+ if (!hw_ep->tx_channel)
+ musb_h_tx_start(hw_ep);
+ }
+}
+
+/* Context: caller owns controller lock, IRQs are blocked */
+static void musb_giveback(struct musb *musb, struct urb *urb, int status)
+__releases(musb->lock)
+__acquires(musb->lock)
+{
+ dev_dbg(musb->controller,
+ "complete %p %pF (%d), dev%d ep%d%s, %d/%d\n",
+ urb, urb->complete, status,
+ usb_pipedevice(urb->pipe),
+ usb_pipeendpoint(urb->pipe),
+ usb_pipein(urb->pipe) ? "in" : "out",
+ urb->actual_length, urb->transfer_buffer_length
+ );
+
+ usb_hcd_unlink_urb_from_ep(musb->hcd, urb);
+ spin_unlock(&musb->lock);
+ usb_hcd_giveback_urb(musb->hcd, urb, status);
+ spin_lock(&musb->lock);
+}
+
+/* For bulk/interrupt endpoints only */
+static inline void musb_save_toggle(struct musb_qh *qh, int is_in,
+ struct urb *urb)
+{
+ void __iomem *epio = qh->hw_ep->regs;
+ u16 csr;
+
+ /*
+ * FIXME: the current Mentor DMA code seems to have
+ * problems getting toggle correct.
+ */
+
+ if (is_in)
+ csr = musb_readw(epio, MUSB_RXCSR) & MUSB_RXCSR_H_DATATOGGLE;
+ else
+ csr = musb_readw(epio, MUSB_TXCSR) & MUSB_TXCSR_H_DATATOGGLE;
+
+ usb_settoggle(urb->dev, qh->epnum, !is_in, csr ? 1 : 0);
+}
+
+/*
+ * Advance this hardware endpoint's queue, completing the specified URB and
+ * advancing to either the next URB queued to that qh, or else invalidating
+ * that qh and advancing to the next qh scheduled after the current one.
+ *
+ * Context: caller owns controller lock, IRQs are blocked
+ */
+static void musb_advance_schedule(struct musb *musb, struct urb *urb,
+ struct musb_hw_ep *hw_ep, int is_in)
+{
+ struct musb_qh *qh = musb_ep_get_qh(hw_ep, is_in);
+ struct musb_hw_ep *ep = qh->hw_ep;
+ int ready = qh->is_ready;
+ int status;
+
+ status = (urb->status == -EINPROGRESS) ? 0 : urb->status;
+
+ /* save toggle eagerly, for paranoia */
+ switch (qh->type) {
+ case USB_ENDPOINT_XFER_BULK:
+ case USB_ENDPOINT_XFER_INT:
+ musb_save_toggle(qh, is_in, urb);
+ break;
+ }
+
+ qh->is_ready = 0;
+ musb_giveback(musb, urb, status);
+ qh->is_ready = ready;
+
+ /* reclaim resources (and bandwidth) ASAP; deschedule it, and
+ * invalidate qh as soon as list_empty(&hep->urb_list)
+ */
+ if (list_empty(&qh->hep->urb_list)) {
+ struct list_head *head;
+ struct dma_controller *dma = musb->dma_controller;
+
+ if (is_in) {
+ ep->rx_reinit = 1;
+ if (ep->rx_channel) {
+ dma->channel_release(ep->rx_channel);
+ ep->rx_channel = NULL;
+ }
+ } else {
+ ep->tx_reinit = 1;
+ if (ep->tx_channel) {
+ dma->channel_release(ep->tx_channel);
+ ep->tx_channel = NULL;
+ }
+ }
+
+ /* Clobber old pointers to this qh */
+ musb_ep_set_qh(ep, is_in, NULL);
+ qh->hep->hcpriv = NULL;
+
+ switch (qh->type) {
+
+ case USB_ENDPOINT_XFER_CONTROL:
+ case USB_ENDPOINT_XFER_BULK:
+ /* fifo policy for these lists, except that NAKing
+ * should rotate a qh to the end (for fairness).
+ */
+ if (qh->mux == 1) {
+ head = qh->ring.prev;
+ list_del(&qh->ring);
+ kfree(qh);
+ qh = first_qh(head);
+ break;
+ }
+
+ case USB_ENDPOINT_XFER_INT:
+ /* this is where periodic bandwidth should be
+ * de-allocated if it's tracked and allocated;
+ * and where we'd update the schedule tree...
+ */
+ kfree(qh);
+ qh = NULL;
+ break;
+ }
+ }
+
+ if (qh != NULL && qh->is_ready) {
+ dev_dbg(musb->controller, "... next ep%d %cX urb %p\n",
+ hw_ep->epnum, is_in ? 'R' : 'T', next_urb(qh));
+ musb_start_urb(musb, is_in, qh);
+ }
+}
+
+static u16 musb_h_flush_rxfifo(struct musb_hw_ep *hw_ep, u16 csr)
+{
+ /* we don't want fifo to fill itself again;
+ * ignore dma (various models),
+ * leave toggle alone (may not have been saved yet)
+ */
+ csr |= MUSB_RXCSR_FLUSHFIFO | MUSB_RXCSR_RXPKTRDY;
+ csr &= ~(MUSB_RXCSR_H_REQPKT
+ | MUSB_RXCSR_H_AUTOREQ
+ | MUSB_RXCSR_AUTOCLEAR);
+
+ /* write 2x to allow double buffering */
+ musb_writew(hw_ep->regs, MUSB_RXCSR, csr);
+ musb_writew(hw_ep->regs, MUSB_RXCSR, csr);
+
+ /* flush writebuffer */
+ return musb_readw(hw_ep->regs, MUSB_RXCSR);
+}
+
+/*
+ * PIO RX for a packet (or part of it).
+ */
+static bool
+musb_host_packet_rx(struct musb *musb, struct urb *urb, u8 epnum, u8 iso_err)
+{
+ u16 rx_count;
+ u8 *buf;
+ u16 csr;
+ bool done = false;
+ u32 length;
+ int do_flush = 0;
+ struct musb_hw_ep *hw_ep = musb->endpoints + epnum;
+ void __iomem *epio = hw_ep->regs;
+ struct musb_qh *qh = hw_ep->in_qh;
+ void *buffer = urb->transfer_buffer;
+
+ /* musb_ep_select(mbase, epnum); */
+ rx_count = musb_readw(epio, MUSB_RXCOUNT);
+ dev_dbg(musb->controller, "RX%d count %d, buffer %p len %d/%d\n", epnum, rx_count,
+ urb->transfer_buffer, qh->offset,
+ urb->transfer_buffer_length);
+
+ /* unload FIFO */
+ if (0) {
+ } else {
+ /* non-isoch */
+ buf = buffer + qh->offset;
+ length = urb->transfer_buffer_length - qh->offset;
+ if (rx_count > length) {
+ if (urb->status == -EINPROGRESS)
+ urb->status = -EOVERFLOW;
+ dev_dbg(musb->controller, "** OVERFLOW %d into %d\n", rx_count, length);
+ do_flush = 1;
+ } else
+ length = rx_count;
+ urb->actual_length += length;
+ qh->offset += length;
+
+ /* see if we are done */
+ done = (urb->actual_length == urb->transfer_buffer_length)
+ || (rx_count < qh->maxpacket)
+ || (urb->status != -EINPROGRESS);
+ if (done
+ && (urb->status == -EINPROGRESS)
+ && (urb->transfer_flags & URB_SHORT_NOT_OK)
+ && (urb->actual_length
+ < urb->transfer_buffer_length))
+ urb->status = -EREMOTEIO;
+ }
+
+ musb_read_fifo(hw_ep, length, buf);
+
+ csr = musb_readw(epio, MUSB_RXCSR);
+ csr |= MUSB_RXCSR_H_WZC_BITS;
+ if (unlikely(do_flush))
+ musb_h_flush_rxfifo(hw_ep, csr);
+ else {
+ /* REVISIT this assumes AUTOCLEAR is never set */
+ csr &= ~(MUSB_RXCSR_RXPKTRDY | MUSB_RXCSR_H_REQPKT);
+ if (!done)
+ csr |= MUSB_RXCSR_H_REQPKT;
+ musb_writew(epio, MUSB_RXCSR, csr);
+ }
+
+ return done;
+}
+
+/* we don't always need to reinit a given side of an endpoint...
+ * when we do, use tx/rx reinit routine and then construct a new CSR
+ * to address data toggle, NYET, and DMA or PIO.
+ *
+ * it's possible that driver bugs (especially for DMA) or aborting a
+ * transfer might have left the endpoint busier than it should be.
+ * the busy/not-empty tests are basically paranoia.
+ */
+static void
+musb_rx_reinit(struct musb *musb, struct musb_qh *qh, struct musb_hw_ep *ep)
+{
+ u16 csr;
+
+ /* NOTE: we know the "rx" fifo reinit never triggers for ep0.
+ * That always uses tx_reinit since ep0 repurposes TX register
+ * offsets; the initial SETUP packet is also a kind of OUT.
+ */
+
+ /* if programmed for Tx, put it in RX mode */
+ if (ep->is_shared_fifo) {
+ csr = musb_readw(ep->regs, MUSB_TXCSR);
+ if (csr & MUSB_TXCSR_MODE) {
+ musb_h_tx_flush_fifo(ep);
+ csr = musb_readw(ep->regs, MUSB_TXCSR);
+ musb_writew(ep->regs, MUSB_TXCSR,
+ csr | MUSB_TXCSR_FRCDATATOG);
+ }
+
+ /*
+ * Clear the MODE bit (and everything else) to enable Rx.
+ * NOTE: we mustn't clear the DMAMODE bit before DMAENAB.
+ */
+ if (csr & MUSB_TXCSR_DMAMODE)
+ musb_writew(ep->regs, MUSB_TXCSR, MUSB_TXCSR_DMAMODE);
+ musb_writew(ep->regs, MUSB_TXCSR, 0);
+
+ /* scrub all previous state, clearing toggle */
+ } else {
+ csr = musb_readw(ep->regs, MUSB_RXCSR);
+ if (csr & MUSB_RXCSR_RXPKTRDY)
+ dev_warn(musb->controller, "rx%d, packet/%d ready?\n", ep->epnum,
+ musb_readw(ep->regs, MUSB_RXCOUNT));
+
+ musb_h_flush_rxfifo(ep, MUSB_RXCSR_CLRDATATOG);
+ }
+
+ /* target addr and (for multipoint) hub addr/port */
+ if (musb->is_multipoint) {
+ musb_write_rxfunaddr(ep->target_regs, qh->addr_reg);
+ musb_write_rxhubaddr(ep->target_regs, qh->h_addr_reg);
+ musb_write_rxhubport(ep->target_regs, qh->h_port_reg);
+
+ } else
+ musb_writeb(musb->mregs, MUSB_FADDR, qh->addr_reg);
+
+ /* protocol/endpoint, interval/NAKlimit, i/o size */
+ musb_writeb(ep->regs, MUSB_RXTYPE, qh->type_reg);
+ musb_writeb(ep->regs, MUSB_RXINTERVAL, qh->intv_reg);
+ /* NOTE: bulk combining rewrites high bits of maxpacket */
+ /* Set RXMAXP with the FIFO size of the endpoint
+ * to disable double buffer mode.
+ */
+ if (musb->double_buffer_not_ok)
+ musb_writew(ep->regs, MUSB_RXMAXP, ep->max_packet_sz_rx);
+ else
+ musb_writew(ep->regs, MUSB_RXMAXP,
+ qh->maxpacket | ((qh->hb_mult - 1) << 11));
+
+ ep->rx_reinit = 0;
+}
+
+/*
+ * Program an HDRC endpoint as per the given URB
+ * Context: irqs blocked, controller lock held
+ */
+static void musb_ep_program(struct musb *musb, u8 epnum,
+ struct urb *urb, int is_out,
+ u8 *buf, u32 offset, u32 len)
+{
+ void __iomem *mbase = musb->mregs;
+ struct musb_hw_ep *hw_ep = musb->endpoints + epnum;
+ void __iomem *epio = hw_ep->regs;
+ struct musb_qh *qh = musb_ep_get_qh(hw_ep, !is_out);
+ u16 packet_sz = qh->maxpacket;
+ u16 csr;
+
+ dev_dbg(musb->controller, "%s hw%d urb %p spd%d dev%d ep%d%s "
+ "h_addr%02x h_port%02x bytes %d\n",
+ is_out ? "-->" : "<--",
+ epnum, urb, urb->dev->speed,
+ qh->addr_reg, qh->epnum, is_out ? "out" : "in",
+ qh->h_addr_reg, qh->h_port_reg,
+ len);
+
+ musb_ep_select(mbase, epnum);
+
+ if (is_out && !len) {
+ csr = musb_readw(epio, MUSB_TXCSR);
+ csr &= ~MUSB_TXCSR_DMAENAB;
+ musb_writew(epio, MUSB_TXCSR, csr);
+ hw_ep->tx_channel = NULL;
+ }
+
+ /* OUT/transmit/EP0 or IN/receive? */
+ if (is_out) {
+ u16 csr;
+ u16 int_txe;
+ u16 load_count;
+
+ csr = musb_readw(epio, MUSB_TXCSR);
+
+ /* disable interrupt in case we flush */
+ int_txe = musb->intrtxe;
+ musb_writew(mbase, MUSB_INTRTXE, int_txe & ~(1 << epnum));
+
+ /* general endpoint setup */
+ if (epnum) {
+ /* flush all old state, set default */
+ /*
+ * We could be flushing valid
+ * packets in double buffering
+ * case
+ */
+ if (!hw_ep->tx_double_buffered)
+ musb_h_tx_flush_fifo(hw_ep);
+
+ /*
+ * We must not clear the DMAMODE bit before or in
+ * the same cycle with the DMAENAB bit, so we clear
+ * the latter first...
+ */
+ csr &= ~(MUSB_TXCSR_H_NAKTIMEOUT
+ | MUSB_TXCSR_AUTOSET
+ | MUSB_TXCSR_DMAENAB
+ | MUSB_TXCSR_FRCDATATOG
+ | MUSB_TXCSR_H_RXSTALL
+ | MUSB_TXCSR_H_ERROR
+ | MUSB_TXCSR_TXPKTRDY
+ );
+ csr |= MUSB_TXCSR_MODE;
+
+ if (!hw_ep->tx_double_buffered) {
+ if (usb_gettoggle(urb->dev, qh->epnum, 1))
+ csr |= MUSB_TXCSR_H_WR_DATATOGGLE
+ | MUSB_TXCSR_H_DATATOGGLE;
+ else
+ csr |= MUSB_TXCSR_CLRDATATOG;
+ }
+
+ musb_writew(epio, MUSB_TXCSR, csr);
+ /* REVISIT may need to clear FLUSHFIFO ... */
+ csr &= ~MUSB_TXCSR_DMAMODE;
+ musb_writew(epio, MUSB_TXCSR, csr);
+ csr = musb_readw(epio, MUSB_TXCSR);
+ } else {
+ /* endpoint 0: just flush */
+ musb_h_ep0_flush_fifo(hw_ep);
+ }
+
+ /* target addr and (for multipoint) hub addr/port */
+ if (musb->is_multipoint) {
+ musb_write_txfunaddr(mbase, epnum, qh->addr_reg);
+ musb_write_txhubaddr(mbase, epnum, qh->h_addr_reg);
+ musb_write_txhubport(mbase, epnum, qh->h_port_reg);
+/* FIXME if !epnum, do the same for RX ... */
+ } else
+ musb_writeb(mbase, MUSB_FADDR, qh->addr_reg);
+
+ /* protocol/endpoint/interval/NAKlimit */
+ if (epnum) {
+ musb_writeb(epio, MUSB_TXTYPE, qh->type_reg);
+ if (musb->double_buffer_not_ok) {
+ musb_writew(epio, MUSB_TXMAXP,
+ hw_ep->max_packet_sz_tx);
+ } else if (can_bulk_split(musb, qh->type)) {
+ qh->hb_mult = hw_ep->max_packet_sz_tx
+ / packet_sz;
+ musb_writew(epio, MUSB_TXMAXP, packet_sz
+ | ((qh->hb_mult) - 1) << 11);
+ } else {
+ musb_writew(epio, MUSB_TXMAXP,
+ qh->maxpacket |
+ ((qh->hb_mult - 1) << 11));
+ }
+ musb_writeb(epio, MUSB_TXINTERVAL, qh->intv_reg);
+ } else {
+ musb_writeb(epio, MUSB_NAKLIMIT0, qh->intv_reg);
+ if (musb->is_multipoint)
+ musb_writeb(epio, MUSB_TYPE0,
+ qh->type_reg);
+ }
+
+ if (can_bulk_split(musb, qh->type))
+ load_count = min((u32) hw_ep->max_packet_sz_tx,
+ len);
+ else
+ load_count = min((u32) packet_sz, len);
+
+ if (load_count) {
+ /* PIO to load FIFO */
+ qh->segsize = load_count;
+ musb_write_fifo(hw_ep, load_count, buf);
+ }
+
+ /* re-enable interrupt */
+ musb_writew(mbase, MUSB_INTRTXE, int_txe);
+
+ /* IN/receive */
+ } else {
+ u16 csr;
+
+ if (hw_ep->rx_reinit) {
+ musb_rx_reinit(musb, qh, hw_ep);
+
+ /* init new state: toggle and NYET, maybe DMA later */
+ if (usb_gettoggle(urb->dev, qh->epnum, 0))
+ csr = MUSB_RXCSR_H_WR_DATATOGGLE
+ | MUSB_RXCSR_H_DATATOGGLE;
+ else
+ csr = 0;
+ if (qh->type == USB_ENDPOINT_XFER_INT)
+ csr |= MUSB_RXCSR_DISNYET;
+
+ } else {
+ csr = musb_readw(hw_ep->regs, MUSB_RXCSR);
+
+ if (csr & (MUSB_RXCSR_RXPKTRDY
+ | MUSB_RXCSR_DMAENAB
+ | MUSB_RXCSR_H_REQPKT))
+ dev_err(musb->controller, "broken !rx_reinit, ep%d csr %04x\n",
+ hw_ep->epnum, csr);
+
+ /* scrub any stale state, leaving toggle alone */
+ csr &= MUSB_RXCSR_DISNYET;
+ }
+
+ /* kick things off */
+
+ csr |= MUSB_RXCSR_H_REQPKT;
+ dev_dbg(musb->controller, "RXCSR%d := %04x\n", epnum, csr);
+ musb_writew(hw_ep->regs, MUSB_RXCSR, csr);
+ csr = musb_readw(hw_ep->regs, MUSB_RXCSR);
+ }
+}
+
+/* Schedule next QH from musb->in_bulk/out_bulk and move the current qh to
+ * the end; avoids starvation for other endpoints.
+ */
+static void musb_bulk_nak_timeout(struct musb *musb, struct musb_hw_ep *ep,
+ int is_in)
+{
+ struct urb *urb;
+ void __iomem *mbase = musb->mregs;
+ void __iomem *epio = ep->regs;
+ struct musb_qh *cur_qh, *next_qh;
+ u16 rx_csr, tx_csr;
+
+ musb_ep_select(mbase, ep->epnum);
+ if (is_in) {
+ /* clear nak timeout bit */
+ rx_csr = musb_readw(epio, MUSB_RXCSR);
+ rx_csr |= MUSB_RXCSR_H_WZC_BITS;
+ rx_csr &= ~MUSB_RXCSR_DATAERROR;
+ musb_writew(epio, MUSB_RXCSR, rx_csr);
+
+ cur_qh = first_qh(&musb->in_bulk);
+ } else {
+ /* clear nak timeout bit */
+ tx_csr = musb_readw(epio, MUSB_TXCSR);
+ tx_csr |= MUSB_TXCSR_H_WZC_BITS;
+ tx_csr &= ~MUSB_TXCSR_H_NAKTIMEOUT;
+ musb_writew(epio, MUSB_TXCSR, tx_csr);
+
+ cur_qh = first_qh(&musb->out_bulk);
+ }
+ if (cur_qh) {
+ urb = next_urb(cur_qh);
+ musb_save_toggle(cur_qh, is_in, urb);
+
+ if (is_in) {
+ /* move cur_qh to end of queue */
+ list_move_tail(&cur_qh->ring, &musb->in_bulk);
+
+ /* get the next qh from musb->in_bulk */
+ next_qh = first_qh(&musb->in_bulk);
+
+ /* set rx_reinit and schedule the next qh */
+ ep->rx_reinit = 1;
+ } else {
+ /* move cur_qh to end of queue */
+ list_move_tail(&cur_qh->ring, &musb->out_bulk);
+
+ /* get the next qh from musb->out_bulk */
+ next_qh = first_qh(&musb->out_bulk);
+
+ /* set tx_reinit and schedule the next qh */
+ ep->tx_reinit = 1;
+ }
+ musb_start_urb(musb, is_in, next_qh);
+ }
+}
+
+/*
+ * Service the default endpoint (ep0) as host.
+ * Return true until it's time to start the status stage.
+ */
+static bool musb_h_ep0_continue(struct musb *musb, u16 len, struct urb *urb)
+{
+ bool more = false;
+ u8 *fifo_dest = NULL;
+ u16 fifo_count = 0;
+ struct musb_hw_ep *hw_ep = musb->control_ep;
+ struct musb_qh *qh = hw_ep->in_qh;
+ struct usb_ctrlrequest *request;
+
+ switch (musb->ep0_stage) {
+ case MUSB_EP0_IN:
+ fifo_dest = urb->transfer_buffer + urb->actual_length;
+ fifo_count = min_t(size_t, len, urb->transfer_buffer_length -
+ urb->actual_length);
+ if (fifo_count < len)
+ urb->status = -EOVERFLOW;
+
+ musb_read_fifo(hw_ep, fifo_count, fifo_dest);
+
+ urb->actual_length += fifo_count;
+ if (len < qh->maxpacket) {
+ /* always terminate on short read; it's
+ * rarely reported as an error.
+ */
+ } else if (urb->actual_length <
+ urb->transfer_buffer_length)
+ more = true;
+ break;
+ case MUSB_EP0_START:
+ request = (struct usb_ctrlrequest *) urb->setup_packet;
+
+ if (!request->wLength) {
+ dev_dbg(musb->controller, "start no-DATA\n");
+ break;
+ } else if (request->bRequestType & USB_DIR_IN) {
+ dev_dbg(musb->controller, "start IN-DATA\n");
+ musb->ep0_stage = MUSB_EP0_IN;
+ more = true;
+ break;
+ } else {
+ dev_dbg(musb->controller, "start OUT-DATA\n");
+ musb->ep0_stage = MUSB_EP0_OUT;
+ more = true;
+ }
+ /* FALLTHROUGH */
+ case MUSB_EP0_OUT:
+ fifo_count = min_t(size_t, qh->maxpacket,
+ urb->transfer_buffer_length -
+ urb->actual_length);
+ if (fifo_count) {
+ fifo_dest = (u8 *) (urb->transfer_buffer
+ + urb->actual_length);
+ dev_dbg(musb->controller, "Sending %d byte%s to ep0 fifo %p\n",
+ fifo_count,
+ (fifo_count == 1) ? "" : "s",
+ fifo_dest);
+ musb_write_fifo(hw_ep, fifo_count, fifo_dest);
+
+ urb->actual_length += fifo_count;
+ more = true;
+ }
+ break;
+ default:
+ dev_err(musb->controller, "bogus ep0 stage %d\n", musb->ep0_stage);
+ break;
+ }
+
+ return more;
+}
+
+/*
+ * Handle default endpoint interrupt as host. Only called in IRQ time
+ * from musb_interrupt().
+ *
+ * called with controller irqlocked
+ */
+irqreturn_t musb_h_ep0_irq(struct musb *musb)
+{
+ struct urb *urb;
+ u16 csr, len;
+ int status = 0;
+ void __iomem *mbase = musb->mregs;
+ struct musb_hw_ep *hw_ep = musb->control_ep;
+ void __iomem *epio = hw_ep->regs;
+ struct musb_qh *qh = hw_ep->in_qh;
+ bool complete = false;
+ irqreturn_t retval = IRQ_NONE;
+
+ /* ep0 only has one queue, "in" */
+ urb = next_urb(qh);
+
+ musb_ep_select(mbase, 0);
+ csr = musb_readw(epio, MUSB_CSR0);
+ len = (csr & MUSB_CSR0_RXPKTRDY)
+ ? musb_readb(epio, MUSB_COUNT0)
+ : 0;
+
+ dev_dbg(musb->controller, "<== csr0 %04x, qh %p, count %d, urb %p, stage %d\n",
+ csr, qh, len, urb, musb->ep0_stage);
+
+ /* if we just did status stage, we are done */
+ if (MUSB_EP0_STATUS == musb->ep0_stage) {
+ retval = IRQ_HANDLED;
+ complete = true;
+ }
+
+ /* prepare status */
+ if (csr & MUSB_CSR0_H_RXSTALL) {
+ dev_dbg(musb->controller, "STALLING ENDPOINT\n");
+ status = -EPIPE;
+
+ } else if (csr & MUSB_CSR0_H_ERROR) {
+ dev_dbg(musb->controller, "no response, csr0 %04x\n", csr);
+ status = -EPROTO;
+
+ } else if (csr & MUSB_CSR0_H_NAKTIMEOUT) {
+ dev_dbg(musb->controller, "control NAK timeout\n");
+
+ /* NOTE: this code path would be a good place to PAUSE a
+ * control transfer, if another one is queued, so that
+ * ep0 is more likely to stay busy. That's already done
+ * for bulk RX transfers.
+ *
+ * if (qh->ring.next != &musb->control), then
+ * we have a candidate... NAKing is *NOT* an error
+ */
+ musb_writew(epio, MUSB_CSR0, 0);
+ retval = IRQ_HANDLED;
+ }
+
+ if (status) {
+ dev_dbg(musb->controller, "aborting\n");
+ retval = IRQ_HANDLED;
+ if (urb)
+ urb->status = status;
+ complete = true;
+
+ /* use the proper sequence to abort the transfer */
+ if (csr & MUSB_CSR0_H_REQPKT) {
+ csr &= ~MUSB_CSR0_H_REQPKT;
+ musb_writew(epio, MUSB_CSR0, csr);
+ csr &= ~MUSB_CSR0_H_NAKTIMEOUT;
+ musb_writew(epio, MUSB_CSR0, csr);
+ } else {
+ musb_h_ep0_flush_fifo(hw_ep);
+ }
+
+ musb_writeb(epio, MUSB_NAKLIMIT0, 0);
+
+ /* clear it */
+ musb_writew(epio, MUSB_CSR0, 0);
+ }
+
+ if (unlikely(!urb)) {
+ /* stop endpoint since we have no place for its data, this
+ * SHOULD NEVER HAPPEN! */
+ dev_err(musb->controller, "no URB for end 0\n");
+
+ musb_h_ep0_flush_fifo(hw_ep);
+ goto done;
+ }
+
+ if (!complete) {
+ /* call common logic and prepare response */
+ if (musb_h_ep0_continue(musb, len, urb)) {
+ /* more packets required */
+ csr = (MUSB_EP0_IN == musb->ep0_stage)
+ ? MUSB_CSR0_H_REQPKT : MUSB_CSR0_TXPKTRDY;
+ } else {
+ /* data transfer complete; perform status phase */
+ if (usb_pipeout(urb->pipe)
+ || !urb->transfer_buffer_length)
+ csr = MUSB_CSR0_H_STATUSPKT
+ | MUSB_CSR0_H_REQPKT;
+ else
+ csr = MUSB_CSR0_H_STATUSPKT
+ | MUSB_CSR0_TXPKTRDY;
+
+ /* flag status stage */
+ musb->ep0_stage = MUSB_EP0_STATUS;
+
+ dev_dbg(musb->controller, "ep0 STATUS, csr %04x\n", csr);
+
+ }
+ musb_writew(epio, MUSB_CSR0, csr);
+ retval = IRQ_HANDLED;
+ } else
+ musb->ep0_stage = MUSB_EP0_IDLE;
+
+ /* call completion handler if done */
+ if (complete)
+ musb_advance_schedule(musb, urb, hw_ep, 1);
+done:
+ return retval;
+}
+
+/* Service a Tx-Available or dma completion irq for the endpoint */
+void musb_host_tx(struct musb *musb, u8 epnum)
+{
+ int pipe;
+ bool done = false;
+ u16 tx_csr;
+ size_t length = 0;
+ size_t offset = 0;
+ struct musb_hw_ep *hw_ep = musb->endpoints + epnum;
+ void __iomem *epio = hw_ep->regs;
+ struct musb_qh *qh = hw_ep->out_qh;
+ struct urb *urb = next_urb(qh);
+ u32 status = 0;
+ void __iomem *mbase = musb->mregs;
+ bool transfer_pending = false;
+
+ musb_ep_select(mbase, epnum);
+ tx_csr = musb_readw(epio, MUSB_TXCSR);
+
+ /* with CPPI, DMA sometimes triggers "extra" irqs */
+ if (!urb) {
+ dev_dbg(musb->controller, "extra TX%d ready, csr %04x\n", epnum, tx_csr);
+ return;
+ }
+
+ pipe = urb->pipe;
+ dev_dbg(musb->controller, "OUT/TX%d end, csr %04x\n", epnum, tx_csr);
+
+ /* check for errors */
+ if (tx_csr & MUSB_TXCSR_H_RXSTALL) {
+ /* dma was disabled, fifo flushed */
+ dev_dbg(musb->controller, "TX end %d stall\n", epnum);
+
+ /* stall; record URB status */
+ status = -EPIPE;
+
+ } else if (tx_csr & MUSB_TXCSR_H_ERROR) {
+ /* (NON-ISO) dma was disabled, fifo flushed */
+ dev_dbg(musb->controller, "TX 3strikes on ep=%d\n", epnum);
+
+ status = -ETIMEDOUT;
+
+ } else if (tx_csr & MUSB_TXCSR_H_NAKTIMEOUT) {
+ if (USB_ENDPOINT_XFER_BULK == qh->type && qh->mux == 1
+ && !list_is_singular(&musb->out_bulk)) {
+ dev_dbg(musb->controller,
+ "NAK timeout on TX%d ep\n", epnum);
+ musb_bulk_nak_timeout(musb, hw_ep, 0);
+ } else {
+ dev_dbg(musb->controller,
+ "TX end=%d device not responding\n", epnum);
+ /* NOTE: this code path would be a good place to PAUSE a
+ * transfer, if there's some other (nonperiodic) tx urb
+ * that could use this fifo. (dma complicates it...)
+ * That's already done for bulk RX transfers.
+ *
+ * if (bulk && qh->ring.next != &musb->out_bulk), then
+ * we have a candidate... NAKing is *NOT* an error
+ */
+ musb_ep_select(mbase, epnum);
+ musb_writew(epio, MUSB_TXCSR,
+ MUSB_TXCSR_H_WZC_BITS
+ | MUSB_TXCSR_TXPKTRDY);
+ }
+ return;
+ }
+
+ if (status) {
+ /* do the proper sequence to abort the transfer in the
+ * usb core; the dma engine should already be stopped.
+ */
+ musb_h_tx_flush_fifo(hw_ep);
+ tx_csr &= ~(MUSB_TXCSR_AUTOSET
+ | MUSB_TXCSR_DMAENAB
+ | MUSB_TXCSR_H_ERROR
+ | MUSB_TXCSR_H_RXSTALL
+ | MUSB_TXCSR_H_NAKTIMEOUT
+ );
+
+ musb_ep_select(mbase, epnum);
+ musb_writew(epio, MUSB_TXCSR, tx_csr);
+ /* REVISIT may need to clear FLUSHFIFO ... */
+ musb_writew(epio, MUSB_TXCSR, tx_csr);
+ musb_writeb(epio, MUSB_TXINTERVAL, 0);
+
+ done = true;
+ }
+
+ if (!status) {
+ length = qh->segsize;
+ qh->offset += length;
+
+ if (0) {
+ } else {
+ /* see if we need to send more data, or ZLP */
+ if (qh->segsize < qh->maxpacket)
+ done = true;
+ else if (qh->offset == urb->transfer_buffer_length
+ && !(urb->transfer_flags
+ & URB_ZERO_PACKET))
+ done = true;
+ if (!done) {
+ offset = qh->offset;
+ length = urb->transfer_buffer_length - offset;
+ transfer_pending = true;
+ }
+ }
+ }
+
+ /* urb->status != -EINPROGRESS means request has been faulted,
+ * so we must abort this transfer after cleanup
+ */
+ if (urb->status != -EINPROGRESS) {
+ done = true;
+ if (status == 0)
+ status = urb->status;
+ }
+
+ if (done) {
+ /* set status */
+ urb->status = status;
+ urb->actual_length = qh->offset;
+ musb_advance_schedule(musb, urb, hw_ep, USB_DIR_OUT);
+ return;
+ } else if (tx_csr & MUSB_TXCSR_DMAENAB) {
+ dev_dbg(musb->controller, "not complete, but DMA enabled?\n");
+ return;
+ }
+
+ /*
+ * PIO: start next packet in this URB.
+ *
+ * REVISIT: some docs say that when hw_ep->tx_double_buffered,
+ * (and presumably, FIFO is not half-full) we should write *two*
+ * packets before updating TXCSR; other docs disagree...
+ */
+ if (length > qh->maxpacket)
+ length = qh->maxpacket;
+
+ musb_write_fifo(hw_ep, length, urb->transfer_buffer + offset);
+
+ qh->segsize = length;
+
+ musb_ep_select(mbase, epnum);
+ musb_writew(epio, MUSB_TXCSR,
+ MUSB_TXCSR_H_WZC_BITS | MUSB_TXCSR_TXPKTRDY);
+}
+
+/*
+ * Service an RX interrupt for the given IN endpoint; docs cover bulk, iso,
+ * and high-bandwidth IN transfer cases.
+ */
+void musb_host_rx(struct musb *musb, u8 epnum)
+{
+ struct urb *urb;
+ struct musb_hw_ep *hw_ep = musb->endpoints + epnum;
+ void __iomem *epio = hw_ep->regs;
+ struct musb_qh *qh = hw_ep->in_qh;
+ size_t xfer_len;
+ void __iomem *mbase = musb->mregs;
+ int pipe;
+ u16 rx_csr, val;
+ bool iso_err = false;
+ bool done = false;
+ u32 status;
+
+ musb_ep_select(mbase, epnum);
+
+ urb = next_urb(qh);
+ status = 0;
+ xfer_len = 0;
+
+ rx_csr = musb_readw(epio, MUSB_RXCSR);
+ val = rx_csr;
+
+ if (unlikely(!urb)) {
+ /* REVISIT -- THIS SHOULD NEVER HAPPEN ... but, at least
+ * usbtest #11 (unlinks) triggers it regularly, sometimes
+ * with fifo full. (Only with DMA??)
+ */
+ dev_dbg(musb->controller, "BOGUS RX%d ready, csr %04x, count %d\n", epnum, val,
+ musb_readw(epio, MUSB_RXCOUNT));
+ musb_h_flush_rxfifo(hw_ep, MUSB_RXCSR_CLRDATATOG);
+ return;
+ }
+
+ pipe = urb->pipe;
+
+ dev_dbg(musb->controller, "<== hw %d rxcsr %04x, urb actual %d (+dma %zu)\n",
+ epnum, rx_csr, urb->actual_length, 0);
+
+ /* check for errors, concurrent stall & unlink is not really
+ * handled yet! */
+ if (rx_csr & MUSB_RXCSR_H_RXSTALL) {
+ dev_dbg(musb->controller, "RX end %d STALL\n", epnum);
+
+ /* stall; record URB status */
+ status = -EPIPE;
+
+ } else if (rx_csr & MUSB_RXCSR_H_ERROR) {
+ dev_dbg(musb->controller, "end %d RX proto error\n", epnum);
+
+ status = -EPROTO;
+ musb_writeb(epio, MUSB_RXINTERVAL, 0);
+
+ } else if (rx_csr & MUSB_RXCSR_DATAERROR) {
+
+ if (USB_ENDPOINT_XFER_ISOC != qh->type) {
+ dev_dbg(musb->controller, "RX end %d NAK timeout\n", epnum);
+
+ /* NOTE: NAKing is *NOT* an error, so we want to
+ * continue. Except ... if there's a request for
+ * another QH, use that instead of starving it.
+ *
+ * Devices like Ethernet and serial adapters keep
+ * reads posted at all times, which will starve
+ * other devices without this logic.
+ */
+ if (usb_pipebulk(urb->pipe)
+ && qh->mux == 1
+ && !list_is_singular(&musb->in_bulk)) {
+ musb_bulk_nak_timeout(musb, hw_ep, 1);
+ return;
+ }
+ musb_ep_select(mbase, epnum);
+ rx_csr |= MUSB_RXCSR_H_WZC_BITS;
+ rx_csr &= ~MUSB_RXCSR_DATAERROR;
+ musb_writew(epio, MUSB_RXCSR, rx_csr);
+
+ goto finish;
+ } else {
+ dev_dbg(musb->controller, "RX end %d ISO data error\n", epnum);
+ /* packet error reported later */
+ iso_err = true;
+ }
+ } else if (rx_csr & MUSB_RXCSR_INCOMPRX) {
+ dev_dbg(musb->controller, "end %d high bandwidth incomplete ISO packet RX\n",
+ epnum);
+ status = -EPROTO;
+ }
+
+ /* faults abort the transfer */
+ if (status) {
+ musb_h_flush_rxfifo(hw_ep, MUSB_RXCSR_CLRDATATOG);
+ musb_writeb(epio, MUSB_RXINTERVAL, 0);
+ done = true;
+ goto finish;
+ }
+
+ /* thorough shutdown for now ... given more precise fault handling
+ * and better queueing support, we might keep a DMA pipeline going
+ * while processing this irq for earlier completions.
+ */
+
+ if (rx_csr & MUSB_RXCSR_H_REQPKT) {
+ dev_dbg(musb->controller, "RXCSR%d %04x, reqpkt, len %zu%s\n", epnum, rx_csr,
+ xfer_len, "");
+ rx_csr &= ~MUSB_RXCSR_H_REQPKT;
+
+ musb_ep_select(mbase, epnum);
+ musb_writew(epio, MUSB_RXCSR,
+ MUSB_RXCSR_H_WZC_BITS | rx_csr);
+ }
+
+ if (urb->status == -EINPROGRESS) {
+ /* if no errors, be sure a packet is ready for unloading */
+ if (unlikely(!(rx_csr & MUSB_RXCSR_RXPKTRDY))) {
+ status = -EPROTO;
+ dev_err(musb->controller, "Rx interrupt with no errors or packet!\n");
+
+ /* FIXME this is another "SHOULD NEVER HAPPEN" */
+
+/* SCRUB (RX) */
+ /* do the proper sequence to abort the transfer */
+ musb_ep_select(mbase, epnum);
+ val &= ~MUSB_RXCSR_H_REQPKT;
+ musb_writew(epio, MUSB_RXCSR, val);
+ goto finish;
+ }
+
+ /* we are expecting IN packets */
+ if (1) {
+ done = musb_host_packet_rx(musb, urb,
+ epnum, iso_err);
+
+ dev_dbg(musb->controller, "read %spacket\n", done ? "last " : "");
+ }
+ }
+
+finish:
+ urb->actual_length += xfer_len;
+ qh->offset += xfer_len;
+ if (done) {
+
+ if (urb->status == -EINPROGRESS)
+ urb->status = status;
+ musb_advance_schedule(musb, urb, hw_ep, USB_DIR_IN);
+ }
+}
+
+/* schedule nodes correspond to peripheral endpoints, like an OHCI QH.
+ * the software schedule associates multiple such nodes with a given
+ * host side hardware endpoint + direction; scheduling may activate
+ * that hardware endpoint.
+ */
+static int musb_schedule(
+ struct musb *musb,
+ struct musb_qh *qh,
+ int is_in)
+{
+ int idle;
+ int best_diff;
+ int best_end, epnum;
+ struct musb_hw_ep *hw_ep = NULL;
+ struct list_head *head = NULL;
+ u8 toggle;
+ u8 txtype;
+ struct urb *urb = next_urb(qh);
+
+ /* use fixed hardware for control and bulk */
+ if (qh->type == USB_ENDPOINT_XFER_CONTROL) {
+ head = &musb->control;
+ hw_ep = musb->control_ep;
+ goto success;
+ }
+
+ /* else, periodic transfers get muxed to other endpoints */
+
+ /*
+ * We know this qh hasn't been scheduled, so all we need to do
+ * is choose which hardware endpoint to put it on ...
+ *
+ * REVISIT what we really want here is a regular schedule tree
+ * like e.g. OHCI uses.
+ */
+ best_diff = 4096;
+ best_end = -1;
+
+ for (epnum = 1, hw_ep = musb->endpoints + 1;
+ epnum < musb->nr_endpoints;
+ epnum++, hw_ep++) {
+ int diff;
+
+ if (musb_ep_get_qh(hw_ep, is_in) != NULL)
+ continue;
+
+ if (hw_ep == musb->bulk_ep)
+ continue;
+
+ if (is_in)
+ diff = hw_ep->max_packet_sz_rx;
+ else
+ diff = hw_ep->max_packet_sz_tx;
+ diff -= (qh->maxpacket * qh->hb_mult);
+
+ if (diff >= 0 && best_diff > diff) {
+
+ /*
+ * Mentor controller has a bug in that if we schedule
+ * a BULK Tx transfer on an endpoint that had earlier
+ * handled ISOC then the BULK transfer has to start on
+ * a zero toggle. If the BULK transfer starts on a 1
+ * toggle then this transfer will fail as the mentor
+ * controller starts the Bulk transfer on a 0 toggle
+ * irrespective of the programming of the toggle bits
+ * in the TXCSR register. Check for this condition
+ * while allocating the EP for a Tx Bulk transfer. If
+ * so skip this EP.
+ */
+ hw_ep = musb->endpoints + epnum;
+ toggle = usb_gettoggle(urb->dev, qh->epnum, !is_in);
+ txtype = (musb_readb(hw_ep->regs, MUSB_TXTYPE)
+ >> 4) & 0x3;
+ if (!is_in && (qh->type == USB_ENDPOINT_XFER_BULK) &&
+ toggle && (txtype == USB_ENDPOINT_XFER_ISOC))
+ continue;
+
+ best_diff = diff;
+ best_end = epnum;
+ }
+ }
+ /* use bulk reserved ep1 if no other ep is free */
+ if (best_end < 0 && qh->type == USB_ENDPOINT_XFER_BULK) {
+ hw_ep = musb->bulk_ep;
+ if (is_in)
+ head = &musb->in_bulk;
+ else
+ head = &musb->out_bulk;
+
+ /* Enable bulk RX/TX NAK timeout scheme when bulk requests are
+ * multiplexed. This scheme doen't work in high speed to full
+ * speed scenario as NAK interrupts are not coming from a
+ * full speed device connected to a high speed device.
+ * NAK timeout interval is 8 (128 uframe or 16ms) for HS and
+ * 4 (8 frame or 8ms) for FS device.
+ */
+ if (qh->dev)
+ qh->intv_reg =
+ (USB_SPEED_HIGH == qh->dev->speed) ? 8 : 4;
+ goto success;
+ } else if (best_end < 0) {
+ return -ENOSPC;
+ }
+
+ idle = 1;
+ qh->mux = 0;
+ hw_ep = musb->endpoints + best_end;
+ dev_dbg(musb->controller, "qh %p periodic slot %d\n", qh, best_end);
+success:
+ if (head) {
+ idle = list_empty(head);
+ list_add_tail(&qh->ring, head);
+ qh->mux = 1;
+ }
+ qh->hw_ep = hw_ep;
+ qh->hep->hcpriv = qh;
+ if (idle)
+ musb_start_urb(musb, is_in, qh);
+ return 0;
+}
+
+
+/* check if transaction translator is needed for device */
+static int tt_needed(struct musb *musb, struct usb_device *dev)
+{
+ if ((musb_readb(musb->mregs, MUSB_POWER) & MUSB_POWER_HSMODE) &&
+ (dev->speed < USB_SPEED_HIGH))
+ return 1;
+ return 0;
+}
+
+int musb_urb_enqueue(
+ struct usb_hcd *hcd,
+ struct urb *urb,
+ gfp_t mem_flags)
+{
+ unsigned long flags;
+ struct musb *musb = hcd_to_musb(hcd);
+ struct usb_host_endpoint *hep = urb->ep;
+ struct musb_qh *qh;
+ struct usb_endpoint_descriptor *epd = &hep->desc;
+ int ret;
+ unsigned type_reg;
+ unsigned interval;
+ /* host role must be active */
+ if (!is_host_active(musb) || !musb->is_active)
+ return -ENODEV;
+
+ spin_lock_irqsave(&musb->lock, flags);
+ ret = usb_hcd_link_urb_to_ep(hcd, urb);
+ qh = ret ? NULL : hep->hcpriv;
+ if (qh)
+ urb->hcpriv = qh;
+ spin_unlock_irqrestore(&musb->lock, flags);
+
+ /* DMA mapping was already done, if needed, and this urb is on
+ * hep->urb_list now ... so we're done, unless hep wasn't yet
+ * scheduled onto a live qh.
+ *
+ * REVISIT best to keep hep->hcpriv valid until the endpoint gets
+ * disabled, testing for empty qh->ring and avoiding qh setup costs
+ * except for the first urb queued after a config change.
+ */
+ if (qh || ret)
+ return ret;
+
+ /* Allocate and initialize qh, minimizing the work done each time
+ * hw_ep gets reprogrammed, or with irqs blocked. Then schedule it.
+ *
+ * REVISIT consider a dedicated qh kmem_cache, so it's harder
+ * for bugs in other kernel code to break this driver...
+ */
+ qh = kzalloc(sizeof *qh, mem_flags);
+ if (!qh) {
+ spin_lock_irqsave(&musb->lock, flags);
+ usb_hcd_unlink_urb_from_ep(hcd, urb);
+ spin_unlock_irqrestore(&musb->lock, flags);
+ return -ENOMEM;
+ }
+
+ qh->hep = hep;
+ qh->dev = urb->dev;
+ INIT_LIST_HEAD(&qh->ring);
+ qh->is_ready = 1;
+
+ qh->maxpacket = usb_endpoint_maxp(epd);
+ qh->type = usb_endpoint_type(epd);
+
+ /* Bits 11 & 12 of wMaxPacketSize encode high bandwidth multiplier.
+ * Some musb cores don't support high bandwidth ISO transfers; and
+ * we don't (yet!) support high bandwidth interrupt transfers.
+ */
+ qh->hb_mult = 1 + ((qh->maxpacket >> 11) & 0x03);
+ if (qh->hb_mult > 1) {
+ int ok = (qh->type == USB_ENDPOINT_XFER_ISOC);
+
+ if (ok)
+ ok = (usb_pipein(urb->pipe) && musb->hb_iso_rx)
+ || (usb_pipeout(urb->pipe) && musb->hb_iso_tx);
+ if (!ok) {
+ ret = -EMSGSIZE;
+ goto done;
+ }
+ qh->maxpacket &= 0x7ff;
+ }
+
+ qh->epnum = usb_endpoint_num(epd);
+
+ /* NOTE: urb->dev->devnum is wrong during SET_ADDRESS */
+ qh->addr_reg = (u8) usb_pipedevice(urb->pipe);
+
+ /* precompute rxtype/txtype/type0 register */
+ type_reg = (qh->type << 4) | qh->epnum;
+ switch (urb->dev->speed) {
+ case USB_SPEED_LOW:
+ type_reg |= 0xc0;
+ break;
+ case USB_SPEED_FULL:
+ type_reg |= 0x80;
+ break;
+ default:
+ type_reg |= 0x40;
+ }
+ qh->type_reg = type_reg;
+
+ /* Precompute RXINTERVAL/TXINTERVAL register */
+ switch (qh->type) {
+ case USB_ENDPOINT_XFER_INT:
+ /*
+ * Full/low speeds use the linear encoding,
+ * high speed uses the logarithmic encoding.
+ */
+ if (urb->dev->speed <= USB_SPEED_FULL) {
+ interval = max_t(u8, epd->bInterval, 1);
+ break;
+ }
+ /* FALLTHROUGH */
+ case USB_ENDPOINT_XFER_ISOC:
+ /* ISO always uses logarithmic encoding */
+ interval = min_t(u8, epd->bInterval, 16);
+ break;
+ default:
+ /* REVISIT we actually want to use NAK limits, hinting to the
+ * transfer scheduling logic to try some other qh, e.g. try
+ * for 2 msec first:
+ *
+ * interval = (USB_SPEED_HIGH == urb->dev->speed) ? 16 : 2;
+ *
+ * The downside of disabling this is that transfer scheduling
+ * gets VERY unfair for nonperiodic transfers; a misbehaving
+ * peripheral could make that hurt. That's perfectly normal
+ * for reads from network or serial adapters ... so we have
+ * partial NAKlimit support for bulk RX.
+ *
+ * The upside of disabling it is simpler transfer scheduling.
+ */
+ interval = 0;
+ }
+ qh->intv_reg = interval;
+
+ /* precompute addressing for external hub/tt ports */
+ if (musb->is_multipoint) {
+ struct usb_device *parent = urb->dev->parent;
+
+ if (parent) {
+ qh->h_addr_reg = (u8) parent->devnum;
+
+ if (tt_needed(musb, urb->dev)) {
+ u16 hub_port = find_tt(urb->dev);
+ qh->h_addr_reg = (u8) (hub_port >> 8);
+ qh->h_port_reg = (u8) (hub_port & 0xff);
+ }
+ }
+ }
+
+ /* invariant: hep->hcpriv is null OR the qh that's already scheduled.
+ * until we get real dma queues (with an entry for each urb/buffer),
+ * we only have work to do in the former case.
+ */
+ spin_lock_irqsave(&musb->lock, flags);
+ if (hep->hcpriv || !next_urb(qh)) {
+ /* some concurrent activity submitted another urb to hep...
+ * odd, rare, error prone, but legal.
+ */
+ kfree(qh);
+ qh = NULL;
+ ret = 0;
+ } else
+ ret = musb_schedule(musb, qh,
+ epd->bEndpointAddress & USB_ENDPOINT_DIR_MASK);
+
+ if (ret == 0) {
+ urb->hcpriv = qh;
+ /* FIXME set urb->start_frame for iso/intr, it's tested in
+ * musb_start_urb(), but otherwise only konicawc cares ...
+ */
+ }
+ spin_unlock_irqrestore(&musb->lock, flags);
+
+done:
+ if (ret != 0) {
+ spin_lock_irqsave(&musb->lock, flags);
+ usb_hcd_unlink_urb_from_ep(hcd, urb);
+ spin_unlock_irqrestore(&musb->lock, flags);
+ kfree(qh);
+ }
+ return ret;
+}
+
+/*
+ * abort a transfer that's at the head of a hardware queue.
+ * called with controller locked, irqs blocked
+ * that hardware queue advances to the next transfer, unless prevented
+ */
+static noinline int musb_cleanup_urb(struct urb *urb, struct musb_qh *qh)
+{
+ struct musb_hw_ep *ep = qh->hw_ep;
+ void __iomem *epio = ep->regs;
+ unsigned hw_end = ep->epnum;
+ void __iomem *regs = ep->musb->mregs;
+ int is_in = usb_pipein(urb->pipe);
+ int status = 0;
+ u16 csr;
+
+ musb_ep_select(regs, hw_end);
+
+ /* turn off DMA requests, discard state, stop polling ... */
+ if (ep->epnum && is_in) {
+ /* giveback saves bulk toggle */
+ csr = musb_h_flush_rxfifo(ep, 0);
+
+ /* REVISIT we still get an irq; should likely clear the
+ * endpoint's irq status here to avoid bogus irqs.
+ * clearing that status is platform-specific...
+ */
+ } else if (ep->epnum) {
+ musb_h_tx_flush_fifo(ep);
+ csr = musb_readw(epio, MUSB_TXCSR);
+ csr &= ~(MUSB_TXCSR_AUTOSET
+ | MUSB_TXCSR_DMAENAB
+ | MUSB_TXCSR_H_RXSTALL
+ | MUSB_TXCSR_H_NAKTIMEOUT
+ | MUSB_TXCSR_H_ERROR
+ | MUSB_TXCSR_TXPKTRDY);
+ musb_writew(epio, MUSB_TXCSR, csr);
+ /* REVISIT may need to clear FLUSHFIFO ... */
+ musb_writew(epio, MUSB_TXCSR, csr);
+ /* flush cpu writebuffer */
+ csr = musb_readw(epio, MUSB_TXCSR);
+ } else {
+ musb_h_ep0_flush_fifo(ep);
+ }
+ if (status == 0)
+ musb_advance_schedule(ep->musb, urb, ep, is_in);
+ return status;
+}
+
+int musb_urb_dequeue(struct usb_hcd *hcd, struct urb *urb, int status)
+{
+ struct musb *musb = hcd_to_musb(hcd);
+ struct musb_qh *qh;
+ unsigned long flags;
+ int is_in = usb_pipein(urb->pipe);
+ int ret = 0;
+
+ dev_dbg(musb->controller, "urb=%p, dev%d ep%d%s\n", urb,
+ usb_pipedevice(urb->pipe),
+ usb_pipeendpoint(urb->pipe),
+ is_in ? "in" : "out");
+
+ spin_lock_irqsave(&musb->lock, flags);
+
+ qh = urb->hcpriv;
+ if (!qh)
+ goto done;
+
+ /*
+ * Any URB not actively programmed into endpoint hardware can be
+ * immediately given back; that's any URB not at the head of an
+ * endpoint queue, unless someday we get real DMA queues. And even
+ * if it's at the head, it might not be known to the hardware...
+ *
+ * Otherwise abort current transfer, pending DMA, etc.; urb->status
+ * has already been updated. This is a synchronous abort; it'd be
+ * OK to hold off until after some IRQ, though.
+ *
+ * NOTE: qh is invalid unless !list_empty(&hep->urb_list)
+ */
+ if (!qh->is_ready
+ || urb->urb_list.prev != &qh->hep->urb_list
+ || musb_ep_get_qh(qh->hw_ep, is_in) != qh) {
+ int ready = qh->is_ready;
+
+ qh->is_ready = 0;
+ musb_giveback(musb, urb, 0);
+ qh->is_ready = ready;
+
+ /* If nothing else (usually musb_giveback) is using it
+ * and its URB list has emptied, recycle this qh.
+ */
+ if (ready && list_empty(&qh->hep->urb_list)) {
+ qh->hep->hcpriv = NULL;
+ list_del(&qh->ring);
+ kfree(qh);
+ }
+ } else
+ ret = musb_cleanup_urb(urb, qh);
+done:
+ spin_unlock_irqrestore(&musb->lock, flags);
+ return ret;
+}
+
+int musb_host_alloc(struct musb *musb)
+{
+ /* usbcore sets dev->driver_data to hcd, and sometimes uses that... */
+ musb->hcd = xzalloc(sizeof(struct usb_hcd));
+ if (!musb->hcd)
+ return -EINVAL;
+
+ musb->hcd->hcd_priv = musb;
+
+ return 0;
+}
+
+void musb_host_free(struct musb *musb)
+{
+}
+
+int musb_host_setup(struct musb *musb, int power_budget)
+{
+ struct usb_hcd *hcd = musb->hcd;
+
+ MUSB_HST_MODE(musb);
+
+ hcd->self.otg_port = 1;
+
+ return 0;
+}
+
+void musb_host_resume_root_hub(struct musb *musb)
+{
+}
+
+void musb_host_poke_root_hub(struct musb *musb)
+{
+}
diff --git a/drivers/usb/musb/musb_host.h b/drivers/usb/musb/musb_host.h
new file mode 100644
index 0000000000..0937808de8
--- /dev/null
+++ b/drivers/usb/musb/musb_host.h
@@ -0,0 +1,258 @@
+/*
+ * MUSB OTG driver host defines
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#ifndef _MUSB_HOST_H
+#define _MUSB_HOST_H
+
+//#include <linux/scatterlist.h>
+#include <linux/list.h>
+#include <usb/usb.h>
+#include <asm/unaligned.h>
+
+/*
+ * urb->transfer_flags:
+ *
+ * Note: URB_DIR_IN/OUT is automatically set in usb_submit_urb().
+ */
+#define URB_SHORT_NOT_OK 0x0001 /* report short reads as errors. */
+#define URB_ZERO_PACKET 0x0040 /* Finish bulk OUT with short packet */
+
+#define usb_hcd_link_urb_to_ep(hcd, urb) ({ \
+ int ret = 0; \
+ list_add_tail(&urb->urb_list, &urb->ep->urb_list); \
+ ret; })
+
+#define usb_hcd_unlink_urb_from_ep(hcd, urb) list_del_init(&urb->urb_list)
+
+struct ep_device;
+struct urb;
+
+typedef void (*usb_complete_t)(struct urb *urb);
+
+struct urb {
+ void *hcpriv; /* private data for host controller */
+ struct list_head urb_list; /* list head for use by the urb's
+ * current owner */
+ struct usb_device *dev; /* (in) pointer to associated device */
+ struct usb_host_endpoint *ep; /* (internal) pointer to endpoint */
+ unsigned int pipe; /* (in) pipe information */
+ int status; /* (return) non-ISO status */
+ unsigned int transfer_flags; /* (in) URB_SHORT_NOT_OK | ...*/
+ void *transfer_buffer; /* (in) associated data buffer */
+ dma_addr_t transfer_dma; /* (in) dma addr for transfer_buffer */
+ u32 transfer_buffer_length; /* (in) data buffer length */
+ u32 actual_length; /* (return) actual transfer length */
+ unsigned char *setup_packet; /* (in) setup packet (control only) */
+ int start_frame; /* (modify) start frame (ISO) */
+ int error_count; /* (return) number of ISO errors */
+ usb_complete_t complete; /* (in) completion routine */
+};
+
+#define USB_DT_SS_EP_COMP_SIZE 6
+
+/**
+ * struct usb_host_endpoint - host-side endpoint descriptor and queue
+ * @desc: descriptor for this endpoint, wMaxPacketSize in native byteorder
+ * @ss_ep_comp: SuperSpeed companion descriptor for this endpoint
+ * @urb_list: urbs queued to this endpoint; maintained by usbcore
+ * @hcpriv: for use by HCD; typically holds hardware dma queue head (QH)
+ * with one or more transfer descriptors (TDs) per urb
+ * @ep_dev: ep_device for sysfs info
+ * @extra: descriptors following this endpoint in the configuration
+ * @extralen: how many bytes of "extra" are valid
+ * @enabled: URBs may be submitted to this endpoint
+ *
+ * USB requests are always queued to a given endpoint, identified by a
+ * descriptor within an active interface in a given USB configuration.
+ */
+struct usb_host_endpoint {
+ struct usb_endpoint_descriptor desc;
+ struct usb_ss_ep_comp_descriptor ss_ep_comp;
+ struct list_head urb_list;
+ void *hcpriv;
+ //struct ep_device *ep_dev; /* For sysfs info */
+
+ unsigned char *extra; /* Extra descriptors */
+ int extralen;
+ int enabled;
+};
+
+/* stored in "usb_host_endpoint.hcpriv" for scheduled endpoints */
+struct musb_qh {
+ struct usb_host_endpoint *hep; /* usbcore info */
+ struct usb_device *dev;
+ struct musb_hw_ep *hw_ep; /* current binding */
+
+ struct list_head ring; /* of musb_qh */
+ /* struct musb_qh *next; */ /* for periodic tree */
+ u8 mux; /* qh multiplexed to hw_ep */
+
+ unsigned offset; /* in urb->transfer_buffer */
+ unsigned segsize; /* current xfer fragment */
+
+ u8 type_reg; /* {rx,tx} type register */
+ u8 intv_reg; /* {rx,tx} interval register */
+ u8 addr_reg; /* device address register */
+ u8 h_addr_reg; /* hub address register */
+ u8 h_port_reg; /* hub port register */
+
+ u8 is_ready; /* safe to modify hw_ep */
+ u8 type; /* XFERTYPE_* */
+ u8 epnum;
+ u8 hb_mult; /* high bandwidth pkts per uf */
+ u16 maxpacket;
+ u16 frame; /* for periodic schedule */
+ unsigned iso_idx; /* in urb->iso_frame_desc[] */
+ //struct sg_mapping_iter sg_miter; /* for highmem in PIO mode */
+ //bool use_sg; /* to track urb using sglist */
+};
+
+/* map from control or bulk queue head to the first qh on that ring */
+static inline struct musb_qh *first_qh(struct list_head *q)
+{
+ if (list_empty(q))
+ return NULL;
+ return list_entry(q->next, struct musb_qh, ring);
+}
+
+struct usb_hcd;
+
+#if IS_ENABLED(CONFIG_USB_MUSB_HOST)
+extern struct musb *hcd_to_musb(struct usb_hcd *);
+extern irqreturn_t musb_h_ep0_irq(struct musb *);
+extern int musb_host_alloc(struct musb *);
+extern int musb_host_setup(struct musb *, int);
+extern void musb_root_disconnect(struct musb *musb);
+extern void musb_host_free(struct musb *);
+extern void musb_host_cleanup(struct musb *);
+extern void musb_host_tx(struct musb *, u8);
+extern void musb_host_rx(struct musb *, u8);
+extern void musb_host_resume_root_hub(struct musb *musb);
+extern void musb_host_poke_root_hub(struct musb *musb);
+extern void musb_port_reset(struct musb *musb, bool do_reset);
+#else
+static inline struct musb *hcd_to_musb(struct usb_hcd *hcd)
+{
+ return NULL;
+}
+
+static inline irqreturn_t musb_h_ep0_irq(struct musb *musb)
+{
+ return 0;
+}
+
+static inline int musb_host_alloc(struct musb *musb)
+{
+ return 0;
+}
+
+static inline int musb_host_setup(struct musb *musb, int power_budget)
+{
+ return 0;
+}
+
+static inline void musb_host_cleanup(struct musb *musb) {}
+static inline void musb_host_free(struct musb *musb) {}
+static inline void musb_host_tx(struct musb *musb, u8 epnum) {}
+static inline void musb_host_rx(struct musb *musb, u8 epnum) {}
+static inline void musb_root_disconnect(struct musb *musb) {}
+static inline void musb_host_resume_root_hub(struct musb *musb) {}
+static inline void musb_host_poll_rh_status(struct musb *musb) {}
+static inline void musb_host_poke_root_hub(struct musb *musb) {}
+static inline void musb_port_reset(struct musb *musb, bool do_reset) {}
+#endif
+
+struct usb_hcd;
+
+extern int musb_hub_status_data(struct usb_hcd *hcd, char *buf);
+extern int musb_hub_control(struct usb_hcd *hcd,
+ u16 typeReq, u16 wValue, u16 wIndex,
+ char *buf, u16 wLength);
+
+static inline struct urb *next_urb(struct musb_qh *qh)
+{
+ struct list_head *queue;
+
+ if (!qh)
+ return NULL;
+ queue = &qh->hep->urb_list;
+ if (list_empty(queue))
+ return NULL;
+ return list_entry(queue->next, struct urb, urb_list);
+}
+
+/*
+ * Endpoints
+ */
+#define USB_ENDPOINT_NUMBER_MASK 0x0f /* in bEndpointAddress */
+#define USB_ENDPOINT_XFERTYPE_MASK 0x03 /* in bmAttributes */
+
+static inline u16 find_tt(struct usb_device *dev)
+{
+ u8 chid;
+ u8 hub;
+
+ /* Find out the nearest parent which is high speed */
+ while (dev->parent->parent != NULL)
+ if (dev->parent->speed != USB_SPEED_HIGH)
+ dev = dev->parent;
+ else
+ break;
+
+ /* determine the port address at that hub */
+ hub = dev->parent->devnum;
+ for (chid = 0; chid < USB_MAXCHILDREN; chid++)
+ if (dev->parent->children[chid] == dev)
+ break;
+
+ return (hub << 8) | chid;
+}
+
+int musb_urb_enqueue(
+ struct usb_hcd *hcd,
+ struct urb *urb,
+ gfp_t mem_flags);
+
+int musb_urb_dequeue(struct usb_hcd *hcd, struct urb *urb, int status);
+
+static inline void usb_hcd_giveback_urb(struct usb_hcd *hcd,
+ struct urb *urb,
+ int status)
+{
+ urb->status = status;
+ if (urb->complete)
+ urb->complete(urb);
+}
+
+#endif /* _MUSB_HOST_H */
diff --git a/drivers/usb/musb/musb_io.h b/drivers/usb/musb/musb_io.h
new file mode 100644
index 0000000000..a4be339355
--- /dev/null
+++ b/drivers/usb/musb/musb_io.h
@@ -0,0 +1,122 @@
+/*
+ * MUSB OTG driver register I/O
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#ifndef __MUSB_LINUX_PLATFORM_ARCH_H__
+#define __MUSB_LINUX_PLATFORM_ARCH_H__
+
+#include <io.h>
+
+#ifndef CONFIG_BLACKFIN
+
+/* NOTE: these offsets are all in bytes */
+
+static inline u16 musb_readw(const void __iomem *addr, unsigned offset)
+ { return __raw_readw(addr + offset); }
+
+static inline u32 musb_readl(const void __iomem *addr, unsigned offset)
+ { return __raw_readl(addr + offset); }
+
+
+static inline void musb_writew(void __iomem *addr, unsigned offset, u16 data)
+ { __raw_writew(data, addr + offset); }
+
+static inline void musb_writel(void __iomem *addr, unsigned offset, u32 data)
+ { __raw_writel(data, addr + offset); }
+
+
+#if defined(CONFIG_USB_MUSB_TUSB6010) || defined (CONFIG_USB_MUSB_TUSB6010_MODULE)
+
+/*
+ * TUSB6010 doesn't allow 8-bit access; 16-bit access is the minimum.
+ */
+static inline u8 musb_readb(const void __iomem *addr, unsigned offset)
+{
+ u16 tmp;
+ u8 val;
+
+ tmp = __raw_readw(addr + (offset & ~1));
+ if (offset & 1)
+ val = (tmp >> 8);
+ else
+ val = tmp & 0xff;
+
+ return val;
+}
+
+static inline void musb_writeb(void __iomem *addr, unsigned offset, u8 data)
+{
+ u16 tmp;
+
+ tmp = __raw_readw(addr + (offset & ~1));
+ if (offset & 1)
+ tmp = (data << 8) | (tmp & 0xff);
+ else
+ tmp = (tmp & 0xff00) | data;
+
+ __raw_writew(tmp, addr + (offset & ~1));
+}
+
+#else
+
+static inline u8 musb_readb(const void __iomem *addr, unsigned offset)
+ { return __raw_readb(addr + offset); }
+
+static inline void musb_writeb(void __iomem *addr, unsigned offset, u8 data)
+ { __raw_writeb(data, addr + offset); }
+
+#endif /* CONFIG_USB_MUSB_TUSB6010 */
+
+#else
+
+static inline u8 musb_readb(const void __iomem *addr, unsigned offset)
+ { return (u8) (bfin_read16(addr + offset)); }
+
+static inline u16 musb_readw(const void __iomem *addr, unsigned offset)
+ { return bfin_read16(addr + offset); }
+
+static inline u32 musb_readl(const void __iomem *addr, unsigned offset)
+ { return (u32) (bfin_read16(addr + offset)); }
+
+static inline void musb_writeb(void __iomem *addr, unsigned offset, u8 data)
+ { bfin_write16(addr + offset, (u16) data); }
+
+static inline void musb_writew(void __iomem *addr, unsigned offset, u16 data)
+ { bfin_write16(addr + offset, data); }
+
+static inline void musb_writel(void __iomem *addr, unsigned offset, u32 data)
+ { bfin_write16(addr + offset, (u16) data); }
+
+#endif /* CONFIG_BLACKFIN */
+
+#endif
diff --git a/drivers/usb/musb/musb_regs.h b/drivers/usb/musb/musb_regs.h
new file mode 100644
index 0000000000..b9bcda5e39
--- /dev/null
+++ b/drivers/usb/musb/musb_regs.h
@@ -0,0 +1,652 @@
+/*
+ * MUSB OTG driver register defines
+ *
+ * Copyright 2005 Mentor Graphics Corporation
+ * Copyright (C) 2005-2006 by Texas Instruments
+ * Copyright (C) 2006-2007 Nokia Corporation
+ *
+ * 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, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * THIS SOFTWARE IS PROVIDED "AS IS" AND ANY EXPRESS OR IMPLIED
+ * WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN
+ * NO EVENT SHALL THE AUTHORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF
+ * USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ * ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ *
+ */
+
+#ifndef __MUSB_REGS_H__
+#define __MUSB_REGS_H__
+
+#define MUSB_EP0_FIFOSIZE 64 /* This is non-configurable */
+
+/*
+ * MUSB Register bits
+ */
+
+/* POWER */
+#define MUSB_POWER_ISOUPDATE 0x80
+#define MUSB_POWER_SOFTCONN 0x40
+#define MUSB_POWER_HSENAB 0x20
+#define MUSB_POWER_HSMODE 0x10
+#define MUSB_POWER_RESET 0x08
+#define MUSB_POWER_RESUME 0x04
+#define MUSB_POWER_SUSPENDM 0x02
+#define MUSB_POWER_ENSUSPEND 0x01
+
+/* INTRUSB */
+#define MUSB_INTR_SUSPEND 0x01
+#define MUSB_INTR_RESUME 0x02
+#define MUSB_INTR_RESET 0x04
+#define MUSB_INTR_BABBLE 0x04
+#define MUSB_INTR_SOF 0x08
+#define MUSB_INTR_CONNECT 0x10
+#define MUSB_INTR_DISCONNECT 0x20
+#define MUSB_INTR_SESSREQ 0x40
+#define MUSB_INTR_VBUSERROR 0x80 /* For SESSION end */
+
+/* DEVCTL */
+#define MUSB_DEVCTL_BDEVICE 0x80
+#define MUSB_DEVCTL_FSDEV 0x40
+#define MUSB_DEVCTL_LSDEV 0x20
+#define MUSB_DEVCTL_VBUS 0x18
+#define MUSB_DEVCTL_VBUS_SHIFT 3
+#define MUSB_DEVCTL_HM 0x04
+#define MUSB_DEVCTL_HR 0x02
+#define MUSB_DEVCTL_SESSION 0x01
+
+/* BABBLE_CTL */
+#define MUSB_BABBLE_FORCE_TXIDLE 0x80
+#define MUSB_BABBLE_SW_SESSION_CTRL 0x40
+#define MUSB_BABBLE_STUCK_J 0x20
+#define MUSB_BABBLE_RCV_DISABLE 0x04
+
+/* MUSB ULPI VBUSCONTROL */
+#define MUSB_ULPI_USE_EXTVBUS 0x01
+#define MUSB_ULPI_USE_EXTVBUSIND 0x02
+/* ULPI_REG_CONTROL */
+#define MUSB_ULPI_REG_REQ (1 << 0)
+#define MUSB_ULPI_REG_CMPLT (1 << 1)
+#define MUSB_ULPI_RDN_WR (1 << 2)
+
+/* TESTMODE */
+#define MUSB_TEST_FORCE_HOST 0x80
+#define MUSB_TEST_FIFO_ACCESS 0x40
+#define MUSB_TEST_FORCE_FS 0x20
+#define MUSB_TEST_FORCE_HS 0x10
+#define MUSB_TEST_PACKET 0x08
+#define MUSB_TEST_K 0x04
+#define MUSB_TEST_J 0x02
+#define MUSB_TEST_SE0_NAK 0x01
+
+/* Allocate for double-packet buffering (effectively doubles assigned _SIZE) */
+#define MUSB_FIFOSZ_DPB 0x10
+/* Allocation size (8, 16, 32, ... 4096) */
+#define MUSB_FIFOSZ_SIZE 0x0f
+
+/* CSR0 */
+#define MUSB_CSR0_FLUSHFIFO 0x0100
+#define MUSB_CSR0_TXPKTRDY 0x0002
+#define MUSB_CSR0_RXPKTRDY 0x0001
+
+/* CSR0 in Peripheral mode */
+#define MUSB_CSR0_P_SVDSETUPEND 0x0080
+#define MUSB_CSR0_P_SVDRXPKTRDY 0x0040
+#define MUSB_CSR0_P_SENDSTALL 0x0020
+#define MUSB_CSR0_P_SETUPEND 0x0010
+#define MUSB_CSR0_P_DATAEND 0x0008
+#define MUSB_CSR0_P_SENTSTALL 0x0004
+
+/* CSR0 in Host mode */
+#define MUSB_CSR0_H_DIS_PING 0x0800
+#define MUSB_CSR0_H_WR_DATATOGGLE 0x0400 /* Set to allow setting: */
+#define MUSB_CSR0_H_DATATOGGLE 0x0200 /* Data toggle control */
+#define MUSB_CSR0_H_NAKTIMEOUT 0x0080
+#define MUSB_CSR0_H_STATUSPKT 0x0040
+#define MUSB_CSR0_H_REQPKT 0x0020
+#define MUSB_CSR0_H_ERROR 0x0010
+#define MUSB_CSR0_H_SETUPPKT 0x0008
+#define MUSB_CSR0_H_RXSTALL 0x0004
+
+/* CSR0 bits to avoid zeroing (write zero clears, write 1 ignored) */
+#define MUSB_CSR0_P_WZC_BITS \
+ (MUSB_CSR0_P_SENTSTALL)
+#define MUSB_CSR0_H_WZC_BITS \
+ (MUSB_CSR0_H_NAKTIMEOUT | MUSB_CSR0_H_RXSTALL \
+ | MUSB_CSR0_RXPKTRDY)
+
+/* TxType/RxType */
+#define MUSB_TYPE_SPEED 0xc0
+#define MUSB_TYPE_SPEED_SHIFT 6
+#define MUSB_TYPE_PROTO 0x30 /* Implicitly zero for ep0 */
+#define MUSB_TYPE_PROTO_SHIFT 4
+#define MUSB_TYPE_REMOTE_END 0xf /* Implicitly zero for ep0 */
+
+/* CONFIGDATA */
+#define MUSB_CONFIGDATA_MPRXE 0x80 /* Auto bulk pkt combining */
+#define MUSB_CONFIGDATA_MPTXE 0x40 /* Auto bulk pkt splitting */
+#define MUSB_CONFIGDATA_BIGENDIAN 0x20
+#define MUSB_CONFIGDATA_HBRXE 0x10 /* HB-ISO for RX */
+#define MUSB_CONFIGDATA_HBTXE 0x08 /* HB-ISO for TX */
+#define MUSB_CONFIGDATA_DYNFIFO 0x04 /* Dynamic FIFO sizing */
+#define MUSB_CONFIGDATA_SOFTCONE 0x02 /* SoftConnect */
+#define MUSB_CONFIGDATA_UTMIDW 0x01 /* Data width 0/1 => 8/16bits */
+
+/* TXCSR in Peripheral and Host mode */
+#define MUSB_TXCSR_AUTOSET 0x8000
+#define MUSB_TXCSR_DMAENAB 0x1000
+#define MUSB_TXCSR_FRCDATATOG 0x0800
+#define MUSB_TXCSR_DMAMODE 0x0400
+#define MUSB_TXCSR_CLRDATATOG 0x0040
+#define MUSB_TXCSR_FLUSHFIFO 0x0008
+#define MUSB_TXCSR_FIFONOTEMPTY 0x0002
+#define MUSB_TXCSR_TXPKTRDY 0x0001
+
+/* TXCSR in Peripheral mode */
+#define MUSB_TXCSR_P_ISO 0x4000
+#define MUSB_TXCSR_P_INCOMPTX 0x0080
+#define MUSB_TXCSR_P_SENTSTALL 0x0020
+#define MUSB_TXCSR_P_SENDSTALL 0x0010
+#define MUSB_TXCSR_P_UNDERRUN 0x0004
+
+/* TXCSR in Host mode */
+#define MUSB_TXCSR_H_WR_DATATOGGLE 0x0200
+#define MUSB_TXCSR_H_DATATOGGLE 0x0100
+#define MUSB_TXCSR_H_NAKTIMEOUT 0x0080
+#define MUSB_TXCSR_H_RXSTALL 0x0020
+#define MUSB_TXCSR_H_ERROR 0x0004
+
+/* TXCSR bits to avoid zeroing (write zero clears, write 1 ignored) */
+#define MUSB_TXCSR_P_WZC_BITS \
+ (MUSB_TXCSR_P_INCOMPTX | MUSB_TXCSR_P_SENTSTALL \
+ | MUSB_TXCSR_P_UNDERRUN | MUSB_TXCSR_FIFONOTEMPTY)
+#define MUSB_TXCSR_H_WZC_BITS \
+ (MUSB_TXCSR_H_NAKTIMEOUT | MUSB_TXCSR_H_RXSTALL \
+ | MUSB_TXCSR_H_ERROR | MUSB_TXCSR_FIFONOTEMPTY)
+
+/* RXCSR in Peripheral and Host mode */
+#define MUSB_RXCSR_AUTOCLEAR 0x8000
+#define MUSB_RXCSR_DMAENAB 0x2000
+#define MUSB_RXCSR_DISNYET 0x1000
+#define MUSB_RXCSR_PID_ERR 0x1000
+#define MUSB_RXCSR_DMAMODE 0x0800
+#define MUSB_RXCSR_INCOMPRX 0x0100
+#define MUSB_RXCSR_CLRDATATOG 0x0080
+#define MUSB_RXCSR_FLUSHFIFO 0x0010
+#define MUSB_RXCSR_DATAERROR 0x0008
+#define MUSB_RXCSR_FIFOFULL 0x0002
+#define MUSB_RXCSR_RXPKTRDY 0x0001
+
+/* RXCSR in Peripheral mode */
+#define MUSB_RXCSR_P_ISO 0x4000
+#define MUSB_RXCSR_P_SENTSTALL 0x0040
+#define MUSB_RXCSR_P_SENDSTALL 0x0020
+#define MUSB_RXCSR_P_OVERRUN 0x0004
+
+/* RXCSR in Host mode */
+#define MUSB_RXCSR_H_AUTOREQ 0x4000
+#define MUSB_RXCSR_H_WR_DATATOGGLE 0x0400
+#define MUSB_RXCSR_H_DATATOGGLE 0x0200
+#define MUSB_RXCSR_H_RXSTALL 0x0040
+#define MUSB_RXCSR_H_REQPKT 0x0020
+#define MUSB_RXCSR_H_ERROR 0x0004
+
+/* RXCSR bits to avoid zeroing (write zero clears, write 1 ignored) */
+#define MUSB_RXCSR_P_WZC_BITS \
+ (MUSB_RXCSR_P_SENTSTALL | MUSB_RXCSR_P_OVERRUN \
+ | MUSB_RXCSR_RXPKTRDY)
+#define MUSB_RXCSR_H_WZC_BITS \
+ (MUSB_RXCSR_H_RXSTALL | MUSB_RXCSR_H_ERROR \
+ | MUSB_RXCSR_DATAERROR | MUSB_RXCSR_RXPKTRDY)
+
+/* HUBADDR */
+#define MUSB_HUBADDR_MULTI_TT 0x80
+
+
+#ifndef CONFIG_BLACKFIN
+
+/*
+ * Common USB registers
+ */
+
+#define MUSB_FADDR 0x00 /* 8-bit */
+#define MUSB_POWER 0x01 /* 8-bit */
+
+#define MUSB_INTRTX 0x02 /* 16-bit */
+#define MUSB_INTRRX 0x04
+#define MUSB_INTRTXE 0x06
+#define MUSB_INTRRXE 0x08
+#define MUSB_INTRUSB 0x0A /* 8 bit */
+#define MUSB_INTRUSBE 0x0B /* 8 bit */
+#define MUSB_FRAME 0x0C
+#define MUSB_INDEX 0x0E /* 8 bit */
+#define MUSB_TESTMODE 0x0F /* 8 bit */
+
+/* Get offset for a given FIFO from musb->mregs */
+#if defined(CONFIG_USB_MUSB_TUSB6010) || \
+ defined(CONFIG_USB_MUSB_TUSB6010_MODULE)
+#define MUSB_FIFO_OFFSET(epnum) (0x200 + ((epnum) * 0x20))
+#else
+#define MUSB_FIFO_OFFSET(epnum) (0x20 + ((epnum) * 4))
+#endif
+
+/*
+ * Additional Control Registers
+ */
+
+#define MUSB_DEVCTL 0x60 /* 8 bit */
+#define MUSB_BABBLE_CTL 0x61 /* 8 bit */
+
+/* These are always controlled through the INDEX register */
+#define MUSB_TXFIFOSZ 0x62 /* 8-bit (see masks) */
+#define MUSB_RXFIFOSZ 0x63 /* 8-bit (see masks) */
+#define MUSB_TXFIFOADD 0x64 /* 16-bit offset shifted right 3 */
+#define MUSB_RXFIFOADD 0x66 /* 16-bit offset shifted right 3 */
+
+/* REVISIT: vctrl/vstatus: optional vendor utmi+phy register at 0x68 */
+#define MUSB_HWVERS 0x6C /* 8 bit */
+#define MUSB_ULPI_BUSCONTROL 0x70 /* 8 bit */
+#define MUSB_ULPI_INT_MASK 0x72 /* 8 bit */
+#define MUSB_ULPI_INT_SRC 0x73 /* 8 bit */
+#define MUSB_ULPI_REG_DATA 0x74 /* 8 bit */
+#define MUSB_ULPI_REG_ADDR 0x75 /* 8 bit */
+#define MUSB_ULPI_REG_CONTROL 0x76 /* 8 bit */
+#define MUSB_ULPI_RAW_DATA 0x77 /* 8 bit */
+
+#define MUSB_EPINFO 0x78 /* 8 bit */
+#define MUSB_RAMINFO 0x79 /* 8 bit */
+#define MUSB_LINKINFO 0x7a /* 8 bit */
+#define MUSB_VPLEN 0x7b /* 8 bit */
+#define MUSB_HS_EOF1 0x7c /* 8 bit */
+#define MUSB_FS_EOF1 0x7d /* 8 bit */
+#define MUSB_LS_EOF1 0x7e /* 8 bit */
+
+/* Offsets to endpoint registers */
+#define MUSB_TXMAXP 0x00
+#define MUSB_TXCSR 0x02
+#define MUSB_CSR0 MUSB_TXCSR /* Re-used for EP0 */
+#define MUSB_RXMAXP 0x04
+#define MUSB_RXCSR 0x06
+#define MUSB_RXCOUNT 0x08
+#define MUSB_COUNT0 MUSB_RXCOUNT /* Re-used for EP0 */
+#define MUSB_TXTYPE 0x0A
+#define MUSB_TYPE0 MUSB_TXTYPE /* Re-used for EP0 */
+#define MUSB_TXINTERVAL 0x0B
+#define MUSB_NAKLIMIT0 MUSB_TXINTERVAL /* Re-used for EP0 */
+#define MUSB_RXTYPE 0x0C
+#define MUSB_RXINTERVAL 0x0D
+#define MUSB_FIFOSIZE 0x0F
+#define MUSB_CONFIGDATA MUSB_FIFOSIZE /* Re-used for EP0 */
+
+/* Offsets to endpoint registers in indexed model (using INDEX register) */
+#define MUSB_INDEXED_OFFSET(_epnum, _offset) \
+ (0x10 + (_offset))
+
+/* Offsets to endpoint registers in flat models */
+#define MUSB_FLAT_OFFSET(_epnum, _offset) \
+ (0x100 + (0x10*(_epnum)) + (_offset))
+
+#if defined(CONFIG_USB_MUSB_TUSB6010) || \
+ defined(CONFIG_USB_MUSB_TUSB6010_MODULE)
+/* TUSB6010 EP0 configuration register is special */
+#define MUSB_TUSB_OFFSET(_epnum, _offset) \
+ (0x10 + _offset)
+#include "tusb6010.h" /* Needed "only" for TUSB_EP0_CONF */
+#endif
+
+#define MUSB_TXCSR_MODE 0x2000
+
+/* "bus control"/target registers, for host side multipoint (external hubs) */
+#define MUSB_TXFUNCADDR 0x00
+#define MUSB_TXHUBADDR 0x02
+#define MUSB_TXHUBPORT 0x03
+
+#define MUSB_RXFUNCADDR 0x04
+#define MUSB_RXHUBADDR 0x06
+#define MUSB_RXHUBPORT 0x07
+
+#define MUSB_BUSCTL_OFFSET(_epnum, _offset) \
+ (0x80 + (8*(_epnum)) + (_offset))
+
+static inline void musb_write_txfifosz(void __iomem *mbase, u8 c_size)
+{
+ musb_writeb(mbase, MUSB_TXFIFOSZ, c_size);
+}
+
+static inline void musb_write_txfifoadd(void __iomem *mbase, u16 c_off)
+{
+ musb_writew(mbase, MUSB_TXFIFOADD, c_off);
+}
+
+static inline void musb_write_rxfifosz(void __iomem *mbase, u8 c_size)
+{
+ musb_writeb(mbase, MUSB_RXFIFOSZ, c_size);
+}
+
+static inline void musb_write_rxfifoadd(void __iomem *mbase, u16 c_off)
+{
+ musb_writew(mbase, MUSB_RXFIFOADD, c_off);
+}
+
+static inline void musb_write_ulpi_buscontrol(void __iomem *mbase, u8 val)
+{
+ musb_writeb(mbase, MUSB_ULPI_BUSCONTROL, val);
+}
+
+static inline u8 musb_read_txfifosz(void __iomem *mbase)
+{
+ return musb_readb(mbase, MUSB_TXFIFOSZ);
+}
+
+static inline u16 musb_read_txfifoadd(void __iomem *mbase)
+{
+ return musb_readw(mbase, MUSB_TXFIFOADD);
+}
+
+static inline u8 musb_read_rxfifosz(void __iomem *mbase)
+{
+ return musb_readb(mbase, MUSB_RXFIFOSZ);
+}
+
+static inline u16 musb_read_rxfifoadd(void __iomem *mbase)
+{
+ return musb_readw(mbase, MUSB_RXFIFOADD);
+}
+
+static inline u8 musb_read_ulpi_buscontrol(void __iomem *mbase)
+{
+ return musb_readb(mbase, MUSB_ULPI_BUSCONTROL);
+}
+
+static inline u8 musb_read_configdata(void __iomem *mbase)
+{
+ musb_writeb(mbase, MUSB_INDEX, 0);
+ return musb_readb(mbase, 0x10 + MUSB_CONFIGDATA);
+}
+
+static inline u16 musb_read_hwvers(void __iomem *mbase)
+{
+ return musb_readw(mbase, MUSB_HWVERS);
+}
+
+static inline void __iomem *musb_read_target_reg_base(u8 i, void __iomem *mbase)
+{
+ return (MUSB_BUSCTL_OFFSET(i, 0) + mbase);
+}
+
+static inline void musb_write_rxfunaddr(void __iomem *ep_target_regs,
+ u8 qh_addr_reg)
+{
+ musb_writeb(ep_target_regs, MUSB_RXFUNCADDR, qh_addr_reg);
+}
+
+static inline void musb_write_rxhubaddr(void __iomem *ep_target_regs,
+ u8 qh_h_addr_reg)
+{
+ musb_writeb(ep_target_regs, MUSB_RXHUBADDR, qh_h_addr_reg);
+}
+
+static inline void musb_write_rxhubport(void __iomem *ep_target_regs,
+ u8 qh_h_port_reg)
+{
+ musb_writeb(ep_target_regs, MUSB_RXHUBPORT, qh_h_port_reg);
+}
+
+static inline void musb_write_txfunaddr(void __iomem *mbase, u8 epnum,
+ u8 qh_addr_reg)
+{
+ musb_writeb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_TXFUNCADDR),
+ qh_addr_reg);
+}
+
+static inline void musb_write_txhubaddr(void __iomem *mbase, u8 epnum,
+ u8 qh_addr_reg)
+{
+ musb_writeb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_TXHUBADDR),
+ qh_addr_reg);
+}
+
+static inline void musb_write_txhubport(void __iomem *mbase, u8 epnum,
+ u8 qh_h_port_reg)
+{
+ musb_writeb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_TXHUBPORT),
+ qh_h_port_reg);
+}
+
+static inline u8 musb_read_rxfunaddr(void __iomem *mbase, u8 epnum)
+{
+ return musb_readb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_RXFUNCADDR));
+}
+
+static inline u8 musb_read_rxhubaddr(void __iomem *mbase, u8 epnum)
+{
+ return musb_readb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_RXHUBADDR));
+}
+
+static inline u8 musb_read_rxhubport(void __iomem *mbase, u8 epnum)
+{
+ return musb_readb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_RXHUBPORT));
+}
+
+static inline u8 musb_read_txfunaddr(void __iomem *mbase, u8 epnum)
+{
+ return musb_readb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_TXFUNCADDR));
+}
+
+static inline u8 musb_read_txhubaddr(void __iomem *mbase, u8 epnum)
+{
+ return musb_readb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_TXHUBADDR));
+}
+
+static inline u8 musb_read_txhubport(void __iomem *mbase, u8 epnum)
+{
+ return musb_readb(mbase, MUSB_BUSCTL_OFFSET(epnum, MUSB_TXHUBPORT));
+}
+
+#else /* CONFIG_BLACKFIN */
+
+#define USB_BASE USB_FADDR
+#define USB_OFFSET(reg) (reg - USB_BASE)
+
+/*
+ * Common USB registers
+ */
+#define MUSB_FADDR USB_OFFSET(USB_FADDR) /* 8-bit */
+#define MUSB_POWER USB_OFFSET(USB_POWER) /* 8-bit */
+#define MUSB_INTRTX USB_OFFSET(USB_INTRTX) /* 16-bit */
+#define MUSB_INTRRX USB_OFFSET(USB_INTRRX)
+#define MUSB_INTRTXE USB_OFFSET(USB_INTRTXE)
+#define MUSB_INTRRXE USB_OFFSET(USB_INTRRXE)
+#define MUSB_INTRUSB USB_OFFSET(USB_INTRUSB) /* 8 bit */
+#define MUSB_INTRUSBE USB_OFFSET(USB_INTRUSBE)/* 8 bit */
+#define MUSB_FRAME USB_OFFSET(USB_FRAME)
+#define MUSB_INDEX USB_OFFSET(USB_INDEX) /* 8 bit */
+#define MUSB_TESTMODE USB_OFFSET(USB_TESTMODE)/* 8 bit */
+
+/* Get offset for a given FIFO from musb->mregs */
+#define MUSB_FIFO_OFFSET(epnum) \
+ (USB_OFFSET(USB_EP0_FIFO) + ((epnum) * 8))
+
+/*
+ * Additional Control Registers
+ */
+
+#define MUSB_DEVCTL USB_OFFSET(USB_OTG_DEV_CTL) /* 8 bit */
+
+#define MUSB_LINKINFO USB_OFFSET(USB_LINKINFO)/* 8 bit */
+#define MUSB_VPLEN USB_OFFSET(USB_VPLEN) /* 8 bit */
+#define MUSB_HS_EOF1 USB_OFFSET(USB_HS_EOF1) /* 8 bit */
+#define MUSB_FS_EOF1 USB_OFFSET(USB_FS_EOF1) /* 8 bit */
+#define MUSB_LS_EOF1 USB_OFFSET(USB_LS_EOF1) /* 8 bit */
+
+/* Offsets to endpoint registers */
+#define MUSB_TXMAXP 0x00
+#define MUSB_TXCSR 0x04
+#define MUSB_CSR0 MUSB_TXCSR /* Re-used for EP0 */
+#define MUSB_RXMAXP 0x08
+#define MUSB_RXCSR 0x0C
+#define MUSB_RXCOUNT 0x10
+#define MUSB_COUNT0 MUSB_RXCOUNT /* Re-used for EP0 */
+#define MUSB_TXTYPE 0x14
+#define MUSB_TYPE0 MUSB_TXTYPE /* Re-used for EP0 */
+#define MUSB_TXINTERVAL 0x18
+#define MUSB_NAKLIMIT0 MUSB_TXINTERVAL /* Re-used for EP0 */
+#define MUSB_RXTYPE 0x1C
+#define MUSB_RXINTERVAL 0x20
+#define MUSB_TXCOUNT 0x28
+
+/* Offsets to endpoint registers in indexed model (using INDEX register) */
+#define MUSB_INDEXED_OFFSET(_epnum, _offset) \
+ (0x40 + (_offset))
+
+/* Offsets to endpoint registers in flat models */
+#define MUSB_FLAT_OFFSET(_epnum, _offset) \
+ (USB_OFFSET(USB_EP_NI0_TXMAXP) + (0x40 * (_epnum)) + (_offset))
+
+/* Not implemented - HW has separate Tx/Rx FIFO */
+#define MUSB_TXCSR_MODE 0x0000
+
+static inline void musb_write_txfifosz(void __iomem *mbase, u8 c_size)
+{
+}
+
+static inline void musb_write_txfifoadd(void __iomem *mbase, u16 c_off)
+{
+}
+
+static inline void musb_write_rxfifosz(void __iomem *mbase, u8 c_size)
+{
+}
+
+static inline void musb_write_rxfifoadd(void __iomem *mbase, u16 c_off)
+{
+}
+
+static inline void musb_write_ulpi_buscontrol(void __iomem *mbase, u8 val)
+{
+}
+
+static inline u8 musb_read_txfifosz(void __iomem *mbase)
+{
+ return 0;
+}
+
+static inline u16 musb_read_txfifoadd(void __iomem *mbase)
+{
+ return 0;
+}
+
+static inline u8 musb_read_rxfifosz(void __iomem *mbase)
+{
+ return 0;
+}
+
+static inline u16 musb_read_rxfifoadd(void __iomem *mbase)
+{
+ return 0;
+}
+
+static inline u8 musb_read_ulpi_buscontrol(void __iomem *mbase)
+{
+ return 0;
+}
+
+static inline u8 musb_read_configdata(void __iomem *mbase)
+{
+ return 0;
+}
+
+static inline u16 musb_read_hwvers(void __iomem *mbase)
+{
+ /*
+ * This register is invisible on Blackfin, actually the MUSB
+ * RTL version of Blackfin is 1.9, so just harcode its value.
+ */
+ return MUSB_HWVERS_1900;
+}
+
+static inline void __iomem *musb_read_target_reg_base(u8 i, void __iomem *mbase)
+{
+ return NULL;
+}
+
+static inline void musb_write_rxfunaddr(void __iomem *ep_target_regs,
+ u8 qh_addr_req)
+{
+}
+
+static inline void musb_write_rxhubaddr(void __iomem *ep_target_regs,
+ u8 qh_h_addr_reg)
+{
+}
+
+static inline void musb_write_rxhubport(void __iomem *ep_target_regs,
+ u8 qh_h_port_reg)
+{
+}
+
+static inline void musb_write_txfunaddr(void __iomem *mbase, u8 epnum,
+ u8 qh_addr_reg)
+{
+}
+
+static inline void musb_write_txhubaddr(void __iomem *mbase, u8 epnum,
+ u8 qh_addr_reg)
+{
+}
+
+static inline void musb_write_txhubport(void __iomem *mbase, u8 epnum,
+ u8 qh_h_port_reg)
+{
+}
+
+static inline u8 musb_read_rxfunaddr(void __iomem *mbase, u8 epnum)
+{
+ return 0;
+}
+
+static inline u8 musb_read_rxhubaddr(void __iomem *mbase, u8 epnum)
+{
+ return 0;
+}
+
+static inline u8 musb_read_rxhubport(void __iomem *mbase, u8 epnum)
+{
+ return 0;
+}
+
+static inline u8 musb_read_txfunaddr(void __iomem *mbase, u8 epnum)
+{
+ return 0;
+}
+
+static inline u8 musb_read_txhubaddr(void __iomem *mbase, u8 epnum)
+{
+ return 0;
+}
+
+static inline u8 musb_read_txhubport(void __iomem *mbase, u8 epnum)
+{
+ return 0;
+}
+
+#endif /* CONFIG_BLACKFIN */
+
+#endif /* __MUSB_REGS_H__ */
diff --git a/drivers/usb/musb/phy-am335x-control.c b/drivers/usb/musb/phy-am335x-control.c
new file mode 100644
index 0000000000..a241c84fed
--- /dev/null
+++ b/drivers/usb/musb/phy-am335x-control.c
@@ -0,0 +1,168 @@
+#include <common.h>
+#include <init.h>
+#include <io.h>
+#include <linux/err.h>
+
+struct phy_control {
+ void (*phy_power)(struct phy_control *phy_ctrl, u32 id, bool on);
+ void (*phy_wkup)(struct phy_control *phy_ctrl, u32 id, bool on);
+};
+
+struct am335x_control_usb {
+ struct device_d *dev;
+ void __iomem *phy_reg;
+ void __iomem *wkup;
+ spinlock_t lock;
+ struct phy_control phy_ctrl;
+};
+
+#define AM335X_USB0_CTRL 0x0
+#define AM335X_USB1_CTRL 0x8
+#define AM335x_USB_WKUP 0x0
+
+#define USBPHY_CM_PWRDN (1 << 0)
+#define USBPHY_OTG_PWRDN (1 << 1)
+#define USBPHY_OTGVDET_EN (1 << 19)
+#define USBPHY_OTGSESSEND_EN (1 << 20)
+
+#define AM335X_PHY0_WK_EN (1 << 0)
+#define AM335X_PHY1_WK_EN (1 << 8)
+
+static void am335x_phy_wkup(struct phy_control *phy_ctrl, u32 id, bool on)
+{
+ struct am335x_control_usb *usb_ctrl;
+ u32 val;
+ u32 reg;
+
+ usb_ctrl = container_of(phy_ctrl, struct am335x_control_usb, phy_ctrl);
+
+ switch (id) {
+ case 0:
+ reg = AM335X_PHY0_WK_EN;
+ break;
+ case 1:
+ reg = AM335X_PHY1_WK_EN;
+ break;
+ default:
+ WARN_ON(1);
+ return;
+ }
+
+ spin_lock(&usb_ctrl->lock);
+ val = readl(usb_ctrl->wkup);
+
+ if (on)
+ val |= reg;
+ else
+ val &= ~reg;
+
+ writel(val, usb_ctrl->wkup);
+ spin_unlock(&usb_ctrl->lock);
+}
+
+static void am335x_phy_power(struct phy_control *phy_ctrl, u32 id, bool on)
+{
+ struct am335x_control_usb *usb_ctrl;
+ u32 val;
+ u32 reg;
+
+ usb_ctrl = container_of(phy_ctrl, struct am335x_control_usb, phy_ctrl);
+
+ switch (id) {
+ case 0:
+ reg = AM335X_USB0_CTRL;
+ break;
+ case 1:
+ reg = AM335X_USB1_CTRL;
+ break;
+ default:
+ WARN_ON(1);
+ return;
+ }
+
+ val = readl(usb_ctrl->phy_reg + reg);
+ if (on) {
+ val &= ~(USBPHY_CM_PWRDN | USBPHY_OTG_PWRDN);
+ val |= USBPHY_OTGVDET_EN | USBPHY_OTGSESSEND_EN;
+ } else {
+ val |= USBPHY_CM_PWRDN | USBPHY_OTG_PWRDN;
+ }
+
+ writel(val, usb_ctrl->phy_reg + reg);
+}
+
+static const struct phy_control ctrl_am335x = {
+ .phy_power = am335x_phy_power,
+ .phy_wkup = am335x_phy_wkup,
+};
+
+static __maybe_unused struct of_device_id omap_control_usb_dt_ids[] = {
+ {
+ .compatible = "ti,am335x-usb-ctrl-module", .data = (unsigned long)&ctrl_am335x
+ }, {
+ /* sentinel */
+ },
+};
+
+struct phy_control *am335x_get_phy_control(struct device_d *dev)
+{
+ struct device_node *node;
+ struct am335x_control_usb *ctrl_usb;
+
+ node = of_parse_phandle(dev->device_node, "ti,ctrl_mod", 0);
+ if (!node)
+ return NULL;
+
+ dev = of_find_device_by_node(node);
+ if (!dev)
+ return NULL;
+
+ ctrl_usb = dev->priv;
+ if (!ctrl_usb)
+ return NULL;
+
+ return &ctrl_usb->phy_ctrl;
+}
+EXPORT_SYMBOL(am335x_get_phy_control);
+
+
+static int am335x_control_usb_probe(struct device_d *dev)
+{
+ /*struct resource *res;*/
+ struct am335x_control_usb *ctrl_usb;
+ const struct phy_control *phy_ctrl;
+ int ret;
+
+ ret = dev_get_drvdata(dev, (unsigned long *)&phy_ctrl);
+ if (ret)
+ return ret;
+
+ ctrl_usb = xzalloc(sizeof(*ctrl_usb));
+ if (!ctrl_usb) {
+ dev_err(dev, "unable to alloc memory for control usb\n");
+ return -ENOMEM;
+ }
+
+ ctrl_usb->dev = dev;
+
+ ctrl_usb->phy_reg = dev_request_mem_region(dev, 0);
+ if (IS_ERR(ctrl_usb->phy_reg))
+ return PTR_ERR(ctrl_usb->phy_reg);
+
+ ctrl_usb->wkup = dev_request_mem_region(dev, 1);
+ if (IS_ERR(ctrl_usb->wkup))
+ return PTR_ERR(ctrl_usb->wkup);
+
+ spin_lock_init(&ctrl_usb->lock);
+ ctrl_usb->phy_ctrl = *phy_ctrl;
+
+ dev->priv = ctrl_usb;
+ return 0;
+};
+
+static struct driver_d am335x_control_driver = {
+ .name = "am335x-control-usb",
+ .probe = am335x_control_usb_probe,
+ .of_compatible = DRV_OF_COMPAT(omap_control_usb_dt_ids),
+};
+device_platform_driver(am335x_control_driver);
diff --git a/drivers/usb/musb/phy-am335x.c b/drivers/usb/musb/phy-am335x.c
new file mode 100644
index 0000000000..2d58bbedb4
--- /dev/null
+++ b/drivers/usb/musb/phy-am335x.c
@@ -0,0 +1,86 @@
+#include <common.h>
+#include <init.h>
+#include <io.h>
+#include <malloc.h>
+#include <linux/err.h>
+#include "am35x-phy-control.h"
+#include "musb_core.h"
+
+struct am335x_usbphy {
+ void __iomem *base;
+ struct phy_control *phy_ctrl;
+ int id;
+ struct usb_phy phy;
+};
+
+static struct am335x_usbphy *am_usbphy;
+
+struct usb_phy *am335x_get_usb_phy(void)
+{
+ return &am_usbphy->phy;
+}
+
+static int am335x_init(struct usb_phy *phy)
+{
+ struct am335x_usbphy *am_usbphy = container_of(phy, struct am335x_usbphy, phy);
+
+ phy_ctrl_power(am_usbphy->phy_ctrl, am_usbphy->id, true);
+ return 0;
+}
+
+static int am335x_phy_probe(struct device_d *dev)
+{
+ int ret;
+
+ am_usbphy = xzalloc(sizeof(*am_usbphy));
+ if (!am_usbphy)
+ return -ENOMEM;
+
+ am_usbphy->base = dev_request_mem_region(dev, 0);
+ if (!am_usbphy->base) {
+ ret = -ENODEV;
+ goto err_free;
+ }
+
+ am_usbphy->phy_ctrl = am335x_get_phy_control(dev);
+ if (!am_usbphy->phy_ctrl)
+ return -ENODEV;
+
+ am_usbphy->id = of_alias_get_id(dev->device_node, "phy");
+ if (am_usbphy->id < 0) {
+ dev_err(dev, "Missing PHY id: %d\n", am_usbphy->id);
+ return am_usbphy->id;
+ }
+
+ am_usbphy->phy.init = am335x_init;
+ dev->priv = am_usbphy;
+
+ dev_info(dev, "am_usbphy %p enabled\n", &am_usbphy->phy);
+
+ return 0;
+
+err_free:
+ free(am_usbphy);
+
+ return ret;
+};
+
+static __maybe_unused struct of_device_id am335x_phy_dt_ids[] = {
+ {
+ .compatible = "ti,am335x-usb-phy",
+ }, {
+ /* sentinel */
+ },
+};
+
+static struct driver_d am335x_phy_driver = {
+ .name = "am335x-phy-driver",
+ .probe = am335x_phy_probe,
+ .of_compatible = DRV_OF_COMPAT(am335x_phy_dt_ids),
+};
+
+static int am335x_phy_init(void)
+{
+ return platform_driver_register(&am335x_phy_driver);
+}
+fs_initcall(am335x_phy_init);
diff --git a/drivers/usb/musb/phy-am335x.h b/drivers/usb/musb/phy-am335x.h
new file mode 100644
index 0000000000..27da2e3b10
--- /dev/null
+++ b/drivers/usb/musb/phy-am335x.h
@@ -0,0 +1,6 @@
+#ifndef _PHY_AM335x_H_
+#define _PHY_AM335x_H_
+
+struct usb_phy *am335x_get_usb_phy(void);
+
+#endif