usb: isp1760: Move driver from drivers/usb/host/ to drivers/usb/isp1760/

Now that this is DRD, it doesn't make sense to keep it under
drivers/usb/host.

Signed-off-by: Laurent Pinchart <laurent.pinchart@ideasonboard.com>
Signed-off-by: Felipe Balbi <balbi@ti.com>
This commit is contained in:
Laurent Pinchart
2015-01-21 00:56:02 +02:00
committato da Felipe Balbi
parent 0316ca6319
commit 7ef077a8ad
15 ha cambiato i file con 29 aggiunte e 26 eliminazioni

Vedi File

@@ -0,0 +1,22 @@
config USB_ISP1760
tristate "NXP ISP 1760/1761 support"
depends on USB
help
Say Y or M here if your system as an ISP1760 USB host controller
or an ISP1761 USB dual-role controller.
This driver does not support isochronous transfers or OTG.
This USB controller is usually attached to a non-DMA-Master
capable bus. NXP's eval kit brings this chip on PCI card
where the chip itself is behind a PLB to simulate such
a bus.
To compile this driver as a module, choose M here: the
module will be called isp1760.
config USB_ISP1761_UDC
boolean "NXP ISP1761 USB Device Controller"
depends on USB_ISP1760 && USB_GADGET
help
The NXP ISP1761 is a dual-role high-speed USB host and device
controller.

Vedi File

@@ -0,0 +1,4 @@
isp1760-y := isp1760-core.o isp1760-hcd.o isp1760-if.o
isp1760-$(CONFIG_USB_ISP1761_UDC) += isp1760-udc.o
obj-$(CONFIG_USB_ISP1760) += isp1760.o

Vedi File

