2017-07-06 20:49:25

by Anatolij Gustschin

[permalink] [raw]
Subject: [PATCH 0/3] FPGA Manager support for FPP via FT232H FT245-FIFO

This series adds support for fast passive parallel (FPP) Altera
FPGA configuration using FTDI FT232H chip in FT245-FIFO mode.
It has been used to configure Arria 10 FPGAs.

Patch 1 adds an FT232H MFD driver with common functions that
can be used for FT232H USB-GPIO/I2C/SPI master adapter drivers.
Currently it is used for FT232H GPIO support (in patch 2) and
for FT245 FIFO transfers in FPP FPGA manager driver in patch 3.
Driver support for FT232H USB-I2C/SPI master adapters can be
added later.

Patch 2 adds a simple GPIO driver supporting four FT232H CBUS GPIOs.

Patch 3 adds an FPGA Manager driver for Altera FPP FPGA configuration
via FT232H FT245-FIFO interface.

Anatolij Gustschin (3):
mfd: Add support for FTDI FT232H devices
gpio: Add FT232H CBUS GPIO driver
fpga manager: Add FT232H driver for Altera FPP

drivers/fpga/Kconfig | 7 +
drivers/fpga/Makefile | 1 +
drivers/fpga/ftdi-fifo-fpp.c | 569 ++++++++++++++++++++++++++++++++++++++++++
drivers/gpio/Kconfig | 11 +
drivers/gpio/Makefile | 1 +
drivers/gpio/gpio-ftdi-cbus.c | 251 +++++++++++++++++++
drivers/mfd/Kconfig | 9 +
drivers/mfd/Makefile | 1 +
drivers/mfd/ftdi-ft232h.c | 470 ++++++++++++++++++++++++++++++++++
include/linux/mfd/ftdi/ftdi.h | 71 ++++++
10 files changed, 1391 insertions(+)
create mode 100644 drivers/fpga/ftdi-fifo-fpp.c
create mode 100644 drivers/gpio/gpio-ftdi-cbus.c
create mode 100644 drivers/mfd/ftdi-ft232h.c
create mode 100644 include/linux/mfd/ftdi/ftdi.h

--
2.7.4


2017-07-06 20:49:29

by Anatolij Gustschin

[permalink] [raw]
Subject: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

Add USB part with common functions for USB-GPIO/I2C/SPI master
adapters. These allow communication with chip's control, transmit
and receive endpoints and will be used by various FT232H drivers.

Signed-off-by: Anatolij Gustschin <[email protected]>
---
drivers/mfd/Kconfig | 9 +
drivers/mfd/Makefile | 1 +
drivers/mfd/ftdi-ft232h.c | 470 ++++++++++++++++++++++++++++++++++++++++++
include/linux/mfd/ftdi/ftdi.h | 71 +++++++
4 files changed, 551 insertions(+)
create mode 100644 drivers/mfd/ftdi-ft232h.c
create mode 100644 include/linux/mfd/ftdi/ftdi.h

diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
index 94ad2c1..2c4e6f2 100644
--- a/drivers/mfd/Kconfig
+++ b/drivers/mfd/Kconfig
@@ -327,6 +327,15 @@ config MFD_EXYNOS_LPASS
Select this option to enable support for Samsung Exynos Low Power
Audio Subsystem.

+config MFD_FTDI_FT232H
+ tristate "FTDI FT232H MFD driver"
+ select MFD_CORE
+ depends on USB
+ help
+ Enable support for the FTDI FT232H USB-GPIO/I2C/SPI/FIFO
+ Master Adapter. Additional drivers such as CBUS_GPIO, etc.
+ must be enabled in order to use the functionality of the device.
+
config MFD_MC13XXX
tristate
depends on (SPI_MASTER || I2C)
diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
index 080793b..a75163a 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -223,3 +223,4 @@ obj-$(CONFIG_MFD_SUN4I_GPADC) += sun4i-gpadc.o

