* [PATCH 0/5] Review request: Cypress c67x00 OTG controller
@ 2007-11-24 0:24 Grant Likely
2007-11-24 0:24 ` [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq Grant Likely
` (5 more replies)
0 siblings, 6 replies; 20+ messages in thread
From: Grant Likely @ 2007-11-24 0:24 UTC (permalink / raw)
To: linux-usb-devel, akpm, dbrownell, gregkh, linuxppc-dev
This patch series is based on the c67x00 work done by Peter Korsgaard and
posted back in April this year.
The Cypress c67x00 is an OTG controller so it can behave as either a host
or gadget controller. This series implements the HCD behaviour.
The c67x00 is found on a number of the Xilinx MLxxx series of boards.
I've been performing my testing on a board derived from the ML403.
My goal is to get this driver queued up for inclusion in 2.6.25, but I've
been looking at this code for so long that I'm going crosseyed and missing
obvious issues. Plus, I am by no means a USB expert and I'm not sure that
I'm using the USB HCD API correctly.
So, this email is a request for review. I've got some time cleared away
to work on this over the next week so I should be able to address comments
quickly with the goal of getting it picked up for the next merge window.
Thanks,
g.
--
Grant Likely, B.Sc. P.Eng.
Secret Lab Technologies Ltd.
^ permalink raw reply [flat|nested] 20+ messages in thread
* [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq
2007-11-24 0:24 [PATCH 0/5] Review request: Cypress c67x00 OTG controller Grant Likely
@ 2007-11-24 0:24 ` Grant Likely
2007-11-24 5:10 ` Greg KH
2007-11-24 19:06 ` David Brownell
2007-11-24 0:24 ` [PATCH 2/5] USB: Add Cypress c67x00 low level interface code Grant Likely
` (4 subsequent siblings)
5 siblings, 2 replies; 20+ messages in thread
From: Grant Likely @ 2007-11-24 0:24 UTC (permalink / raw)
To: linux-usb-devel, akpm, dbrownell, gregkh, linuxppc-dev
From: Peter Korsgaard <peter.korsgaard@barco.com>
Some multi-role (host/peripheral) USB controllers use a shared interrupt
line for all parts of the chip. Export usb_hcd_irq so drivers can call it
from their interrupt handler instead of duplicating code.
Drivers pass an irqnum of 0 to usb_add_hcd to signal that the interrupt handler
shouldn't be registerred by the core.
Signed-off-by: Peter Korsgaard <peter.korsgaard@barco.com>
Signed-off-by: Grant Likely <grant.likely@secretlab.ca>
---
drivers/usb/core/hcd.c | 6 +++++-
1 files changed, 5 insertions(+), 1 deletions(-)
diff --git a/drivers/usb/core/hcd.c b/drivers/usb/core/hcd.c
index fea8256..6ce305c 100644
--- a/drivers/usb/core/hcd.c
+++ b/drivers/usb/core/hcd.c
@@ -1562,6 +1562,7 @@ irqreturn_t usb_hcd_irq (int irq, void *__hcd)
usb_hc_died (hcd);
return IRQ_HANDLED;
}
+EXPORT_SYMBOL_GPL (usb_hcd_irq);
/*-------------------------------------------------------------------------*/
@@ -1670,6 +1671,9 @@ EXPORT_SYMBOL (usb_put_hcd);
* Finish the remaining parts of generic HCD initialization: allocate the
* buffers of consistent memory, register the bus, request the IRQ line,
* and call the driver's reset() and start() routines.
+ *
+ * If irqnum is 0, the irq will not be requested. The caller is responsible
+ * for calling usb_hcd_irq at the correct time.
*/
int usb_add_hcd(struct usb_hcd *hcd,
unsigned int irqnum, unsigned long irqflags)
@@ -1723,7 +1727,7 @@ int usb_add_hcd(struct usb_hcd *hcd,
dev_dbg(hcd->self.controller, "supports USB remote wakeup\n");
/* enable irqs just before we start the controller */
- if (hcd->driver->irq) {
+ if (hcd->driver->irq && irqnum) {
snprintf(hcd->irq_descr, sizeof(hcd->irq_descr), "%s:usb%d",
hcd->driver->description, hcd->self.busnum);
if ((retval = request_irq(irqnum, &usb_hcd_irq, irqflags,
^ permalink raw reply related [flat|nested] 20+ messages in thread
* [PATCH 2/5] USB: Add Cypress c67x00 low level interface code
2007-11-24 0:24 [PATCH 0/5] Review request: Cypress c67x00 OTG controller Grant Likely
2007-11-24 0:24 ` [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq Grant Likely
@ 2007-11-24 0:24 ` Grant Likely
2007-11-24 19:39 ` David Brownell
2007-11-24 0:24 ` [PATCH 3/5] USB: add Cypress c67x00 OTG controller core driver Grant Likely
` (3 subsequent siblings)
5 siblings, 1 reply; 20+ messages in thread
From: Grant Likely @ 2007-11-24 0:24 UTC (permalink / raw)
To: linux-usb-devel, akpm, dbrownell, gregkh, linuxppc-dev
From: Grant Likely <grant.likely@secretlab.ca>
This patch adds the low level support code for the Cypress c67x00 family of
OTG controllers. The low level code is responsible for register access and
implements the software protocol for communicating with the c67x00 device.
Signed-off-by: Grant Likely <grant.likely@secretlab.ca>
---
drivers/usb/c67x00/c67x00-ll-hpi.c | 512 ++++++++++++++++++++++++++++++++++++
drivers/usb/c67x00/c67x00.h | 236 +++++++++++++++++
2 files changed, 748 insertions(+), 0 deletions(-)
diff --git a/drivers/usb/c67x00/c67x00-ll-hpi.c b/drivers/usb/c67x00/c67x00-ll-hpi.c
new file mode 100644
index 0000000..5e1bd73
--- /dev/null
+++ b/drivers/usb/c67x00/c67x00-ll-hpi.c
@@ -0,0 +1,512 @@
+/*
+ * c67x00-ll-hpi.c: Cypress C67X00 USB Low level interface using HPI
+ *
+ * Copyright (C) 2006-2007 Barco N.V.
+ * Derived from the Cypress cy7c67200/300 ezusb linux driver and
+ * based on multiple host controller drivers inside the linux kernel.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+ * MA 02110-1301 USA.
+ */
+
+#include <asm/io.h>
+#include <asm/byteorder.h>
+#include "c67x00.h"
+
+/* -------------------------------------------------------------------------- */
+/* Interface definitions */
+
+#define COMM_ACK 0x0FED
+#define COMM_NAK 0xDEAD
+
+#define COMM_CTRL_REG_ADDR 0x01BC
+#define COMM_CTRL_REG_DATA 0x01BE
+#define COMM_CTRL_REG_LOGIC 0x01C0
+#define COMM_WRITE_CTRL_REG 0xCE03
+#define COMM_READ_CTRL_REG 0xCE02
+
+#define COMM_RESET 0xFA50
+#define COMM_EXEC_INT 0xCE01
+#define COMM_INT_NUM 0x01C2
+/* Registers 0 to COMM_REGS-1 */
+#define COMM_R(x) (0x01C4 + 2 * (x))
+
+#define HUSB_SIE_pCurrentTDPtr(x) ( (x) ? 0x01B2 : 0x01B0 )
+#define HUSB_SIE_pTDListDone_Sem(x) ( (x) ? 0x01B8 : 0x01B6 )
+#define HUSB_pEOT 0x01B4
+
+/* Software interrupts */
+/* 114, 115: */
+#define HUSB_SIE_INIT_INT(x) ( (x) ? 0x0073 : 0x0072 )
+#define HUSB_RESET_INT 0x0074 /* 116 */
+
+#define SUSB_INIT_INT 0x0071
+/* -------------------------------------------------------------------------- */
+/* HPI implementation */
+
+/* HPI registers */
+#define HPI_DATA 0
+#define HPI_MAILBOX 1
+#define HPI_ADDR 2
+#define HPI_STATUS 3
+
+/* These functions could also be implemented with SPI of HSS.
+ * This is currently not supported */
+static inline u16 hpi_read_reg(struct c67x00_device *dev, int reg)
+{
+ return __raw_readw(dev->hpi.base + reg * dev->hpi.regstep);
+}
+
+static inline void hpi_write_reg(struct c67x00_device *dev, int reg, u16 value)
+{
+ __raw_writew(value, dev->hpi.base + reg * dev->hpi.regstep);
+}
+
+static inline u16 hpi_read_word_nolock(struct c67x00_device *dev, u16 reg)
+{
+ hpi_write_reg(dev, HPI_ADDR, reg);
+ return hpi_read_reg(dev, HPI_DATA);
+}
+
+static inline u16 hpi_read_word(struct c67x00_device *dev, u16 reg)
+{
+ u16 value;
+ unsigned long flags;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ value = hpi_read_word_nolock(dev, reg);
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+
+ return value;
+}
+
+static inline void hpi_write_word_nolock(struct c67x00_device *dev, u16 reg,
+ u16 value)
+{
+ hpi_write_reg(dev, HPI_ADDR, reg);
+ hpi_write_reg(dev, HPI_DATA, value);
+}
+
+static inline void hpi_write_word(struct c67x00_device *dev, u16 reg, u16 value)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ hpi_write_word_nolock(dev, reg, value);
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+}
+
+/*
+ * Only data is little endian, addr has cpu endianess
+ */
+static inline void hpi_write_words_le16(struct c67x00_device *dev, u16 addr,
+ u16 * data, u16 count)
+{
+ unsigned long flags;
+ int i;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+
+ hpi_write_reg(dev, HPI_ADDR, addr);
+ for (i = 0; i < count; i++)
+ hpi_write_reg(dev, HPI_DATA, cpu_to_le16(*data++));
+
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+}
+
+/*
+ * Only data is little endian, addr has cpu endianess
+ */
+static inline void hpi_read_words_le16(struct c67x00_device *dev, u16 addr,
+ u16 * data, u16 count)
+{
+ unsigned long flags;
+ int i;
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ hpi_write_reg(dev, HPI_ADDR, addr);
+ for (i = 0; i < count; i++)
+ *data++ = le16_to_cpu(hpi_read_reg(dev, HPI_DATA));
+
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+}
+
+static inline void hpi_set_bits(struct c67x00_device *dev, u16 reg, u16 mask)
+{
+ u16 value;
+ unsigned long flags;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ value = hpi_read_word_nolock(dev, reg);
+ hpi_write_word_nolock(dev, reg, value | mask);
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+}
+
+static inline void hpi_clear_bits(struct c67x00_device *dev, u16 reg, u16 mask)
+{
+ u16 value;
+ unsigned long flags;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ value = hpi_read_word_nolock(dev, reg);
+ hpi_write_word_nolock(dev, reg, value & ~mask);
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+}
+
+static inline u16 hpi_recv_mbox(struct c67x00_device *dev)
+{
+ u16 value;
+ unsigned long flags;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ value = hpi_read_reg(dev, HPI_MAILBOX);
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+
+ return value;
+}
+
+static inline u16 hpi_send_mbox(struct c67x00_device *dev, u16 value)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ hpi_write_reg(dev, HPI_MAILBOX, value);
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+
+ return value;
+}
+
+u16 c67x00_ll_hpi_status(struct c67x00_device * dev)
+{
+ u16 value;
+ unsigned long flags;
+
+ spin_lock_irqsave(&dev->hw_lock, flags);
+ value = hpi_read_reg(dev, HPI_STATUS);
+ spin_unlock_irqrestore(&dev->hw_lock, flags);
+
+ return value;
+}
+
+void c67x00_ll_hpi_reg_init(struct c67x00_device *dev)
+{
+ int i;
+
+ hpi_recv_mbox(dev);
+ c67x00_ll_hpi_status(dev);
+ hpi_write_word(dev, HPI_IRQ_ROUTING_REG, 0);
+
+ for (i=0; i<C67X00_SIES; i++) {
+ hpi_write_word(dev, SIEMSG_REG(i), 0);
+ hpi_read_word(dev, SIEMSG_REG(i));
+ }
+}
+
+void c67x00_ll_hpi_enable_sofeop(struct c67x00_sie *sie)
+{
+ hpi_set_bits(sie->dev, HPI_IRQ_ROUTING_REG,
+ SOFEOP_TO_HPI_EN(sie->sie_num));
+}
+
+void c67x00_ll_hpi_disable_sofeop(struct c67x00_sie *sie)
+{
+ hpi_clear_bits(sie->dev, HPI_IRQ_ROUTING_REG,
+ SOFEOP_TO_HPI_EN(sie->sie_num));
+}
+
+/* -------------------------------------------------------------------------- */
+/* Transactions */
+
+static inline u16 ll_recv_msg(struct c67x00_device *dev)
+{
+ u16 res;
+
+ res = wait_for_completion_timeout(&dev->lcp.msg_received, 5 * HZ);
+ WARN_ON(!res);
+
+ return (res == 0) ? -EIO : 0;
+}
+
+/* -------------------------------------------------------------------------- */
+
+u16 c67x00_comm_read_ctrl_reg(struct c67x00_device * dev, u16 addr)
+{
+ unsigned long msg, res;
+ int rc;
+
+ mutex_lock(&dev->lcp.mutex);
+ hpi_write_word(dev, COMM_CTRL_REG_ADDR, addr);
+ hpi_send_mbox(dev, COMM_READ_CTRL_REG);
+ rc = ll_recv_msg(dev);
+
+ BUG_ON(rc); /* No return path for error code; crash spectacularly */
+
+ msg = dev->lcp.last_msg;
+ if (msg != COMM_ACK) {
+ dev_warn(&dev->pdev->dev, "COMM_READ_CTRL_REG didn't ACK!\n");
+ res = 0;
+ } else {
+ res = hpi_read_word(dev, COMM_CTRL_REG_DATA);
+ }
+ mutex_unlock(&dev->lcp.mutex);
+ return res;
+}
+
+int c67x00_comm_exec_int(struct c67x00_device *dev, u16 nr,
+ struct c67x00_lcp_int_data *data)
+{
+ int i, rc;
+
+ mutex_lock(&dev->lcp.mutex);
+ hpi_write_word(dev, COMM_INT_NUM, nr);
+ for (i = 0; i < COMM_REGS; i++)
+ hpi_write_word(dev, COMM_R(i), data->regs[i]);
+ hpi_send_mbox(dev, COMM_EXEC_INT);
+ rc = ll_recv_msg(dev);
+ mutex_unlock(&dev->lcp.mutex);
+
+ return rc;
+}
+
+/* -------------------------------------------------------------------------- */
+/* General functions */
+
+u16 c67x00_ll_get_siemsg(struct c67x00_device *dev, int sie)
+{
+ return hpi_read_word(dev, SIEMSG_REG(sie));
+}
+
+void c67x00_ll_set_siemsg(struct c67x00_device *dev, int sie, u16 val)
+{
+ hpi_write_word(dev, SIEMSG_REG(sie), val);
+}
+
+u16 c67x00_ll_get_usb_ctl(struct c67x00_sie *sie)
+{
+ return hpi_read_word(sie->dev, USB_CTL_REG(sie->sie_num));
+}
+
+/* -------------------------------------------------------------------------- */
+/* Host specific functions */
+
+void c67x00_ll_set_husb_eot(struct c67x00_device *dev, u16 value)
+{
+ mutex_lock(&dev->lcp.mutex);
+ hpi_write_word(dev, HUSB_pEOT, value);
+ mutex_unlock(&dev->lcp.mutex);
+}
+
+static inline void c67x00_ll_husb_sie_init(struct c67x00_sie *sie)
+{
+ struct c67x00_device *dev = sie->dev;
+ struct c67x00_lcp_int_data data;
+ int rc;
+
+ rc = c67x00_comm_exec_int(dev, HUSB_SIE_INIT_INT(sie->sie_num), &data);
+ BUG_ON(rc); /* No return path for error code; crash spectacularly */
+}
+
+void c67x00_ll_husb_reset(struct c67x00_sie *sie, int port)
+{
+ struct c67x00_device *dev = sie->dev;
+ struct c67x00_lcp_int_data data;
+ int rc;
+
+ data.regs[0] = 50; /* Reset USB port for 50ms */
+ data.regs[1] = port | (sie->sie_num << 1);
+ rc = c67x00_comm_exec_int(dev, HUSB_RESET_INT, &data);
+ BUG_ON(rc); /* No return path for error code; crash spectacularly */
+}
+
+void c67x00_ll_husb_set_current_td(struct c67x00_sie *sie, u16 addr)
+{
+ hpi_write_word(sie->dev, HUSB_SIE_pCurrentTDPtr(sie->sie_num), addr);
+}
+
+u16 c67x00_ll_husb_get_current_td(struct c67x00_sie *sie)
+{
+ return hpi_read_word(sie->dev, HUSB_SIE_pCurrentTDPtr(sie->sie_num));
+}
+
+/**
+ * c67x00_ll_husb_clear_status - clear the host status bits
+ */
+void c67x00_ll_husb_clear_status(struct c67x00_sie *sie, u16 bits)
+{
+ hpi_write_word(sie->dev, HOST_STAT_REG(sie->sie_num), bits);
+}
+
+u16 c67x00_ll_husb_get_status(struct c67x00_sie *sie)
+{
+ return hpi_read_word(sie->dev, HOST_STAT_REG(sie->sie_num));
+}
+
+u16 c67x00_ll_husb_get_frame(struct c67x00_sie * sie)
+{
+ return hpi_read_word(sie->dev, HOST_FRAME_REG(sie->sie_num));
+}
+
+void c67x00_ll_husb_init_host_port(struct c67x00_sie *sie)
+{
+ /* Set port into host mode */
+ hpi_set_bits(sie->dev, USB_CTL_REG(sie->sie_num), HOST_MODE);
+ c67x00_ll_husb_sie_init(sie);
+ /* Clear interrupts */
+ c67x00_ll_husb_clear_status(sie, HOST_STAT_MASK);
+ /* Check */
+ if (!(hpi_read_word(sie->dev, USB_CTL_REG(sie->sie_num)) & HOST_MODE))
+ dev_warn(sie_dev(sie),
+ "SIE %d not set to host mode\n", sie->sie_num);
+}
+
+void c67x00_ll_husb_reset_port(struct c67x00_sie *sie, int port)
+{
+ /* Clear connect change */
+ c67x00_ll_husb_clear_status(sie, PORT_CONNECT_CHANGE(port));
+
+ /* Enable interrupts */
+ hpi_set_bits(sie->dev, HPI_IRQ_ROUTING_REG,
+ SOFEOP_TO_CPU_EN(sie->sie_num));
+ hpi_set_bits(sie->dev, HOST_IRQ_EN_REG(sie->sie_num),
+ SOF_EOP_IRQ_EN | DONE_IRQ_EN);
+
+ /* Enable pull down transistors */
+ hpi_set_bits(sie->dev, USB_CTL_REG(sie->sie_num), PORT_RES_EN(port));
+}
+
+/* -------------------------------------------------------------------------- */
+void c67x00_ll_susb_init(struct c67x00_sie *sie)
+{
+ struct c67x00_device *dev = sie->dev;
+ struct c67x00_lcp_int_data data;
+ int rc;
+
+ data.regs[1] = 1; /* full speed */
+ data.regs[2] = sie->sie_num + 1;
+ rc = c67x00_comm_exec_int(dev, SUSB_INIT_INT, &data);
+ BUG_ON(rc); /* No return path for error code; crash spectacularly */
+
+ hpi_clear_bits(dev, HPI_IRQ_ROUTING_REG,
+ SOFEOP_TO_HPI_EN(sie->sie_num));
+ hpi_set_bits(dev, HPI_IRQ_ROUTING_REG, SOFEOP_TO_CPU_EN(sie->sie_num));
+}
+
+/* -------------------------------------------------------------------------- */
+
+void c67x00_ll_irq(struct c67x00_device *dev)
+{
+ if ((dev->int_status & MBX_OUT_FLG) == 0)
+ return;
+
+ dev->lcp.last_msg = hpi_recv_mbox(dev);
+ complete(&dev->lcp.msg_received);
+}
+
+/* -------------------------------------------------------------------------- */
+
+int c67x00_ll_reset(struct c67x00_device *dev)
+{
+ int rc;
+
+ mutex_lock(&dev->lcp.mutex);
+ hpi_send_mbox(dev, COMM_RESET);
+ rc = ll_recv_msg(dev);
+ mutex_unlock(&dev->lcp.mutex);
+
+ return rc;
+}
+
+/* -------------------------------------------------------------------------- */
+
+/**
+ * c67x00_write_mem_le16 - write into c67x00 memory
+ * Only data is little endian, addr has cpu endianess.
+ */
+void c67x00_ll_hpi_write_mem_le16(struct c67x00_device *dev, u16 addr, int len,
+ char *data)
+{
+ /* Sanity check */
+ if (addr + len > 0xffff) {
+ dev_err(&dev->pdev->dev,
+ "Trying to write beyond writable region!\n");
+ return;
+ }
+
+ if (addr & 0x01) {
+ /* unaligned access */
+ u16 tmp;
+ tmp = hpi_read_word(dev, addr - 1);
+ tmp = (tmp & 0x00ff) | (*data++ << 8);
+ hpi_write_word(dev, addr - 1, tmp);
+ addr++;
+ len--;
+ }
+
+ hpi_write_words_le16(dev, addr, (u16 *) data, len / 2);
+ data += len & ~0x01;
+ addr += len & ~0x01;
+ len &= 0x01;
+
+ if (len) {
+ u16 tmp;
+ tmp = hpi_read_word(dev, addr);
+ tmp = (tmp & 0xff00) | (*data++);
+ hpi_write_word(dev, addr, tmp);
+ addr++;
+ len--;
+ }
+
+}
+
+/**
+ * c67x00_ll_hpi_read_mem_le16 - read from c67x00 memory
+ * Only data is little endian, addr has cpu endianess.
+ */
+void c67x00_ll_hpi_read_mem_le16(struct c67x00_device *dev, u16 addr, int len,
+ char *data)
+{
+ if (addr & 0x01) {
+ /* unaligned access */
+ u16 tmp;
+ tmp = hpi_read_word(dev, addr - 1);
+ *data++ = (tmp >> 8) & 0x00ff;
+ addr++;
+ len--;
+ }
+
+ hpi_read_words_le16(dev, addr, (u16 *) data, len / 2);
+ data += len & ~0x01;
+ addr += len & ~0x01;
+ len &= 0x01;
+
+ if (len) {
+ u16 tmp;
+ tmp = hpi_read_word(dev, addr);
+ *data++ = tmp & 0x00ff;
+ addr++;
+ len--;
+ }
+}
+
+/* -------------------------------------------------------------------------- */
+
+void c67x00_ll_init(struct c67x00_device *dev)
+{
+ mutex_init(&dev->lcp.mutex);
+ init_completion(&dev->lcp.msg_received);
+}
+
+void c67x00_ll_release(struct c67x00_device *dev)
+{
+}
diff --git a/drivers/usb/c67x00/c67x00.h b/drivers/usb/c67x00/c67x00.h
new file mode 100644
index 0000000..ca8ed69
--- /dev/null
+++ b/drivers/usb/c67x00/c67x00.h
@@ -0,0 +1,236 @@
+/*
+ * c67x00.h: Cypress C67X00 USB register and field definitions
+ *
+ * Copyright (C) 2006-2007 Barco N.V.
+ * Derived from the Cypress cy7c67200/300 ezusb linux driver and
+ * based on multiple host controller drivers inside the linux kernel.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+ * MA 02110-1301 USA.
+ */
+
+#ifndef _USB_C67X00_H
+#define _USB_C67X00_H
+
+#include <linux/interrupt.h>
+#include <linux/list.h>
+#include <linux/platform_device.h>
+#include <linux/completion.h>
+#include <linux/mutex.h>
+
+/* ---------------------------------------------------------------------
+ * Cypress C67x00 register definitions
+ */
+
+/* Processor control registers */
+/* =========================== */
+
+/* Hardware Revision Register */
+#define HW_REV_REG 0xC004
+
+/* General USB registers */
+/* ===================== */
+
+/* USB Control Register */
+#define USB_CTL_REG(x) ( (x) ? 0xC0AA : 0xC08A )
+
+#define LOW_SPEED_PORT(x) ( (x) ? 0x0800 : 0x0400 )
+#define HOST_MODE 0x0200
+#define PORT_RES_EN(x) ( (x) ? 0x0100 : 0x0080 )
+#define SOF_EOP_EN(x) ( (x) ? 0x0002 : 0x0001 )
+
+/* USB Host only registers */
+/* ======================= */
+
+/* Host n Control Register */
+#define HOST_CTL_REG(x) ((x) ? 0xC0A0 : 0xC080)
+
+#define PREAMBLE_EN 0x0080 /* Preamble enable */
+#define SEQ_SEL 0x0040 /* Data Toggle Sequence Bit Select */
+#define ISO_EN 0x0010 /* Isochronous enable */
+#define ARM_EN 0x0001 /* Arm operation */
+
+/* Host n Interrupt Enable Register */
+#define HOST_IRQ_EN_REG(x) ( (x) ? 0xC0AC : 0xC08C)
+
+#define SOF_EOP_IRQ_EN 0x0200 /* SOF/EOP Interrupt Enable */
+#define DONE_IRQ_EN 0x0001 /* Done Interrupt Enable */
+
+/* Host n status register */
+#define HOST_STAT_REG(x) ( (x) ? 0xC0B0 : 0xC090 )
+
+#define HOST_STAT_MASK 0x02FD
+#define SOF_EOP_IRQ_FLG 0x0200
+#define PORT_CONNECT_CHANGE(x) ( (x) ? 0x0020 : 0x0010 )
+#define PORT_SE0_STATUS(x) ( (x) ? 0x0008 : 0x0004 )
+
+/* Host Frame Register */
+#define HOST_FRAME_REG(x) ( (x) ? 0xC0B6 : 0xC096 )
+
+#define HOST_FRAME_MASK 0x07FF
+
+/* HPI registers */
+/* ============= */
+
+/* HPI Status register */
+#define SOFEOP_FLG(x) (1 << ( (x) ? 12 : 10 ))
+#define SIEMSG_FLAG(x) (1 << (4 + (x)))
+#define MBX_OUT_FLG 0x0001 /* Message out available */
+
+/* Interrupt routing register */
+#define HPI_IRQ_ROUTING_REG 0x0142
+
+#define SOFEOP_TO_HPI_EN(x) ( (x) ? 0x2000 : 0x0800 )
+#define SOFEOP_TO_CPU_EN(x) ( (x) ? 0x1000 : 0x0400 )
+
+/* SIE msg registers */
+#define SIEMSG_REG(x) ( (x) ? 0x0148 : 0x0144 )
+
+#define HUSB_TDListDone 0x1000
+
+#define CY_HCD_BUF_ADDR 0x500 /* Base address for host */
+#define SIE_TD_SIZE 0x200 /* size of the td list */
+#define SIE_TD_BUF_SIZE 0x400 /* size of the data buffer */
+
+#define SIE_TD_OFFSET(host) ( (host) ? (SIE_TD_SIZE+SIE_TD_BUF_SIZE) : 0 )
+#define SIE_BUF_OFFSET(host) (SIE_TD_OFFSET(host) + SIE_TD_SIZE)
+
+/* ---------------------------------------------------------------------
+ * Driver data structures
+ */
+
+struct c67x00_device;
+
+/**
+ * struct c67x00_lcp
+ */
+struct c67x00_lcp {
+ /* Internal use only */
+ struct mutex mutex;
+ struct completion msg_received;
+ u16 last_msg;
+};
+
+/**
+ * struct c67x00_lcp_data
+ */
+#define COMM_REGS 14
+struct c67x00_lcp_int_data {
+ u16 regs[COMM_REGS];
+};
+
+/**
+ * struct c67x00_sie - Common data associated with an SIE
+ * @lock: lock to protect this struct
+ * @private_data: subdriver dependent data
+ * @pdev: platform device associated with this SIE, created in c67x00-drv.c
+ * @irq: subdriver depenent irq handler, set NULL when not used
+ * @msg_received: called when an SIEmsg has been received
+ * @dev: link to common driver structure
+ * @sie_num: SIE number on chip, starting from 0
+ * @mode: SIE mode (host/peripheral/otg/not used)
+ *
+ * Each SIE has a separate platform_device associated with it, because the
+ * hcd needs such a device for itself (TODO: use a struct device instead
+ * of a new platform device).
+ */
+struct c67x00_sie {
+ /* Entries to be used by the subdrivers */
+ spinlock_t lock; /* protect this structure */
+ void *private_data;
+ struct platform_device *pdev;
+ irqreturn_t(*irq) (int irq, struct c67x00_sie * sie);
+ void (*msg_received) (struct c67x00_sie * sie, u16 msg);
+
+ /* Read only: */
+ struct c67x00_device *dev;
+ int sie_num;
+ int mode;
+};
+
+#define sie_dev(s) (&(s)->pdev->dev)
+
+struct c67x00_hpi {
+ void __iomem *base;
+ int regstep;
+};
+
+#define C67X00_SIES 2
+#define C67X00_PORTS 2
+
+/**
+ * struct c67x00_device - Common data structure for a c67x00 instance
+ * @hpi: hpi addresses
+ * @sie: array of sie's on this chip
+ * @pdata: configuration provided by the platform
+ * @hw_lock: hardware lock
+ * @int_status: interrupt status register, only valid in_interrupt()
+ * @lcp: link control protocol dependent data
+ */
+struct c67x00_device {
+ struct c67x00_hpi hpi;
+ struct c67x00_sie sie[C67X00_SIES];
+ struct platform_device *pdev;
+ struct c67x00_platform_data *pdata;
+ spinlock_t hw_lock;
+
+ u16 int_status;
+ struct c67x00_lcp lcp;
+};
+
+/* ---------------------------------------------------------------------
+ * Low level interface functions
+ */
+
+/* Host Port Interface (hpi) functions */
+u16 c67x00_ll_hpi_status(struct c67x00_device *dev);
+void c67x00_ll_hpi_reg_init(struct c67x00_device *dev);
+void c67x00_ll_hpi_enable_sofeop(struct c67x00_sie *sie);
+void c67x00_ll_hpi_disable_sofeop(struct c67x00_sie *sie);
+
+/* General functions */
+u16 c67x00_ll_get_siemsg(struct c67x00_device *dev, int sie);
+void c67x00_ll_set_siemsg(struct c67x00_device *dev, int sie, u16 val);
+u16 c67x00_ll_get_usb_ctl(struct c67x00_sie *sie);
+
+/* Host specific functions */
+void c67x00_ll_set_husb_eot(struct c67x00_device *dev, u16 value);
+void c67x00_ll_husb_reset(struct c67x00_sie *sie, int port);
+void c67x00_ll_husb_set_current_td(struct c67x00_sie *sie, u16 addr);
+u16 c67x00_ll_husb_get_current_td(struct c67x00_sie *sie);
+void c67x00_ll_husb_clear_status(struct c67x00_sie *sie, u16 bits);
+u16 c67x00_ll_husb_get_status(struct c67x00_sie *sie);
+u16 c67x00_ll_husb_get_frame(struct c67x00_sie *sie);
+void c67x00_ll_husb_init_host_port(struct c67x00_sie *sie);
+void c67x00_ll_husb_reset_port(struct c67x00_sie *sie, int port);
+
+/* Slave specific functions */
+void c67x00_ll_susb_init(struct c67x00_sie *sie);
+
+/* Read and write to memory */
+void c67x00_ll_hpi_write_mem_le16(struct c67x00_device *dev, u16 addr,
+ int len, char *data);
+void c67x00_ll_hpi_read_mem_le16(struct c67x00_device *dev, u16 addr,
+ int len, char *data);
+
+/* Called by c67x00_irq to handle lcp interrupts */
+void c67x00_ll_irq(struct c67x00_device *dev);
+
+/* Setup and teardown */
+void c67x00_ll_init(struct c67x00_device *dev);
+void c67x00_ll_release(struct c67x00_device *dev);
+int c67x00_ll_reset(struct c67x00_device *dev);
+
+#endif /* _USB_C67X00_H */
^ permalink raw reply related [flat|nested] 20+ messages in thread
* [PATCH 3/5] USB: add Cypress c67x00 OTG controller core driver
2007-11-24 0:24 [PATCH 0/5] Review request: Cypress c67x00 OTG controller Grant Likely
2007-11-24 0:24 ` [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq Grant Likely
2007-11-24 0:24 ` [PATCH 2/5] USB: Add Cypress c67x00 low level interface code Grant Likely
@ 2007-11-24 0:24 ` Grant Likely
2007-11-24 0:24 ` [PATCH 4/5] USB: add Cypress c67x00 OTG controller HCD driver Grant Likely
` (2 subsequent siblings)
5 siblings, 0 replies; 20+ messages in thread
From: Grant Likely @ 2007-11-24 0:24 UTC (permalink / raw)
To: linux-usb-devel, akpm, dbrownell, gregkh, linuxppc-dev
From: Grant Likely <grant.likely@secretlab.ca>
This patch add the core driver for the c67x00 USB OTG controller. The core
driver is responsible for the platform bus binding and creating either
USB HCD or USB Gadget instances for each of the serial interface engines
on the chip.
This driver does not directly implement the HCD or gadget behaviours; it
just controls access to the chip.
Signed-off-by: Grant Likely <grant.likely@secretlab.ca>
---
drivers/usb/c67x00/c67x00-drv.c | 301 +++++++++++++++++++++++++++++++++++++++
include/linux/usb/c67x00.h | 45 ++++++
2 files changed, 346 insertions(+), 0 deletions(-)
diff --git a/drivers/usb/c67x00/c67x00-drv.c b/drivers/usb/c67x00/c67x00-drv.c
new file mode 100644
index 0000000..e1b1db1
--- /dev/null
+++ b/drivers/usb/c67x00/c67x00-drv.c
@@ -0,0 +1,301 @@
+/*
+ * c67x00-drv.c: Cypress C67X00 USB Common infrastructure
+ *
+ * Copyright (C) 2006-2007 Barco N.V.
+ * Derived from the Cypress cy7c67200/300 ezusb linux driver and
+ * based on multiple host controller drivers inside the linux kernel.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+ * MA 02110-1301 USA.
+ */
+
+/*
+ * This file implements the common infrastructure for using the c67x00.
+ * It is both the link between the platform configuration and subdrivers and
+ * the link between the common hardware parts and the subdrivers (e.g.
+ * interrupt handling).
+ *
+ * The c67x00 has 2 SIE's (serial interface engine) wich can be configured
+ * to be host, device or OTG (with some limitations, E.G. only SIE1 can be OTG).
+ *
+ * Depending on the platform configuration, the SIE's are created (setup_sie)
+ * and the corresponding subdriver is initialized (c67x00_probe_sie).
+ */
+
+#include <linux/device.h>
+#include <linux/list.h>
+#include <linux/usb.h>
+#include <linux/usb/c67x00.h>
+#include <asm/io.h>
+
+#include "c67x00.h"
+#include "c67x00-hcd.h"
+#include "c67x00-udc.h"
+
+static struct platform_driver c67x00_driver;
+
+static void
+c67x00_setup_sie(struct c67x00_sie *sie, struct c67x00_device *dev, int sie_num)
+{
+ static unsigned int id = 0;
+
+ /* Fill in needed attributes */
+ sie->pdev = platform_device_register_simple("c67x00_sie",
+ id++, NULL, 0);
+ /* driver used in hub.c: hub_port_init */
+ sie->pdev->dev.driver = &c67x00_driver.driver;
+ spin_lock_init(&sie->lock);
+ sie->dev = dev;
+ sie->sie_num = sie_num;
+ sie->mode = c67x00_sie_config(dev->pdata->sie_config, sie_num);
+}
+
+static void c67x00_teardown_sie(struct c67x00_sie *sie)
+{
+ sie->pdev->dev.driver = NULL;
+ platform_device_unregister(sie->pdev);
+}
+
+/* ------------------------------------------------------------------ */
+
+static void c67x00_probe_sie(struct c67x00_sie *sie)
+{
+ switch (c67x00_sie_config(sie->dev->pdata->sie_config, sie->sie_num)) {
+ case C67X00_SIE_HOST:
+ c67x00_hcd_probe(sie);
+ break;
+
+ case C67X00_SIE_PERIPHERAL:
+ c67x00_udc_probe(sie);
+ break;
+
+ case C67X00_SIE_UNUSED:
+ dev_info(sie_dev(sie),
+ "Not using SIE %d as requested\n", sie->sie_num);
+ break;
+
+ default:
+ dev_err(sie_dev(sie),
+ "Unsupported configuration: 0x%x for SIE %d\n",
+ c67x00_sie_config(sie->dev->pdata->sie_config,
+ sie->sie_num), sie->sie_num);
+ break;
+ }
+}
+
+static void c67x00_remove_sie(struct c67x00_sie *sie)
+{
+ switch (c67x00_sie_config(sie->dev->pdata->sie_config, sie->sie_num)) {
+ case C67X00_SIE_HOST:
+ c67x00_hcd_remove(sie);
+ break;
+
+ case C67X00_SIE_PERIPHERAL:
+ c67x00_udc_remove(sie);
+ break;
+
+ default:
+ break;
+ }
+}
+
+/* ------------------------------------------------------------------ */
+
+static void
+c67x00_sie_irq(struct c67x00_device *c67x00, int sie_idx, int irq)
+{
+ struct c67x00_sie *sie = &c67x00->sie[sie_idx];
+
+ spin_lock(&sie->lock);
+ if (c67x00->int_status & SIEMSG_FLAG(sie_idx)) {
+ u16 msg = c67x00_ll_get_siemsg(c67x00, sie_idx);
+ if (sie->msg_received)
+ sie->msg_received(sie, msg);
+ }
+ if (sie->irq)
+ sie->irq(irq, sie);
+ spin_unlock(&sie->lock);
+}
+
+static irqreturn_t c67x00_irq(int irq, void *__dev)
+{
+ struct c67x00_device *c67x00 = __dev;
+ int i, count = 8;
+
+ c67x00->int_status = c67x00_ll_hpi_status(c67x00);
+ if (!c67x00->int_status)
+ return IRQ_NONE;
+
+ while (c67x00->int_status != 0 && (count-- >= 0)) {
+ c67x00_ll_irq(c67x00);
+ for (i = 0; i < C67X00_SIES; i++)
+ c67x00_sie_irq(c67x00, i, irq);
+ c67x00->int_status = c67x00_ll_hpi_status(c67x00);
+ }
+
+ if (c67x00->int_status)
+ dev_warn(&c67x00->pdev->dev, "Not all interrupts handled! "
+ "status = 0x%04x\n", c67x00->int_status);
+
+ return IRQ_HANDLED;
+}
+
+/* ---------------------------------------------------------------------
+ * Platform bus binding
+ */
+
+static int __devinit c67x00_drv_probe(struct platform_device *pdev)
+{
+ struct c67x00_device *c67x00;
+ struct c67x00_platform_data *pdata;
+ struct resource *res, *res2;
+ int ret, i;
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (!res)
+ return -ENODEV;
+
+ res2 = platform_get_resource(pdev, IORESOURCE_IRQ, 0);
+ if (!res2)
+ return -ENODEV;
+
+ pdata = (struct c67x00_platform_data*)pdev->dev.platform_data;
+ if (!pdata)
+ return -ENODEV;
+
+ c67x00 = kzalloc(sizeof(*c67x00), GFP_KERNEL);
+ if (!c67x00)
+ return -ENOMEM;
+
+ if (!request_mem_region(res->start, res->end - res->start + 1,
+ pdev->name)) {
+ dev_err(&pdev->dev, "Memory region busy\n");
+ ret = -EBUSY;
+ goto request_mem_failed;
+ }
+ c67x00->hpi.base = ioremap(res->start, res->end - res->start + 1);
+ if (!c67x00->hpi.base) {
+ dev_err(&pdev->dev, "Unable to map HPI registers\n");
+ ret = -EIO;
+ goto map_failed;
+ }
+
+ spin_lock_init(&c67x00->hw_lock);
+ c67x00->hpi.regstep = pdata->hpi_regstep;
+ c67x00->pdata = pdev->dev.platform_data;
+ c67x00->pdev = pdev;
+
+ for (i = 0; i < C67X00_SIES; i++)
+ c67x00_setup_sie(&c67x00->sie[i], c67x00, i);
+
+ c67x00_ll_init(c67x00);
+ c67x00_ll_hpi_reg_init(c67x00);
+
+ dev_info(&pdev->dev, "USB OTG controller, p:0x%x, v:0x%p, irq:%i\n",
+ res->start, c67x00->hpi.base, res2->start);
+
+ ret = request_irq(res2->start, c67x00_irq, 0, pdev->name, c67x00);
+ if (ret) {
+ dev_err(&pdev->dev, "Cannot claim IRQ\n");
+ goto request_irq_failed;
+ }
+
+ ret = c67x00_ll_reset(c67x00);
+ if (ret) {
+ dev_err(&pdev->dev, "Device reset failed\n");
+ goto reset_failed;
+ }
+
+ for (i = 0; i < C67X00_SIES; i++)
+ c67x00_probe_sie(&c67x00->sie[i]);
+
+ platform_set_drvdata(pdev, c67x00);
+
+ return 0;
+
+ reset_failed:
+ free_irq(res2->start, c67x00);
+ request_irq_failed:
+ iounmap(c67x00->hpi.base);
+ map_failed:
+ release_mem_region(res->start, res->end - res->start + 1);
+ request_mem_failed:
+ kfree(c67x00);
+
+ return ret;
+}
+
+static int __devexit c67x00_drv_remove(struct platform_device *pdev)
+{
+ struct c67x00_device *c67x00 = platform_get_drvdata(pdev);
+ struct resource *res;
+ int i;
+
+ for (i = 0; i < C67X00_SIES; i++) {
+ c67x00_remove_sie(&c67x00->sie[i]);
+ c67x00_teardown_sie(&c67x00->sie[i]);
+ }
+
+ c67x00_ll_release(c67x00);
+
+ res = platform_get_resource(pdev, IORESOURCE_IRQ, 0);
+ if (res)
+ free_irq(res->start, c67x00);
+
+ iounmap(c67x00->hpi.base);
+
+ res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ if (res)
+ release_mem_region(res->start, res->end - res->start + 1);
+
+ kfree(c67x00);
+
+ return 0;
+}
+
+static struct platform_driver c67x00_driver = {
+ .probe = c67x00_drv_probe,
+ .remove = c67x00_drv_remove,
+ .driver = {
+ .owner = THIS_MODULE,
+ .name = "c67x00",
+ },
+};
+
+static int __init c67x00_init(void)
+{
+ int ret;
+
+ if (usb_disabled())
+ return -ENODEV;
+
+ ret = c67x00_udc_init();
+ if (ret)
+ return ret;
+
+ return platform_driver_register(&c67x00_driver);
+}
+module_init(c67x00_init);
+
+static void __exit c67x00_exit(void)
+{
+ c67x00_udc_cleanup();
+ platform_driver_unregister(&c67x00_driver);
+}
+module_exit(c67x00_exit);
+
+MODULE_AUTHOR("Peter Korsgaard, Jan Veldeman, Grant Likely");
+MODULE_DESCRIPTION("Cypress C67X00 USB Controller Driver");
+MODULE_LICENSE("GPL");
diff --git a/include/linux/usb/c67x00.h b/include/linux/usb/c67x00.h
new file mode 100644
index 0000000..80b1a87
--- /dev/null
+++ b/include/linux/usb/c67x00.h
@@ -0,0 +1,45 @@
+/*
+ * usb_c67x00.h: platform definitions for the Cypress C67X00 USB chip
+ *
+ * Copyright (C) 2006-2007 Barco N.V.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+ * MA 02110-1301 USA.
+ */
+
+#ifndef _LINUX_USB_C67X00_H
+#define _LINUX_USB_C67X00_H
+
+/* SIE configuration */
+#define C67X00_SIE_UNUSED 0
+#define C67X00_SIE_HOST 1
+#define C67X00_SIE_PERIPHERAL 2
+
+#define c67x00_sie_config(config, n) (((config)>>(4*(n)))&0x3)
+
+#define C67X00_SIE1_UNUSED (C67X00_SIE_UNUSED << 0)
+#define C67X00_SIE1_HOST (C67X00_SIE_HOST << 0)
+#define C67X00_SIE1_PERIPHERAL (C67X00_SIE_PERIPHERAL << 0)
+
+#define C67X00_SIE2_UNUSED (C67X00_SIE_UNUSED << 4)
+#define C67X00_SIE2_HOST (C67X00_SIE_HOST << 4)
+#define C67X00_SIE2_PERIPHERAL (C67X00_SIE_PERIPHERAL << 4)
+
+struct c67x00_platform_data {
+ int sie_config; /* SIEs config (C67X00_SIEx_*) */
+ unsigned long hpi_regstep; /* Step between HPI registers */
+};
+
+#endif /* _LINUX_USB_C67X00_H */
^ permalink raw reply related [flat|nested] 20+ messages in thread
* [PATCH 4/5] USB: add Cypress c67x00 OTG controller HCD driver
2007-11-24 0:24 [PATCH 0/5] Review request: Cypress c67x00 OTG controller Grant Likely
` (2 preceding siblings ...)
2007-11-24 0:24 ` [PATCH 3/5] USB: add Cypress c67x00 OTG controller core driver Grant Likely
@ 2007-11-24 0:24 ` Grant Likely
2007-11-24 3:56 ` [linux-usb-devel] " Alan Stern
2007-11-24 0:24 ` [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles Grant Likely
2007-11-24 17:57 ` [PATCH 0/5] Review request: Cypress c67x00 OTG controller David Brownell
5 siblings, 1 reply; 20+ messages in thread
From: Grant Likely @ 2007-11-24 0:24 UTC (permalink / raw)
To: linux-usb-devel, akpm, dbrownell, gregkh, linuxppc-dev
From: Grant Likely <grant.likely@secretlab.ca>
This patch adds HDC support for the Cypress c67x00 family of devices.
Signed-off-by: Grant Likely <grant.likely@secretlab.ca>
---
drivers/usb/c67x00/c67x00-hcd.c | 390 ++++++++++++
drivers/usb/c67x00/c67x00-hcd.h | 163 +++++
drivers/usb/c67x00/c67x00-sched.c | 1215 +++++++++++++++++++++++++++++++++++++
3 files changed, 1768 insertions(+), 0 deletions(-)
diff --git a/drivers/usb/c67x00/c67x00-hcd.c b/drivers/usb/c67x00/c67x00-hcd.c
new file mode 100644
index 0000000..6ffca60
--- /dev/null
+++ b/drivers/usb/c67x00/c67x00-hcd.c
@@ -0,0 +1,390 @@
+/*
+ * c67x00-hcd.c: Cypress C67X00 USB Host Controller Driver
+ *
+ * Copyright (C) 2006-2007 Barco N.V.
+ * Derived from the Cypress cy7c67200/300 ezusb linux driver and
+ * based on multiple host controller drivers inside the linux kernel.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+ * MA 02110-1301 USA.
+ */
+
+#include <linux/device.h>
+#include <linux/platform_device.h>
+#include <linux/usb.h>
+
+#include "c67x00.h"
+#include "c67x00-hcd.h"
+
+/* --------------------------------------------------------------------------
+ * Root Hub Support
+ */
+
+static __u8 c67x00_hub_des[] = {
+ 0x09, /* __u8 bLength; */
+ 0x29, /* __u8 bDescriptorType; Hub-descriptor */
+ 0x02, /* __u8 bNbrPorts; */
+ 0x00, /* __u16 wHubCharacteristics; */
+ 0x00, /* (per-port OC, no power switching) */
+ 0x32, /* __u8 bPwrOn2pwrGood; 2ms */
+ 0x00, /* __u8 bHubContrCurrent; 0 mA */
+ 0x00, /* __u8 DeviceRemovable; ** 7 Ports max ** */
+ 0xff, /* __u8 PortPwrCtrlMask; ** 7 ports max ** */
+};
+
+#define OK(x) len = (x); break
+
+static void c67x00_hub_reset_host_port(struct c67x00_sie *sie, int port)
+{
+ struct c67x00_hcd *c67x00 = sie->private_data;
+ unsigned long flags;
+
+ c67x00_ll_husb_reset(sie, port);
+
+ spin_lock_irqsave(&c67x00->lock, flags);
+ c67x00_ll_husb_reset_port(sie, port);
+ spin_unlock_irqrestore(&c67x00->lock, flags);
+
+ c67x00_ll_set_husb_eot(sie->dev, DEFAULT_EOT);
+}
+
+static int c67x00_hub_status_data(struct usb_hcd *hcd, char *buf)
+{
+ struct c67x00_hcd *c67x00 = hcd_to_c67x00_hcd(hcd);
+ struct c67x00_sie *sie = c67x00->sie;
+ u16 status;
+ int i;
+
+ *buf = 0;
+ status = c67x00_ll_husb_get_status(sie);
+ for (i=0; i<C67X00_PORTS; i++)
+ if (status & PORT_CONNECT_CHANGE(i))
+ *buf |= (1 << i);
+
+ /* bit 0 denotes hub change, b1..n port change */
+ *buf <<= 1;
+
+ return !!*buf;
+}
+
+static int c67x00_hub_control(struct usb_hcd *hcd, u16 typeReq, u16 wValue,
+ u16 wIndex, char *buf, u16 wLength)
+{
+ struct c67x00_hcd *c67x00 = hcd_to_c67x00_hcd(hcd);
+ struct c67x00_sie *sie = c67x00->sie;
+ u16 status, usb_status;
+ int len = 0;
+ unsigned int port = wIndex-1;
+ u16 wPortChange, wPortStatus;
+
+ switch (typeReq) {
+
+ case GetHubStatus:
+ *(__le32 *) buf = cpu_to_le32(0);
+ len = 4; /* hub power */
+ break;
+ case GetPortStatus:
+ if (wIndex > C67X00_PORTS)
+ return -EPIPE;
+
+ status = c67x00_ll_husb_get_status(sie);
+ usb_status = c67x00_ll_get_usb_ctl(sie);
+
+ wPortChange = 0;
+ if (status & PORT_CONNECT_CHANGE(port))
+ wPortChange |= USB_PORT_STAT_C_CONNECTION;
+
+ wPortStatus = USB_PORT_STAT_POWER;
+ if (!(status & PORT_SE0_STATUS(port)))
+ wPortStatus |= USB_PORT_STAT_CONNECTION;
+ if (usb_status & LOW_SPEED_PORT(port)) {
+ wPortStatus |= USB_PORT_STAT_LOW_SPEED;
+ c67x00->low_speed_ports |= (1 << port);
+ } else
+ c67x00->low_speed_ports &= ~(1 << port);
+
+ if (usb_status & SOF_EOP_EN(port))
+ wPortStatus |= USB_PORT_STAT_ENABLE;
+
+ *(__le16 *) buf = cpu_to_le16(wPortStatus);
+ *(__le16 *) (buf + 2) = cpu_to_le16(wPortChange);
+ len = 4;
+ break;
+ case SetHubFeature: /* We don't implement these */
+ case ClearHubFeature:
+ switch (wValue) {
+ case C_HUB_OVER_CURRENT:
+ case C_HUB_LOCAL_POWER:
+ len = 0;
+ break;
+ default:
+ return -EPIPE;
+ }
+ break;
+ case SetPortFeature:
+ if (wIndex > C67X00_PORTS)
+ return -EPIPE;
+
+ switch (wValue) {
+ case USB_PORT_FEAT_SUSPEND:
+ dev_dbg(c67x00_dev(c67x00),
+ "SetPortFeature %d (SUSPEND)\n", port);
+ len = 0;
+ break;
+ case USB_PORT_FEAT_RESET:
+ c67x00_hub_reset_host_port(sie, port);
+ len = 0;
+ break;
+ case USB_PORT_FEAT_POWER:
+ /* Power always enabled */
+ len = 0;
+ break;
+ default:
+ dev_dbg(c67x00_dev(c67x00),
+ "%s: SetPortFeature %d (0x%04x) Error!\n",
+ __FUNCTION__, port, wValue);
+ return -EPIPE;
+ }
+ break;
+ case ClearPortFeature:
+ if (wIndex > C67X00_PORTS)
+ return -EPIPE;
+
+ switch (wValue) {
+ case USB_PORT_FEAT_ENABLE:
+ /* Reset the port so that the c67x00 also notices the
+ * disconnect */
+ c67x00_hub_reset_host_port(sie, port);
+ len = 0;
+ break;
+ case USB_PORT_FEAT_C_ENABLE:
+ dev_dbg(c67x00_dev(c67x00),
+ "ClearPortFeature (%d): C_ENABLE\n", port);
+ len = 0;
+ break;
+ case USB_PORT_FEAT_SUSPEND:
+ dev_dbg(c67x00_dev(c67x00),
+ "ClearPortFeature (%d): SUSPEND\n", port);
+ len = 0;
+ break;
+ case USB_PORT_FEAT_C_SUSPEND:
+ dev_dbg(c67x00_dev(c67x00),
+ "ClearPortFeature (%d): C_SUSPEND\n", port);
+ len = 0;
+ break;
+ case USB_PORT_FEAT_POWER:
+ dev_dbg(c67x00_dev(c67x00),
+ "ClearPortFeature (%d): POWER\n", port);
+ return -EPIPE;
+ case USB_PORT_FEAT_C_CONNECTION:
+ c67x00_ll_husb_clear_status(sie,
+ PORT_CONNECT_CHANGE(port));
+ len = 0;
+ break;
+ case USB_PORT_FEAT_C_OVER_CURRENT:
+ dev_dbg(c67x00_dev(c67x00),
+ "ClearPortFeature (%d): OVER_CURRENT\n", port);
+ len = 0;
+ break;
+ case USB_PORT_FEAT_C_RESET:
+ dev_dbg(c67x00_dev(c67x00),
+ "ClearPortFeature (%d): C_RESET\n", port);
+ len = 0;
+ break;
+ default:
+ dev_dbg(c67x00_dev(c67x00),
+ "%s: ClearPortFeature %d (0x%04x) Error!\n",
+ __FUNCTION__, port, wValue);
+ return -EPIPE;
+ }
+ break;
+ case GetHubDescriptor:
+ len = min_t(unsigned int, sizeof(c67x00_hub_des), wLength);
+ memcpy(buf, c67x00_hub_des, len);
+ break;
+ default:
+ dev_dbg(c67x00_dev(c67x00), "%s: unknown\n", __FUNCTION__);
+ }
+
+ return 0;
+}
+
+/* ---------------------------------------------------------------------
+ * Main part of host controller driver
+ */
+
+/**
+ * c67x00_hcd_drv_irq
+ *
+ * This function is called from the interrupt handler in c67x00-drv.c
+ * We can't have the hcd register the irq (it has already been registerd
+ * by the common driver), so we must fake it through this call.
+ */
+static irqreturn_t c67x00_hcd_drv_irq(int irq, struct c67x00_sie *sie)
+{
+ struct c67x00_hcd *c67x00 = sie->private_data;
+ return usb_hcd_irq(irq, c67x00_hcd_to_hcd(c67x00));
+}
+
+static irqreturn_t c67x00_hcd_irq(struct usb_hcd *hcd)
+{
+ struct c67x00_hcd *c67x00 = hcd_to_c67x00_hcd(hcd);
+ struct c67x00_sie *sie = c67x00->sie;
+
+ if (sie->dev->int_status & SOFEOP_FLG(sie->sie_num)) {
+ c67x00_ll_husb_clear_status(sie, SOF_EOP_IRQ_FLG);
+ c67x00_sched_kick(c67x00);
+ return IRQ_HANDLED;
+ }
+ return IRQ_NONE;
+}
+
+/**
+ * c67x00_hcd_start: Host Controller start hook
+ */
+static int c67x00_hcd_start(struct usb_hcd *hcd)
+{
+ hcd->uses_new_polling = 1;
+ hcd->state = HC_STATE_RUNNING;
+ hcd->poll_rh = 1;
+ return 0;
+}
+
+/**
+ * c67x00_hcd_start: Host Controller stop hook
+ */
+static void c67x00_hcd_stop(struct usb_hcd *hcd)
+{
+ /* Nothing todo */
+}
+
+static int c67x00_hcd_get_frame(struct usb_hcd *hcd)
+{
+ struct c67x00_hcd *c67x00 = hcd_to_c67x00_hcd(hcd);
+ u16 temp_val;
+ dev_dbg(c67x00_dev(c67x00), "%s\n", __FUNCTION__);
+ temp_val = c67x00_ll_husb_get_frame(c67x00->sie);
+ temp_val &= HOST_FRAME_MASK;
+ return temp_val ? (temp_val - 1) : HOST_FRAME_MASK;
+}
+
+static struct hc_driver c67x00_hc_driver = {
+ .description = "c67x00-hcd",
+ .product_desc = "Cypress C67X00 Host Controller",
+ .hcd_priv_size = sizeof(struct c67x00_hcd),
+
+ /*
+ * generic hardware linkage
+ */
+ .irq = c67x00_hcd_irq,
+ .flags = HCD_USB11 | HCD_MEMORY,
+
+ /*
+ * basic lifecycle operations
+ */
+ .start = c67x00_hcd_start,
+ .stop = c67x00_hcd_stop,
+
+ /*
+ * managing i/o requests and associated device resources
+ */
+ .urb_enqueue = c67x00_urb_enqueue,
+ .urb_dequeue = c67x00_urb_dequeue,
+ .endpoint_disable = c67x00_endpoint_disable,
+
+ /*
+ * scheduling support
+ */
+ .get_frame_number = c67x00_hcd_get_frame,
+
+ /*
+ * root hub support
+ */
+ .hub_status_data = c67x00_hub_status_data,
+ .hub_control = c67x00_hub_control,
+};
+
+/* ---------------------------------------------------------------------
+ * Setup/Teardown routines
+ */
+
+int c67x00_hcd_probe(struct c67x00_sie *sie)
+{
+ int retval;
+ struct usb_hcd *hcd = NULL;
+ struct c67x00_hcd *c67x00;
+
+ hcd = usb_create_hcd(&c67x00_hc_driver, sie_dev(sie), "c67x00_sie");
+ if (!hcd) {
+ retval = -ENOMEM;
+ goto err0;
+ }
+ c67x00 = hcd_to_c67x00_hcd(hcd);
+
+ spin_lock_init(&c67x00->lock);
+ c67x00->sie = sie;
+
+ INIT_LIST_HEAD(&c67x00->list[PIPE_ISOCHRONOUS]);
+ INIT_LIST_HEAD(&c67x00->list[PIPE_INTERRUPT]);
+ INIT_LIST_HEAD(&c67x00->list[PIPE_CONTROL]);
+ INIT_LIST_HEAD(&c67x00->list[PIPE_BULK]);
+ c67x00->urb_count = 0;
+ INIT_LIST_HEAD(&c67x00->td_list);
+ INIT_LIST_HEAD(&c67x00->done_list);
+ c67x00->td_base_addr = CY_HCD_BUF_ADDR + SIE_TD_OFFSET(sie->sie_num);
+ c67x00->buf_base_addr = CY_HCD_BUF_ADDR + SIE_BUF_OFFSET(sie->sie_num);
+ c67x00->max_frame_bw = MAX_FRAME_BW_STD;
+
+ spin_lock(&sie->lock);
+ sie->private_data = c67x00;
+ sie->irq = c67x00_hcd_drv_irq;
+ sie->msg_received = c67x00_hcd_msg_received;
+ spin_unlock(&sie->lock);
+
+ c67x00_ll_husb_init_host_port(sie);
+
+ init_completion(&c67x00->endpoint_disable);
+ retval = c67x00_sched_start_scheduler(c67x00);
+ if (retval)
+ goto err1;
+
+ retval = usb_add_hcd(hcd, 0, 0);
+ if (retval) {
+ dev_dbg(sie_dev(sie), "%s: usb_add_hcd returned %d\n",
+ __FUNCTION__, retval);
+ goto err2;
+ }
+
+ return retval;
+ err2:
+ c67x00_sched_stop_scheduler(c67x00);
+ err1:
+ usb_put_hcd(hcd);
+ err0:
+ return retval;
+}
+
+/* may be called with controller, bus, and devices active */
+void c67x00_hcd_remove(struct c67x00_sie *sie)
+{
+ struct usb_hcd *hcd;
+ struct c67x00_hcd *c67x00;
+
+ c67x00 = sie->private_data;
+ hcd = c67x00_hcd_to_hcd(c67x00);
+ c67x00_sched_stop_scheduler(c67x00);
+ usb_remove_hcd(hcd);
+ usb_put_hcd(hcd);
+}
diff --git a/drivers/usb/c67x00/c67x00-hcd.h b/drivers/usb/c67x00/c67x00-hcd.h
new file mode 100644
index 0000000..02efa17
--- /dev/null
+++ b/drivers/usb/c67x00/c67x00-hcd.h
@@ -0,0 +1,163 @@
+/*
+ * c67x00-hcd.h: Cypress C67X00 USB HCD
+ *
+ * Copyright (C) 2006-2007 Barco N.V.
+ * Derived from the Cypress cy7c67200/300 ezusb linux driver and
+ * based on multiple host controller drivers inside the linux kernel.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+ * MA 02110-1301 USA.
+ */
+
+#ifndef _USB_C67X00_HCD_H
+#define _USB_C67X00_HCD_H
+
+#include <linux/kernel.h>
+#include <linux/spinlock.h>
+#include <linux/list.h>
+#include <linux/usb.h>
+#include "../core/hcd.h"
+#include "c67x00.h"
+
+/*
+ * The following parameters depend on the CPU speed, bus speed, ...
+ * These can be tuned for specific use cases, e.g. if isochronous transfers
+ * are very important, bandwith can be sacrificed to guarantee that the
+ * 1ms deadline will be met.
+ * If bulk transfers are important, the MAX_FRAME_BW can be increased,
+ * but some (or many) isochronous deadlines might not be met.
+ *
+ * The values are specified in bittime.
+ */
+
+/*
+ * The current implementation switches between _STD (default) and _ISO (when
+ * isochronous transfers are scheduled), in order to optimize the throughput
+ * in normal cicrumstances, but also provide good isochronous behaviour.
+ *
+ * Bandwidth is described in bit time so with a 12MHz USB clock and 1ms
+ * frames; there are 12000 bit times per frame.
+ */
+
+#define TOTAL_FRAME_BW 12000
+#define DEFAULT_EOT 2250
+
+#define MAX_FRAME_BW_STD (TOTAL_FRAME_BW - DEFAULT_EOT)
+#define MAX_FRAME_BW_ISO 2400
+
+/*
+ * Periodic transfers may only use 90% of the full frame, but as
+ * we currently don't even use 90% of the full frame, we may
+ * use the full usable time for periodic transfers.
+ */
+#define MAX_PERIODIC_BW(full_bw) full_bw
+
+/* -------------------------------------------------------------------------- */
+
+struct c67x00_hcd {
+ spinlock_t lock;
+ struct c67x00_sie *sie;
+ /* Requirement:
+ * All enabled bits in ports must have a position <= MAX_NB_HCD_PORTS
+ * (position starts counting from 1!)
+ * ( ports & ~((1<<MAX_NB_HCD_PORTS)-1) ) == 0
+ *
+ * This might be relaxed if needed by using an other indexing scheme
+ * for port[] (e.g. use wIndex instead of real port number)
+ * */
+#define MAX_NB_HCD_PORTS 2
+ unsigned int low_speed_ports; /* bitmask of low speed ports */
+ unsigned int urb_count;
+ unsigned int urb_iso_count;
+
+ struct list_head list[4]; /* iso, int, ctrl, bulk */
+#if PIPE_BULK != 3
+#error "Sanity check failed, this code presumes PIPE_... to range from 0 to 3"
+#endif
+
+ /* USB bandwidth allocated to td_list */
+ int bandwidth_allocated;
+ /* USB bandwidth allocated for isoc/int transfer */
+ int periodic_bw_allocated;
+ struct list_head td_list;
+ struct list_head done_list;
+ int max_frame_bw;
+
+ u16 td_base_addr;
+ u16 buf_base_addr;
+ u16 next_td_addr;
+ u16 next_buf_addr;
+
+ struct tasklet_struct tasklet;
+ struct tasklet_struct done_tasklet;
+
+ struct completion endpoint_disable;
+
+ u16 current_frame;
+ u16 last_frame;
+};
+
+static inline struct c67x00_hcd *hcd_to_c67x00_hcd(struct usb_hcd *hcd)
+{
+ return (struct c67x00_hcd *)(hcd->hcd_priv);
+}
+
+static inline struct usb_hcd *c67x00_hcd_to_hcd(struct c67x00_hcd *c67x00)
+{
+ return container_of((void *)c67x00, struct usb_hcd, hcd_priv);
+}
+
+/* ---------------------------------------------------------------------
+ * Transfer Descriptor scheduling functions
+ */
+int c67x00_urb_enqueue(struct usb_hcd *hcd, struct urb *urb, gfp_t mem_flags);
+int c67x00_urb_dequeue(struct usb_hcd *hcd, struct urb *urb, int status);
+void c67x00_endpoint_disable(struct usb_hcd *hcd,
+ struct usb_host_endpoint *ep);
+
+void c67x00_hcd_msg_received(struct c67x00_sie *sie, u16 msg);
+void c67x00_sched_kick(struct c67x00_hcd *c67x00);
+int c67x00_sched_start_scheduler(struct c67x00_hcd *c67x00);
+void c67x00_sched_stop_scheduler(struct c67x00_hcd *c67x00);
+
+
+/* ---------------------------------------------------------------------
+ * Setup and teardown functions
+ */
+#ifdef CONFIG_USB_C67X00_HCD
+/* Functions used by drv */
+int c67x00_hcd_probe(struct c67x00_sie *sie);
+void c67x00_hcd_remove(struct c67x00_sie *sie);
+#else
+static inline int c67x00_hcd_probe(struct c67x00_sie *sie)
+{
+ printk(KERN_ERR "hcd requested but CONFIG_USB_C67X00_HCD "
+ "not enabled!\n");
+ return -ENODEV;
+}
+
+static inline void c67x00_hcd_remove(struct c67x00_sie *sie)
+{
+}
+
+static int usb_disabled(void)
+{
+ return 0;
+}
+#endif /* CONFIG_USB_C67X00_HCD */
+
+#define c67x00_dev(x) (c67x00_hcd_to_hcd(x)->self.controller)
+
+#endif /* _USB_C67X00_HCD_H */
diff --git a/drivers/usb/c67x00/c67x00-sched.c b/drivers/usb/c67x00/c67x00-sched.c
new file mode 100644
index 0000000..484e291
--- /dev/null
+++ b/drivers/usb/c67x00/c67x00-sched.c
@@ -0,0 +1,1215 @@
+/*
+ * c67x00-sched.c: Cypress C67X00 USB Host Controller Driver - TD scheduling
+ *
+ * Copyright (C) 2006-2007 Barco N.V.
+ * Derived from the Cypress cy7c67200/300 ezusb linux driver and
+ * based on multiple host controller drivers inside the linux kernel.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston,
+ * MA 02110-1301 USA.
+ */
+
+#include <linux/kthread.h>
+
+#include "c67x00.h"
+#include "c67x00-hcd.h"
+
+/*
+ * These are the stages for a control urb, they are kept
+ * in both urb->interval and td->privdata.
+ */
+#define SETUP_STAGE 0
+#define DATA_STAGE 1
+#define STATUS_STAGE 2
+
+/* -------------------------------------------------------------------------- */
+
+/**
+ * struct c67x00_ep_data: Host endpoint data structure
+ */
+struct c67x00_ep_data {
+ struct list_head queue;
+ struct list_head node;
+ struct usb_host_endpoint *hep;
+ struct usb_device *dev;
+ u16 next_frame; /* For int/isoc transactions */
+};
+
+/**
+ * struct c67x00_td
+ *
+ * Hardware parts are little endiannes, SW in CPU endianess.
+ */
+struct c67x00_td {
+ /* HW specific part */
+ __le16 ly_base_addr; /* Bytes 0-1 */
+ __le16 port_length; /* Bytes 2-3 */
+ u8 pid_ep; /* Byte 4 */
+ u8 dev_addr; /* Byte 5 */
+ u8 ctrl_reg; /* Byte 6 */
+ u8 status; /* Byte 7 */
+ u8 retry_cnt; /* Byte 8 */
+#define TT_OFFSET 2
+#define TT_CONTROL 0
+#define TT_ISOCHRONOUS 1
+#define TT_BULK 2
+#define TT_INTERRUPT 3
+ u8 residue; /* Byte 9 */
+ __le16 next_td_addr; /* Bytes 10-11 */
+ /* SW part */
+ struct list_head td_list;
+ u16 td_addr;
+ char *data;
+ struct urb *urb;
+ unsigned long privdata;
+
+ /* These are needed for handling the toggle bits:
+ * an urb can be dequeued while a td is in progress
+ * after checking the td, the toggle bit might need to
+ * be fixed */
+ struct c67x00_ep_data *ep_data;
+ unsigned int pipe;
+};
+
+struct c67x00_urb_priv {
+ struct list_head hep_node;
+ struct urb *urb;
+ int port;
+ int cnt; /* packet number for isoc */
+ int status;
+ struct c67x00_ep_data *ep_data;
+};
+
+#define td_udev(td) ((td)->ep_data->dev)
+
+#define CY_TD_SIZE 12
+
+#define TD_PIDEP_OFFSET 0x04
+#define TD_PIDEPMASK_PID 0xF0
+#define TD_PIDEPMASK_EP 0x0F
+#define TD_PORTLENMASK_DL 0x02FF
+#define TD_PORTLENMASK_PN 0xC000
+
+#define TD_STATUS_OFFSET 0x07
+#define TD_STATUSMASK_ACK 0x01
+#define TD_STATUSMASK_ERR 0x02
+#define TD_STATUSMASK_TMOUT 0x04
+#define TD_STATUSMASK_SEQ 0x08
+#define TD_STATUSMASK_SETUP 0x10
+#define TD_STATUSMASK_OVF 0x20
+#define TD_STATUSMASK_NAK 0x40
+#define TD_STATUSMASK_STALL 0x80
+
+#define TD_ERROR_MASK (TD_STATUSMASK_ERR | TD_STATUSMASK_TMOUT | \
+ TD_STATUSMASK_STALL )
+
+#define TD_RETRYCNT_OFFSET 0x08
+#define TD_RETRYCNTMASK_ACT_FLG 0x10
+#define TD_RETRYCNTMASK_TX_TYPE 0x0C
+#define TD_RETRYCNTMASK_RTY_CNT 0x03
+
+#define TD_RESIDUE_OVERFLOW 0x80
+
+#define TD_PID_IN 0x90
+
+/* Residue: signed 8bits, neg -> OVERFLOW, pos -> UNDERFLOW */
+#define td_residue(td) ((__s8)(td->residue))
+#define td_ly_base_addr(td) (__le16_to_cpu((td)->ly_base_addr))
+#define td_port_length(td) (__le16_to_cpu((td)->port_length))
+#define td_next_td_addr(td) (__le16_to_cpu((td)->next_td_addr))
+
+#define td_active(td) ((td)->retry_cnt & TD_RETRYCNTMASK_ACT_FLG)
+#define td_length(td) (td_port_length(td) & TD_PORTLENMASK_DL)
+
+#define td_sequence_ok(td) (!td->status || \
+ ( !(td->status & TD_STATUSMASK_SEQ) == \
+ !(td->ctrl_reg & SEQ_SEL) ))
+
+#define td_acked(td) (!td->status || \
+ (td->status & TD_STATUSMASK_ACK))
+#define td_actual_bytes(td) (td_length(td) - td_residue(td))
+
+/* -------------------------------------------------------------------------- */
+
+#ifdef DEBUG
+/*
+ * These patterns are written into the c67x00 internal memory and the
+ * urb->transfer_buffer respectively in order to simplify debugging.
+ */
+#define NON_RECEIVED_PATTERN 0xac
+#define UNREAD_PATTERN 0x0c
+/* #define DEBUG_PATTERN */
+
+/**
+ * dbg_td - Dump the contents of the TD
+ */
+static void dbg_td(struct c67x00_hcd *c67x00, struct c67x00_td *td, char *msg)
+{
+ struct device *dev = c67x00_dev(c67x00);
+ int i, len = td_length(td);
+ dev_dbg(dev, "### %s at 0x%04x\n", msg, td->td_addr);
+ dev_dbg(dev, "urb: 0x%p\n", td->urb);
+ dev_dbg(dev, "endpoint: %4d\n", usb_pipeendpoint(td->pipe));
+ dev_dbg(dev, "pipeout: %4d\n", usb_pipeout(td->pipe));
+ dev_dbg(dev, "ly_base_addr: 0x%04x\n", td_ly_base_addr(td));
+ dev_dbg(dev, "port_length: 0x%04x\n", td_port_length(td));
+ dev_dbg(dev, "pid_ep: 0x%02x\n", td->pid_ep);
+ dev_dbg(dev, "dev_addr: 0x%02x\n", td->dev_addr);
+ dev_dbg(dev, "ctrl_reg: 0x%02x\n", td->ctrl_reg);
+ dev_dbg(dev, "status: 0x%02x\n", td->status);
+ dev_dbg(dev, "retry_cnt: 0x%02x\n", td->retry_cnt);
+ dev_dbg(dev, "residue: 0x%02x\n", td->residue);
+ dev_dbg(dev, "next_td_addr: 0x%04x\n", td_next_td_addr(td));
+ dev_dbg(dev, "data:");
+ for (i = 0; i < len; i++) {
+ if (!(i % 8))
+ printk("\n ");
+ printk(" 0x%02x", td->data[i]);
+ }
+ printk("\n");
+}
+#else /* DEBUG */
+
+static inline void
+dbg_td(struct c67x00_hcd *c67x00, struct c67x00_td *td, char *msg) { }
+
+#endif /* DEBUG */
+
+/* -------------------------------------------------------------------------- */
+/* Helper functions */
+
+/* -------------------------------------------------------------------------- */
+
+static inline u16 c67x00_get_current_frame_number(struct c67x00_hcd *c67x00)
+{
+ u16 temp_val;
+ temp_val = c67x00_ll_husb_get_frame(c67x00->sie);
+ temp_val &= HOST_FRAME_MASK;
+ return temp_val;
+}
+
+/**
+ * frame_add
+ * Software wraparound for framenumbers.
+ */
+static inline u16 frame_add(u16 a, u16 b)
+{
+ return (a + b) & HOST_FRAME_MASK;
+}
+
+/**
+ * frame_after - is frame a after frame b
+ */
+static inline int frame_after(u16 a, u16 b)
+{
+ return ((HOST_FRAME_MASK + a - b) & HOST_FRAME_MASK) <
+ (HOST_FRAME_MASK / 2);
+}
+
+/**
+ * frame_after_eq - is frame a after or equal to frame b
+ */
+static inline int frame_after_eq(u16 a, u16 b)
+{
+ return ((HOST_FRAME_MASK + 1 + a - b) & HOST_FRAME_MASK) <
+ (HOST_FRAME_MASK / 2);
+}
+
+/* -------------------------------------------------------------------------- */
+
+/**
+ * c67x00_release_urb - remove link from all tds to this urb
+ * Disconnects the urb from it's tds, so that it can be given back.
+ * pre: urb->hcpriv != NULL
+ */
+static void c67x00_release_urb(struct c67x00_hcd *c67x00, struct urb *urb)
+{
+ struct c67x00_td *td;
+ struct c67x00_urb_priv *urbp;
+
+ BUG_ON(!urb);
+
+ c67x00->urb_count--;
+
+ if (usb_pipetype(urb->pipe) == PIPE_ISOCHRONOUS) {
+ c67x00->urb_iso_count--;
+ if (c67x00->urb_iso_count == 0)
+ c67x00->max_frame_bw = MAX_FRAME_BW_STD;
+ }
+
+ /* TODO this might be not so efficient when we've got many urbs!
+ * Alternatives:
+ * * only clear when needed
+ * * keep a list of tds with earch urbp
+ */
+ list_for_each_entry(td, &c67x00->td_list, td_list) {
+ if (urb == td->urb)
+ td->urb = NULL;
+ }
+
+ /* Discard the urb private data */
+ urbp = urb->hcpriv;
+ urb->hcpriv = NULL;
+ list_del(&urbp->hep_node);
+ kfree(urbp);
+}
+
+/* -------------------------------------------------------------------------- */
+
+static struct c67x00_ep_data *
+c67x00_ep_data_alloc(struct c67x00_hcd *c67x00, struct urb *urb)
+{
+ //struct usb_device *udev = urb->dev;
+ struct usb_host_endpoint *hep = urb->ep;
+ struct c67x00_ep_data *ep_data;
+ struct c67x00_ep_data *prev;
+ int type;
+
+ c67x00->current_frame = c67x00_get_current_frame_number(c67x00);
+
+ /* Check if endpoint already has a c67x00_ep_data struct allocated */
+ if (hep->hcpriv) {
+ ep_data = hep->hcpriv;
+ if (frame_after(c67x00->current_frame, ep_data->next_frame))
+ ep_data->next_frame =
+ frame_add(c67x00->current_frame, 1);
+ return hep->hcpriv;
+ }
+
+ /* Allocate and initialize a new c67x00 endpoint data structure */
+ ep_data = kzalloc(sizeof(*ep_data), GFP_ATOMIC);
+ if (!ep_data)
+ return NULL;
+
+ INIT_LIST_HEAD(&ep_data->queue);
+ INIT_LIST_HEAD(&ep_data->node);
+ ep_data->hep = hep;
+
+ /* hold a reference to udev as long as this endpoint lives,
+ * this is needed to possibly fix the data toggle */
+ ep_data->dev = usb_get_dev(urb->dev);
+ hep->hcpriv = ep_data;
+
+ /* For ISOC and INT endpoints, start ASAP: */
+ ep_data->next_frame = frame_add(c67x00->current_frame, 1);
+
+ /* Add the endpoint data to one of the pipe lists; must be added
+ * in order of endpoint address */
+ type = usb_pipetype(urb->pipe);
+ if (list_empty(&ep_data->node)) {
+ list_add(&ep_data->node, &c67x00->list[type]);
+ } else {
+ list_for_each_entry(prev, &c67x00->list[type], node) {
+ if (prev->hep->desc.bEndpointAddress >
+ hep->desc.bEndpointAddress) {
+ list_add(&ep_data->node, prev->node.prev);
+ break;
+ }
+ }
+ }
+
+ return ep_data;
+}
+
+static int c67x00_ep_data_free(struct usb_host_endpoint *hep)
+{
+ struct c67x00_ep_data *ep_data = hep->hcpriv;
+ if (!ep_data)
+ return 0;
+
+ if (!list_empty(&ep_data->queue))
+ return -EBUSY;
+
+ usb_put_dev(ep_data->dev);
+ list_del(&ep_data->queue);
+ list_del(&ep_data->node);
+
+ kfree(ep_data);
+ hep->hcpriv = NULL;
+
+ return 0;
+}
+
+void c67x00_endpoint_disable(struct usb_hcd *hcd, struct usb_host_endpoint *ep)
+{
+ struct c67x00_hcd *c67x00 = hcd_to_c67x00_hcd(hcd);
+ unsigned long flags;
+
+ if (!list_empty(&ep->urb_list))
+ dev_warn(c67x00_dev(c67x00), "error: urb list not empty\n");
+
+ spin_lock_irqsave(&c67x00->lock, flags);
+
+ /* Loop waiting for all transfers in the endpoint queue to complete */
+ while (c67x00_ep_data_free(ep)) {
+ /* Drop the lock so we can sleep waiting for the hardware */
+ spin_unlock_irqrestore(&c67x00->lock, flags);
+
+ /* it could happen that we reinitialize this completion, while
+ * somebody was waiting for that completion. The timeout and
+ * while loop handle such cases, but this might be improved */
+ INIT_COMPLETION(c67x00->endpoint_disable);
+ c67x00_sched_kick(c67x00);
+ wait_for_completion_timeout(&c67x00->endpoint_disable, 1 * HZ);
+
+ spin_lock_irqsave(&c67x00->lock, flags);
+ }
+
+ spin_unlock_irqrestore(&c67x00->lock, flags);
+}
+
+/* -------------------------------------------------------------------------- */
+
+static inline int get_root_port(struct usb_device *dev)
+{
+ while (dev->parent->parent)
+ dev = dev->parent;
+ return dev->portnum;
+}
+
+int c67x00_urb_enqueue(struct usb_hcd *hcd,
+ struct urb *urb, gfp_t mem_flags)
+{
+ int ret;
+ unsigned long flags;
+ struct c67x00_urb_priv *urbp = NULL;
+ struct c67x00_hcd *c67x00 = hcd_to_c67x00_hcd(hcd);
+ int port = get_root_port(urb->dev)-1;
+
+ spin_lock_irqsave(&c67x00->lock, flags);
+
+ /* Make sure host controller is running */
+ if (!HC_IS_RUNNING(hcd->state)) {
+ ret = -ENODEV;
+ goto err_not_linked;
+ }
+
+ ret = usb_hcd_link_urb_to_ep(hcd, urb);
+ if (ret)
+ goto err_not_linked;
+
+ /* Allocate and initialize urb private data */
+ urbp = kzalloc(sizeof(*urbp), mem_flags);
+ if (!urbp) {
+ ret = -ENOMEM;
+ goto err_urbp;
+ }
+ INIT_LIST_HEAD(&urbp->hep_node);
+ urbp->urb = urb;
+ urbp->port = port;
+
+ urbp->ep_data = c67x00_ep_data_alloc(c67x00, urb);
+ if (!urbp->ep_data) {
+ ret = -ENOMEM;
+ goto err_epdata;
+ }
+
+ /* TODO claim bandwidth with usb_claim_bandwidth?
+ * also release it somewhere! */
+
+ urb->hcpriv = urbp;
+
+ urb->actual_length = 0; /* Nothing received/transmitted yet */
+
+ switch (usb_pipetype(urb->pipe)) {
+ case PIPE_CONTROL:
+ urb->interval = SETUP_STAGE;
+ break;
+ case PIPE_INTERRUPT:
+ break;
+ case PIPE_BULK:
+ break;
+ case PIPE_ISOCHRONOUS:
+ if (c67x00->urb_iso_count == 0)
+ c67x00->max_frame_bw = MAX_FRAME_BW_ISO;
+ c67x00->urb_iso_count++;
+ /* Assume always URB_ISO_ASAP, FIXME */
+ if (list_empty(&urbp->ep_data->queue))
+ urb->start_frame = urbp->ep_data->next_frame;
+ else {
+ /* Go right after the last one */
+ struct urb *last_urb;
+
+ last_urb = list_entry(urbp->ep_data->queue.prev,
+ struct c67x00_urb_priv, hep_node)->urb;
+ urb->start_frame =
+ frame_add(last_urb->start_frame,
+ last_urb->number_of_packets *
+ last_urb->interval);
+ }
+ urbp->cnt = 0;
+ break;
+ }
+
+ /* Add the URB to the endpoint queue */
+ list_add_tail(&urbp->hep_node, &urbp->ep_data->queue);
+
+ /* If this is the only urb, kick start the controller */
+ if (!c67x00->urb_count++)
+ c67x00_ll_hpi_enable_sofeop(c67x00->sie);
+
+ c67x00_sched_kick(c67x00);
+
+ spin_unlock_irqrestore(&c67x00->lock, flags);
+ return 0;
+
+ /* Something went wrong; unwind the allocations */
+ err_epdata:
+ kfree(urbp);
+ err_urbp:
+ usb_hcd_unlink_urb_from_ep(hcd, urb);
+ err_not_linked:
+ spin_unlock_irqrestore(&c67x00->lock, flags);
+ return ret;
+}
+
+int c67x00_urb_dequeue(struct usb_hcd *hcd, struct urb *urb, int status)
+{
+ struct c67x00_hcd *c67x00 = hcd_to_c67x00_hcd(hcd);
+ unsigned long flags;
+ int rc;
+
+ spin_lock_irqsave(&c67x00->lock, flags);
+ rc = usb_hcd_check_unlink_urb(hcd, urb, status);
+ if (rc)
+ goto done;
+
+ c67x00_release_urb(c67x00, urb);
+ //gcl//usb_hcd_giveback_urb(c67x00_hcd_to_hcd(c67x00), urb, status);
+
+done:
+ spin_unlock_irqrestore(&c67x00->lock, flags);
+ return rc;
+}
+
+/* -------------------------------------------------------------------------- */
+
+/*
+ * pre: urb != NULL and c67x00 locked, urb unlocked
+ */
+static inline void
+c67x00_giveback_urb(struct c67x00_hcd *c67x00, struct urb *urb, int status)
+{
+ struct c67x00_urb_priv *urbp;
+ if (!urb)
+ return;
+
+ urbp = urb->hcpriv;
+ urbp->status = status;
+
+ list_del_init(&urbp->hep_node);
+ list_add_tail(&urbp->hep_node, &c67x00->done_list);
+ tasklet_schedule(&c67x00->done_tasklet);
+}
+
+/* -------------------------------------------------------------------------- */
+
+static int claim_frame_bw(struct c67x00_hcd *c67x00, struct urb *urb,
+ int len, int periodic)
+{
+ struct c67x00_urb_priv *urbp = urb->hcpriv;
+ int bit_time;
+
+ /* According to the C67x00 BIOS user manual, page 3-18,19, the
+ * following calculations provide the full speed bit times for
+ * a transaction.
+ *
+ * FS(in) = 112.5 + 9.36*BC + HOST_DELAY
+ * FS(in,iso) = 90.5 + 9.36*BC + HOST_DELAY
+ * FS(out) = 112.5 + 9.36*BC + HOST_DELAY
+ * FS(out,iso) = 78.4 + 9.36*BC + HOST_DELAY
+ * LS(in) = 802.4 + 75.78*BC + HOST_DELAY
+ * LS(out) = 802.6 + 74.67*BC + HOST_DELAY
+ *
+ * HOST_DELAY == 106 for the c67200 and c67300.
+ */
+
+ /* make calculations in 1/100 bit times to maintain resolution */
+ if (urbp->ep_data->dev->speed == USB_SPEED_LOW) {
+ /* Low speed pipe */
+ if (usb_pipein(urb->pipe))
+ bit_time = 80240 + 7578*len;
+ else
+ bit_time = 80260 + 7467*len;
+ } else {
+ /* FS pipes */
+ if (usb_pipeisoc(urb->pipe))
+ bit_time = usb_pipein(urb->pipe) ? 9050 : 7840;
+ else
+ bit_time = 11250;
+ bit_time += 936*len;
+ }
+
+ /* Scale back down to integer bit times. Use a host delay of 106.
+ * (this is the only place it is used) */
+ bit_time = ((bit_time+50) / 100) + 106;
+
+ if (unlikely(bit_time + c67x00->bandwidth_allocated >=
+ c67x00->max_frame_bw))
+ return -EMSGSIZE;
+
+ if (unlikely(c67x00->next_td_addr + CY_TD_SIZE >=
+ c67x00->td_base_addr + SIE_TD_SIZE))
+ return -EMSGSIZE;
+
+ if (unlikely(c67x00->next_buf_addr + len >=
+ c67x00->buf_base_addr + SIE_TD_BUF_SIZE))
+ return -EMSGSIZE;
+
+ if (periodic) {
+ if (unlikely(bit_time + c67x00->periodic_bw_allocated >=
+ MAX_PERIODIC_BW(c67x00->max_frame_bw)))
+ return -EMSGSIZE;
+ c67x00->periodic_bw_allocated += bit_time;
+ }
+
+ c67x00->bandwidth_allocated += bit_time;
+ return 0;
+}
+
+/* -------------------------------------------------------------------------- */
+
+/**
+ * td_addr and buf_addr must be word aligned
+ */
+static int create_td(struct c67x00_hcd *c67x00,
+ struct urb *urb,
+ char *data,
+ int len, int pid, int toggle, unsigned long privdata)
+{
+ struct c67x00_td *td;
+ struct c67x00_urb_priv *urbp = urb->hcpriv;
+ const __u8 active_flag = 1, retry_cnt = 1;
+ __u8 cmd = 0;
+ int tt = 0;
+
+ if (claim_frame_bw(c67x00, urb, len,
+ usb_pipeisoc(urb->pipe) || usb_pipeint(urb->pipe)))
+ return -EMSGSIZE; /* Not really an error, but expected */
+
+ td = kzalloc(sizeof(*td), GFP_ATOMIC);
+ if (!td)
+ return -ENOMEM;
+
+ td->pipe = urb->pipe;
+ td->ep_data = urbp->ep_data;
+
+ if ((td_udev(td)->speed == USB_SPEED_LOW) &&
+ !(c67x00->low_speed_ports & (1 << urbp->port)))
+ cmd |= PREAMBLE_EN;
+
+ switch (usb_pipetype(td->pipe)) {
+ case PIPE_ISOCHRONOUS:
+ tt = TT_ISOCHRONOUS;
+ cmd |= ISO_EN;
+ break;
+ case PIPE_CONTROL:
+ tt = TT_CONTROL;
+ break;
+ case PIPE_BULK:
+ tt = TT_BULK;
+ break;
+ case PIPE_INTERRUPT:
+ tt = TT_INTERRUPT;
+ break;
+ }
+
+ if (toggle)
+ cmd |= SEQ_SEL;
+
+ cmd |= ARM_EN;
+
+ /* SW part */
+ td->td_addr = c67x00->next_td_addr;
+ c67x00->next_td_addr = c67x00->next_td_addr + CY_TD_SIZE;
+
+ /* HW part */
+ td->ly_base_addr = __cpu_to_le16(c67x00->next_buf_addr);
+ td->port_length = __cpu_to_le16((c67x00->sie->sie_num << 15) |
+ (urbp->port << 14) | (len & 0x3FF));
+ td->pid_ep = ((pid & 0xF) << TD_PIDEP_OFFSET) |
+ (usb_pipeendpoint(td->pipe) & 0xF);
+ td->dev_addr = usb_pipedevice(td->pipe) & 0x7F;
+ td->ctrl_reg = cmd;
+ td->status = 0;
+ td->retry_cnt = (tt << TT_OFFSET) | (active_flag << 4) | retry_cnt;
+ td->residue = 0;
+ td->next_td_addr = __cpu_to_le16(c67x00->next_td_addr);
+
+ /* SW part */
+ td->data = data;
+ td->urb = urb;
+ td->privdata = privdata;
+
+ c67x00->next_buf_addr += (len + 1) & ~0x01; /* properly align */
+
+ list_add_tail(&td->td_list, &c67x00->td_list);
+ return 0;
+}
+
+static inline void release_td(struct c67x00_td *td)
+{
+ list_del_init(&td->td_list);
+ kfree(td);
+}
+
+/* -------------------------------------------------------------------------- */
+
+static int add_data_urb(struct c67x00_hcd *c67x00, struct urb *urb)
+{
+ int remaining;
+ int toggle;
+ int pid;
+ int ret = 0;
+ int maxps;
+ int need_empty;
+
+ toggle = usb_gettoggle(urb->dev, usb_pipeendpoint(urb->pipe),
+ usb_pipeout(urb->pipe));
+ remaining = urb->transfer_buffer_length - urb->actual_length;
+
+ maxps = usb_maxpacket(urb->dev, urb->pipe, usb_pipeout(urb->pipe));
+
+ need_empty = (urb->transfer_flags & URB_ZERO_PACKET) &&
+ usb_pipeout(urb->pipe) && !(remaining % maxps);
+
+ while (remaining || need_empty) {
+ int len;
+ char *td_buf;
+
+ len = (remaining > maxps) ? maxps : remaining;
+ if (!len)
+ need_empty = 0;
+
+ pid = usb_pipeout(urb->pipe) ? USB_PID_OUT : USB_PID_IN;
+ td_buf = urb->transfer_buffer + urb->transfer_buffer_length -
+ remaining;
+ ret = create_td(c67x00, urb, td_buf, len, pid, toggle,
+ DATA_STAGE);
+ if (ret)
+ goto out; /* td wasn't created */
+ toggle ^= 1;
+ remaining -= len;
+ if (usb_pipecontrol(urb->pipe))
+ break;
+ }
+ out:
+ return ret;
+}
+
+/**
+ *
+ * return 0 in case more bandwidth is available, else errorcode
+ */
+static int add_ctrl_urb(struct c67x00_hcd *c67x00, struct urb *urb)
+{
+ int ret;
+ int pid;
+
+ switch (urb->interval) {
+ default:
+ case SETUP_STAGE:
+ ret = create_td(c67x00, urb,
+ urb->setup_packet,
+ 8, USB_PID_SETUP, 0, SETUP_STAGE);
+ if (ret)
+ return ret;
+ urb->interval = SETUP_STAGE;
+ usb_settoggle(urb->dev, usb_pipeendpoint(urb->pipe),
+ usb_pipeout(urb->pipe), 1);
+ break;
+ case DATA_STAGE:
+ if (urb->transfer_buffer_length) {
+ ret = add_data_urb(c67x00, urb);
+ if (ret)
+ return ret;
+ break;
+ } /* else fallthrough */
+ case STATUS_STAGE:
+ pid = !usb_pipeout(urb->pipe) ? USB_PID_OUT : USB_PID_IN;
+ ret = create_td(c67x00, urb, NULL, 0, pid, 1, STATUS_STAGE);
+ if (ret)
+ return ret;
+ break;
+ }
+
+ return 0;
+}
+
+/*
+ * return 0 in case more bandwidth is available, else errorcode
+ */
+static int add_int_urb(struct c67x00_hcd *c67x00, struct urb *urb)
+{
+ struct c67x00_urb_priv *urbp = urb->hcpriv;
+
+ if (frame_after_eq(c67x00->current_frame, urbp->ep_data->next_frame)) {
+ urbp->ep_data->next_frame =
+ frame_add(urbp->ep_data->next_frame, urb->interval);
+ return add_data_urb(c67x00, urb);
+ }
+ return 0;
+}
+
+static int add_iso_urb(struct c67x00_hcd *c67x00, struct urb *urb)
+{
+ struct c67x00_urb_priv *urbp = urb->hcpriv;
+
+ if (frame_after_eq(c67x00->current_frame, urbp->ep_data->next_frame)) {
+ char *td_buf;
+ int len, pid, ret;
+
+ BUG_ON(urbp->cnt >= urb->number_of_packets);
+
+ td_buf = urb->transfer_buffer +
+ urb->iso_frame_desc[urbp->cnt].offset;
+ len = urb->iso_frame_desc[urbp->cnt].length;
+ pid = usb_pipeout(urb->pipe) ? USB_PID_OUT : USB_PID_IN;
+
+ ret = create_td(c67x00, urb, td_buf, len, pid, 0, urbp->cnt);
+ if (ret) {
+ printk(KERN_DEBUG "create failed: %d\n", ret);
+ urb->iso_frame_desc[urbp->cnt].actual_length = 0;
+ urb->iso_frame_desc[urbp->cnt].status = ret;
+ if (urbp->cnt + 1 == urb->number_of_packets)
+ c67x00_giveback_urb(c67x00, urb, 0);
+ }
+
+ urbp->ep_data->next_frame =
+ frame_add(urbp->ep_data->next_frame, urb->interval);
+ urbp->cnt++;
+ }
+ return 0;
+}
+
+/* -------------------------------------------------------------------------- */
+
+static void c67x00_fill_from_list(struct c67x00_hcd *c67x00, int type,
+ int (*add)(struct c67x00_hcd *, struct urb *))
+{
+ struct c67x00_ep_data *ep_data;
+ struct urb *urb;
+
+ /* traverse every endpoint on the list */
+ list_for_each_entry(ep_data, &c67x00->list[type], node) {
+ if (!list_empty(&ep_data->queue)) {
+ /* and add the first urb */
+ /* isochronous transfer rely on this */
+ urb = list_entry(ep_data->queue.next, struct c67x00_urb_priv,
+ hep_node)->urb;
+ add(c67x00, urb);
+ }
+ }
+}
+
+static void c67x00_fill_frame(struct c67x00_hcd *c67x00)
+{
+ struct c67x00_td *td, *ttd;
+
+ /* Check if we can proceed */
+ if (!list_empty(&c67x00->td_list)) {
+ dev_warn(c67x00_dev(c67x00),
+ "TD list not empty! This should not happen!\n");
+ list_for_each_entry_safe(td, ttd, &c67x00->td_list, td_list) {
+ dbg_td(c67x00, td, "Unprocessed td");
+ release_td(td);
+ }
+ }
+
+ /* Reinitialize variables */
+ c67x00->bandwidth_allocated = 0;
+ c67x00->periodic_bw_allocated = 0;
+
+ c67x00->next_td_addr = c67x00->td_base_addr;
+ c67x00->next_buf_addr = c67x00->buf_base_addr;
+
+ /* Fill the list */
+ c67x00_fill_from_list(c67x00, PIPE_ISOCHRONOUS, add_iso_urb);
+ c67x00_fill_from_list(c67x00, PIPE_INTERRUPT, add_int_urb);
+ c67x00_fill_from_list(c67x00, PIPE_CONTROL, add_ctrl_urb);
+ c67x00_fill_from_list(c67x00, PIPE_BULK, add_data_urb);
+}
+
+/* -------------------------------------------------------------------------- */
+
+/**
+ * Get TD from C67X00
+ */
+static inline void
+c67x00_parse_td(struct c67x00_hcd *c67x00, struct c67x00_td *td)
+{
+ c67x00_ll_hpi_read_mem_le16(c67x00->sie->dev, td->td_addr, CY_TD_SIZE,
+ (char *)td);
+
+ if (usb_pipein(td->pipe) && td_actual_bytes(td))
+ c67x00_ll_hpi_read_mem_le16(c67x00->sie->dev,
+ td_ly_base_addr(td),
+ td_actual_bytes(td), td->data);
+}
+
+/* -------------------------------------------------------------------------- */
+
+static int
+c67x00_td_to_error(struct c67x00_hcd *c67x00, struct c67x00_td *td)
+{
+ if (td->status & TD_STATUSMASK_ERR) {
+ dbg_td(c67x00, td, "ERROR_FLAG");
+ return -EILSEQ;
+ }
+ if (td->status & TD_STATUSMASK_STALL) {
+ /* dbg_td(c67x00, td, "STALL"); */
+ return -EPIPE;
+ }
+ if (td->status & TD_STATUSMASK_TMOUT) {
+ dbg_td(c67x00, td, "TIMEOUT");
+ return -ETIMEDOUT;
+ }
+
+ return 0;
+}
+
+static inline int c67x00_end_of_data(struct c67x00_td *td)
+{
+ int maxps, need_empty, remaining;
+ struct urb *urb = td->urb;
+ int act_bytes;
+
+ act_bytes = td_actual_bytes(td);
+
+ if (unlikely(!act_bytes))
+ return 1; /* This was an empty packet */
+
+ maxps = usb_maxpacket(td_udev(td), td->pipe, usb_pipeout(td->pipe));
+
+ if (unlikely(act_bytes < maxps))
+ return 1; /* Smaller then full packet */
+
+ remaining = urb->transfer_buffer_length - urb->actual_length;
+ need_empty = (urb->transfer_flags & URB_ZERO_PACKET) &&
+ usb_pipeout(urb->pipe) && !(remaining % maxps);
+
+ if (unlikely(!remaining && !need_empty))
+ return 1;
+
+ return 0;
+}
+
+/* -------------------------------------------------------------------------- */
+
+/* Remove all td's from the list which come
+ * after last_td and are meant for the same pipe.
+ * This is used when a short packet has occured */
+static inline void
+c67x00_clear_pipe(struct c67x00_hcd *c67x00, struct c67x00_td *last_td)
+{
+ struct c67x00_td *td, *tmp;
+ td = last_td;
+ tmp = last_td;
+ while (td->td_list.next != &c67x00->td_list) {
+ td = list_entry(td->td_list.next, struct c67x00_td, td_list);
+ if (td->pipe == last_td->pipe) {
+ release_td(td);
+ td = tmp;
+ }
+ tmp = td;
+ }
+}
+
+/* -------------------------------------------------------------------------- */
+
+static void c67x00_handle_successful_td(struct c67x00_hcd *c67x00,
+ struct c67x00_td *td)
+{
+ struct urb *urb = td->urb;
+
+ if (!urb)
+ return;
+
+ urb->actual_length += td_actual_bytes(td);
+
+ switch (usb_pipetype(td->pipe)) {
+ /* isochronous tds are handled separately */
+ case PIPE_CONTROL:
+ switch (td->privdata) {
+ case SETUP_STAGE:
+ urb->interval =
+ urb->transfer_buffer_length ?
+ DATA_STAGE : STATUS_STAGE;
+ /* Don't count setup_packet with normal data: */
+ urb->actual_length = 0;
+ break;
+ case DATA_STAGE:
+ if (c67x00_end_of_data(td)) {
+ urb->interval = STATUS_STAGE;
+ c67x00_clear_pipe(c67x00, td);
+ }
+ break;
+ case STATUS_STAGE:
+ urb->interval = 0;
+ c67x00_giveback_urb(c67x00, urb, 0);
+ break;
+ }
+ break;
+ case PIPE_INTERRUPT:
+ case PIPE_BULK:
+ if (unlikely(c67x00_end_of_data(td))) {
+ c67x00_clear_pipe(c67x00, td);
+ c67x00_giveback_urb(c67x00, urb, 0);
+ }
+ break;
+ }
+}
+
+static void c67x00_handle_isoc(struct c67x00_hcd *c67x00, struct c67x00_td *td)
+{
+ struct urb *urb = td->urb;
+ struct c67x00_urb_priv *urbp;
+ int cnt;
+
+ if (!urb)
+ return;
+
+ urbp = urb->hcpriv;
+ cnt = td->privdata;
+
+ if (td->status & TD_ERROR_MASK)
+ urb->error_count++;
+
+ urb->iso_frame_desc[cnt].actual_length = td_actual_bytes(td);
+ urb->iso_frame_desc[cnt].status = c67x00_td_to_error(c67x00, td);
+ if (cnt + 1 == urb->number_of_packets) /* Last packet */
+ c67x00_giveback_urb(c67x00, urb, 0);
+}
+
+/* -------------------------------------------------------------------------- */
+
+/**
+ * c67x00_check_td_list - handle tds which have been processed by the c67x00
+ * pre: current_td == 0
+ */
+static inline void c67x00_check_td_list(struct c67x00_hcd *c67x00)
+{
+ struct c67x00_td *td, *tmp;
+ struct urb *urb;
+ int ack_ok;
+ int clear_endpoint;
+
+ list_for_each_entry_safe(td, tmp, &c67x00->td_list, td_list) {
+ /* get the TD */
+ c67x00_parse_td(c67x00, td);
+ urb = td->urb; /* urb can be NULL! */
+ ack_ok = 0;
+ clear_endpoint = 1;
+
+ /* Handle isochronous transfers separately */
+ if (usb_pipeisoc(td->pipe)) {
+ clear_endpoint = 0;
+ c67x00_handle_isoc(c67x00, td);
+ goto cont;
+ }
+
+ /* When an error occurs, all td's for that pipe go into an
+ * inactive state. This state matches successful transfers so
+ * we must make sure not to service them. */
+ if (td->status & TD_ERROR_MASK) {
+ c67x00_giveback_urb(c67x00, urb, c67x00_td_to_error(c67x00, td));
+ goto cont;
+ }
+
+ if ((td->status & TD_STATUSMASK_NAK) || !td_sequence_ok(td) ||
+ !td_acked(td))
+ goto cont;
+
+ /* Sequence ok and acked, don't need to fix toggle */
+ ack_ok = 1;
+
+ if (unlikely(td->status & TD_STATUSMASK_OVF)) {
+ if (td_residue(td) & TD_RESIDUE_OVERFLOW) {
+ /* Overflow */
+ c67x00_giveback_urb(c67x00, urb, -EOVERFLOW);
+ goto cont;
+ }
+ }
+
+ clear_endpoint = 0;
+ c67x00_handle_successful_td(c67x00, td);
+
+ cont:
+ if (clear_endpoint)
+ c67x00_clear_pipe(c67x00, td);
+ if (ack_ok)
+ usb_settoggle(td_udev(td), usb_pipeendpoint(td->pipe),
+ usb_pipeout(td->pipe),
+ !(td->ctrl_reg & SEQ_SEL));
+ /* next in list could have been removed, due to clear_pipe! */
+ tmp = list_entry(td->td_list.next, typeof(*td), td_list);
+ release_td(td);
+ }
+}
+
+/* -------------------------------------------------------------------------- */
+
+void c67x00_hcd_msg_received(struct c67x00_sie *sie, u16 msg)
+{
+ struct c67x00_hcd *c67x00 = sie->private_data;
+ if (msg & HUSB_TDListDone) {
+ msg &= ~HUSB_TDListDone;
+ c67x00_sched_kick(c67x00);
+ }
+ if (msg)
+ dev_warn(c67x00_dev(c67x00),
+ "Unknown SIE msg flag(s): 0x%04x\n", msg);
+}
+
+/* -------------------------------------------------------------------------- */
+
+static inline int c67x00_all_tds_processed(struct c67x00_hcd *c67x00)
+{
+ /* If all tds are processed, we can check the previous frame (if
+ * there was any) and start our next frame.
+ */
+ return !c67x00_ll_husb_get_current_td(c67x00->sie);
+}
+
+/**
+ * Send td to C67X00
+ */
+static void c67x00_send_td(struct c67x00_hcd *c67x00, struct c67x00_td *td)
+{
+ int len = td_length(td);
+
+ if (len && ((td->pid_ep & TD_PIDEPMASK_PID) != TD_PID_IN))
+ c67x00_ll_hpi_write_mem_le16(c67x00->sie->dev,
+ td_ly_base_addr(td),
+ len, td->data);
+
+ c67x00_ll_hpi_write_mem_le16(c67x00->sie->dev, td->td_addr,
+ CY_TD_SIZE, (char *)td);
+}
+
+static void c67x00_send_frame(struct c67x00_hcd *c67x00)
+{
+ struct c67x00_td *td;
+
+ if (list_empty(&c67x00->td_list))
+ dev_warn(c67x00_dev(c67x00),
+ "%s: td list should not be empty here!\n",
+ __FUNCTION__);
+
+ list_for_each_entry(td, &c67x00->td_list, td_list) {
+ if (td->td_list.next == &c67x00->td_list)
+ td->next_td_addr = 0; /* Last td in list */
+
+ c67x00_send_td(c67x00, td);
+ }
+
+ c67x00_ll_husb_set_current_td(c67x00->sie, c67x00->td_base_addr);
+}
+
+/* -------------------------------------------------------------------------- */
+
+/**
+ * c67x00_do_work - Schedulers state machine
+ */
+static void c67x00_do_work(struct c67x00_hcd *c67x00)
+{
+ spin_lock(&c67x00->lock);
+ /* Make sure all tds are processed */
+ if (!c67x00_all_tds_processed(c67x00))
+ goto out;
+
+ c67x00_check_td_list(c67x00);
+
+ /* no td's are being processed (current == 0)
+ * and all have been "checked" */
+ complete(&c67x00->endpoint_disable);
+
+ if (!list_empty(&c67x00->td_list))
+ goto out;
+
+ c67x00->current_frame = c67x00_get_current_frame_number(c67x00);
+ if (c67x00->current_frame == c67x00->last_frame)
+ goto out; /* Don't send tds in same frame */
+ c67x00->last_frame = c67x00->current_frame;
+
+ /* If no urbs are scheduled, our work is done */
+ if (!c67x00->urb_count) {
+ c67x00_ll_hpi_disable_sofeop(c67x00->sie);
+ goto out;
+ }
+
+ c67x00_fill_frame(c67x00);
+ if (list_empty(&c67x00->td_list))
+ /* URBs aren't for this frame */
+ goto out;
+ else {
+ /* TD's have been added to the frame */
+ c67x00_send_frame(c67x00);
+ goto out;
+ }
+ out:
+ spin_unlock(&c67x00->lock);
+}
+
+/* -------------------------------------------------------------------------- */
+
+static void c67x00_sched_tasklet(unsigned long __c67x00)
+{
+ struct c67x00_hcd *c67x00 = (struct c67x00_hcd *)__c67x00;
+ c67x00_do_work(c67x00);
+}
+
+static void c67x00_sched_done(unsigned long __c67x00)
+{
+ struct c67x00_hcd *c67x00 = (struct c67x00_hcd *)__c67x00;
+ struct c67x00_urb_priv *urbp, *tmp;
+ struct usb_hcd *hcd = c67x00_hcd_to_hcd(c67x00);
+ struct urb *urb;
+ int status;
+
+ spin_lock(&c67x00->lock);
+
+ /* Loop over the done list and give back all the urbs */
+ list_for_each_entry_safe(urbp, tmp, &c67x00->done_list, hep_node) {
+ urb = urbp->urb;
+ status = urbp->status;
+
+ c67x00_release_urb(c67x00, urb);
+
+ usb_hcd_unlink_urb_from_ep(hcd, urb);
+ usb_hcd_giveback_urb(hcd, urb, status);
+ }
+ spin_unlock(&c67x00->lock);
+}
+
+void c67x00_sched_kick(struct c67x00_hcd *c67x00)
+{
+ tasklet_hi_schedule(&c67x00->tasklet);
+}
+
+int c67x00_sched_start_scheduler(struct c67x00_hcd *c67x00)
+{
+ tasklet_init(&c67x00->tasklet, c67x00_sched_tasklet,
+ (unsigned long)c67x00);
+ tasklet_init(&c67x00->done_tasklet, c67x00_sched_done,
+ (unsigned long)c67x00);
+ return 0;
+}
+
+void c67x00_sched_stop_scheduler(struct c67x00_hcd *c67x00)
+{
+ tasklet_kill(&c67x00->tasklet);
+ tasklet_kill(&c67x00->done_tasklet);
+}
^ permalink raw reply related [flat|nested] 20+ messages in thread
* [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles
2007-11-24 0:24 [PATCH 0/5] Review request: Cypress c67x00 OTG controller Grant Likely
` (3 preceding siblings ...)
2007-11-24 0:24 ` [PATCH 4/5] USB: add Cypress c67x00 OTG controller HCD driver Grant Likely
@ 2007-11-24 0:24 ` Grant Likely
2007-11-24 20:12 ` David Brownell
2007-11-24 17:57 ` [PATCH 0/5] Review request: Cypress c67x00 OTG controller David Brownell
5 siblings, 1 reply; 20+ messages in thread
From: Grant Likely @ 2007-11-24 0:24 UTC (permalink / raw)
To: linux-usb-devel, akpm, dbrownell, gregkh, linuxppc-dev
From: Grant Likely <grant.likely@secretlab.ca>
add c67x00 driver to build
Signed-off-by: Grant Likely <grant.likely@secretlab.ca>
---
drivers/usb/Kconfig | 2 ++
drivers/usb/Makefile | 2 ++
drivers/usb/c67x00/Kconfig | 22 ++++++++++++++++++++++
drivers/usb/c67x00/Makefile | 14 ++++++++++++++
4 files changed, 40 insertions(+), 0 deletions(-)
diff --git a/drivers/usb/Kconfig b/drivers/usb/Kconfig
index 7580aa5..a497f96 100644
--- a/drivers/usb/Kconfig
+++ b/drivers/usb/Kconfig
@@ -91,6 +91,8 @@ source "drivers/usb/core/Kconfig"
source "drivers/usb/host/Kconfig"
+source "drivers/usb/c67x00/Kconfig"
+
source "drivers/usb/class/Kconfig"
source "drivers/usb/storage/Kconfig"
diff --git a/drivers/usb/Makefile b/drivers/usb/Makefile
index 516a640..a1ae51d 100644
--- a/drivers/usb/Makefile
+++ b/drivers/usb/Makefile
@@ -17,6 +17,8 @@ obj-$(CONFIG_USB_SL811_HCD) += host/
obj-$(CONFIG_USB_U132_HCD) += host/
obj-$(CONFIG_USB_R8A66597_HCD) += host/
+obj-$(CONFIG_USB_C67X00_DRV) += c67x00/
+
obj-$(CONFIG_USB_ACM) += class/
obj-$(CONFIG_USB_PRINTER) += class/
diff --git a/drivers/usb/c67x00/Kconfig b/drivers/usb/c67x00/Kconfig
new file mode 100644
index 0000000..efd7923
--- /dev/null
+++ b/drivers/usb/c67x00/Kconfig
@@ -0,0 +1,22 @@
+#
+# Cypress C67x00 USB controller
+#
+config USB_C67X00_DRV
+ tristate "Cypress C67x00 support"
+ # only allowed to be =y if both USB!=m and USB_GADGET!=m
+ depends on (!USB && USB_GADGET) || (!USB_GADGET && USB) || (USB && USB_GADGET)
+ default n
+ help
+ The Cypress C67x00 (EZ-Host/EZ-OTG) chips are dual-role
+ host/peripheral USB controllers.
+
+ To compile this driver as a module, choose M here: the
+ module will be called c67x00.
+
+config USB_C67X00_HCD
+ bool "Cypress C67X00 Host support"
+ depends on USB_C67X00_DRV
+ depends on USB
+ default y
+ help
+ This enables the host functionality of the Cypress C67X00.
diff --git a/drivers/usb/c67x00/Makefile b/drivers/usb/c67x00/Makefile
new file mode 100644
index 0000000..8ff5cd0
--- /dev/null
+++ b/drivers/usb/c67x00/Makefile
@@ -0,0 +1,14 @@
+#
+# Makefile for Cypress C67X00 USB Controller
+#
+
+ifeq ($(CONFIG_USB_DEBUG),y)
+ EXTRA_CFLAGS += -DDEBUG
+endif
+
+obj-$(CONFIG_USB_C67X00_DRV) += c67x00.o
+
+c67x00-y += c67x00-drv.o
+c67x00-y += c67x00-ll-hpi.o
+
+c67x00-$(CONFIG_USB_C67X00_HCD) += c67x00-hcd.o c67x00-sched.o
^ permalink raw reply related [flat|nested] 20+ messages in thread
* Re: [linux-usb-devel] [PATCH 4/5] USB: add Cypress c67x00 OTG controller HCD driver
2007-11-24 0:24 ` [PATCH 4/5] USB: add Cypress c67x00 OTG controller HCD driver Grant Likely
@ 2007-11-24 3:56 ` Alan Stern
0 siblings, 0 replies; 20+ messages in thread
From: Alan Stern @ 2007-11-24 3:56 UTC (permalink / raw)
To: Grant Likely; +Cc: akpm, linuxppc-dev, dbrownell, linux-usb-devel, gregkh
On Fri, 23 Nov 2007, Grant Likely wrote:
> From: Grant Likely <grant.likely@secretlab.ca>
>
> This patch adds HDC support for the Cypress c67x00 family of devices.
>
> Signed-off-by: Grant Likely <grant.likely@secretlab.ca>
> +static void c67x00_sched_done(unsigned long __c67x00)
> +{
> + struct c67x00_hcd *c67x00 = (struct c67x00_hcd *)__c67x00;
> + struct c67x00_urb_priv *urbp, *tmp;
> + struct usb_hcd *hcd = c67x00_hcd_to_hcd(c67x00);
> + struct urb *urb;
> + int status;
> +
> + spin_lock(&c67x00->lock);
> +
> + /* Loop over the done list and give back all the urbs */
> + list_for_each_entry_safe(urbp, tmp, &c67x00->done_list, hep_node) {
> + urb = urbp->urb;
> + status = urbp->status;
> +
> + c67x00_release_urb(c67x00, urb);
> +
> + usb_hcd_unlink_urb_from_ep(hcd, urb);
> + usb_hcd_giveback_urb(hcd, urb, status);
> + }
> + spin_unlock(&c67x00->lock);
> +}
You need to release the spinlock around the call to
usb_hcd_giveback_urb(). Otherwise you will deadlock if the completion
routine submits another URB.
Alan Stern
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq
2007-11-24 0:24 ` [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq Grant Likely
@ 2007-11-24 5:10 ` Greg KH
2007-11-24 17:03 ` [linux-usb-devel] " Alan Cox
2007-11-24 19:06 ` David Brownell
1 sibling, 1 reply; 20+ messages in thread
From: Greg KH @ 2007-11-24 5:10 UTC (permalink / raw)
To: Grant Likely; +Cc: akpm, linuxppc-dev, dbrownell, linux-usb-devel
On Fri, Nov 23, 2007 at 05:24:31PM -0700, Grant Likely wrote:
> From: Peter Korsgaard <peter.korsgaard@barco.com>
>
> Some multi-role (host/peripheral) USB controllers use a shared interrupt
> line for all parts of the chip. Export usb_hcd_irq so drivers can call it
> from their interrupt handler instead of duplicating code.
> Drivers pass an irqnum of 0 to usb_add_hcd to signal that the interrupt handler
> shouldn't be registerred by the core.
What about for platforms where irq 0 is a valid irq?
thanks,
greg k-h
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [linux-usb-devel] [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq
2007-11-24 5:10 ` Greg KH
@ 2007-11-24 17:03 ` Alan Cox
2007-11-24 17:15 ` Grant Likely
2007-11-24 17:50 ` David Brownell
0 siblings, 2 replies; 20+ messages in thread
From: Alan Cox @ 2007-11-24 17:03 UTC (permalink / raw)
To: Greg KH; +Cc: akpm, dbrownell, linux-usb-devel, linuxppc-dev
On Fri, 23 Nov 2007 21:10:39 -0800
Greg KH <gregkh@suse.de> wrote:
> On Fri, Nov 23, 2007 at 05:24:31PM -0700, Grant Likely wrote:
> > From: Peter Korsgaard <peter.korsgaard@barco.com>
> >
> > Some multi-role (host/peripheral) USB controllers use a shared interrupt
> > line for all parts of the chip. Export usb_hcd_irq so drivers can call it
> > from their interrupt handler instead of duplicating code.
> > Drivers pass an irqnum of 0 to usb_add_hcd to signal that the interrupt handler
> > shouldn't be registerred by the core.
>
> What about for platforms where irq 0 is a valid irq?
There are no such platforms. Linus made that absolutely clear every time
this came up before
0 - No IRQ
A platform with a physical or bus IRQ of 0 needs to remap it to a
different constant.
Alan
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [linux-usb-devel] [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq
2007-11-24 17:03 ` [linux-usb-devel] " Alan Cox
@ 2007-11-24 17:15 ` Grant Likely
2007-11-24 17:50 ` David Brownell
1 sibling, 0 replies; 20+ messages in thread
From: Grant Likely @ 2007-11-24 17:15 UTC (permalink / raw)
To: Alan Cox; +Cc: akpm, linuxppc-dev, Greg KH, linux-usb-devel, dbrownell
On 11/24/07, Alan Cox <alan@lxorguk.ukuu.org.uk> wrote:
> On Fri, 23 Nov 2007 21:10:39 -0800
> Greg KH <gregkh@suse.de> wrote:
>
> > On Fri, Nov 23, 2007 at 05:24:31PM -0700, Grant Likely wrote:
> > > From: Peter Korsgaard <peter.korsgaard@barco.com>
> > >
> > > Some multi-role (host/peripheral) USB controllers use a shared interrupt
> > > line for all parts of the chip. Export usb_hcd_irq so drivers can call it
> > > from their interrupt handler instead of duplicating code.
> > > Drivers pass an irqnum of 0 to usb_add_hcd to signal that the interrupt handler
> > > shouldn't be registerred by the core.
> >
> > What about for platforms where irq 0 is a valid irq?
>
> There are no such platforms. Linus made that absolutely clear every time
> this came up before
>
> 0 - No IRQ
>
> A platform with a physical or bus IRQ of 0 needs to remap it to a
> different constant.
Regardless, I should probably use the NO_IRQ macro instead.
g.
--
Grant Likely, B.Sc., P.Eng.
Secret Lab Technologies Ltd.
grant.likely@secretlab.ca
(403) 399-0195
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [linux-usb-devel] [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq
2007-11-24 17:03 ` [linux-usb-devel] " Alan Cox
2007-11-24 17:15 ` Grant Likely
@ 2007-11-24 17:50 ` David Brownell
1 sibling, 0 replies; 20+ messages in thread
From: David Brownell @ 2007-11-24 17:50 UTC (permalink / raw)
To: Alan Cox; +Cc: akpm, Greg KH, linux-usb-devel, linuxppc-dev
On Saturday 24 November 2007, Alan Cox wrote:
> >
> > What about for platforms where irq 0 is a valid irq?
>
> There are no such platforms. Linus made that absolutely clear every time
> this came up before
>
> 0 - No IRQ
>
> A platform with a physical or bus IRQ of 0 needs to remap it to a
> different constant.
However it's also common practice to use negative numbers to
flag "this is no IRQ" ... avoiding all confusions with zero.
- platform_get_irq(), platform_get_irq_byname() ... never
return zero, they return irq (positive) or errno
- PNP initializes invalid IRQs to "-1", and pnp_check_irq()
handles irq zero as in-range
- I'm sure I've seen negative numbers used elsewhere too
Something like
#define is_valid_irq(x) ((x) >= 0)
would work better than expecting sudden agreement everywhere
about a single number representing "this is not an IRQ".
- Dave
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 0/5] Review request: Cypress c67x00 OTG controller
2007-11-24 0:24 [PATCH 0/5] Review request: Cypress c67x00 OTG controller Grant Likely
` (4 preceding siblings ...)
2007-11-24 0:24 ` [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles Grant Likely
@ 2007-11-24 17:57 ` David Brownell
2007-11-24 19:27 ` Grant Likely
5 siblings, 1 reply; 20+ messages in thread
From: David Brownell @ 2007-11-24 17:57 UTC (permalink / raw)
To: Grant Likely; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On Friday 23 November 2007, Grant Likely wrote:
>
> This patch series is based on the c67x00 work done by Peter Korsgaard and
> posted back in April this year.
What's changed since that version? Were the comments sent
at that time addressed?
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq
2007-11-24 0:24 ` [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq Grant Likely
2007-11-24 5:10 ` Greg KH
@ 2007-11-24 19:06 ` David Brownell
2007-11-24 19:28 ` Grant Likely
1 sibling, 1 reply; 20+ messages in thread
From: David Brownell @ 2007-11-24 19:06 UTC (permalink / raw)
To: Grant Likely; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On Friday 23 November 2007, Grant Likely wrote:
> Some multi-role (host/peripheral) USB controllers use a shared interrupt
> line for all parts of the chip.
Like the musb_hdrc code ... soonish to go upstream (it needs some
updates to catch up to usbcore urb->status changes), this is used
by the Nokia 800 and 810. In terms of chips with Linux support:
DaVinci, TUSB60x0, OMAP 2430, OMAP 3430, Blackfin BF527; and ISTR
a few less-publicised ones (including, yes, some PPC SOCs).
That driver hasn't needed to change usbcore for IRQ handling though.
> Export usb_hcd_irq so drivers can call it
> from their interrupt handler instead of duplicating code.
This seems to be the main point of this patch. I'd rather just
make that "static" though; it should already be marked that way.
That routine doesn't do enough to make me like it any more; and
with dual-role controllers, the driver lifecycle is more complex
than usbcore can be expected to mediate. Best to just call the
host side IRQ logic directly from your toplevel IRQ handler.
> Drivers pass an irqnum of 0 to usb_add_hcd to signal that the interrupt handler
> shouldn't be registerred by the core.
The current way to get that behavior is to leave hcd->driver->irq
as zero; then "irqnum" is ignored, and your dual role driver can
register its own handler.
- Dave
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 0/5] Review request: Cypress c67x00 OTG controller
2007-11-24 17:57 ` [PATCH 0/5] Review request: Cypress c67x00 OTG controller David Brownell
@ 2007-11-24 19:27 ` Grant Likely
0 siblings, 0 replies; 20+ messages in thread
From: Grant Likely @ 2007-11-24 19:27 UTC (permalink / raw)
To: David Brownell; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On 11/24/07, David Brownell <david-b@pacbell.net> wrote:
> On Friday 23 November 2007, Grant Likely wrote:
> >
> > This patch series is based on the c67x00 work done by Peter Korsgaard and
> > posted back in April this year.
>
> What's changed since that version? Were the comments sent
> at that time addressed?
A lot has changes since that version. I'm not sure if all the
comments at that time were addressed (as in it's been a while since
I've looked at them; I'll go back and take another look).
You can see my progression from Peter's version and my version here:
http://git.secretlab.ca/git/gitweb.cgi?p=linux-2.6-virtex.git;a=shortlog;h=virtex-c67x00-dev
The patches I posted are the consolidation of the series in that git tree.
Cheers,
g.
--
Grant Likely, B.Sc., P.Eng.
Secret Lab Technologies Ltd.
grant.likely@secretlab.ca
(403) 399-0195
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq
2007-11-24 19:06 ` David Brownell
@ 2007-11-24 19:28 ` Grant Likely
0 siblings, 0 replies; 20+ messages in thread
From: Grant Likely @ 2007-11-24 19:28 UTC (permalink / raw)
To: David Brownell; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On 11/24/07, David Brownell <david-b@pacbell.net> wrote:
> On Friday 23 November 2007, Grant Likely wrote:
> > Some multi-role (host/peripheral) USB controllers use a shared interrupt
> > line for all parts of the chip.
>
> Like the musb_hdrc code ... soonish to go upstream (it needs some
> updates to catch up to usbcore urb->status changes), this is used
> by the Nokia 800 and 810. In terms of chips with Linux support:
> DaVinci, TUSB60x0, OMAP 2430, OMAP 3430, Blackfin BF527; and ISTR
> a few less-publicised ones (including, yes, some PPC SOCs).
>
> That driver hasn't needed to change usbcore for IRQ handling though.
>
>
> > Export usb_hcd_irq so drivers can call it
> > from their interrupt handler instead of duplicating code.
>
> This seems to be the main point of this patch. I'd rather just
> make that "static" though; it should already be marked that way.
>
> That routine doesn't do enough to make me like it any more; and
> with dual-role controllers, the driver lifecycle is more complex
> than usbcore can be expected to mediate. Best to just call the
> host side IRQ logic directly from your toplevel IRQ handler.
>
>
> > Drivers pass an irqnum of 0 to usb_add_hcd to signal that the interrupt handler
> > shouldn't be registerred by the core.
>
> The current way to get that behavior is to leave hcd->driver->irq
> as zero; then "irqnum" is ignored, and your dual role driver can
> register its own handler.
Okay, I'll make that change.
Cheers,
g.
--
Grant Likely, B.Sc., P.Eng.
Secret Lab Technologies Ltd.
grant.likely@secretlab.ca
(403) 399-0195
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 2/5] USB: Add Cypress c67x00 low level interface code
2007-11-24 0:24 ` [PATCH 2/5] USB: Add Cypress c67x00 low level interface code Grant Likely
@ 2007-11-24 19:39 ` David Brownell
0 siblings, 0 replies; 20+ messages in thread
From: David Brownell @ 2007-11-24 19:39 UTC (permalink / raw)
To: Grant Likely; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On Friday 23 November 2007, Grant Likely wrote:
> +/* These functions could also be implemented with SPI of HSS.
> + * This is currently not supported */
Give that this "HPI" interface seems to use a parallel bus
with irq-safe synchronous accesses, and SPI is a serial bus
where synchronous accesses can't be done in IRQ context ...
that comment doesn't seem accurate.
Surely a more correct statement would be that while the chip
can also be accessed using SPI, that would require updating
the driver structure to stop assuming register accesses can
always be done from IRQ context?
If that's not the case, then those spinlocks are overkill,
and they should become mutexes. :)
- Dave
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles
2007-11-24 0:24 ` [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles Grant Likely
@ 2007-11-24 20:12 ` David Brownell
2007-11-24 20:20 ` Grant Likely
0 siblings, 1 reply; 20+ messages in thread
From: David Brownell @ 2007-11-24 20:12 UTC (permalink / raw)
To: Grant Likely; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On Friday 23 November 2007, Grant Likely wrote:
> +config USB_C67X00_DRV
> + tristate "Cypress C67x00 support"
> + # only allowed to be =y if both USB!=m and USB_GADGET!=m
This is wrong. Remember that since this is a dual-role driver,
there are exactly three possible driver modes ... and the driver
must support only one of them at a time:
- Host-only ... only allowed if host side USB is enabled. The
controller driver can be statically linked iff usbcore is too.
- Peripheral-only ... only allowed if peripheral side USB is
enabled. Only one port may be used as the peripheral; the
controller driver can be linked statically or as a module.
- OTG ... only allowed if both host and peripheral side USB
are enabled. Only one port can be the OTG port, but other
ports can be used for host functionality. Static/modular
linkage follows (more restrictive) the host-only rule.
And of course, what a given board supports is controlled by the
connectors it has ... A, B, or AB. (Possibly AB plus n*A.) So
the driver should probably be able to make sense of having OTG
support, but needing to cope with a non-OTG board ... or having
an OTG board, a driver that only copes with one role.
Hmmm ... your patches don't include peripheral mode support yet.
Either all these gadget hooks should vanish, or you should try
to get the controller mode stuff right from the beginning.
I've appended the relevant Kconfig bits from the musb_hdrc
driver, which (despite some glitches) are pretty much correct.
- Dave
> + depends on (!USB && USB_GADGET) || (!USB_GADGET && USB) || (USB && USB_GADGET)
> + default n
> + help
> + The Cypress C67x00 (EZ-Host/EZ-OTG) chips are dual-role
> + host/peripheral USB controllers.
> +
> + To compile this driver as a module, choose M here: the
> + module will be called c67x00.
> +
> +config USB_C67X00_HCD
> + bool "Cypress C67X00 Host support"
> + depends on USB_C67X00_DRV
> + depends on USB
> + default y
> + help
> + This enables the host functionality of the Cypress C67X00.
>
================
#
# USB Dual Role (OTG-ready) Controller Drivers
# for silicon based on Mentor Graphics INVENTRA designs
#
comment "Enable Host or Gadget support to see Inventra options"
depends on !USB && USB_GADGET=n
# (M)HDRC = (Multipoint) Highspeed Dual-Role Controller
config USB_MUSB_HDRC
depends on USB || USB_GADGET
tristate 'Inventra Highspeed Dual Role Controller (TI, ...)'
help
Say Y here if your system has a dual role high speed USB
controller based on the Mentor Graphics silicon IP. Then
configure options to match your silicon and the board
it's being used with, including the USB peripheral role,
or the USB host role, or both.
Texas Instruments parts using this IP include DaVinci 644x,
OMAP 243x, OMAP 343x, and TUSB 6010.
If you do not know what this is, please say N.
To compile this driver as a module, choose M here; the
module will be called "musb_hdrc".
config USB_MUSB_SOC
boolean
depends on USB_MUSB_HDRC
default y if ARCH_DAVINCI
default y if ARCH_OMAP2430
default y if ARCH_OMAP343X
help
Use a static <asm/arch/hdrc_cnf.h> file to describe how the
controller is configured (endpoints, mechanisms, etc) on the
current iteration of a given system-on-chip.
comment "DaVinci 644x USB support"
depends on USB_MUSB_HDRC && ARCH_DAVINCI
comment "OMAP 243x high speed USB support"
depends on USB_MUSB_HDRC && ARCH_OMAP2430
comment "OMAP 343x high speed USB support"
depends on USB_MUSB_HDRC && ARCH_OMAP343X
config USB_TUSB6010
boolean "TUSB 6010 support"
depends on USB_MUSB_HDRC && !USB_MUSB_SOC
default y
help
The TUSB 6010 chip, from Texas Instruments, connects a discrete
HDRC core using a 16-bit parallel bus. It can use system-specific
external DMA controllers.
choice
prompt "Driver Mode"
depends on USB_MUSB_HDRC
help
Dual-Role devices can support both host and peripheral roles,
as well as a the special "OTG Device" role which can switch
between both roles as needed.
# use USB_MUSB_HDRC_HCD not USB_MUSB_HOST to #ifdef host side support;
# OTG needs both roles, not just USB_MUSB_HOST.
config USB_MUSB_HOST
depends on USB
bool "USB Host"
help
Say Y here if your system supports the USB host role.
If it has a USB "A" (rectangular), "Mini-A" (uncommon),
or "Mini-AB" connector, it supports the host role.
(With a "Mini-AB" connector, you should enable USB OTG.)
# use USB_GADGET_MUSB_HDRC not USB_MUSB_PERIPHERAL to #ifdef peripheral
# side support ... OTG needs both roles
config USB_MUSB_PERIPHERAL
depends on USB_GADGET
bool "USB Peripheral (gadget stack)"
select USB_GADGET_MUSB_HDRC
help
Say Y here if your system supports the USB peripheral role.
If it has a USB "B" (squarish), "Mini-B", or "Mini-AB"
connector, it supports the peripheral role.
(With a "Mini-AB" connector, you should enable USB OTG.)
config USB_MUSB_OTG
depends on USB && USB_GADGET && EXPERIMENTAL
bool "Both host and peripheral: USB OTG (On The Go) Device"
select USB_GADGET_MUSB_HDRC
select USB_OTG
select PM
help
The most notable feature of USB OTG is support for a
"Dual-Role" device, which can act as either a device
or a host. The initial role choice can be changed
later, when two dual-role devices talk to each other.
Select this if your system has a Mini-AB connector, or
to simplify certain kinds of configuration.
To implement your OTG Targeted Peripherals List (TPL), enable
USB_OTG_WHITELIST and update "drivers/usb/core/otg_whitelist.h"
to match your requirements.
endchoice
# enable peripheral support (including with OTG)
config USB_GADGET_MUSB_HDRC
bool
depends on USB_MUSB_HDRC && (USB_MUSB_PERIPHERAL || USB_MUSB_OTG)
# enables host support (including with OTG)
config USB_MUSB_HDRC_HCD
bool
depends on USB_MUSB_HDRC && (USB_MUSB_HOST || USB_MUSB_OTG)
select USB_OTG if USB_GADGET_MUSB_HDRC
default y
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles
2007-11-24 20:12 ` David Brownell
@ 2007-11-24 20:20 ` Grant Likely
2007-11-24 21:03 ` David Brownell
0 siblings, 1 reply; 20+ messages in thread
From: Grant Likely @ 2007-11-24 20:20 UTC (permalink / raw)
To: David Brownell; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On 11/24/07, David Brownell <david-b@pacbell.net> wrote:
> On Friday 23 November 2007, Grant Likely wrote:
> > +config USB_C67X00_DRV
> > +tristate "Cypress C67x00 support"
> > +# only allowed to be =y if both USB!=m and USB_GADGET!=m
>
> This is wrong. Remember that since this is a dual-role driver,
> there are exactly three possible driver modes ... and the driver
> must support only one of them at a time:
Actually, this part has 2 serial in interface engines; either of which
can be in host, peripheral or OTG mode. So; it is entirely relevant
for the driver to be doing both host and peripheral at the same time
with a single device.
>
> - Host-only ... only allowed if host side USB is enabled. The
> controller driver can be statically linked iff usbcore is too.
>
> - Peripheral-only ... only allowed if peripheral side USB is
> enabled. Only one port may be used as the peripheral; the
> controller driver can be linked statically or as a module.
>
> - OTG ... only allowed if both host and peripheral side USB
> are enabled. Only one port can be the OTG port, but other
> ports can be used for host functionality. Static/modular
> linkage follows (more restrictive) the host-only rule.
>
> And of course, what a given board supports is controlled by the
> connectors it has ... A, B, or AB. (Possibly AB plus n*A.) So
> the driver should probably be able to make sense of having OTG
> support, but needing to cope with a non-OTG board ... or having
> an OTG board, a driver that only copes with one role.
>
> Hmmm ... your patches don't include peripheral mode support yet.
No, nobody has written it yet.
>
> Either all these gadget hooks should vanish, or you should try
> to get the controller mode stuff right from the beginning.
>
> I've appended the relevant Kconfig bits from the musb_hdrc
> driver, which (despite some glitches) are pretty much correct.
I'll drop the gadget hooks for now. Most likely gadget and OTG
support will require more changes to this driver regardless, so it's
not a big deal.
Cheers,
g.
--
Grant Likely, B.Sc., P.Eng.
Secret Lab Technologies Ltd.
grant.likely@secretlab.ca
(403) 399-0195
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles
2007-11-24 20:20 ` Grant Likely
@ 2007-11-24 21:03 ` David Brownell
2007-11-24 21:13 ` Grant Likely
0 siblings, 1 reply; 20+ messages in thread
From: David Brownell @ 2007-11-24 21:03 UTC (permalink / raw)
To: Grant Likely; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On Saturday 24 November 2007, Grant Likely wrote:
> On 11/24/07, David Brownell <david-b@pacbell.net> wrote:
> > On Friday 23 November 2007, Grant Likely wrote:
> > > +config USB_C67X00_DRV
> > > +tristate "Cypress C67x00 support"
> > > +# only allowed to be =y if both USB!=m and USB_GADGET!=m
> >
> > This is wrong. Remember that since this is a dual-role driver,
> > there are exactly three possible driver modes ... and the driver
> > must support only one of them at a time:
>
> Actually, this part has 2 serial in interface engines; either of which
> can be in host, peripheral or OTG mode. So; it is entirely relevant
> for the driver to be doing both host and peripheral at the same time
> with a single device.
While conforming with USB specs? Has that changed recently?
In the not-too-distant past I know there was explicit language
saying that such configurations are not allowed. (At least,
in terms of external connectors. A board using USB for internal
peripheral connections would be OK.)
Those issues can be deferred until peripheral support exists.
At that point you'll need to get better solutions to those config
issues...
> > Hmmm ... your patches don't include peripheral mode support yet.
>
> No, nobody has written it yet.
Then what's it doing in that GIT tree you pointed me at? :)
> > Either all these gadget hooks should vanish, or you should try
> > to get the controller mode stuff right from the beginning.
> >
> > I've appended the relevant Kconfig bits from the musb_hdrc
> > driver, which (despite some glitches) are pretty much correct.
>
> I'll drop the gadget hooks for now. Most likely gadget and OTG
> support will require more changes to this driver regardless, so it's
> not a big deal.
OK. Then the first incaration of this will be as a host-only
driver, in its own directory, and adding peripheral support will
cause minor lunacy. :)
- Dave
^ permalink raw reply [flat|nested] 20+ messages in thread
* Re: [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles
2007-11-24 21:03 ` David Brownell
@ 2007-11-24 21:13 ` Grant Likely
0 siblings, 0 replies; 20+ messages in thread
From: Grant Likely @ 2007-11-24 21:13 UTC (permalink / raw)
To: David Brownell; +Cc: akpm, linuxppc-dev, gregkh, linux-usb-devel
On 11/24/07, David Brownell <david-b@pacbell.net> wrote:
> On Saturday 24 November 2007, Grant Likely wrote:
> > On 11/24/07, David Brownell <david-b@pacbell.net> wrote:
> > > On Friday 23 November 2007, Grant Likely wrote:
> > > > +config USB_C67X00_DRV
> > > > +tristate "Cypress C67x00 support"
> > > > +# only allowed to be =y if both USB!=m and USB_GADGET!=m
> > >
> > > This is wrong. Remember that since this is a dual-role driver,
> > > there are exactly three possible driver modes ... and the driver
> > > must support only one of them at a time:
> >
> > Actually, this part has 2 serial in interface engines; either of which
> > can be in host, peripheral or OTG mode. So; it is entirely relevant
> > for the driver to be doing both host and peripheral at the same time
> > with a single device.
>
> While conforming with USB specs? Has that changed recently?
Let me rephrase; the silicon implements 2 USB engines with separate
pinouts. They can be configured as 2 host controllers; 2 peripheral
controllers or 1 of each. They share registers and the IRQ line from
the software interface, but they are distinctly separate USB busses.
This driver actually implements 2 sub devices. Each sub device is
either bound to the host part of the driver or the gadget part.
>
> In the not-too-distant past I know there was explicit language
> saying that such configurations are not allowed. (At least,
> in terms of external connectors. A board using USB for internal
> peripheral connections would be OK.)
>
> Those issues can be deferred until peripheral support exists.
> At that point you'll need to get better solutions to those config
> issues...
ok
>
>
> > > Hmmm ... your patches don't include peripheral mode support yet.
> >
> > No, nobody has written it yet.
>
> Then what's it doing in that GIT tree you pointed me at? :)
Sitting there being useless. :-) That driver doesn't actually work;
it's just a proof of concept placeholder (which is why I didn't
include it in my series)
>
>
> > > Either all these gadget hooks should vanish, or you should try
> > > to get the controller mode stuff right from the beginning.
> > >
> > > I've appended the relevant Kconfig bits from the musb_hdrc
> > > driver, which (despite some glitches) are pretty much correct.
> >
> > I'll drop the gadget hooks for now. Most likely gadget and OTG
> > support will require more changes to this driver regardless, so it's
> > not a big deal.
>
> OK. Then the first incaration of this will be as a host-only
> driver, in its own directory, and adding peripheral support will
> cause minor lunacy. :)
:-)
g.
--
Grant Likely, B.Sc., P.Eng.
Secret Lab Technologies Ltd.
grant.likely@secretlab.ca
(403) 399-0195
^ permalink raw reply [flat|nested] 20+ messages in thread
end of thread, other threads:[~2007-11-24 21:13 UTC | newest]
Thread overview: 20+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2007-11-24 0:24 [PATCH 0/5] Review request: Cypress c67x00 OTG controller Grant Likely
2007-11-24 0:24 ` [PATCH 1/5] USB: Make usb_hcd_irq work for multi-role USB controllers w/ shared irq Grant Likely
2007-11-24 5:10 ` Greg KH
2007-11-24 17:03 ` [linux-usb-devel] " Alan Cox
2007-11-24 17:15 ` Grant Likely
2007-11-24 17:50 ` David Brownell
2007-11-24 19:06 ` David Brownell
2007-11-24 19:28 ` Grant Likely
2007-11-24 0:24 ` [PATCH 2/5] USB: Add Cypress c67x00 low level interface code Grant Likely
2007-11-24 19:39 ` David Brownell
2007-11-24 0:24 ` [PATCH 3/5] USB: add Cypress c67x00 OTG controller core driver Grant Likely
2007-11-24 0:24 ` [PATCH 4/5] USB: add Cypress c67x00 OTG controller HCD driver Grant Likely
2007-11-24 3:56 ` [linux-usb-devel] " Alan Stern
2007-11-24 0:24 ` [PATCH 5/5] USB: Add Cypress c67x00 OTG controller driver to Kconfig and Makefiles Grant Likely
2007-11-24 20:12 ` David Brownell
2007-11-24 20:20 ` Grant Likely
2007-11-24 21:03 ` David Brownell
2007-11-24 21:13 ` Grant Likely
2007-11-24 17:57 ` [PATCH 0/5] Review request: Cypress c67x00 OTG controller David Brownell
2007-11-24 19:27 ` Grant Likely
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).