@@ -0,0 +1,171 @@
/*
* Driver for the NXP ISP1760 chip
*
* Copyright 2014 Laurent Pinchart
* Copyright 2007 Sebastian Siewior
*
* Contacts:
* Sebastian Siewior <bigeasy@linutronix.de>
* Laurent Pinchart <laurent.pinchart@ideasonboard.com>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License
* version 2 as published by the Free Software Foundation.
*/
#include <linux/delay.h>
#include <linux/gpio/consumer.h>
#include <linux/io.h>
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/slab.h>
#include <linux/usb.h>
#include "isp1760-core.h"
#include "isp1760-hcd.h"
#include "isp1760-regs.h"
#include "isp1760-udc.h"
static void isp1760_init_core(struct isp1760_device *isp)
{
u32 otgctrl;
u32 hwmode;
/* Low-level chip reset */
if (isp->rst_gpio) {
gpiod_set_value_cansleep(isp->rst_gpio, 1);
mdelay(50);
gpiod_set_value_cansleep(isp->rst_gpio, 0);
}
/*
* Reset the host controller, including the CPU interface
* configuration.
*/
isp1760_write32(isp->regs, HC_RESET_REG, SW_RESET_RESET_ALL);
msleep(100);
/* Setup HW Mode Control: This assumes a level active-low interrupt */
hwmode = HW_DATA_BUS_32BIT;
if (isp->devflags & ISP1760_FLAG_BUS_WIDTH_16)
hwmode &= ~HW_DATA_BUS_32BIT;
if (isp->devflags & ISP1760_FLAG_ANALOG_OC)
hwmode |= HW_ANA_DIGI_OC;
if (isp->devflags & ISP1760_FLAG_DACK_POL_HIGH)
hwmode |= HW_DACK_POL_HIGH;
if (isp->devflags & ISP1760_FLAG_DREQ_POL_HIGH)
hwmode |= HW_DREQ_POL_HIGH;
if (isp->devflags & ISP1760_FLAG_INTR_POL_HIGH)
hwmode |= HW_INTR_HIGH_ACT;
if (isp->devflags & ISP1760_FLAG_INTR_EDGE_TRIG)
hwmode |= HW_INTR_EDGE_TRIG;
/*
* The ISP1761 has a dedicated DC IRQ line but supports sharing the HC
* IRQ line for both the host and device controllers. Hardcode IRQ
* sharing for now and disable the DC interrupts globally to avoid
* spurious interrupts during HCD registration.
*/
if (isp->devflags & ISP1760_FLAG_ISP1761) {
isp1760_write32(isp->regs, DC_MODE, 0);
hwmode |= HW_COMN_IRQ;
}
/*
* We have to set this first in case we're in 16-bit mode.
* Write it twice to ensure correct upper bits if switching
* to 16-bit mode.
*/
isp1760_write32(isp->regs, HC_HW_MODE_CTRL, hwmode);
isp1760_write32(isp->regs, HC_HW_MODE_CTRL, hwmode);
/*
* PORT 1 Control register of the ISP1760 is the OTG control register
* on ISP1761.
*
* TODO: Really support OTG. For now we configure port 1 in device mode
* when OTG is requested.
*/
if ((isp->devflags & ISP1760_FLAG_ISP1761) &&
(isp->devflags & ISP1760_FLAG_OTG_EN))
otgctrl = ((HW_DM_PULLDOWN | HW_DP_PULLDOWN) << 16)
| HW_OTG_DISABLE;
else
otgctrl = (HW_SW_SEL_HC_DC << 16)
| (HW_VBUS_DRV | HW_SEL_CP_EXT);
isp1760_write32(isp->regs, HC_PORT1_CTRL, otgctrl);
dev_info(isp->dev, "bus width: %u, oc: %s\n",
isp->devflags & ISP1760_FLAG_BUS_WIDTH_16 ? 16 : 32,
isp->devflags & ISP1760_FLAG_ANALOG_OC ? "analog" : "digital");
}
void isp1760_set_pullup(struct isp1760_device *isp, bool enable)
{
isp1760_write32(isp->regs, HW_OTG_CTRL_SET,
enable ? HW_DP_PULLUP : HW_DP_PULLUP << 16);
}
int isp1760_register(struct resource *mem, int irq, unsigned long irqflags,
struct device *dev, unsigned int devflags)
{
struct isp1760_device *isp;
int ret;
if (usb_disabled())
return -ENODEV;
/* prevent usb-core allocating DMA pages */
dev->dma_mask = NULL;
isp = devm_kzalloc(dev, sizeof(*isp), GFP_KERNEL);
if (!isp)
return -ENOMEM;
isp->dev = dev;
isp->devflags = devflags;
isp->rst_gpio = devm_gpiod_get_optional(dev, NULL, GPIOD_OUT_HIGH);
if (IS_ERR(isp->rst_gpio))
return PTR_ERR(isp->rst_gpio);
isp->regs = devm_ioremap_resource(dev, mem);
if (IS_ERR(isp->regs))
return PTR_ERR(isp->regs);
isp1760_init_core(isp);
ret = isp1760_hcd_register(&isp->hcd, isp->regs, mem, irq,
irqflags | IRQF_SHARED, dev);
if (ret < 0)
return ret;
if (devflags & ISP1760_FLAG_ISP1761) {
ret = isp1760_udc_register(isp, irq, irqflags | IRQF_SHARED |
IRQF_DISABLED);
if (ret < 0) {
isp1760_hcd_unregister(&isp->hcd);
return ret;
}
}
dev_set_drvdata(dev, isp);
return 0;
}
void isp1760_unregister(struct device *dev)
{
struct isp1760_device *isp = dev_get_drvdata(dev);
if (isp->devflags & ISP1760_FLAG_ISP1761)
isp1760_udc_unregister(isp);
isp1760_hcd_unregister(&isp->hcd);
}
MODULE_DESCRIPTION("Driver for the ISP1760 USB-controller from NXP");
MODULE_AUTHOR("Sebastian Siewior <bigeasy@linuxtronix.de>");
MODULE_LICENSE("GPL v2");

Vedi File