obj-$(CONFIG_MFD_STM32_TIMERS) += stm32-timers.o
obj-$(CONFIG_MFD_MXS_LRADC) += mxs-lradc.o
+obj-$(CONFIG_MFD_FTDI_FT232H) += ftdi-ft232h.o
diff --git a/drivers/mfd/ftdi-ft232h.c b/drivers/mfd/ftdi-ft232h.c
new file mode 100644
index 0000000..d5d6d35
--- /dev/null
+++ b/drivers/mfd/ftdi-ft232h.c
@@ -0,0 +1,470 @@
+/*
+ * FTDI FT232H MFD driver
+ *
+ * Copyright (C) 2017 DENX Software Engineering
+ * Anatolij Gustschin <[email protected]>
+ *
+ * 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/kernel.h>
+#include <linux/module.h>
+#include <linux/mutex.h>
+#include <linux/platform_device.h>
+#include <linux/slab.h>
+#include <linux/usb.h>
+#include <linux/mfd/core.h>
+#include <linux/mfd/ftdi/ftdi.h>
+
+struct ftdi_mfd_priv {
+ struct usb_interface *intf;
+ struct usb_device *udev;
+ struct mutex io_mutex; /* sync I/O with disconnect */
+ int bitbang_enabled;
+ int index;
+ u8 bulk_in;
+ u8 bulk_out;
+ size_t bulk_in_sz;
+ void *bulk_in_buf;
+};
+
+/* Use baudrate calculation from libftdi */
+static int ftdi_to_clkbits(int baudrate, unsigned int clk, int clk_div,
+ unsigned long *encoded_divisor)
+{
+ static const char frac_code[8] = { 0, 3, 2, 4, 1, 5, 6, 7 };
+ int best_baud = 0;
+ int div, best_div;
+
+ if (baudrate >= clk / clk_div) {
+ *encoded_divisor = 0;
+ best_baud = clk / clk_div;
+ } else if (baudrate >= clk / (clk_div + clk_div / 2)) {
+ *encoded_divisor = 1;
+ best_baud = clk / (clk_div + clk_div / 2);
+ } else if (baudrate >= clk / (2 * clk_div)) {
+ *encoded_divisor = 2;
+ best_baud = clk / (2 * clk_div);
+ } else {
+ /*
+ * Divide by 16 to have 3 fractional bits and
+ * one bit for rounding
+ */
+ div = clk * 16 / clk_div / baudrate;
+ if (div & 1) /* Decide if to round up or down */
+ best_div = div / 2 + 1;
+ else
+ best_div = div / 2;
+ if (best_div > 0x20000)
+ best_div = 0x1ffff;
+ best_baud = clk * 16 / clk_div / best_div;
+ if (best_baud & 1) /* Decide if to round up or down */
+ best_baud = best_baud / 2 + 1;
+ else
+ best_baud = best_baud / 2;
+ *encoded_divisor = (best_div >> 3) |
+ (frac_code[best_div & 0x7] << 14);
+ }
+ return best_baud;
+}
+
+#define H_CLK 120000000
+#define C_CLK 48000000
+static int ftdi_convert_baudrate(struct ftdi_mfd_priv *priv, int baud,
+ u16 *value, u16 *index)
+{
+ unsigned long encoded_divisor = 0;
+ int best_baud = 0;
+
+ if (baud <= 0)
+ return -EINVAL;
+
+ /*
+ * On H Devices, use 12000000 baudrate when possible.
+ * We have a 14 bit divisor, a 1 bit divisor switch (10 or 16),
+ * three fractional bits and a 120 MHz clock. Assume AN_120
+ * "Sub-integer divisors between 0 and 2 are not allowed" holds
+ * for DIV/10 CLK too, so /1, /1.5 and /2 can be handled the same
+ */
+ if (baud * 10 > H_CLK / 0x3fff) {
+ best_baud = ftdi_to_clkbits(baud, H_CLK, 10, &encoded_divisor);
+ encoded_divisor |= 0x20000; /* switch on CLK/10 */
+ } else {
+ best_baud = ftdi_to_clkbits(baud, C_CLK, 16, &encoded_divisor);
+ }
+
+ if (best_baud <= 0) {
+ pr_err("Invalid baudrate: %d\n", best_baud);
+ return -EINVAL;
+ }
+
+ /* Check within tolerance (about 5%) */
+ if ((best_baud * 2 < baud) ||
+ (best_baud < baud
+ ? (best_baud * 21 < baud * 20)
+ : (baud * 21 < best_baud * 20))) {
+ pr_err("Unsupported baudrate.\n");
+ return -EINVAL;
+ }
+
+ /* Split into "value" and "index" values */
+ *value = (u16)(encoded_divisor & 0xffff);
+ *index = (u16)(((encoded_divisor >> 8) & 0xff00) | priv->index);
+
+ dev_dbg(&priv->intf->dev, "best baud %d, v/i: %d, %d\n",
+ best_baud, *value, *index);
+ return best_baud;
+}
+
+/**
+ * ftdi_ctrl_xfer - FTDI control endpoint transfer
+ * @pdev: pointer to FTDI MFD platform device
+ * @desc: pointer to descriptor struct for control transfer
+ *
+ * Return:
+ * Return: If successful, the number of bytes transferred. Otherwise,
+ * a negative error number.
+ */
+int ftdi_ctrl_xfer(struct platform_device *pdev, struct ctrl_desc *desc)
+{
+ struct ftdi_mfd_priv *priv;
+ struct usb_device *udev;
+ unsigned int pipe;
+ int ret;
+
+ priv = dev_get_drvdata(pdev->dev.parent);
+ udev = priv->udev;
+
+ mutex_lock(&priv->io_mutex);
+ if (!priv->intf) {
+ ret = -ENODEV;
+ goto exit;
+ }
+
+ if (!desc->data && desc->size)
+ desc->data = priv->bulk_in_buf;
+
+ if (desc->dir_out)
+ pipe = usb_sndctrlpipe(udev, 0);
+ else
+ pipe = usb_rcvctrlpipe(udev, 0);
+
+ ret = usb_control_msg(udev, pipe, desc->request, desc->requesttype,
+ desc->value, desc->index, desc->data, desc->size,
+ desc->timeout);
+ if (ret < 0)
+ dev_err(&udev->dev, "ctrl msg failed: %d\n", ret);
+exit:
+ mutex_unlock(&priv->io_mutex);
+ return ret;
+}
+EXPORT_SYMBOL_GPL(ftdi_ctrl_xfer);
+
+/**
+ * ftdi_bulk_xfer - FTDI bulk endpoint transfer
+ * @pdev: pointer to FTDI MFD platform device
+ * @desc: pointer to descriptor struct for bulk-in or bulk-out transfer
+ *
+ * Return:
+ * If successful, 0. Otherwise a negative error number. The number of actual
+ * bytes transferred will be stored in the @desc->act_len field of the
+ * descriptor struct.
+ */
+int ftdi_bulk_xfer(struct platform_device *pdev, struct bulk_desc *desc)
+{
+ struct ftdi_mfd_priv *priv = dev_get_drvdata(pdev->dev.parent);
+ struct usb_device *udev = priv->udev;
+ unsigned int pipe;
+ int ret;
+
+ mutex_lock(&priv->io_mutex);
+ if (!priv->intf) {
+ ret = -ENODEV;
+ goto exit;
+ }
+
+ if (desc->dir_out)
+ pipe = usb_sndbulkpipe(udev, priv->bulk_out);
+ else
+ pipe = usb_rcvbulkpipe(udev, priv->bulk_in);
+
+ ret = usb_bulk_msg(udev, pipe, desc->data, desc->len,
+ &desc->act_len, desc->timeout);
+ if (ret)
+ dev_err(&udev->dev, "bulk msg failed: %d\n", ret);
+
+exit:
+ mutex_unlock(&priv->io_mutex);
+ return ret;
+}
+EXPORT_SYMBOL_GPL(ftdi_bulk_xfer);
+
+/**
+ * ftdi_set_baudrate - set the device baud rate
+ * @pdev: pointer to FTDI MFD platform device
+ * @baudrate: baud rate value to set
+ *
+ * Return: If successful, 0. Otherwise a negative error number.
+ */
+int ftdi_set_baudrate(struct platform_device *pdev, int baudrate)
+{
+ struct ftdi_mfd_priv *priv = dev_get_drvdata(pdev->dev.parent);
+ struct ctrl_desc desc;
+ u16 index, value;
+ int ret;
+
+ if (priv->bitbang_enabled)
+ baudrate *= 4;
+
+ ret = ftdi_convert_baudrate(priv, baudrate, &value, &index);
+ if (ret < 0)
+ return ret;
+
+ desc.dir_out = true;
+ desc.request = FTDI_SIO_SET_BAUDRATE_REQUEST;
+ desc.requesttype = USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_DIR_OUT;
+ desc.value = value;
+ desc.index = index;
+ desc.data = NULL;
+ desc.size = 0;
+ desc.timeout = USB_CTRL_SET_TIMEOUT;
+
+ ret = ftdi_ctrl_xfer(pdev, &desc);
+ if (ret < 0) {
+ dev_dbg(&pdev->dev, "failed to set baudrate: %d\n", ret);
+ return ret;
+ }
+
+ return 0;
+}
+EXPORT_SYMBOL_GPL(ftdi_set_baudrate);
+
+/**
+ * ftdi_read_data - read from FTDI bulk-in endpoint
+ * @pdev: pointer to FTDI MFD platform device
+ * @buf: pointer to data buffer
+ * @len: length in bytes of the data to read
+ *
+ * The two modem status bytes transferred in every read will
+ * be removed and will not appear in the data buffer.
+ *
+ * Return:
+ * If successful, the number of data bytes received (can be 0).
+ * Otherwise, a negative error number.
+ */
+int ftdi_read_data(struct platform_device *pdev, void *buf, size_t len)
+{
+ struct ftdi_mfd_priv *priv = dev_get_drvdata(pdev->dev.parent);
+ struct bulk_desc desc;
+ int ret;
+
+ desc.act_len = 0;
+ desc.dir_out = false;
+ desc.data = priv->bulk_in_buf;
+ /* Device sends 2 additional status bytes, read at least len + 2 */
+ desc.len = min_t(size_t, len + 2, priv->bulk_in_sz);
+ desc.timeout = FTDI_USB_READ_TIMEOUT;
+
+ ret = ftdi_bulk_xfer(pdev, &desc);
+ if (ret)
+ return ret;
+
+ /* Only status bytes and no data? */
+ if (desc.act_len <= 2)
+ return 0;
+
+ /* Skip first two status bytes */
+ ret = desc.act_len - 2;
+ memcpy(buf, desc.data + 2, ret);
+ return ret;
+}
+EXPORT_SYMBOL_GPL(ftdi_read_data);
+
+/**
+ * ftdi_write_data - write to FTDI bulk-out endpoint
+ * @pdev: pointer to FTDI MFD platform device
+ * @buf: pointer to data buffer
+ * @len: length in bytes of the data to send
+ *
+ * Return:
+ * If successful, the number of bytes transferred. Otherwise a negative
+ * error number.
+ */
+int ftdi_write_data(struct platform_device *pdev, const char *buf, size_t len)
+{
+ struct bulk_desc desc;
+ int ret;
+
+ desc.act_len = 0;
+ desc.dir_out = true;
+ desc.data = (char *)buf;
+ desc.len = len;
+ desc.timeout = FTDI_USB_WRITE_TIMEOUT;
+
+ ret = ftdi_bulk_xfer(pdev, &desc);
+ if (ret < 0)
+ return ret;
+
+ return desc.act_len;
+}
+EXPORT_SYMBOL_GPL(ftdi_write_data);
+
+/**
+ * ftdi_set_bitmode - configure bitbang mode
+ * @pdev: pointer to FTDI MFD platform device
+ * @bitmask: line configuration bitmask
+ * @mode: bitbang mode to set
+ *
+ * Return:
+ * If successful, 0. Otherwise a negative error number.
+ */
+int ftdi_set_bitmode(struct platform_device *pdev, unsigned char bitmask,
+ unsigned char mode)
+{
+ struct ftdi_mfd_priv *priv = dev_get_drvdata(pdev->dev.parent);
+ struct ctrl_desc desc;
+ int ret;
+
+ desc.dir_out = true;
+ desc.data = NULL;
+ desc.request = FTDI_SIO_SET_BITMODE_REQUEST;
+ desc.requesttype = USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_DIR_OUT;
+ desc.index = 1;
+ desc.value = (mode << 8) | bitmask;
+ desc.size = 0;
+ desc.timeout = USB_CTRL_SET_TIMEOUT;
+
+ ret = ftdi_ctrl_xfer(pdev, &desc);
+ if (ret < 0)
+ return ret;
+
+ switch (mode) {
+ case BITMODE_BITBANG:
+ case BITMODE_CBUS:
+ case BITMODE_SYNCBB:
+ case BITMODE_SYNCFF:
+ priv->bitbang_enabled = 1;
+ break;
+ case BITMODE_MPSSE:
+ case BITMODE_RESET:
+ default:
+ priv->bitbang_enabled = 0;
+ break;
+ }
+
+ return 0;
+}
+EXPORT_SYMBOL_GPL(ftdi_set_bitmode);
+
+/**
+ * ftdi_disable_bitbang - disable bitbang mode
+ * @pdev: pointer to FTDI MFD platform device
+ *
+ * Return:
+ * If successful, 0. Otherwise a negative error number.
+ */
+int ftdi_disable_bitbang(struct platform_device *pdev)
+{
+ int ret;
+
+ ret = ftdi_set_bitmode(pdev, 0, BITMODE_RESET);
+ if (ret < 0) {
+ dev_dbg(&pdev->dev, "disable bitbang failed: %d\n", ret);
+ return ret;
+ }
+
+ return 0;
+}
+EXPORT_SYMBOL_GPL(ftdi_disable_bitbang);
+
+static const struct mfd_cell ftdi_cells[] = {
+ { .name = "ftdi-cbus-gpio", },
+ { .name = "ftdi-mpsse-i2c", },
+ { .name = "ftdi-mpsse-spi", },
+ { .name = "ftdi-fifo-fpp-mgr", },
+};
+
+static int ftdi_mfd_probe(struct usb_interface *intf,
+ const struct usb_device_id *id)
+{
+ struct ftdi_mfd_priv *priv;
+ struct device *dev = &intf->dev;
+ struct usb_host_interface *iface_desc;
+ struct usb_endpoint_descriptor *endpoint;
+ unsigned int i;
+ int ret;
+
+ priv = devm_kzalloc(dev, sizeof(*priv), GFP_KERNEL);
+ if (!priv)
+ return -ENOMEM;
+
+ iface_desc = intf->cur_altsetting;
+
+ for (i = 0; i < iface_desc->desc.bNumEndpoints; i++) {
+ endpoint = &iface_desc->endpoint[i].desc;
+
+ if (usb_endpoint_is_bulk_out(endpoint))
+ priv->bulk_out = endpoint->bEndpointAddress;
+
+ if (usb_endpoint_is_bulk_in(endpoint)) {
+ priv->bulk_in = endpoint->bEndpointAddress;
+ priv->bulk_in_sz = usb_endpoint_maxp(endpoint);
+ }
+ }
+
+ priv->index = 1;
+ priv->intf = intf;
+
+ mutex_init(&priv->io_mutex);
+ usb_set_intfdata(intf, priv);
+
+ priv->bulk_in_buf = devm_kmalloc(dev, priv->bulk_in_sz,
+ GFP_KERNEL | GFP_DMA32);
+ if (!priv->bulk_in_buf)
+ return -ENOMEM;
+
+ priv->udev = usb_get_dev(interface_to_usbdev(intf));
+
+ ret = mfd_add_hotplug_devices(dev, ftdi_cells, ARRAY_SIZE(ftdi_cells));
+ if (ret) {
+ usb_put_dev(priv->udev);
+ dev_err(dev, "failed to add mfd devices\n");
+ }
+
+ return ret;
+}
+
+static void ftdi_mfd_disconnect(struct usb_interface *intf)
+{
+ struct ftdi_mfd_priv *priv = usb_get_intfdata(intf);
+
+ mutex_lock(&priv->io_mutex);
+ priv->intf = NULL;
+ mutex_unlock(&priv->io_mutex);
+
+ mfd_remove_devices(&intf->dev);
+ usb_set_intfdata(intf, NULL);
+ usb_put_dev(priv->udev);
+}
+
+static struct usb_device_id ftdi_mfd_table[] = {
+ { USB_DEVICE(0x0403, 0x6014) },
+ {}
+};
+MODULE_DEVICE_TABLE(usb, ftdi_mfd_table);
+
+static struct usb_driver ftdi_mfd_driver = {
+ .name = "ftdi-mfd",
+ .id_table = ftdi_mfd_table,
+ .probe = ftdi_mfd_probe,
+ .disconnect = ftdi_mfd_disconnect,
+};
+
+module_usb_driver(ftdi_mfd_driver);
+
+MODULE_ALIAS("ftdi-mfd");
+MODULE_AUTHOR("Anatolij Gustschin <[email protected]>");
+MODULE_DESCRIPTION("FTDI FT232H MFD core driver");
+MODULE_LICENSE("GPL v2");
diff --git a/include/linux/mfd/ftdi/ftdi.h b/include/linux/mfd/ftdi/ftdi.h
new file mode 100644
index 0000000..0fc9317
--- /dev/null
+++ b/include/linux/mfd/ftdi/ftdi.h
@@ -0,0 +1,71 @@
+/*
+ * Common definitions for FTDI FT232H device
+ *
+ * Copyright (C) 2017 DENX Software Engineering
+ * Anatolij Gustschin <[email protected]>
+ *
+ * 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 MFD_FTDI_H
+#define MFD_FTDI_H
+
+/* Used FTDI USB Requests */
+#define FTDI_SIO_RESET_REQUEST 0x00
+#define FTDI_SIO_SET_BAUDRATE_REQUEST 0x03
+#define FTDI_SIO_SET_BITMODE_REQUEST 0x0B
+#define FTDI_SIO_READ_PINS_REQUEST 0x0C
+#define FTDI_SIO_READ_EEPROM_REQUEST 0x90
+
+/* For EEPROM I/O mode */
+#define FTDI_MAX_EEPROM_SIZE 256
+#define FTDI_232H_CBUS_IOMODE 0x08
+
+#define FTDI_USB_READ_TIMEOUT 5000
+#define FTDI_USB_WRITE_TIMEOUT 5000
+
+/* MPSSE bitbang modes */
+enum ftdi_mpsse_mode {
+ BITMODE_RESET = 0x00, /* switch off bitbang mode */
+ BITMODE_BITBANG = 0x01, /* asynchronous bitbang mode */
+ BITMODE_MPSSE = 0x02, /* MPSSE mode, on 2232x chips */
+ BITMODE_SYNCBB = 0x04, /* synchronous bitbang mode */
+ BITMODE_MCU = 0x08, /* MCU Host Bus Emulation mode */
+ /* CPU-style fifo mode gets set via EEPROM */
+ BITMODE_OPTO = 0x10, /* Fast Opto-Isolated Serial Interface Mode */
+ BITMODE_CBUS = 0x20, /* Bitbang on CBUS pins, EEPROM config needed */
+ BITMODE_SYNCFF = 0x40, /* Single Channel Synchronous FIFO mode */
+ BITMODE_FT1284 = 0x80, /* FT1284 mode, available on 232H chips */
+};
+
+struct ctrl_desc {
+ bool dir_out;
+ u8 request;
+ u8 requesttype;
+ u16 value;
+ u16 index;
+ void *data;
+ u16 size;
+ int timeout;
+};
+
+struct bulk_desc {
+ bool dir_out;
+ void *data;
+ int len;
+ int act_len;
+ int timeout;
+};
+
+int ftdi_ctrl_xfer(struct platform_device *pdev, struct ctrl_desc *desc);
+int ftdi_bulk_xfer(struct platform_device *pdev, struct bulk_desc *desc);
+int ftdi_read_data(struct platform_device *pdev, void *buf, size_t len);
+int ftdi_write_data(struct platform_device *pdev, const char *buf, size_t len);
+int ftdi_set_baudrate(struct platform_device *pdev, int baudrate);
+int ftdi_set_bitmode(struct platform_device *pdev, unsigned char bitmask,
+ unsigned char mode);
+int ftdi_disable_bitbang(struct platform_device *pdev);
+
+#endif /* MFD_FTDI_H */
--
2.7.4

2017-07-06 20:49:34

by Anatolij Gustschin

[permalink] [raw]
Subject: [PATCH 3/3] fpga manager: Add FT232H driver for Altera FPP

Add FPGA manager driver for loading Altera FPGAs via fast
passive parallel (FPP) interface using FTDI FT232H chip.

Signed-off-by: Anatolij Gustschin <[email protected]>
---
drivers/fpga/Kconfig | 7 +
drivers/fpga/Makefile | 1 +
drivers/fpga/ftdi-fifo-fpp.c | 569 +++++++++++++++++++++++++++++++++++++++++++
3 files changed, 577 insertions(+)
create mode 100644 drivers/fpga/ftdi-fifo-fpp.c

diff --git a/drivers/fpga/Kconfig b/drivers/fpga/Kconfig
index ad5448f..3ccc7a8 100644
--- a/drivers/fpga/Kconfig
+++ b/drivers/fpga/Kconfig
@@ -38,6 +38,13 @@ config FPGA_MGR_ALTERA_PS_SPI
FPGA manager driver support for Altera Arria/Cyclone/Stratix
using the passive serial interface over SPI.

+config FPGA_MGR_FTDI_FIFO_FPP
+ tristate "Altera FPP over FT232H FIFO"
+ depends on MFD_FTDI_FT232H
+ help
+ FPGA manager driver support for Altera fast passive parallel
+ interface (FPP) over FT232H FT245 FIFO.
+
config FPGA_MGR_SOCFPGA
tristate "Altera SOCFPGA FPGA Manager"
depends on ARCH_SOCFPGA || COMPILE_TEST
diff --git a/drivers/fpga/Makefile b/drivers/fpga/Makefile
index e09895f..66821c2 100644
--- a/drivers/fpga/Makefile
+++ b/drivers/fpga/Makefile
@@ -8,6 +8,7 @@ obj-$(CONFIG_FPGA) += fpga-mgr.o
# FPGA Manager Drivers
obj-$(CONFIG_FPGA_MGR_ALTERA_CVP) += altera-cvp.o
obj-$(CONFIG_FPGA_MGR_ALTERA_PS_SPI) += altera-ps-spi.o
+obj-$(CONFIG_FPGA_MGR_FTDI_FIFO_FPP) += ftdi-fifo-fpp.o
obj-$(CONFIG_FPGA_MGR_ICE40_SPI) += ice40-spi.o
obj-$(CONFIG_FPGA_MGR_SOCFPGA) += socfpga.o
obj-$(CONFIG_FPGA_MGR_SOCFPGA_A10) += socfpga-a10.o
diff --git a/drivers/fpga/ftdi-fifo-fpp.c b/drivers/fpga/ftdi-fifo-fpp.c
new file mode 100644
index 0000000..3981390
--- /dev/null
+++ b/drivers/fpga/ftdi-fifo-fpp.c
@@ -0,0 +1,569 @@
+/*
+ * Altera FPGA firmware upload via FPP using FT232H Bitbang/FT245-FIFO.
+ *
+ * Copyright (C) 2017 DENX Software Engineering
+ * Anatolij Gustschin <[email protected]>
+ *
+ * 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/bitops.h>
+#include <linux/delay.h>
+#include <linux/fpga/fpga-mgr.h>
+#include <linux/module.h>
+#include <linux/kernel.h>
+#include <linux/sizes.h>
+#include <linux/slab.h>
+#include <linux/gpio.h>
+#include <linux/gpio/driver.h>
+#include <linux/gpio/consumer.h>
+#include <linux/gpio/machine.h>
+#include <linux/platform_device.h>
+#include <linux/mfd/ftdi/ftdi.h>
+#include <linux/usb.h>
+
+#define BULK_OUT_BUF_SZ SZ_256K
+#define MAX_RETRIES 10
+
+/*
+ * With logic of CPLD we can write the state of nConfig pin and
+ * read back the state of some pins (conf_done, init_done, nStatus).
+ * Status header and bit assignment in data register on CPLD.
+ */
+#define INPUT_HEADER_0 0xA5
+#define INPUT_HEADER_1 0x5A
+#define IN_CONF_DONE BIT(0)
+#define IN_INIT_DONE BIT(1)
+#define OUT_NCONFIG BIT(0)
+#define OUT_RESET_N BIT(1)
+
+struct fpp_mgr_ops {
+ int (*write_init)(struct fpga_manager *mgr,
+ struct fpga_image_info *info,
+ const char *buf, size_t count);
+ int (*write)(struct fpga_manager *mgr, const char *buf, size_t count);
+ int (*write_complete)(struct fpga_manager *mgr,
+ struct fpga_image_info *info);
+};
+
+struct fpp_fpga_mgr_priv {
+ struct platform_device *pdev;
+ struct fpga_manager *mgr;
+ struct fpp_mgr_ops *ops;
+ struct gpio_chip *gpiochip;
+ struct gpiod_lookup_table *lookup;
+ struct gpio_desc *nconfig;
+ struct gpio_desc *conf_done;
+ char cfg_mode[8];
+ u8 out_data_port;
+ int index;
+ void *bulk_buf;
+ char usb_dev_id[32];
+ char fpga_mgr_name[64];
+};
+
+static int fpp_fpga_mgr_set_data_port(struct fpp_fpga_mgr_priv *priv,
+ u8 bitmask, u8 value)
+{
+ struct device *dev = &priv->pdev->dev;
+ struct bulk_desc desc;
+ u8 *data;
+ int ret;
+
+ /*
+ * With CPLD connected (in FT245 FIFO mode) we use ACBUS8&9
+ * pins to switch between data and command mode:
+ * ACBUS8&9 == 0, 0 --> normal mode (data communication)
+ * ACBUS8&9 == 1, 0 --> command mode
+ */
+ gpiod_set_raw_value_cansleep(priv->nconfig, 1);
+ gpiod_set_raw_value_cansleep(priv->conf_done, 0);
+ msleep(50);
+
+ /* Write commands to CPLD */
+ ret = ftdi_set_bitmode(priv->pdev, 0x00, BITMODE_SYNCFF);
+ if (ret)
+ return ret;
+
+ if (value)
+ priv->out_data_port |= bitmask;
+ else
+ priv->out_data_port &= ~bitmask;
+
+ data = priv->bulk_buf;
+ *data = priv->out_data_port;
+
+ desc.dir_out = true;
+ desc.act_len = 0;
+ desc.len = 1;
+ desc.data = data;
+ desc.timeout = FTDI_USB_WRITE_TIMEOUT;
+
+ ret = ftdi_bulk_xfer(priv->pdev, &desc);
+ if (ret) {
+ dev_err(dev, "Writing in SYNCFF mode failed: %d\n", ret);
+ return ret;
+ }
+
+ msleep(50);
+ /* Switch back to data mode with ACBUS8&9 back to low */
+ gpiod_set_raw_value_cansleep(priv->nconfig, 0);
+ gpiod_set_raw_value_cansleep(priv->conf_done, 0);
+ msleep(50);
+
+ return 0;
+}
+
+static int fpp_fpga_mgr_bitbang_write_init(struct fpga_manager *mgr,
+ struct fpga_image_info *info,
+ const char *buf, size_t count)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+ struct device *dev = &priv->pdev->dev;
+ int retries = MAX_RETRIES;
+ int ret;
+
+ gpiod_set_value_cansleep(priv->nconfig, 0);
+ msleep(50);
+ gpiod_set_value_cansleep(priv->nconfig, 1);
+ msleep(50);
+ gpiod_set_value_cansleep(priv->nconfig, 0);
+
+ /* Wait for CONF_DONE to get low */
+ do {
+ msleep(50);
+
+ ret = gpiod_get_value_cansleep(priv->conf_done);
+ if (ret < 0) {
+ dev_err(dev, "Failed to get CONF_DONE pin: %d\n", ret);
+ return ret;
+ }
+
+ if (!ret)
+ break;
+ } while (--retries > 0);
+
+ if (!retries) {
+ dev_warn(dev, "CONF_DONE low wait timeout\n");
+ return -ETIMEDOUT;
+ }
+
+ ret = ftdi_set_bitmode(priv->pdev, 0xff, BITMODE_BITBANG);
+ if (ret < 0)
+ return ret;
+
+ /* Set max. working baud rate (for hardware without CPLD) */
+ return ftdi_set_baudrate(priv->pdev, 700000);
+}
+
+static int fpp_fpga_mgr_bitbang_write(struct fpga_manager *mgr,
+ const char *buf, size_t count)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+ struct bulk_desc desc;
+ size_t blk_sz;
+ int ret;
+
+ desc.data = priv->bulk_buf;
+ desc.dir_out = true;
+ desc.timeout = FTDI_USB_WRITE_TIMEOUT;
+
+ while (count) {
+ blk_sz = min_t(size_t, count, BULK_OUT_BUF_SZ);
+ memcpy(priv->bulk_buf, buf, blk_sz);
+ desc.act_len = 0;
+ desc.len = blk_sz;
+ ret = ftdi_bulk_xfer(priv->pdev, &desc);
+ if (ret < 0)
+ return ret;
+
+ buf += desc.act_len;
+ count -= desc.act_len;
+ }
+
+ return 0;
+}
+
+static int fpp_fpga_mgr_bitbang_write_complete(struct fpga_manager *mgr,
+ struct fpga_image_info *info)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+ struct device *dev = &priv->pdev->dev;
+ int retries = MAX_RETRIES;
+ int ret;
+
+ /* Wait for CONF_DONE to get high */
+ do {
+ msleep(50);
+
+ ret = gpiod_get_value_cansleep(priv->conf_done);
+ if (ret < 0)
+ return ret;
+
+ if (ret)
+ break;
+ } while (--retries > 0);
+
+ if (!retries) {
+ dev_warn(dev, "CONF_DONE wait timeout\n");
+ return -ETIMEDOUT;
+ }
+
+ ftdi_disable_bitbang(priv->pdev);
+
+ return 0;
+}
+
+static inline bool status_hdr_is_valid(u8 *buf)
+{
+ return buf[0] == INPUT_HEADER_0 && buf[1] == INPUT_HEADER_1;
+}
+
+static int fpp_fpga_mgr_ft245_fifo_write_init(struct fpga_manager *mgr,
+ struct fpga_image_info *info,
+ const char *buf, size_t count)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+ struct device *dev = &priv->pdev->dev;
+ u8 *inbuf = priv->bulk_buf;
+ int retries = MAX_RETRIES;
+ int ret;
+
+ gpiod_direction_output_raw(priv->conf_done, 0);
+
+ /* Set/reset nConfig via commands to CPLD */
+ ret = fpp_fpga_mgr_set_data_port(priv, OUT_NCONFIG, 1);
+ if (ret)
+ return ret;
+ ret = fpp_fpga_mgr_set_data_port(priv, OUT_NCONFIG, 0);
+ if (ret)
+ return ret;
+ ret = fpp_fpga_mgr_set_data_port(priv, OUT_NCONFIG, 1);
+ if (ret)
+ return ret;
+
+ /* In FT245 FIFO mode we need sync FIFO mode to talk to FPGA */
+ ret = ftdi_set_bitmode(priv->pdev, 0xff, BITMODE_SYNCFF);
+ if (ret)
+ return ret;
+
+ /* Wait until FPGA is ready for loading (conf_done zero) or timeout */
+ do {
+ ret = ftdi_read_data(priv->pdev, inbuf, 64);
+ if (ret < 0) {
+ dev_err(dev, "Can't read status data: %d\n", ret);
+ return ret;
+ }
+
+ /* Check input buffer header and conf_done status */
+ if (status_hdr_is_valid(inbuf) &&
+ (inbuf[2] & IN_CONF_DONE) == 0)
+ break;
+
+ msleep(100); /* CPLD sends status every 100ms */
+ } while (--retries > 0);
+
+ if (!retries) {
+ dev_warn(dev, "CONF_DONE wait timeout\n");
+ return -ETIMEDOUT;
+ }
+
+ /* Configure for max. baud rate (3MHz * 4 in bitbang mode) */
+ return ftdi_set_baudrate(priv->pdev, 3000000);
+}
+
+static int fpp_fpga_mgr_ft245_fifo_write(struct fpga_manager *mgr,
+ const char *buf, size_t count)
+{
+ return fpp_fpga_mgr_bitbang_write(mgr, buf, count);
+}
+
+static int fpp_fpga_mgr_ft245_fifo_write_complete(struct fpga_manager *mgr,
+ struct fpga_image_info *info)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+ struct device *dev = &priv->pdev->dev;
+ u8 *inbuf = priv->bulk_buf;
+ int retries = MAX_RETRIES;
+ int ret;
+ u8 mask;
+
+ mask = IN_CONF_DONE | IN_INIT_DONE;
+
+ do {
+ ret = ftdi_read_data(priv->pdev, inbuf, 64);
+ if (ret < 0) {
+ dev_err(dev, "Can't read status data: %d\n", ret);
+ return ret;
+ }
+
+ if (status_hdr_is_valid(inbuf) && (inbuf[2] & mask) == mask)
+ break;
+
+ msleep(100);
+ } while (--retries > 0);
+
+ if (!retries) {
+ dev_warn(dev, "INIT_DONE wait timeout\n");
+ return -ETIMEDOUT;
+ }
+
+ /* Release Reset_n, keep nCONFIG high, too! */
+ return fpp_fpga_mgr_set_data_port(priv, OUT_NCONFIG | OUT_RESET_N, 1);
+}
+
+static enum fpga_mgr_states fpp_fpga_mgr_state(struct fpga_manager *mgr)
+{
+ return FPGA_MGR_STATE_UNKNOWN;
+}
+
+static int fpp_fpga_mgr_write_init(struct fpga_manager *mgr,
+ struct fpga_image_info *info,
+ const char *buf, size_t count)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+
+ if (info && info->flags & FPGA_MGR_PARTIAL_RECONFIG) {
+ dev_err(&mgr->dev, "Partial reconfiguration not supported.\n");
+ return -EINVAL;
+ }
+
+ if (priv->ops->write_init)
+ return priv->ops->write_init(mgr, info, buf, count);
+
+ return -ENODEV;
+}
+
+static int fpp_fpga_mgr_write(struct fpga_manager *mgr, const char *buf,
+ size_t count)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+
+ if (priv->ops->write)
+ return priv->ops->write(mgr, buf, count);
+
+ return -ENODEV;
+}
+
+static int fpp_fpga_mgr_write_complete(struct fpga_manager *mgr,
+ struct fpga_image_info *info)
+{
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+
+ if (priv->ops->write_complete)
+ return priv->ops->write_complete(mgr, info);
+
+ return -ENODEV;
+}
+
+static struct fpp_mgr_ops fpp_mgr_bitbang_ops = {
+ .write_init = fpp_fpga_mgr_bitbang_write_init,
+ .write = fpp_fpga_mgr_bitbang_write,
+ .write_complete = fpp_fpga_mgr_bitbang_write_complete,
+};
+
+static struct fpp_mgr_ops fpp_mgr_ft245_fifo_ops = {
+ .write_init = fpp_fpga_mgr_ft245_fifo_write_init,
+ .write = fpp_fpga_mgr_ft245_fifo_write,
+ .write_complete = fpp_fpga_mgr_ft245_fifo_write_complete,
+};
+
+static const struct fpga_manager_ops fpp_fpga_mgr_ops = {
+ .state = fpp_fpga_mgr_state,
+ .write_init = fpp_fpga_mgr_write_init,
+ .write = fpp_fpga_mgr_write,
+ .write_complete = fpp_fpga_mgr_write_complete,
+};
+
+static ssize_t show_cfg_mode(struct device *dev, struct device_attribute *attr,
+ char *buf)
+{
+ struct platform_device *pdev = to_platform_device(dev);
+ struct fpga_manager *mgr = platform_get_drvdata(pdev);
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+
+ return snprintf(buf, PAGE_SIZE, "%s\n", priv->cfg_mode);
+}
+
+static ssize_t store_cfg_mode(struct device *dev, struct device_attribute *attr,
+ const char *buf, size_t count)
+{
+ struct platform_device *pdev = to_platform_device(dev);
+ struct fpga_manager *mgr = platform_get_drvdata(pdev);
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+
+ if (!count || count > sizeof(priv->cfg_mode))
+ return -EINVAL;
+
+ if (!strncmp(buf, "fifo", 4)) {
+ strncpy(priv->cfg_mode, buf, sizeof(priv->cfg_mode));
+ priv->cfg_mode[4] = 0;
+ priv->ops = &fpp_mgr_ft245_fifo_ops;
+ gpiod_direction_output_raw(priv->conf_done, 0);
+ } else if (!strncmp(buf, "bitbang", 7)) {
+ strncpy(priv->cfg_mode, buf, sizeof(priv->cfg_mode));
+ priv->cfg_mode[7] = 0;
+ priv->ops = &fpp_mgr_bitbang_ops;
+ gpiod_direction_input(priv->conf_done);
+ } else {
+ return -EINVAL;
+ }
+
+ return count;
+}
+
+static DEVICE_ATTR(cfg_mode, 0664, show_cfg_mode, store_cfg_mode);
+
+static int gpiochip_match_mfd_parent(struct gpio_chip *chip, void *data)
+{
+ struct device *gpiodev = chip->parent;
+ struct device *dev = data;
+
+ if (gpiodev->parent == dev)
+ return 1;
+ return 0;
+}
+
+static struct gpio_chip *find_gpiochip_by_parent(struct device *dev)
+{
+ return gpiochip_find((void *)dev, gpiochip_match_mfd_parent);
+}
+
+static int fpp_fpga_mgr_probe(struct platform_device *pdev)
+{
+ struct device *dev = &pdev->dev;
+ struct fpp_fpga_mgr_priv *priv;
+ struct gpiod_lookup_table *lookup;
+ int lookup_size, ret;
+ unsigned int i, gpios = 0;
+
+ priv = devm_kzalloc(dev, sizeof(*priv), GFP_KERNEL);
+ if (!priv)
+ return -ENOMEM;
+
+ ret = sscanf(dev_name(dev->parent), "%s", priv->usb_dev_id);
+ if (ret != 1) {
+ dev_err(dev, "Can't get parent device name: %d\n", ret);
+ return -ENODEV;
+ }
+
+ /* Use unique USB bus/port in FPGA manager name */
+ snprintf(priv->fpga_mgr_name, sizeof(priv->fpga_mgr_name),
+ "ftdi-fpp-fpga-mgr %s", priv->usb_dev_id);
+
+ priv->gpiochip = find_gpiochip_by_parent(dev->parent);
+ if (!priv->gpiochip) {
+ dev_err(dev, "Defer probing FTDI CBUS gpiochip\n");
+ return -EPROBE_DEFER;
+ }
+
+ lookup_size = sizeof(*lookup) + 2 * sizeof(struct gpiod_lookup);
+ lookup = devm_kzalloc(dev, lookup_size, GFP_KERNEL);
+ if (!lookup)
+ return -ENOMEM;
+
+ lookup->dev_id = devm_kstrdup(dev, dev_name(dev), GFP_KERNEL);
+ if (!lookup->dev_id)
+ return -ENOMEM;
+
+ /* Does GPIO controller provide needed ACBUS8 and ACBUS9 pins? */
+ for (i = 0; i < priv->gpiochip->ngpio; i++) {
+ if (!priv->gpiochip->names[i])
+ continue;
+ if (!strncmp(priv->gpiochip->names[i], "ACBUS8", 6)) {
+ lookup->table[0].chip_hwnum = i;
+ gpios++;
+ }
+ if (!strncmp(priv->gpiochip->names[i], "ACBUS9", 6)) {
+ lookup->table[1].chip_hwnum = i;
+ gpios++;
+ }
+ }
+
+ if (gpios < 2) {
+ dev_err(dev, "Missing control GPIOs\n");
+ return -ENODEV;
+ }
+
+ lookup->table[0].chip_label = priv->gpiochip->label;
+ lookup->table[0].con_id = "nconfig";
+ lookup->table[0].flags = GPIO_ACTIVE_LOW;
+ lookup->table[1].chip_label = priv->gpiochip->label;
+ lookup->table[1].con_id = "conf_done";
+ lookup->table[1].flags = GPIO_ACTIVE_HIGH;
+
+ priv->lookup = lookup;
+ gpiod_add_lookup_table(priv->lookup);
+
+ priv->pdev = pdev;
+ priv->ops = &fpp_mgr_ft245_fifo_ops;
+ strncpy(priv->cfg_mode, "fifo", sizeof(priv->cfg_mode));
+
+ priv->nconfig = gpiod_get(dev, "nconfig", GPIOD_OUT_HIGH);
+ if (IS_ERR(priv->nconfig)) {
+ ret = PTR_ERR(priv->nconfig);
+ dev_err(dev, "Failed to get nconfig gpio: %d\n", ret);
+ goto err_cfg0;
+ }
+
+ priv->conf_done = gpiod_get(dev, "conf_done", GPIOD_OUT_LOW);
+ if (IS_ERR(priv->conf_done)) {
+ ret = PTR_ERR(priv->conf_done);
+ dev_err(dev, "Failed to get conf_done gpio: %d\n", ret);
+ goto err_cfg1;
+ }
+
+ priv->bulk_buf = devm_kmalloc(dev, BULK_OUT_BUF_SZ,
+ GFP_KERNEL | GFP_DMA32);
+ if (!priv->bulk_buf) {
+ ret = -ENOMEM;
+ goto err_cfg2;
+ }
+
+ ret = fpga_mgr_register(dev, priv->fpga_mgr_name,
+ &fpp_fpga_mgr_ops, priv);
+ if (ret)
+ goto err_cfg2;
+
+ ret = device_create_file(dev, &dev_attr_cfg_mode);
+ if (ret)
+ dev_warn(dev, "Can't create cfg_mode interface %d\n", ret);
+
+ return 0;
+
+err_cfg2:
+ gpiod_put(priv->conf_done);
+err_cfg1:
+ gpiod_put(priv->nconfig);
+err_cfg0:
+ gpiod_remove_lookup_table(priv->lookup);
+ return ret;
+}
+
+static int fpp_fpga_mgr_remove(struct platform_device *pdev)
+{
+ struct fpga_manager *mgr = platform_get_drvdata(pdev);
+ struct fpp_fpga_mgr_priv *priv = mgr->priv;
+
+ device_remove_file(&pdev->dev, &dev_attr_cfg_mode);
+ fpga_mgr_unregister(&pdev->dev);
+ gpiod_put(priv->conf_done);
+ gpiod_put(priv->nconfig);
+ gpiod_remove_lookup_table(priv->lookup);
+ return 0;
+}
+
+static struct platform_driver fpp_fpga_mgr_driver = {
+ .driver.name = "ftdi-fifo-fpp-mgr",
+ .probe = fpp_fpga_mgr_probe,
+ .remove = fpp_fpga_mgr_remove,
+};
+
+module_platform_driver(fpp_fpga_mgr_driver);
+
+MODULE_ALIAS("platform:ftdi-fifo-fpp-mgr");
+MODULE_AUTHOR("Anatolij Gustschin <[email protected]>");
+MODULE_DESCRIPTION("FT232H Bitbang/FT245-FIFO FPP FPGA Manager Driver");
+MODULE_LICENSE("GPL v2");
--
2.7.4