@@ -0,0 +1,68 @@
/*
* Driver for the NXP ISP1760 chip
*
* Copyright 2014 Laurent Pinchart
* Copyright 2007 Sebastian Siewior
*
* Contacts:
* Sebastian Siewior <bigeasy@linutronix.de>
* Laurent Pinchart <laurent.pinchart@ideasonboard.com>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License
* version 2 as published by the Free Software Foundation.
*/
#ifndef _ISP1760_CORE_H_
#define _ISP1760_CORE_H_
#include <linux/ioport.h>
#include "isp1760-hcd.h"
#include "isp1760-udc.h"
struct device;
struct gpio_desc;
/*
* Device flags that can vary from board to board. All of these
* indicate the most "atypical" case, so that a devflags of 0 is
* a sane default configuration.
*/
#define ISP1760_FLAG_BUS_WIDTH_16 0x00000002 /* 16-bit data bus width */
#define ISP1760_FLAG_OTG_EN 0x00000004 /* Port 1 supports OTG */
#define ISP1760_FLAG_ANALOG_OC 0x00000008 /* Analog overcurrent */
#define ISP1760_FLAG_DACK_POL_HIGH 0x00000010 /* DACK active high */
#define ISP1760_FLAG_DREQ_POL_HIGH 0x00000020 /* DREQ active high */
#define ISP1760_FLAG_ISP1761 0x00000040 /* Chip is ISP1761 */
#define ISP1760_FLAG_INTR_POL_HIGH 0x00000080 /* Interrupt polarity active high */
#define ISP1760_FLAG_INTR_EDGE_TRIG 0x00000100 /* Interrupt edge triggered */
struct isp1760_device {
struct device *dev;
void __iomem *regs;
unsigned int devflags;
struct gpio_desc *rst_gpio;
struct isp1760_hcd hcd;
struct isp1760_udc udc;
};
int isp1760_register(struct resource *mem, int irq, unsigned long irqflags,
struct device *dev, unsigned int devflags);
void isp1760_unregister(struct device *dev);
void isp1760_set_pullup(struct isp1760_device *isp, bool enable);
static inline u32 isp1760_read32(void __iomem *base, u32 reg)
{
return readl(base + reg);
}
static inline void isp1760_write32(void __iomem *base, u32 reg, u32 val)
{
writel(val, base + reg);
}
#endif

File diff soppresso perché troppo grande Carica Diff

Vedi File

@@ -0,0 +1,77 @@
#ifndef _ISP1760_HCD_H_
#define _ISP1760_HCD_H_
#include <linux/spinlock.h>
struct isp1760_qh;
struct isp1760_qtd;
struct resource;
struct usb_hcd;
/*
* 60kb divided in:
* - 32 blocks @ 256 bytes
* - 20 blocks @ 1024 bytes
* - 4 blocks @ 8192 bytes
*/
#define BLOCK_1_NUM 32
#define BLOCK_2_NUM 20
#define BLOCK_3_NUM 4
#define BLOCK_1_SIZE 256
#define BLOCK_2_SIZE 1024
#define BLOCK_3_SIZE 8192
#define BLOCKS (BLOCK_1_NUM + BLOCK_2_NUM + BLOCK_3_NUM)
#define MAX_PAYLOAD_SIZE BLOCK_3_SIZE
#define PAYLOAD_AREA_SIZE 0xf000
struct isp1760_slotinfo {
struct isp1760_qh *qh;
struct isp1760_qtd *qtd;
unsigned long timestamp;
};
/* chip memory management */
struct isp1760_memory_chunk {
unsigned int start;
unsigned int size;
unsigned int free;
};
enum isp1760_queue_head_types {
QH_CONTROL,
QH_BULK,
QH_INTERRUPT,
QH_END
};
struct isp1760_hcd {
struct usb_hcd *hcd;
u32 hcs_params;
spinlock_t lock;
struct isp1760_slotinfo atl_slots[32];
int atl_done_map;
struct isp1760_slotinfo int_slots[32];
int int_done_map;
struct isp1760_memory_chunk memory_pool[BLOCKS];
struct list_head qh_list[QH_END];
/* periodic schedule support */
#define DEFAULT_I_TDPS 1024
unsigned periodic_size;
unsigned i_thresh;
unsigned long reset_done;
unsigned long next_statechange;
};
int isp1760_hcd_register(struct isp1760_hcd *priv, void __iomem *regs,
struct resource *mem, int irq, unsigned long irqflags,
struct device *dev);
void isp1760_hcd_unregister(struct isp1760_hcd *priv);
int isp1760_init_kmem_once(void);
void isp1760_deinit_kmem_cache(void);
#endif /* _ISP1760_HCD_H_ */

Vedi File