2017-07-06 20:49:36

by Anatolij Gustschin

[permalink] [raw]
Subject: [PATCH 2/3] gpio: Add FT232H CBUS GPIO driver

Add driver for CBUS pins on FT232H. The driver supports setting
GPIO direction and getting/setting CBUS 0-3 pin value. The CBUS
pins have to be enabled by configuring I/O mode in the FTDI EEPROM.

Signed-off-by: Anatolij Gustschin <[email protected]>
---
drivers/gpio/Kconfig | 11 ++
drivers/gpio/Makefile | 1 +
drivers/gpio/gpio-ftdi-cbus.c | 251 ++++++++++++++++++++++++++++++++++++++++++
3 files changed, 263 insertions(+)
create mode 100644 drivers/gpio/gpio-ftdi-cbus.c

diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index f235eae..cca784a 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -929,6 +929,17 @@ config HTC_EGPIO
several HTC phones. It provides basic support for input
pins, output pins, and irqs.

+config GPIO_FTDI_CBUS
+ tristate "Support for CBUS GPIO pins on FTDI FT232H"
+ depends on MFD_FTDI_FT232H
+ select GPIO_GENERIC
+ help
+ This driver provides basic support for up to four CBUS GPIOs
+ on FT232H. It allows to configure CBUS pins as input or output
+ and to read and write CBUS pin state. You need to enable I/O-mode
+ for ACBUS 5/6/8/9 pins in FTDI EEPROM first. I/O-mode disabled GPIOs
+ will not be used in the driver.
+
config GPIO_JANZ_TTL
tristate "Janz VMOD-TTL Digital IO Module"
depends on MFD_JANZ_CMODIO
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index a9fda6c..c2ab813 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -49,6 +49,7 @@ obj-$(CONFIG_GPIO_EP93XX) += gpio-ep93xx.o
obj-$(CONFIG_GPIO_ETRAXFS) += gpio-etraxfs.o
obj-$(CONFIG_GPIO_EXAR) += gpio-exar.o
obj-$(CONFIG_GPIO_F7188X) += gpio-f7188x.o
+obj-$(CONFIG_GPIO_FTDI_CBUS) += gpio-ftdi-cbus.o
obj-$(CONFIG_GPIO_FTGPIO010) += gpio-ftgpio010.o
obj-$(CONFIG_GPIO_GE_FPGA) += gpio-ge.o
obj-$(CONFIG_GPIO_GPIO_MM) += gpio-gpio-mm.o
diff --git a/drivers/gpio/gpio-ftdi-cbus.c b/drivers/gpio/gpio-ftdi-cbus.c
new file mode 100644
index 0000000..b0adfe3
--- /dev/null
+++ b/drivers/gpio/gpio-ftdi-cbus.c
@@ -0,0 +1,251 @@
+/*
+ * FTDI FT232H CBUS GPIO driver
+ *
+ * Copyright (C) 2017 DENX Software Engineering
+ * Anatolij Gustschin <[email protected]>
+ *
+ * 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/bitops.h>
+#include <linux/device.h>
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/gpio.h>
+#include <linux/gpio/driver.h>
+#include <linux/platform_device.h>
+#include <linux/slab.h>
+#include <linux/types.h>
+#include <linux/usb.h>
+#include <linux/mfd/ftdi/ftdi.h>
+
+struct ftdi_cbus_gpio {
+ struct platform_device *pdev;
+ struct gpio_chip gpio;
+ const char *gpio_names[4];
+ u8 cbus_pin_offsets[4];
+ u8 cbus_mask;
+ u8 pinbuf[4];
+ u8 eeprom[FTDI_MAX_EEPROM_SIZE];
+};
+
+static const char *ftdi_acbus_names[5] = {
+ "ACBUS5", "ACBUS6", NULL, "ACBUS8", "ACBUS9"
+};
+
+static int ftdi_cbus_gpio_read_pins(struct ftdi_cbus_gpio *priv,
+ unsigned char *pins)
+{
+ struct gpio_chip *chip = &priv->gpio;
+ struct ctrl_desc desc;
+ int ret;
+
+ desc.dir_out = false;
+ desc.request = FTDI_SIO_READ_PINS_REQUEST;
+ desc.requesttype = USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_DIR_IN;
+ desc.value = 0;
+ desc.index = 1;
+ desc.data = &priv->pinbuf[0];
+ desc.size = 1;
+ desc.timeout = USB_CTRL_GET_TIMEOUT;
+
+ ret = ftdi_ctrl_xfer(priv->pdev, &desc);
+ if (ret < 0) {
+ dev_dbg(chip->parent, "failed to get pin values: %d\n", ret);
+ return ret;
+ }
+
+ *pins = priv->pinbuf[0];
+ return 0;
+}
+
+static inline void ftdi_cbus_init_gpio_data(struct ftdi_cbus_gpio *priv,
+ int gpio_num, int cbus_num)
+{
+ switch (cbus_num) {
+ case 5:
+ case 6:
+ priv->cbus_pin_offsets[gpio_num] = cbus_num - 5;
+ break;
+ case 8:
+ case 9:
+ priv->cbus_pin_offsets[gpio_num] = cbus_num - 6;
+ break;
+ default:
+ return;
+ }
+
+ priv->gpio_names[gpio_num] = ftdi_acbus_names[cbus_num - 5];
+}
+
+static int ftdi_read_eeprom(struct ftdi_cbus_gpio *priv)
+{
+ struct ctrl_desc desc;
+ unsigned int i;
+ int ret;
+
+ desc.dir_out = false;
+ desc.request = FTDI_SIO_READ_EEPROM_REQUEST;
+ desc.requesttype = USB_TYPE_VENDOR | USB_RECIP_DEVICE | USB_DIR_IN;
+ desc.value = 0;
+ desc.size = 2;
+ desc.timeout = USB_CTRL_GET_TIMEOUT;
+
+ for (i = 0; i < FTDI_MAX_EEPROM_SIZE / 2; i++) {
+ desc.index = i;
+ desc.data = &priv->eeprom[i * 2];
+
+ ret = ftdi_ctrl_xfer(priv->pdev, &desc);
+ if (ret < 0) {
+ dev_dbg(&priv->pdev->dev, "EEPROM read failed: %d\n",
+ ret);
+ return ret;
+ }
+ }
+
+ print_hex_dump(KERN_DEBUG, "EEPROM: ", DUMP_PREFIX_OFFSET, 16, 1,
+ priv->eeprom, sizeof(priv->eeprom), 1);
+ return 0;
+}
+
+static int ftdi_cbus_gpio_get(struct gpio_chip *chip, unsigned int offset)
+{
+ struct ftdi_cbus_gpio *priv = gpiochip_get_data(chip);
+ unsigned int offs;
+ int ret;
+ u8 pins = 0;
+
+ ret = ftdi_cbus_gpio_read_pins(priv, &pins);
+ if (ret)
+ return ret;
+
+ offs = priv->cbus_pin_offsets[offset];
+
+ return !!(pins & BIT(offs));
+}
+
+static void ftdi_cbus_gpio_set(struct gpio_chip *chip,
+ unsigned int offset, int value)
+{
+ struct ftdi_cbus_gpio *priv = gpiochip_get_data(chip);
+ unsigned int offs;
+ int ret;
+
+ offs = priv->cbus_pin_offsets[offset];
+
+ if (value)
+ priv->cbus_mask |= BIT(offs);
+ else
+ priv->cbus_mask &= ~BIT(offs);
+
+ ret = ftdi_set_bitmode(priv->pdev, priv->cbus_mask, BITMODE_CBUS);
+ if (ret < 0)
+ dev_dbg(chip->parent, "setting pin value failed: %d\n", ret);
+}
+
+static int ftdi_cbus_gpio_direction_input(struct gpio_chip *chip,
+ unsigned int offset)
+{
+ struct ftdi_cbus_gpio *priv = gpiochip_get_data(chip);
+ unsigned int offs;
+
+ offs = priv->cbus_pin_offsets[offset];
+ /* Direction bits are in the upper nibble */
+ priv->cbus_mask &= ~(BIT(offs) << 4);
+
+ return ftdi_set_bitmode(priv->pdev, priv->cbus_mask, BITMODE_CBUS);
+}
+
+static int ftdi_cbus_gpio_direction_output(struct gpio_chip *chip,
+ unsigned int offset, int value)
+{
+ struct ftdi_cbus_gpio *priv = gpiochip_get_data(chip);
+ unsigned int offs;
+
+ offs = priv->cbus_pin_offsets[offset];
+ priv->cbus_mask |= BIT(offs) << 4;
+
+ if (value)
+ priv->cbus_mask |= BIT(offs);
+ else
+ priv->cbus_mask &= ~BIT(offs);
+
+ return ftdi_set_bitmode(priv->pdev, priv->cbus_mask, BITMODE_CBUS);
+}
+
+static int ftdi_cbus_gpio_probe(struct platform_device *pdev)
+{
+ struct device *dev = &pdev->dev;
+ struct ftdi_cbus_gpio *priv;
+ unsigned int i;
+ int ret, ngpio = 0;
+ u8 val;
+
+ priv = devm_kzalloc(&pdev->dev, sizeof(*priv), GFP_KERNEL);
+ if (!priv)
+ return -ENOMEM;
+
+ priv->pdev = pdev;
+ priv->gpio.label = dev_name(&pdev->dev);
+ priv->gpio.parent = dev;
+ priv->gpio.owner = THIS_MODULE;
+ priv->gpio.names = priv->gpio_names;
+ priv->gpio.base = -1;
+ priv->gpio.ngpio = 0; /* will be set if I/O mode enabled in EEPROM */
+ priv->gpio.can_sleep = true;
+ priv->gpio.set = ftdi_cbus_gpio_set;
+ priv->gpio.get = ftdi_cbus_gpio_get;
+ priv->gpio.direction_input = ftdi_cbus_gpio_direction_input;
+ priv->gpio.direction_output = ftdi_cbus_gpio_direction_output;
+
+ ret = ftdi_read_eeprom(priv);
+ if (ret < 0)
+ return ret;
+
+ /* Check if I/O mode is enabled for supported pins 5, 6, 8, 9 */
+ for (i = 5; i < 10; i++) {
+ val = priv->eeprom[0x18 + i / 2] >> (i % 2 ? 4 : 0);
+ if ((val & 0x0f) == FTDI_232H_CBUS_IOMODE) {
+ dev_info(&priv->pdev->dev, "gpio-%d @ ACBUS%d\n",
+ priv->gpio.ngpio++, i);
+ ftdi_cbus_init_gpio_data(priv, ngpio++, i);
+ }
+ }
+
+ if (!priv->gpio.ngpio) {
+ dev_warn(dev, "I/O mode disabled in EEPROM\n");
+ return -ENODEV;
+ }
+
+ platform_set_drvdata(pdev, priv);
+
+ ret = devm_gpiochip_add_data(dev, &priv->gpio, priv);
+ if (ret) {
+ dev_err(dev, "failed to add CBUS gpiochip: %d\n", ret);
+ return ret;
+ }
+
+ dev_info(dev, "using %d CBUS pins\n", priv->gpio.ngpio);
+ return 0;
+}
+
+static int ftdi_cbus_gpio_remove(struct platform_device *pdev)
+{
+ platform_set_drvdata(pdev, NULL);
+ return 0;
+}
+
+static struct platform_driver ftdi_cbus_gpio_driver = {
+ .driver.name = "ftdi-cbus-gpio",
+ .probe = ftdi_cbus_gpio_probe,
+ .remove = ftdi_cbus_gpio_remove,
+};
+
+module_platform_driver(ftdi_cbus_gpio_driver);
+
+MODULE_ALIAS("platform:ftdi-cbus-gpio");
+MODULE_AUTHOR("Anatolij Gustschin <[email protected]");
+MODULE_DESCRIPTION("FT232H CBUS GPIO interface driver");
+MODULE_LICENSE("GPL v2");
--
2.7.4