@@ -0,0 +1,312 @@
/*
* Glue code for the ISP1760 driver and bus
* Currently there is support for
* - OpenFirmware
* - PCI
* - PDEV (generic platform device centralized driver model)
*
* (c) 2007 Sebastian Siewior <bigeasy@linutronix.de>
*
*/
#include <linux/usb.h>
#include <linux/io.h>
#include <linux/module.h>
#include <linux/of.h>
#include <linux/platform_device.h>
#include <linux/slab.h>
#include <linux/usb/isp1760.h>
#include <linux/usb/hcd.h>
#include "isp1760-core.h"
#include "isp1760-regs.h"
#ifdef CONFIG_PCI
#include <linux/pci.h>
#endif
#ifdef CONFIG_PCI
static int isp1761_pci_init(struct pci_dev *dev)
{
resource_size_t mem_start;
resource_size_t mem_length;
u8 __iomem *iobase;
u8 latency, limit;
int retry_count;
u32 reg_data;
/* Grab the PLX PCI shared memory of the ISP 1761 we need */
mem_start = pci_resource_start(dev, 3);
mem_length = pci_resource_len(dev, 3);
if (mem_length < 0xffff) {
printk(KERN_ERR "memory length for this resource is wrong\n");
return -ENOMEM;
}
if (!request_mem_region(mem_start, mem_length, "ISP-PCI")) {
printk(KERN_ERR "host controller already in use\n");
return -EBUSY;
}
/* map available memory */
iobase = ioremap_nocache(mem_start, mem_length);
if (!iobase) {
printk(KERN_ERR "Error ioremap failed\n");
release_mem_region(mem_start, mem_length);
return -ENOMEM;
}
/* bad pci latencies can contribute to overruns */
pci_read_config_byte(dev, PCI_LATENCY_TIMER, &latency);
if (latency) {
pci_read_config_byte(dev, PCI_MAX_LAT, &limit);
if (limit && limit < latency)
pci_write_config_byte(dev, PCI_LATENCY_TIMER, limit);
}
/* Try to check whether we can access Scratch Register of
* Host Controller or not. The initial PCI access is retried until
* local init for the PCI bridge is completed
*/
retry_count = 20;
reg_data = 0;
while ((reg_data != 0xFACE) && retry_count) {
/*by default host is in 16bit mode, so
* io operations at this stage must be 16 bit
* */
writel(0xface, iobase + HC_SCRATCH_REG);
udelay(100);
reg_data = readl(iobase + HC_SCRATCH_REG) & 0x0000ffff;
retry_count--;
}
iounmap(iobase);
release_mem_region(mem_start, mem_length);
/* Host Controller presence is detected by writing to scratch register
* and reading back and checking the contents are same or not
*/
if (reg_data != 0xFACE) {
dev_err(&dev->dev, "scratch register mismatch %x\n", reg_data);
return -ENOMEM;
}
/* Grab the PLX PCI mem maped port start address we need */
mem_start = pci_resource_start(dev, 0);
mem_length = pci_resource_len(dev, 0);
if (!request_mem_region(mem_start, mem_length, "ISP1761 IO MEM")) {
printk(KERN_ERR "request region #1\n");
return -EBUSY;
}
iobase = ioremap_nocache(mem_start, mem_length);
if (!iobase) {
printk(KERN_ERR "ioremap #1\n");
release_mem_region(mem_start, mem_length);
return -ENOMEM;
}
/* configure PLX PCI chip to pass interrupts */
#define PLX_INT_CSR_REG 0x68
reg_data = readl(iobase + PLX_INT_CSR_REG);
reg_data |= 0x900;
writel(reg_data, iobase + PLX_INT_CSR_REG);
/* done with PLX IO access */
iounmap(iobase);
release_mem_region(mem_start, mem_length);
return 0;
}
static int isp1761_pci_probe(struct pci_dev *dev,
const struct pci_device_id *id)
{
unsigned int devflags = 0;
int ret;
if (usb_disabled())
return -ENODEV;
if (!dev->irq)
return -ENODEV;
if (pci_enable_device(dev) < 0)
return -ENODEV;
ret = isp1761_pci_init(dev);
if (ret < 0)
goto error;
pci_set_master(dev);
dev->dev.dma_mask = NULL;
ret = isp1760_register(&dev->resource[3], dev->irq, 0, &dev->dev,
devflags);
if (ret < 0)
goto error;
return 0;
error:
pci_disable_device(dev);
return ret;
}
static void isp1761_pci_remove(struct pci_dev *dev)
{
isp1760_unregister(&dev->dev);
pci_disable_device(dev);
}
static void isp1761_pci_shutdown(struct pci_dev *dev)
{
printk(KERN_ERR "ips1761_pci_shutdown\n");
}
static const struct pci_device_id isp1760_plx [] = {
{
.class = PCI_CLASS_BRIDGE_OTHER << 8,
.class_mask = ~0,
.vendor = PCI_VENDOR_ID_PLX,
.device = 0x5406,
.subvendor = PCI_VENDOR_ID_PLX,
.subdevice = 0x9054,
},
{ }
};
MODULE_DEVICE_TABLE(pci, isp1760_plx);
static struct pci_driver isp1761_pci_driver = {
.name = "isp1760",
.id_table = isp1760_plx,
.probe = isp1761_pci_probe,
.remove = isp1761_pci_remove,
.shutdown = isp1761_pci_shutdown,
};
#endif
static int isp1760_plat_probe(struct platform_device *pdev)
{
unsigned long irqflags;
unsigned int devflags = 0;
struct resource *mem_res;
struct resource *irq_res;
int ret;
mem_res = platform_get_resource(pdev, IORESOURCE_MEM, 0);
irq_res = platform_get_resource(pdev, IORESOURCE_IRQ, 0);
if (!irq_res) {
pr_warning("isp1760: IRQ resource not available\n");
return -ENODEV;
}
irqflags = irq_res->flags & IRQF_TRIGGER_MASK;
if (IS_ENABLED(CONFIG_OF) && pdev->dev.of_node) {
struct device_node *dp = pdev->dev.of_node;
u32 bus_width = 0;
if (of_device_is_compatible(dp, "nxp,usb-isp1761"))
devflags |= ISP1760_FLAG_ISP1761;
/* Some systems wire up only 16 of the 32 data lines */
of_property_read_u32(dp, "bus-width", &bus_width);
if (bus_width == 16)
devflags |= ISP1760_FLAG_BUS_WIDTH_16;
if (of_property_read_bool(dp, "port1-otg"))
devflags |= ISP1760_FLAG_OTG_EN;
if (of_property_read_bool(dp, "analog-oc"))
devflags |= ISP1760_FLAG_ANALOG_OC;
if (of_property_read_bool(dp, "dack-polarity"))
devflags |= ISP1760_FLAG_DACK_POL_HIGH;
if (of_property_read_bool(dp, "dreq-polarity"))
devflags |= ISP1760_FLAG_DREQ_POL_HIGH;
} else if (dev_get_platdata(&pdev->dev)) {
struct isp1760_platform_data *pdata =
dev_get_platdata(&pdev->dev);
if (pdata->is_isp1761)
devflags |= ISP1760_FLAG_ISP1761;
if (pdata->bus_width_16)
devflags |= ISP1760_FLAG_BUS_WIDTH_16;
if (pdata->port1_otg)
devflags |= ISP1760_FLAG_OTG_EN;
if (pdata->analog_oc)
devflags |= ISP1760_FLAG_ANALOG_OC;
if (pdata->dack_polarity_high)
devflags |= ISP1760_FLAG_DACK_POL_HIGH;
if (pdata->dreq_polarity_high)
devflags |= ISP1760_FLAG_DREQ_POL_HIGH;
}
ret = isp1760_register(mem_res, irq_res->start, irqflags, &pdev->dev,
devflags);
if (ret < 0)
return ret;
pr_info("ISP1760 USB device initialised\n");
return 0;
}
static int isp1760_plat_remove(struct platform_device *pdev)
{
isp1760_unregister(&pdev->dev);
return 0;
}
#ifdef CONFIG_OF
static const struct of_device_id isp1760_of_match[] = {
{ .compatible = "nxp,usb-isp1760", },
{ .compatible = "nxp,usb-isp1761", },
{ },
};
MODULE_DEVICE_TABLE(of, isp1760_of_match);
#endif
static struct platform_driver isp1760_plat_driver = {
.probe = isp1760_plat_probe,
.remove = isp1760_plat_remove,
.driver = {
.name = "isp1760",
.of_match_table = of_match_ptr(isp1760_of_match),
},
};
static int __init isp1760_init(void)
{
int ret, any_ret = -ENODEV;
isp1760_init_kmem_once();
ret = platform_driver_register(&isp1760_plat_driver);
if (!ret)
any_ret = 0;
#ifdef CONFIG_PCI
ret = pci_register_driver(&isp1761_pci_driver);
if (!ret)
any_ret = 0;
#endif
if (any_ret)
isp1760_deinit_kmem_cache();
return any_ret;
}
module_init(isp1760_init);
static void __exit isp1760_exit(void)
{
platform_driver_unregister(&isp1760_plat_driver);
#ifdef CONFIG_PCI
pci_unregister_driver(&isp1761_pci_driver);
#endif
isp1760_deinit_kmem_cache();
}
module_exit(isp1760_exit);