2017-07-07 07:49:09

by Bjørn Mork

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

[adding Johan on the CC list]

Anatolij Gustschin <[email protected]> writes:

> +static struct usb_device_id ftdi_mfd_table[] = {
> + { USB_DEVICE(0x0403, 0x6014) },
> + {}
> +};
> +MODULE_DEVICE_TABLE(usb, ftdi_mfd_table);

This device ID is currently handled by the ftdi_sio driver, so I believe
you at least have to explain how you intend these two drivers to
cooperate...



Bjørn

2017-07-07 09:34:54

by David Laight

[permalink] [raw]
Subject: RE: [PATCH 3/3] fpga manager: Add FT232H driver for Altera FPP

From: Anatolij Gustschin
> Sent: 06 July 2017 21:49
>
> Add FPGA manager driver for loading Altera FPGAs via fast
> passive parallel (FPP) interface using FTDI FT232H chip.

I can't help feeling this is very specific for a particular card.

While all(?) Altera (now Intel) FPGA support FPP programming
it will require extra on-board logic to interface to anything
external - especially something as generic as the FT232H.

Since this isn't a connector that Altera put on any of their
dev boards (not any I've seen anyway), the board manufacturer
has probably picked their own assignments for the pins.

The only standard interface for programming the FPGA is the
JTAG one - and the data formats for that probably require
reverse engineering (has been done).

David

2017-07-07 09:53:41

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Fri, 07 Jul 2017 09:48:48 +0200
Bjørn Mork [email protected] wrote:

>[adding Johan on the CC list]
>
>Anatolij Gustschin <[email protected]> writes:
>
>> +static struct usb_device_id ftdi_mfd_table[] = {
>> + { USB_DEVICE(0x0403, 0x6014) },
>> + {}
>> +};
>> +MODULE_DEVICE_TABLE(usb, ftdi_mfd_table);
>
>This device ID is currently handled by the ftdi_sio driver, so I believe
>you at least have to explain how you intend these two drivers to
>cooperate...

these drivers cannot cooperate, the different ftdi function modes
use same device pins as in UART mode. So, you either can use the
device in UART interface mode or in some different mode. I do not
load the ftdi_sio module or do unbind the USB device from the
ftdio_sio driver and bind it to the mfd driver, e.g.:

sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi_sio/unbind"
sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi-mfd/bind"

thanks,

Anatolij

2017-07-10 12:34:34

by Johan Hovold

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Fri, Jul 07, 2017 at 11:53:29AM +0200, Anatolij Gustschin wrote:
> On Fri, 07 Jul 2017 09:48:48 +0200
> Bj?rn Mork [email protected] wrote:
>
> >[adding Johan on the CC list]
> >
> >Anatolij Gustschin <[email protected]> writes:
> >
> >> +static struct usb_device_id ftdi_mfd_table[] = {
> >> + { USB_DEVICE(0x0403, 0x6014) },
> >> + {}
> >> +};
> >> +MODULE_DEVICE_TABLE(usb, ftdi_mfd_table);
> >
> >This device ID is currently handled by the ftdi_sio driver, so I believe
> >you at least have to explain how you intend these two drivers to
> >cooperate...
>
> these drivers cannot cooperate, the different ftdi function modes
> use same device pins as in UART mode. So, you either can use the
> device in UART interface mode or in some different mode. I do not
> load the ftdi_sio module or do unbind the USB device from the
> ftdio_sio driver and bind it to the mfd driver, e.g.:
>
> sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi_sio/unbind"
> sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi-mfd/bind"

I'm afraid that's not good enough. If we're going to support a non-UART
mode through a separate driver, we need to have all drivers for these
devices be able to retrieve the current mode during probe and only bind
when the mode matches.

Johan

2017-07-10 12:52:16

by Johan Hovold

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Thu, Jul 06, 2017 at 10:49:16PM +0200, Anatolij Gustschin wrote:
> Add USB part with common functions for USB-GPIO/I2C/SPI master
> adapters. These allow communication with chip's control, transmit
> and receive endpoints and will be used by various FT232H drivers.

> +static const struct mfd_cell ftdi_cells[] = {
> + { .name = "ftdi-cbus-gpio", },
> + { .name = "ftdi-mpsse-i2c", },
> + { .name = "ftdi-mpsse-spi", },
> + { .name = "ftdi-fifo-fpp-mgr", },
> +};

Correct me if I'm wrong, but aren't these modes really mutually
exclusive, possibly with exception of cbus-gpio (some pins are at least
available as GPIOs in MPSSE mode)? Then MFD is not is not the right fit
here either.

And as David Laight already pointed out, your ftdi-fifo-fpp-mgr driver
seems too application specific for a generic chip like this.

Johan

2017-07-11 06:52:44

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Mon, 10 Jul 2017 14:34:27 +0200
Johan Hovold [email protected] wrote:

>On Fri, Jul 07, 2017 at 11:53:29AM +0200, Anatolij Gustschin wrote:
>> On Fri, 07 Jul 2017 09:48:48 +0200
>> Bjørn Mork [email protected] wrote:
>>
>> >[adding Johan on the CC list]
>> >
>> >Anatolij Gustschin <[email protected]> writes:
>> >
>> >> +static struct usb_device_id ftdi_mfd_table[] = {
>> >> + { USB_DEVICE(0x0403, 0x6014) },
>> >> + {}
>> >> +};
>> >> +MODULE_DEVICE_TABLE(usb, ftdi_mfd_table);
>> >
>> >This device ID is currently handled by the ftdi_sio driver, so I believe
>> >you at least have to explain how you intend these two drivers to
>> >cooperate...
>>
>> these drivers cannot cooperate, the different ftdi function modes
>> use same device pins as in UART mode. So, you either can use the
>> device in UART interface mode or in some different mode. I do not
>> load the ftdi_sio module or do unbind the USB device from the
>> ftdio_sio driver and bind it to the mfd driver, e.g.:
>>
>> sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi_sio/unbind"
>> sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi-mfd/bind"
>
>I'm afraid that's not good enough. If we're going to support a non-UART
>mode through a separate driver, we need to have all drivers for these
>devices be able to retrieve the current mode during probe and only bind
>when the mode matches.

Can we reliably retrieve the current mode? For devices with connected
EEPROM some modes (including UART) are configurable in the EEPROM. For
devices without EEPROM the default mode is always UART, but FIFO-,
Bitbang- and MPSSE-mode can be switched via commands to the the chip.

Anatolij

2017-07-12 08:50:09

by Johan Hovold

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Tue, Jul 11, 2017 at 08:52:37AM +0200, Anatolij Gustschin wrote:
> On Mon, 10 Jul 2017 14:34:27 +0200
> Johan Hovold [email protected] wrote:
>
> >On Fri, Jul 07, 2017 at 11:53:29AM +0200, Anatolij Gustschin wrote:
> >> On Fri, 07 Jul 2017 09:48:48 +0200
> >> Bj?rn Mork [email protected] wrote:
> >>
> >> >[adding Johan on the CC list]
> >> >
> >> >Anatolij Gustschin <[email protected]> writes:
> >> >
> >> >> +static struct usb_device_id ftdi_mfd_table[] = {
> >> >> + { USB_DEVICE(0x0403, 0x6014) },
> >> >> + {}
> >> >> +};
> >> >> +MODULE_DEVICE_TABLE(usb, ftdi_mfd_table);
> >> >
> >> >This device ID is currently handled by the ftdi_sio driver, so I believe
> >> >you at least have to explain how you intend these two drivers to
> >> >cooperate...
> >>
> >> these drivers cannot cooperate, the different ftdi function modes
> >> use same device pins as in UART mode. So, you either can use the
> >> device in UART interface mode or in some different mode. I do not
> >> load the ftdi_sio module or do unbind the USB device from the
> >> ftdio_sio driver and bind it to the mfd driver, e.g.:
> >>
> >> sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi_sio/unbind"
> >> sh -c "echo -n "3-2:1.0" > /sys/bus/usb/drivers/ftdi-mfd/bind"
> >
> >I'm afraid that's not good enough. If we're going to support a non-UART
> >mode through a separate driver, we need to have all drivers for these
> >devices be able to retrieve the current mode during probe and only bind
> >when the mode matches.
>
> Can we reliably retrieve the current mode?

You tell me. ;)

> For devices with connected EEPROM some modes (including UART) are
> configurable in the EEPROM. For devices without EEPROM the default
> mode is always UART, but FIFO-, Bitbang- and MPSSE-mode can be
> switched via commands to the the chip.

IIRC we should be able read from the EEPROM, and I would at least expect
there to be a way to retrieve the current mode as well.

Johan

2017-07-12 09:11:58

by Bjørn Mork

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

Johan Hovold <[email protected]> writes:
> On Tue, Jul 11, 2017 at 08:52:37AM +0200, Anatolij Gustschin wrote:
>
>> For devices with connected EEPROM some modes (including UART) are
>> configurable in the EEPROM. For devices without EEPROM the default
>> mode is always UART, but FIFO-, Bitbang- and MPSSE-mode can be
>> switched via commands to the the chip.
>
> IIRC we should be able read from the EEPROM, and I would at least expect
> there to be a way to retrieve the current mode as well.

Stupid question, I know, but I cannot help thinking: If you have an
EEPROM then why the h... don't you use an application specific device
ID?


Bjørn

2017-07-13 16:32:38

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Wed, 12 Jul 2017 10:50:03 +0200
Johan Hovold [email protected] wrote:
...
>IIRC we should be able read from the EEPROM, and I would at least expect
>there to be a way to retrieve the current mode as well.

I've just send a patch for ftdi_sio.

Thanks,

Anatolij

2017-07-19 08:59:30

by Johan Hovold

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Mon, Jul 10, 2017 at 02:52:10PM +0200, Johan Hovold wrote:
> On Thu, Jul 06, 2017 at 10:49:16PM +0200, Anatolij Gustschin wrote:
> > Add USB part with common functions for USB-GPIO/I2C/SPI master
> > adapters. These allow communication with chip's control, transmit
> > and receive endpoints and will be used by various FT232H drivers.
>
> > +static const struct mfd_cell ftdi_cells[] = {
> > + { .name = "ftdi-cbus-gpio", },
> > + { .name = "ftdi-mpsse-i2c", },
> > + { .name = "ftdi-mpsse-spi", },
> > + { .name = "ftdi-fifo-fpp-mgr", },
> > +};
>
> Correct me if I'm wrong, but aren't these modes really mutually
> exclusive, possibly with exception of cbus-gpio (some pins are at least
> available as GPIOs in MPSSE mode)? Then MFD is not is not the right fit
> here either.

You never replied to this, and I'm afraid there are more issue with this
series.

> And as David Laight already pointed out, your ftdi-fifo-fpp-mgr driver
> seems too application specific for a generic chip like this.

Of which this is one is one of the major.

In short, your driver is much to application specific and is probably
something that needs to be implemented in userspace using libftdi.

Speaking of libftdi, you seem to have copied or borrowed a lot of code
and protocol from libftdi and this should have been mentioned in commit
messages and file headers (not just in a comment to one specific
function).

These chips can be used for a many different applications (also in FIFO
mode) so you cannot tie a driver to it exposing just a specific
interface for programming a certain class of FPGAs.

Johan

2017-07-19 11:58:40

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Mon, 10 Jul 2017 14:52:10 +0200
Johan Hovold [email protected] wrote:

>On Thu, Jul 06, 2017 at 10:49:16PM +0200, Anatolij Gustschin wrote:
>> Add USB part with common functions for USB-GPIO/I2C/SPI master
>> adapters. These allow communication with chip's control, transmit
>> and receive endpoints and will be used by various FT232H drivers.
>
>> +static const struct mfd_cell ftdi_cells[] = {
>> + { .name = "ftdi-cbus-gpio", },
>> + { .name = "ftdi-mpsse-i2c", },
>> + { .name = "ftdi-mpsse-spi", },
>> + { .name = "ftdi-fifo-fpp-mgr", },
>> +};
>
>Correct me if I'm wrong, but aren't these modes really mutually
>exclusive, possibly with exception of cbus-gpio (some pins are at least
>available as GPIOs in MPSSE mode)? Then MFD is not is not the right fit
>here either.

MPSSE and FIFO modes are mutually exclusive, but I'm not sure about
MPSSE and CBUS-GPIO. CBUS-GPIO didn't work as expected when I was
testing with MPSSE SPI master driver, but maybe it is a driver issue.
FT245 FIFO and CBUS GPIO can be switched by a control request, when
FIFO mode is configured in the EEPROM.

>And as David Laight already pointed out, your ftdi-fifo-fpp-mgr driver
>seems too application specific for a generic chip like this.

Yes, I agree. I'm thinking of a rework to add a FIFO driver instead
and use it in the fpp-mgr driver. Is that the right direction?

Thanks,
Anatolij

2017-07-19 12:59:08

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Wed, 19 Jul 2017 10:59:34 +0200
Johan Hovold [email protected] wrote:
...
>> > +static const struct mfd_cell ftdi_cells[] = {
>> > + { .name = "ftdi-cbus-gpio", },
>> > + { .name = "ftdi-mpsse-i2c", },
>> > + { .name = "ftdi-mpsse-spi", },
>> > + { .name = "ftdi-fifo-fpp-mgr", },
>> > +};
>>
>> Correct me if I'm wrong, but aren't these modes really mutually
>> exclusive, possibly with exception of cbus-gpio (some pins are at least
>> available as GPIOs in MPSSE mode)? Then MFD is not is not the right fit
>> here either.
>
>You never replied to this, and I'm afraid there are more issue with this
>series.

Sorry, unfortunately I'm too busy with other stuff. Will try to find
time to rework.

>> And as David Laight already pointed out, your ftdi-fifo-fpp-mgr driver
>> seems too application specific for a generic chip like this.
>
>Of which this is one is one of the major.

Thanks all for feedback. I'm still pondering how to interface the
fpga manager driver to FTDI FIFO driver.

>In short, your driver is much to application specific and is probably
>something that needs to be implemented in userspace using libftdi.

I have a requirement to use the fpga manager framework, therefore the
kernel driver is needed. Our usage scenario is a multi stage fpga
configuration process, the first stage is a pre-configuration via
FTDI SPI/FIFO, all subsequent stages are also done by other fpga
manager drivers. libftdi based driver already existed for hardware
bring-up, now I need similar functionality as kernel fpga manager.