Vedi File

@@ -0,0 +1,230 @@
/*
* Driver for the NXP ISP1760 chip
*
* Copyright 2014 Laurent Pinchart
* Copyright 2007 Sebastian Siewior
*
* Contacts:
* Sebastian Siewior <bigeasy@linutronix.de>
* Laurent Pinchart <laurent.pinchart@ideasonboard.com>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License
* version 2 as published by the Free Software Foundation.
*/
#ifndef _ISP1760_REGS_H_
#define _ISP1760_REGS_H_
/* -----------------------------------------------------------------------------
* Host Controller
*/
/* EHCI capability registers */
#define HC_CAPLENGTH 0x000
#define HC_LENGTH(p) (((p) >> 00) & 0x00ff) /* bits 7:0 */
#define HC_VERSION(p) (((p) >> 16) & 0xffff) /* bits 31:16 */
#define HC_HCSPARAMS 0x004
#define HCS_INDICATOR(p) ((p) & (1 << 16)) /* true: has port indicators */
#define HCS_PPC(p) ((p) & (1 << 4)) /* true: port power control */
#define HCS_N_PORTS(p) (((p) >> 0) & 0xf) /* bits 3:0, ports on HC */
#define HC_HCCPARAMS 0x008
#define HCC_ISOC_CACHE(p) ((p) & (1 << 7)) /* true: can cache isoc frame */
#define HCC_ISOC_THRES(p) (((p) >> 4) & 0x7) /* bits 6:4, uframes cached */
/* EHCI operational registers */
#define HC_USBCMD 0x020
#define CMD_LRESET (1 << 7) /* partial reset (no ports, etc) */
#define CMD_RESET (1 << 1) /* reset HC not bus */
#define CMD_RUN (1 << 0) /* start/stop HC */
#define HC_USBSTS 0x024
#define STS_PCD (1 << 2) /* port change detect */
#define HC_FRINDEX 0x02c
#define HC_CONFIGFLAG 0x060
#define FLAG_CF (1 << 0) /* true: we'll support "high speed" */
#define HC_PORTSC1 0x064
#define PORT_OWNER (1 << 13) /* true: companion hc owns this port */
#define PORT_POWER (1 << 12) /* true: has power (see PPC) */
#define PORT_USB11(x) (((x) & (3 << 10)) == (1 << 10)) /* USB 1.1 device */
#define PORT_RESET (1 << 8) /* reset port */
#define PORT_SUSPEND (1 << 7) /* suspend port */
#define PORT_RESUME (1 << 6) /* resume it */
#define PORT_PE (1 << 2) /* port enable */
#define PORT_CSC (1 << 1) /* connect status change */
#define PORT_CONNECT (1 << 0) /* device connected */
#define PORT_RWC_BITS (PORT_CSC)
#define HC_ISO_PTD_DONEMAP_REG 0x130
#define HC_ISO_PTD_SKIPMAP_REG 0x134
#define HC_ISO_PTD_LASTPTD_REG 0x138
#define HC_INT_PTD_DONEMAP_REG 0x140
#define HC_INT_PTD_SKIPMAP_REG 0x144
#define HC_INT_PTD_LASTPTD_REG 0x148
#define HC_ATL_PTD_DONEMAP_REG 0x150
#define HC_ATL_PTD_SKIPMAP_REG 0x154
#define HC_ATL_PTD_LASTPTD_REG 0x158
/* Configuration Register */
#define HC_HW_MODE_CTRL 0x300
#define ALL_ATX_RESET (1 << 31)
#define HW_ANA_DIGI_OC (1 << 15)
#define HW_DEV_DMA (1 << 11)
#define HW_COMN_IRQ (1 << 10)
#define HW_COMN_DMA (1 << 9)
#define HW_DATA_BUS_32BIT (1 << 8)
#define HW_DACK_POL_HIGH (1 << 6)
#define HW_DREQ_POL_HIGH (1 << 5)
#define HW_INTR_HIGH_ACT (1 << 2)
#define HW_INTR_EDGE_TRIG (1 << 1)
#define HW_GLOBAL_INTR_EN (1 << 0)
#define HC_CHIP_ID_REG 0x304
#define HC_SCRATCH_REG 0x308
#define HC_RESET_REG 0x30c
#define SW_RESET_RESET_HC (1 << 1)
#define SW_RESET_RESET_ALL (1 << 0)
#define HC_BUFFER_STATUS_REG 0x334
#define ISO_BUF_FILL (1 << 2)
#define INT_BUF_FILL (1 << 1)
#define ATL_BUF_FILL (1 << 0)
#define HC_MEMORY_REG 0x33c
#define ISP_BANK(x) ((x) << 16)
#define HC_PORT1_CTRL 0x374
#define PORT1_POWER (3 << 3)
#define PORT1_INIT1 (1 << 7)
#define PORT1_INIT2 (1 << 23)
#define HW_OTG_CTRL_SET 0x374
#define HW_OTG_CTRL_CLR 0x376
#define HW_OTG_DISABLE (1 << 10)
#define HW_OTG_SE0_EN (1 << 9)
#define HW_BDIS_ACON_EN (1 << 8)
#define HW_SW_SEL_HC_DC (1 << 7)
#define HW_VBUS_CHRG (1 << 6)
#define HW_VBUS_DISCHRG (1 << 5)
#define HW_VBUS_DRV (1 << 4)
#define HW_SEL_CP_EXT (1 << 3)
#define HW_DM_PULLDOWN (1 << 2)
#define HW_DP_PULLDOWN (1 << 1)
#define HW_DP_PULLUP (1 << 0)
/* Interrupt Register */
#define HC_INTERRUPT_REG 0x310
#define HC_INTERRUPT_ENABLE 0x314
#define HC_ISO_INT (1 << 9)
#define HC_ATL_INT (1 << 8)
#define HC_INTL_INT (1 << 7)
#define HC_EOT_INT (1 << 3)
#define HC_SOT_INT (1 << 1)
#define INTERRUPT_ENABLE_MASK (HC_INTL_INT | HC_ATL_INT)
#define HC_ISO_IRQ_MASK_OR_REG 0x318
#define HC_INT_IRQ_MASK_OR_REG 0x31c
#define HC_ATL_IRQ_MASK_OR_REG 0x320
#define HC_ISO_IRQ_MASK_AND_REG 0x324
#define HC_INT_IRQ_MASK_AND_REG 0x328
#define HC_ATL_IRQ_MASK_AND_REG 0x32c
/* -----------------------------------------------------------------------------
* Peripheral Controller
*/
/* Initialization Registers */
#define DC_ADDRESS 0x0200
#define DC_DEVEN (1 << 7)
#define DC_MODE 0x020c
#define DC_DMACLKON (1 << 9)
#define DC_VBUSSTAT (1 << 8)
#define DC_CLKAON (1 << 7)
#define DC_SNDRSU (1 << 6)
#define DC_GOSUSP (1 << 5)
#define DC_SFRESET (1 << 4)
#define DC_GLINTENA (1 << 3)
#define DC_WKUPCS (1 << 2)
#define DC_INTCONF 0x0210
#define DC_CDBGMOD_ACK_NAK (0 << 6)
#define DC_CDBGMOD_ACK (1 << 6)
#define DC_CDBGMOD_ACK_1NAK (2 << 6)
#define DC_DDBGMODIN_ACK_NAK (0 << 4)
#define DC_DDBGMODIN_ACK (1 << 4)
#define DC_DDBGMODIN_ACK_1NAK (2 << 4)
#define DC_DDBGMODOUT_ACK_NYET_NAK (0 << 2)
#define DC_DDBGMODOUT_ACK_NYET (1 << 2)
#define DC_DDBGMODOUT_ACK_NYET_1NAK (2 << 2)
#define DC_INTLVL (1 << 1)
#define DC_INTPOL (1 << 0)
#define DC_DEBUG 0x0212
#define DC_INTENABLE 0x0214
#define DC_IEPTX(n) (1 << (11 + 2 * (n)))
#define DC_IEPRX(n) (1 << (10 + 2 * (n)))
#define DC_IEPRXTX(n) (3 << (10 + 2 * (n)))
#define DC_IEP0SETUP (1 << 8)
#define DC_IEVBUS (1 << 7)
#define DC_IEDMA (1 << 6)
#define DC_IEHS_STA (1 << 5)
#define DC_IERESM (1 << 4)
#define DC_IESUSP (1 << 3)
#define DC_IEPSOF (1 << 2)
#define DC_IESOF (1 << 1)
#define DC_IEBRST (1 << 0)
/* Data Flow Registers */
#define DC_EPINDEX 0x022c
#define DC_EP0SETUP (1 << 5)
#define DC_ENDPIDX(n) ((n) << 1)
#define DC_EPDIR (1 << 0)
#define DC_CTRLFUNC 0x0228
#define DC_CLBUF (1 << 4)
#define DC_VENDP (1 << 3)
#define DC_DSEN (1 << 2)
#define DC_STATUS (1 << 1)
#define DC_STALL (1 << 0)
#define DC_DATAPORT 0x0220
#define DC_BUFLEN 0x021c
#define DC_DATACOUNT_MASK 0xffff
#define DC_BUFSTAT 0x021e
#define DC_EPMAXPKTSZ 0x0204
#define DC_EPTYPE 0x0208
#define DC_NOEMPKT (1 << 4)
#define DC_EPENABLE (1 << 3)
#define DC_DBLBUF (1 << 2)
#define DC_ENDPTYP_ISOC (1 << 0)
#define DC_ENDPTYP_BULK (2 << 0)
#define DC_ENDPTYP_INTERRUPT (3 << 0)
/* DMA Registers */
#define DC_DMACMD 0x0230
#define DC_DMATXCOUNT 0x0234
#define DC_DMACONF 0x0238
#define DC_DMAHW 0x023c
#define DC_DMAINTREASON 0x0250
#define DC_DMAINTEN 0x0254
#define DC_DMAEP 0x0258
#define DC_DMABURSTCOUNT 0x0264
/* General Registers */
#define DC_INTERRUPT 0x0218
#define DC_CHIPID 0x0270
#define DC_FRAMENUM 0x0274
#define DC_SCRATCH 0x0278
#define DC_UNLOCKDEV 0x027c
#define DC_INTPULSEWIDTH 0x0280
#define DC_TESTMODE 0x0284
#endif