>Speaking of libftdi, you seem to have copied or borrowed a lot of code
>and protocol from libftdi and this should have been mentioned in commit
>messages and file headers (not just in a comment to one specific
>function).

I'll mention this in next patch series.

>These chips can be used for a many different applications (also in FIFO
>mode) so you cannot tie a driver to it exposing just a specific
>interface for programming a certain class of FPGAs.

Agreed.

Anatolij

2017-07-19 13:29:51

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Wed, 12 Jul 2017 11:11:46 +0200
Bjørn Mork [email protected] wrote:

>Johan Hovold <[email protected]> writes:
>> On Tue, Jul 11, 2017 at 08:52:37AM +0200, Anatolij Gustschin wrote:
>>
>>> For devices with connected EEPROM some modes (including UART) are
>>> configurable in the EEPROM. For devices without EEPROM the default
>>> mode is always UART, but FIFO-, Bitbang- and MPSSE-mode can be
>>> switched via commands to the the chip.
>>
>> IIRC we should be able read from the EEPROM, and I would at least expect
>> there to be a way to retrieve the current mode as well.
>
>Stupid question, I know, but I cannot help thinking: If you have an
>EEPROM then why the h... don't you use an application specific device
>ID?

It would make sense for adapter devices that you can buy and plug.
In my particular case the configuration device with FTDI chips is
internal part of embedded board, the configuration interface is
never exposed to end users. I doesn't make sense to register an
ID for such hardware.

Thanks,
Anatolij

2017-07-19 13:39:50

by David Laight

[permalink] [raw]
Subject: RE: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

From: Anatolij Gustschin
> Sent: 19 July 2017 14:30
...
> >Stupid question, I know, but I cannot help thinking: If you have an
> >EEPROM then why the h... don't you use an application specific device
> >ID?
>
> It would make sense for adapter devices that you can buy and plug.
> In my particular case the configuration device with FTDI chips is
> internal part of embedded board, the configuration interface is
> never exposed to end users. I doesn't make sense to register an
> ID for such hardware.

Sounds like you should absolutely be registering an ID so that
nothing can try to use it using the default one.

David


2017-07-19 15:04:02

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Wed, 19 Jul 2017 13:39:36 +0000
David Laight [email protected] wrote:

>From: Anatolij Gustschin
>> Sent: 19 July 2017 14:30
>...
>> >Stupid question, I know, but I cannot help thinking: If you have an
>> >EEPROM then why the h... don't you use an application specific device
>> >ID?
>>
>> It would make sense for adapter devices that you can buy and plug.
>> In my particular case the configuration device with FTDI chips is
>> internal part of embedded board, the configuration interface is
>> never exposed to end users. I doesn't make sense to register an
>> ID for such hardware.
>
>Sounds like you should absolutely be registering an ID so that
>nothing can try to use it using the default one.

The intended usage can already be enforced by rejecting not signed
bootloader/kernel/firmware.

Anatolij

2017-07-25 11:49:18

by Johan Hovold

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Wed, Jul 19, 2017 at 01:58:30PM +0200, Anatolij Gustschin wrote:
> On Mon, 10 Jul 2017 14:52:10 +0200
> Johan Hovold [email protected] wrote:
>
> >On Thu, Jul 06, 2017 at 10:49:16PM +0200, Anatolij Gustschin wrote:
> >> Add USB part with common functions for USB-GPIO/I2C/SPI master
> >> adapters. These allow communication with chip's control, transmit
> >> and receive endpoints and will be used by various FT232H drivers.
> >
> >> +static const struct mfd_cell ftdi_cells[] = {
> >> + { .name = "ftdi-cbus-gpio", },
> >> + { .name = "ftdi-mpsse-i2c", },
> >> + { .name = "ftdi-mpsse-spi", },
> >> + { .name = "ftdi-fifo-fpp-mgr", },
> >> +};
> >
> >Correct me if I'm wrong, but aren't these modes really mutually
> >exclusive, possibly with exception of cbus-gpio (some pins are at least
> >available as GPIOs in MPSSE mode)? Then MFD is not is not the right fit
> >here either.
>
> MPSSE and FIFO modes are mutually exclusive, but I'm not sure about
> MPSSE and CBUS-GPIO. CBUS-GPIO didn't work as expected when I was
> testing with MPSSE SPI master driver, but maybe it is a driver issue.

Yes, that wasn't clear to me either from just looking at the data
sheets. MPSSE seems to deal with its GPIOs differently.

> FT245 FIFO and CBUS GPIO can be switched by a control request, when
> FIFO mode is configured in the EEPROM.

Since the set_bitmode command is used to control the CBUS gpios, does
that mean that they cannot be toggled independently while FIFO mode is
in use (as the same command is used to set FIFO mode)?

> >And as David Laight already pointed out, your ftdi-fifo-fpp-mgr driver
> >seems too application specific for a generic chip like this.
>
> Yes, I agree. I'm thinking of a rework to add a FIFO driver instead
> and use it in the fpp-mgr driver. Is that the right direction?

That sounds better, but I'm still not sure that we would be able to bind
it to devices with the default (generic) VID/PID.

Thanks,
Johan

2017-07-25 11:52:44

by Johan Hovold

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Wed, Jul 19, 2017 at 02:59:00PM +0200, Anatolij Gustschin wrote:
> On Wed, 19 Jul 2017 10:59:34 +0200
> Johan Hovold [email protected] wrote:

> >> And as David Laight already pointed out, your ftdi-fifo-fpp-mgr driver
> >> seems too application specific for a generic chip like this.
> >
> >Of which this is one is one of the major.
>
> Thanks all for feedback. I'm still pondering how to interface the
> fpga manager driver to FTDI FIFO driver.
>
> >In short, your driver is much to application specific and is probably
> >something that needs to be implemented in userspace using libftdi.
>
> I have a requirement to use the fpga manager framework, therefore the
> kernel driver is needed. Our usage scenario is a multi stage fpga
> configuration process, the first stage is a pre-configuration via
> FTDI SPI/FIFO, all subsequent stages are also done by other fpga
> manager drivers. libftdi based driver already existed for hardware
> bring-up, now I need similar functionality as kernel fpga manager.

How are you even accessing these fpga-managers from userspace? I thought
current interface was for in-kernel use only?

Thanks,
Johan

2017-07-25 12:14:28

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Tue, 25 Jul 2017 13:52:35 +0200
Johan Hovold [email protected] wrote:

>On Wed, Jul 19, 2017 at 02:59:00PM +0200, Anatolij Gustschin wrote:
>> On Wed, 19 Jul 2017 10:59:34 +0200
>> Johan Hovold [email protected] wrote:
>
>> >> And as David Laight already pointed out, your ftdi-fifo-fpp-mgr driver
>> >> seems too application specific for a generic chip like this.
>> >
>> >Of which this is one is one of the major.
>>
>> Thanks all for feedback. I'm still pondering how to interface the
>> fpga manager driver to FTDI FIFO driver.
>>
>> >In short, your driver is much to application specific and is probably
>> >something that needs to be implemented in userspace using libftdi.
>>
>> I have a requirement to use the fpga manager framework, therefore the
>> kernel driver is needed. Our usage scenario is a multi stage fpga
>> configuration process, the first stage is a pre-configuration via
>> FTDI SPI/FIFO, all subsequent stages are also done by other fpga
>> manager drivers. libftdi based driver already existed for hardware
>> bring-up, now I need similar functionality as kernel fpga manager.
>
>How are you even accessing these fpga-managers from userspace? I thought
>current interface was for in-kernel use only?

We have different possibilities to access to these fpga-managers from
userspace. On platforms with device-tree support there is a DT-Overlay
configfs interface for inserting a blob with configuration data and
fpga device description. After inserting the blob the fpga manager is
invoked automatically. There are also fpga-mgr debugfs config interface
patches in Altera linux-socfpga git tree for accessing from userspace.
I used them for initial testing, but now I'm using additional kernel
module with a single configuration interface for different managers.

Thanks,
Anatolij

2017-07-25 12:34:49

by Anatolij Gustschin

[permalink] [raw]
Subject: Re: [PATCH 1/3] mfd: Add support for FTDI FT232H devices

On Tue, 25 Jul 2017 13:49:08 +0200
Johan Hovold [email protected] wrote:

>On Wed, Jul 19, 2017 at 01:58:30PM +0200, Anatolij Gustschin wrote:
>> On Mon, 10 Jul 2017 14:52:10 +0200
>> Johan Hovold [email protected] wrote:
>>
>> >On Thu, Jul 06, 2017 at 10:49:16PM +0200, Anatolij Gustschin wrote:
>> >> Add USB part with common functions for USB-GPIO/I2C/SPI master
>> >> adapters. These allow communication with chip's control, transmit
>> >> and receive endpoints and will be used by various FT232H drivers.
>> >
>> >> +static const struct mfd_cell ftdi_cells[] = {
>> >> + { .name = "ftdi-cbus-gpio", },
>> >> + { .name = "ftdi-mpsse-i2c", },
>> >> + { .name = "ftdi-mpsse-spi", },
>> >> + { .name = "ftdi-fifo-fpp-mgr", },
>> >> +};
>> >
>> >Correct me if I'm wrong, but aren't these modes really mutually
>> >exclusive, possibly with exception of cbus-gpio (some pins are at least
>> >available as GPIOs in MPSSE mode)? Then MFD is not is not the right fit
>> >here either.
>>
>> MPSSE and FIFO modes are mutually exclusive, but I'm not sure about
>> MPSSE and CBUS-GPIO. CBUS-GPIO didn't work as expected when I was
>> testing with MPSSE SPI master driver, but maybe it is a driver issue.
>
>Yes, that wasn't clear to me either from just looking at the data
>sheets. MPSSE seems to deal with its GPIOs differently.

yes, the GPIOs are at different pins in MPSSE mode and these pins are
controlled via writes/reads to/from bulk endpoint with MPSSE commands.

>> FT245 FIFO and CBUS GPIO can be switched by a control request, when
>> FIFO mode is configured in the EEPROM.
>
>Since the set_bitmode command is used to control the CBUS gpios, does
>that mean that they cannot be toggled independently while FIFO mode is
>in use (as the same command is used to set FIFO mode)?

yes.

Thanks,
Anatolij

2017-08-01 06:49:06

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH 2/3] gpio: Add FT232H CBUS GPIO driver

On Thu, Jul 6, 2017 at 10:49 PM, Anatolij Gustschin <[email protected]> wrote:

> Add driver for CBUS pins on FT232H. The driver supports setting
> GPIO direction and getting/setting CBUS 0-3 pin value. The CBUS
> pins have to be enabled by configuring I/O mode in the FTDI EEPROM.
>
> Signed-off-by: Anatolij Gustschin <[email protected]>
(...)

> + select GPIO_GENERIC

You do not seem to be using this.

> +#include <linux/gpio.h>

This include should not be needed. If it is, something is wrong.

> +#include <linux/gpio/driver.h>

Drivers should only include this.

> +#include <linux/platform_device.h>
> +#include <linux/slab.h>
> +#include <linux/types.h>
> +#include <linux/usb.h>

Why is this needed if the device is abstracted behind an MFD interface?

> +#include <linux/mfd/ftdi/ftdi.h>

I.e. this?

Apart from these small things it looks like a solid and nice driver,
do you plan to merge this into MFD or should I merge it? Since it depends
on the Kconfig symbol I guess I can merge it orthogonally if I am sure
Lee will pick the MFD part.

Yours,
Linus Walleij

2017-08-01 09:24:10

by Johan Hovold

[permalink] [raw]
Subject: Re: [PATCH 2/3] gpio: Add FT232H CBUS GPIO driver

On Tue, Aug 01, 2017 at 08:49:02AM +0200, Linus Walleij wrote:
> On Thu, Jul 6, 2017 at 10:49 PM, Anatolij Gustschin <[email protected]> wrote:
>
> > Add driver for CBUS pins on FT232H. The driver supports setting
> > GPIO direction and getting/setting CBUS 0-3 pin value. The CBUS
> > pins have to be enabled by configuring I/O mode in the FTDI EEPROM.
> >
> > Signed-off-by: Anatolij Gustschin <[email protected]>

> Apart from these small things it looks like a solid and nice driver,
> do you plan to merge this into MFD or should I merge it? Since it depends
> on the Kconfig symbol I guess I can merge it orthogonally if I am sure
> Lee will pick the MFD part.

There are some fundamental problems with this series which prevents it
from being merged. Please take a look at the discussion following patch
1/3.

Thanks,
Johan

2017-08-02 12:39:05

by Eric Schwarz

[permalink] [raw]
Subject: Re: [PATCH 0/3] FPGA Manager support for FPP via FT232H FT245-FIFO

Dear all,

DENX Software Engineering develops and brings this driver to mainline on
behalf of us (ARRI*).

Since there was a lot of discussion around this patch series I would
highly appreciate if someone could sum up what needs to be changed in
detail in order to get this driver into the mainline as I am used it
from the other "line-by-line" reviews. I understood that the approach is
not generic enough - please correct me if I am wrong on that point. We
somehow need a commitment that if we change it to another way that the
whole discussion does not start from scratch.

Many thanks
Eric

* I am just writing from my private e-mail address since Outlook
obviously renders all my mails as HTML despite what I am configuring.

[1]... http://www.arri.com

Am 06.07.2017 22:49, schrieb Anatolij Gustschin:

> This series adds support for fast passive parallel (FPP) Altera
> FPGA configuration using FTDI FT232H chip in FT245-FIFO mode.
> It has been used to configure Arria 10 FPGAs.
>
> Patch 1 adds an FT232H MFD driver with common functions that
> can be used for FT232H USB-GPIO/I2C/SPI master adapter drivers.
> Currently it is used for FT232H GPIO support (in patch 2) and
> for FT245 FIFO transfers in FPP FPGA manager driver in patch 3.
> Driver support for FT232H USB-I2C/SPI master adapters can be
> added later.
>
> Patch 2 adds a simple GPIO driver supporting four FT232H CBUS GPIOs.
>
> Patch 3 adds an FPGA Manager driver for Altera FPP FPGA configuration
> via FT232H FT245-FIFO interface.
>
> Anatolij Gustschin (3):
> mfd: Add support for FTDI FT232H devices
> gpio: Add FT232H CBUS GPIO driver
> fpga manager: Add FT232H driver for Altera FPP
>
> drivers/fpga/Kconfig | 7 +
> drivers/fpga/Makefile | 1 +
> drivers/fpga/ftdi-fifo-fpp.c | 569
> ++++++++++++++++++++++++++++++++++++++++++
> drivers/gpio/Kconfig | 11 +
> drivers/gpio/Makefile | 1 +
> drivers/gpio/gpio-ftdi-cbus.c | 251 +++++++++++++++++++
> drivers/mfd/Kconfig | 9 +
> drivers/mfd/Makefile | 1 +
> drivers/mfd/ftdi-ft232h.c | 470 ++++++++++++++++++++++++++++++++++
> include/linux/mfd/ftdi/ftdi.h | 71 ++++++
> 10 files changed, 1391 insertions(+)
> create mode 100644 drivers/fpga/ftdi-fifo-fpp.c
> create mode 100644 drivers/gpio/gpio-ftdi-cbus.c
> create mode 100644 drivers/mfd/ftdi-ft232h.c
> create mode 100644 include/linux/mfd/ftdi/ftdi.h

2017-08-02 14:17:06

by Alan Tull

[permalink] [raw]
Subject: Re: [PATCH 0/3] FPGA Manager support for FPP via FT232H FT245-FIFO

On Wed, Aug 2, 2017 at 6:36 AM, Eric Schwarz <[email protected]> wrote:
> Dear all,
>
> DENX Software Engineering develops and brings this driver to mainline on
> behalf of us (ARRI*).
>
> Since there was a lot of discussion around this patch series I would highly
> appreciate if someone could sum up what needs to be changed in detail in
> order to get this driver into the mainline as I am used it from the other
> "line-by-line" reviews. I understood that the approach is not generic enough
> - please correct me if I am wrong on that point. We somehow need a
> commitment that if we change it to another way that the whole discussion
> does not start from scratch.
>
> Many thanks
> Eric

Hi Eric,

Patchwork collects all email response to patchsets posted on this
mailing list [1] so that could be helpful for you here.

Alan

[1] https://patchwork.kernel.org/project/linux-fpga/list/?submitter=769


>
> * I am just writing from my private e-mail address since Outlook obviously
> renders all my mails as HTML despite what I am configuring.
>
> [1]... http://www.arri.com
>
> Am 06.07.2017 22:49, schrieb Anatolij Gustschin:
>
>> This series adds support for fast passive parallel (FPP) Altera
>> FPGA configuration using FTDI FT232H chip in FT245-FIFO mode.
>> It has been used to configure Arria 10 FPGAs.
>>
>> Patch 1 adds an FT232H MFD driver with common functions that
>> can be used for FT232H USB-GPIO/I2C/SPI master adapter drivers.
>> Currently it is used for FT232H GPIO support (in patch 2) and
>> for FT245 FIFO transfers in FPP FPGA manager driver in patch 3.
>> Driver support for FT232H USB-I2C/SPI master adapters can be
>> added later.
>>
>> Patch 2 adds a simple GPIO driver supporting four FT232H CBUS GPIOs.
>>
>> Patch 3 adds an FPGA Manager driver for Altera FPP FPGA configuration
>> via FT232H FT245-FIFO interface.
>>
>> Anatolij Gustschin (3):
>> mfd: Add support for FTDI FT232H devices
>> gpio: Add FT232H CBUS GPIO driver
>> fpga manager: Add FT232H driver for Altera FPP
>>
>> drivers/fpga/Kconfig | 7 +
>> drivers/fpga/Makefile | 1 +
>> drivers/fpga/ftdi-fifo-fpp.c | 569
>> ++++++++++++++++++++++++++++++++++++++++++
>> drivers/gpio/Kconfig | 11 +
>> drivers/gpio/Makefile | 1 +
>> drivers/gpio/gpio-ftdi-cbus.c | 251 +++++++++++++++++++
>> drivers/mfd/Kconfig | 9 +
>> drivers/mfd/Makefile | 1 +
>> drivers/mfd/ftdi-ft232h.c | 470 ++++++++++++++++++++++++++++++++++
>> include/linux/mfd/ftdi/ftdi.h | 71 ++++++
>> 10 files changed, 1391 insertions(+)
>> create mode 100644 drivers/fpga/ftdi-fifo-fpp.c
>> create mode 100644 drivers/gpio/gpio-ftdi-cbus.c
>> create mode 100644 drivers/mfd/ftdi-ft232h.c
>> create mode 100644 include/linux/mfd/ftdi/ftdi.h

2017-08-02 15:30:43

by Eric Schwarz

[permalink] [raw]
Subject: Re: [PATCH 0/3] FPGA Manager support for FPP via FT232H FT245-FIFO

Hello Alan,

many thanks for your response.
Well, I am following the whole discussion from the very start and for my
taste it is too superficial - don't know whether this is the right
wording. Please get me right. We need some kind of implementation
specification or a sample way on how to implement stuff. At some point I
honestly lost track, thus I was asking for a summary so in the end the
result is what we want. If it is clear to everyone what shall be done it
should not be kind of a big deal to quickly sum it up which I/we would
highly appreciate.

Many thanks
Eric

Am 02.08.2017 16:16, schrieb Alan Tull:

> On Wed, Aug 2, 2017 at 6:36 AM, Eric Schwarz <[email protected]>
> wrote:
>
>> Dear all,
>>
>> DENX Software Engineering develops and brings this driver to mainline
>> on
>> behalf of us (ARRI*).
>>
>> Since there was a lot of discussion around this patch series I would
>> highly
>> appreciate if someone could sum up what needs to be changed in detail
>> in
>> order to get this driver into the mainline as I am used it from the
>> other
>> "line-by-line" reviews. I understood that the approach is not generic
>> enough
>> - please correct me if I am wrong on that point. We somehow need a
>> commitment that if we change it to another way that the whole
>> discussion
>> does not start from scratch.
>>
>> Many thanks
>> Eric
>
> Hi Eric,
>
> Patchwork collects all email response to patchsets posted on this
> mailing list [1] so that could be helpful for you here.
>
> Alan
>
> [1] https://patchwork.kernel.org/project/linux-fpga/list/?submitter=769
>
> * I am just writing from my private e-mail address since Outlook
> obviously
> renders all my mails as HTML despite what I am configuring.
>
> [1]... http://www.arri.com
>
> Am 06.07.2017 22:49, schrieb Anatolij Gustschin:
>
> This series adds support for fast passive parallel (FPP) Altera
> FPGA configuration using FTDI FT232H chip in FT245-FIFO mode.
> It has been used to configure Arria 10 FPGAs.
>
> Patch 1 adds an FT232H MFD driver with common functions that
> can be used for FT232H USB-GPIO/I2C/SPI master adapter drivers.
> Currently it is used for FT232H GPIO support (in patch 2) and
> for FT245 FIFO transfers in FPP FPGA manager driver in patch 3.
> Driver support for FT232H USB-I2C/SPI master adapters can be
> added later.
>
> Patch 2 adds a simple GPIO driver supporting four FT232H CBUS GPIOs.
>
> Patch 3 adds an FPGA Manager driver for Altera FPP FPGA configuration
> via FT232H FT245-FIFO interface.
>
> Anatolij Gustschin (3):
> mfd: Add support for FTDI FT232H devices
> gpio: Add FT232H CBUS GPIO driver
> fpga manager: Add FT232H driver for Altera FPP
>
> drivers/fpga/Kconfig | 7 +
> drivers/fpga/Makefile | 1 +
> drivers/fpga/ftdi-fifo-fpp.c | 569
> ++++++++++++++++++++++++++++++++++++++++++
> drivers/gpio/Kconfig | 11 +
> drivers/gpio/Makefile | 1 +
> drivers/gpio/gpio-ftdi-cbus.c | 251 +++++++++++++++++++
> drivers/mfd/Kconfig | 9 +
> drivers/mfd/Makefile | 1 +
> drivers/mfd/ftdi-ft232h.c | 470 ++++++++++++++++++++++++++++++++++
> include/linux/mfd/ftdi/ftdi.h | 71 ++++++
> 10 files changed, 1391 insertions(+)
> create mode 100644 drivers/fpga/ftdi-fifo-fpp.c
> create mode 100644 drivers/gpio/gpio-ftdi-cbus.c
> create mode 100644 drivers/mfd/ftdi-ft232h.c
> create mode 100644 include/linux/mfd/ftdi/ftdi.h

2017-08-02 16:06:31

by Greg KH

[permalink] [raw]
Subject: Re: [PATCH 0/3] FPGA Manager support for FPP via FT232H FT245-FIFO

On Wed, Aug 02, 2017 at 05:30:36PM +0200, Eric Schwarz wrote:
> Hello Alan,
>
> many thanks for your response.
> Well, I am following the whole discussion from the very start and for my
> taste it is too superficial - don't know whether this is the right wording.
> Please get me right. We need some kind of implementation specification or a
> sample way on how to implement stuff. At some point I honestly lost track,
> thus I was asking for a summary so in the end the result is what we want. If
> it is clear to everyone what shall be done it should not be kind of a big
> deal to quickly sum it up which I/we would highly appreciate.

That's up to the patch submitter to deal with, it's not our job to
provide summaries of each patch review for everyone, otherwise that
would be all that we would ever be writing :)

good luck!

greg k-h

2017-08-07 09:24:54

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH 2/3] gpio: Add FT232H CBUS GPIO driver

On Tue, Aug 1, 2017 at 11:24 AM, Johan Hovold <[email protected]> wrote:
> On Tue, Aug 01, 2017 at 08:49:02AM +0200, Linus Walleij wrote:
>> On Thu, Jul 6, 2017 at 10:49 PM, Anatolij Gustschin <[email protected]> wrote:
>>
>> > Add driver for CBUS pins on FT232H. The driver supports setting
>> > GPIO direction and getting/setting CBUS 0-3 pin value. The CBUS
>> > pins have to be enabled by configuring I/O mode in the FTDI EEPROM.
>> >
>> > Signed-off-by: Anatolij Gustschin <[email protected]>
>
>> Apart from these small things it looks like a solid and nice driver,
>> do you plan to merge this into MFD or should I merge it? Since it depends
>> on the Kconfig symbol I guess I can merge it orthogonally if I am sure
>> Lee will pick the MFD part.
>
> There are some fundamental problems with this series which prevents it
> from being merged. Please take a look at the discussion following patch
> 1/3.

Allright it is on hold pending the MFD discussion.

Yours,
Linus Walleij