File diff soppresso perché troppo grande Carica Diff

Vedi File

@@ -0,0 +1,106 @@
/*
* Driver for the NXP ISP1761 device controller
*
* Copyright 2014 Ideas on Board Oy
*
* Contacts:
* Laurent Pinchart <laurent.pinchart@ideasonboard.com>
*
* This program is free software; you can redistribute it and/or
* modify it under the terms of the GNU General Public License
* version 2 as published by the Free Software Foundation.
*/
#ifndef _ISP1760_UDC_H_
#define _ISP1760_UDC_H_
#include <linux/ioport.h>
#include <linux/list.h>
#include <linux/spinlock.h>
#include <linux/timer.h>
#include <linux/usb/gadget.h>
struct isp1760_device;
struct isp1760_udc;
enum isp1760_ctrl_state {
ISP1760_CTRL_SETUP, /* Waiting for a SETUP transaction */
ISP1760_CTRL_DATA_IN, /* Setup received, data IN stage */
ISP1760_CTRL_DATA_OUT, /* Setup received, data OUT stage */
ISP1760_CTRL_STATUS, /* 0-length request in status stage */
};
struct isp1760_ep {
struct isp1760_udc *udc;
struct usb_ep ep;
struct list_head queue;
unsigned int addr;
unsigned int maxpacket;
char name[7];
const struct usb_endpoint_descriptor *desc;
bool rx_pending;
bool halted;
bool wedged;
};
/**
* struct isp1760_udc - UDC state information
* irq: IRQ number
* irqname: IRQ name (as passed to request_irq)
* regs: Base address of the UDC registers
* driver: Gadget driver
* gadget: Gadget device
* lock: Protects driver, vbus_timer, ep, ep0_*, DC_EPINDEX register
* ep: Array of endpoints
* ep0_state: Control request state for endpoint 0
* ep0_dir: Direction of the current control request
* ep0_length: Length of the current control request
* connected: Tracks gadget driver bus connection state
*/
struct isp1760_udc {
#if CONFIG_USB_ISP1761_UDC
struct isp1760_device *isp;
int irq;
char *irqname;
void __iomem *regs;
struct usb_gadget_driver *driver;
struct usb_gadget gadget;
spinlock_t lock;
struct timer_list vbus_timer;
struct isp1760_ep ep[15];
enum isp1760_ctrl_state ep0_state;
u8 ep0_dir;
u16 ep0_length;
bool connected;
unsigned int devstatus;
#endif
};
#if CONFIG_USB_ISP1761_UDC
int isp1760_udc_register(struct isp1760_device *isp, int irq,
unsigned long irqflags);
void isp1760_udc_unregister(struct isp1760_device *isp);
#else
static inline int isp1760_udc_register(struct isp1760_device *isp, int irq,
unsigned long irqflags)
{
return 0;
}
static inline void isp1760_udc_unregister(struct isp1760_device *isp)
{
}
#endif
#endif