* [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
@ 2016-10-20 8:13 Martyn Welch
[not found] ` <33cb529dad5c28a135e9e21460582c3cc4e6d4b5.1476950450.git.martyn.welch-ZGY8ohtN/8pPYcu2f3hruQ@public.gmane.org>
2016-10-25 9:34 ` Linus Walleij
0 siblings, 2 replies; 8+ messages in thread
From: Martyn Welch @ 2016-10-20 8:13 UTC (permalink / raw)
To: Johan Hovold, Linus Walleij
Cc: Alexandre Courbot, Greg Kroah-Hartman,
linux-usb-u79uwXL29TY76Z2rM5mHXA,
linux-gpio-u79uwXL29TY76Z2rM5mHXA, Karl Palsson,
Konstantin Shkolnyy, Peter Senna Tschudin, Martyn Welch
This patch adds support for the GPIO found on the CP2105. Unlike the GPIO
provided by some of the other devices supported by the cp210x driver, the
GPIO on the CP2015 is muxed on pins otherwise used for serial control
lines. The GPIO have been configured in 2 separate banks as the choice to
configure the pins for GPIO is made separately for pins shared with each
of the 2 serial ports this device provides, though the choice is made for
all pins associated with that port in one go. The choice of whether to use
the pins for GPIO or serial is made by adding configuration to a one-time
programable PROM in the chip and can not be changed at runtime. The device
defaults to GPIO.
This device supports either push-pull or open-drain modes, it doesn't
provide an explicit input mode, though the state of the GPIO can be read
when used in open-drain mode. Like with pin use, the mode is configured in
the one-time programable PROM and can't be changed at runtime.
Signed-off-by: Martyn Welch <martyn.welch-ZGY8ohtN/8pPYcu2f3hruQ@public.gmane.org>
---
V2: - Doesn't break build when gpiolib isn't selected.
V3: - Tracking GPIO state so pins no longer get their state changed should
the pin be in open-drain mode and be pulled down externally whilst
another pin is set.
- Reworked buffers and moved to byte accesses to remove the
questionable buffer size logic and byte swapping.
- Added error reporting.
- Removed incorrect/pointless comments.
- Renamed tmp variable to make use clearer.
V4: - Fixed memory leak in cp210x_gpio_get error path.
V5: - Determining shared GPIO based on device type.
- Reordered vendor specific values by value.
- Use interface device for gpio messages.
- Remove unnecessary empty lines.
- Using kzalloc rather than kcalloc.
- Added locking to port_priv->output_state.
- Added dummy cp2105_shared_gpio_init for !CONFIG_GPIOLIB.
- Removed unnecessary masking on u8.
- Added support for use of GPIO pin as RS485 traffic indication or
activity LEDs.
- Use correct dev for GPIO device.
- Set can_sleep.
- Roll in initial configuration state support.
- Print error message & continue if GPIO fails.
- Simplified ifdef'ing.
V6: - Remove unused define.
- Renamed cp210x_dev_private, cp210x_serial_private.
- Moved GPIO variables to cp210x_serial_private.
- Renamed PARTNUM defines.
- Switched to using bitops for GPIO mode bits.
- Moved vendor-specific defiles to end of defines.
- Added helpers for vendor requests.
- Using structs rather than byte arrays for sent and recieved values.
- Exposing total number of GPIOs and refusing requests for pins not
configured as GPIO, removing gpio_map in process.
- Added checks for allocation failures.
- Using same label for both banks of GPIO.
- Moved GPIO into to attach function.
V7: - Using GPIO private data for GPIO bits.
- Adding limited .set_single_ended() and direction support.
- Simplifying attach() and removing release() as it's no longer required.
V8: - Re-fix for when gpiolib isn't selected.
V9: - Reverted to using cp210x_serial_private.
- Use gpiochip_add_data rather than devm_gpiochip_add_data.
- Tweak struct padding.
- Use common GPIO Mode defines.
- Use USB_CTRL_GET_TIMEOUT rather than USB_CTRL_SET_TIMEOUT when performing USB reads.
- Tweak error messages and return values.
- Add free'ing of priv.
- Add disconnect and release functions (for correctly removing and releasing gpio).
v10:- Remove extraneous "u" in non-GLIOLIB path.
drivers/usb/serial/cp210x.c | 408 +++++++++++++++++++++++++++++++++++++++++++-
1 file changed, 405 insertions(+), 3 deletions(-)
diff --git a/drivers/usb/serial/cp210x.c b/drivers/usb/serial/cp210x.c
index 4d6a5c6..e0573bf 100644
--- a/drivers/usb/serial/cp210x.c
+++ b/drivers/usb/serial/cp210x.c
@@ -23,6 +23,9 @@
#include <linux/usb.h>
#include <linux/uaccess.h>
#include <linux/usb/serial.h>
+#include <linux/gpio/driver.h>
+#include <linux/bitops.h>
+#include <linux/mutex.h>
#define DRIVER_DESC "Silicon Labs CP210x RS232 serial adaptor driver"
@@ -44,6 +47,9 @@ static int cp210x_tiocmset(struct tty_struct *, unsigned int, unsigned int);
static int cp210x_tiocmset_port(struct usb_serial_port *port,
unsigned int, unsigned int);
static void cp210x_break_ctl(struct tty_struct *, int);
+static int cp210x_attach(struct usb_serial *);
+static void cp210x_disconnect(struct usb_serial *);
+static void cp210x_release(struct usb_serial *);
static int cp210x_port_probe(struct usb_serial_port *);
static int cp210x_port_remove(struct usb_serial_port *);
static void cp210x_dtr_rts(struct usb_serial_port *p, int on);
@@ -207,6 +213,15 @@ static const struct usb_device_id id_table[] = {
MODULE_DEVICE_TABLE(usb, id_table);
+#ifdef CONFIG_GPIOLIB
+struct cp210x_serial_private {
+ struct usb_serial *serial;
+ struct gpio_chip gc;
+ u8 config;
+ u8 gpio_mode;
+};
+#endif
+
struct cp210x_port_private {
__u8 bInterfaceNumber;
bool has_swapped_line_ctl;
@@ -228,6 +243,9 @@ static struct usb_serial_driver cp210x_device = {
.tx_empty = cp210x_tx_empty,
.tiocmget = cp210x_tiocmget,
.tiocmset = cp210x_tiocmset,
+ .attach = cp210x_attach,
+ .disconnect = cp210x_disconnect,
+ .release = cp210x_release,
.port_probe = cp210x_port_probe,
.port_remove = cp210x_port_remove,
.dtr_rts = cp210x_dtr_rts
@@ -270,6 +288,7 @@ static struct usb_serial_driver * const serial_drivers[] = {
#define CP210X_SET_CHARS 0x19
#define CP210X_GET_BAUDRATE 0x1D
#define CP210X_SET_BAUDRATE 0x1E
+#define CP210X_VENDOR_SPECIFIC 0xFF
/* CP210X_IFC_ENABLE */
#define UART_ENABLE 0x0001
@@ -312,6 +331,21 @@ static struct usb_serial_driver * const serial_drivers[] = {
#define CONTROL_WRITE_DTR 0x0100
#define CONTROL_WRITE_RTS 0x0200
+/* CP210X_VENDOR_SPECIFIC values */
+#define CP210X_READ_LATCH 0x00C2
+#define CP210X_GET_PARTNUM 0x370B
+#define CP210X_GET_PORTCONFIG 0x370C
+#define CP210X_GET_DEVICEMODE 0x3711
+#define CP210X_WRITE_LATCH 0x37E1
+
+/* Part number definitions */
+#define CP210X_PARTNUM_CP2101 0x01
+#define CP210X_PARTNUM_CP2102 0x02
+#define CP210X_PARTNUM_CP2103 0x03
+#define CP210X_PARTNUM_CP2104 0x04
+#define CP210X_PARTNUM_CP2105 0x05
+#define CP210X_PARTNUM_CP2108 0x08
+
/* CP210X_GET_COMM_STATUS returns these 0x13 bytes */
struct cp210x_comm_status {
__le32 ulErrors;
@@ -367,6 +401,57 @@ struct cp210x_flow_ctl {
#define CP210X_SERIAL_RTS_ACTIVE 1
#define CP210X_SERIAL_RTS_FLOW_CTL 2
+/* CP210X_VENDOR_SPECIFIC, CP210X_GET_DEVICEMODE call reads these 0x2 bytes. */
+struct cp210x_pin_mode {
+ u8 eci;
+ u8 sci;
+} __packed;
+
+/*
+ * CP210X_VENDOR_SPECIFIC, CP210X_GET_DEVICEMODE call reads these 0xf bytes.
+ * Structure needs padding due to unused/unspecified bytes.
+ */
+struct cp210x_config {
+ __le16 gpio_mode;
+ u8 __pad0[2];
+ __le16 reset_state;
+ u8 __pad1[4];
+ __le16 suspend_state;
+ u8 sci_cfg;
+ u8 eci_cfg;
+ u8 device_cfg;
+} __packed;
+
+/* GPIO modes */
+#define CP210X_SCI_GPIO_MODE_OFFSET 9
+#define CP210X_SCI_GPIO_MODE_MASK GENMASK(11, 9)
+
+#define CP210X_ECI_GPIO_MODE_OFFSET 2
+#define CP210X_ECI_GPIO_MODE_MASK GENMASK(3, 2)
+
+/* CP2105 port configuration values */
+#define CP2105_GPIO0_TXLED_MODE BIT(0)
+#define CP2105_GPIO1_RXLED_MODE BIT(1)
+#define CP2105_GPIO1_RS485_MODE BIT(2)
+
+/* CP210X_VENDOR_SPECIFIC, CP210X_WRITE_LATCH call writes these 0x2 bytes. */
+struct cp210x_gpio_write {
+ u8 mask;
+ u8 state;
+} __packed;
+
+/*
+ * Helper to get interface number when we only have struct usb_serial.
+ */
+static u8 cp210x_interface_num(struct usb_serial *serial)
+{
+ struct usb_host_interface *cur_altsetting;
+
+ cur_altsetting = serial->interface->cur_altsetting;
+
+ return cur_altsetting->desc.bInterfaceNumber;
+}
+
/*
* Reads a variable-sized block of CP210X_ registers, identified by req.
* Returns data into buf in native USB byte order.
@@ -463,6 +548,40 @@ static int cp210x_read_u8_reg(struct usb_serial_port *port, u8 req, u8 *val)
}
/*
+ * Reads a variable-sized vendor block of CP210X_ registers, identified by val.
+ * Returns data into buf in native USB byte order.
+ */
+static int cp210x_read_vendor_block(struct usb_serial *serial, u8 type, u16 val,
+ void *buf, int bufsize)
+{
+ void *dmabuf;
+ int result;
+
+ dmabuf = kmalloc(bufsize, GFP_KERNEL);
+ if (!dmabuf)
+ return -ENOMEM;
+
+ result = usb_control_msg(serial->dev, usb_rcvctrlpipe(serial->dev, 0),
+ CP210X_VENDOR_SPECIFIC, type, val,
+ cp210x_interface_num(serial), dmabuf, bufsize,
+ USB_CTRL_GET_TIMEOUT);
+ if (result == bufsize) {
+ memcpy(buf, dmabuf, bufsize);
+ result = 0;
+ } else {
+ dev_err(&serial->interface->dev,
+ "failed to get vendor val 0x%04x size %d: %d\n", val,
+ bufsize, result);
+ if (result >= 0)
+ result = -EIO;
+ }
+
+ kfree(dmabuf);
+
+ return result;
+}
+
+/*
* Writes any 16-bit CP210X_ register (req) whose value is passed
* entirely in the wValue field of the USB request.
*/
@@ -531,6 +650,42 @@ static int cp210x_write_u32_reg(struct usb_serial_port *port, u8 req, u32 val)
return cp210x_write_reg_block(port, req, &le32_val, sizeof(le32_val));
}
+#ifdef CONFIG_GPIOLIB
+/*
+ * Writes a variable-sized vendor block of CP210X_ registers, identified by val.
+ * Data in buf must be in native USB byte order.
+ */
+static int cp210x_write_vendor_block(struct usb_serial *serial, u8 type,
+ u16 val, void *buf, int bufsize)
+{
+ void *dmabuf;
+ int result;
+
+ dmabuf = kmemdup(buf, bufsize, GFP_KERNEL);
+ if (!dmabuf)
+ return -ENOMEM;
+
+ result = usb_control_msg(serial->dev, usb_sndctrlpipe(serial->dev, 0),
+ CP210X_VENDOR_SPECIFIC, type, val,
+ cp210x_interface_num(serial), dmabuf, bufsize,
+ USB_CTRL_SET_TIMEOUT);
+
+ kfree(dmabuf);
+
+ if (result == bufsize) {
+ result = 0;
+ } else {
+ dev_err(&serial->interface->dev,
+ "failed to set vendor val 0x%04x size %d: %d\n", val,
+ bufsize, result);
+ if (result >= 0)
+ result = -EIO;
+ }
+
+ return result;
+}
+#endif
+
/*
* Detect CP2108 GET_LINE_CTL bug and activate workaround.
* Write a known good value 0x800, read it back.
@@ -1104,10 +1259,227 @@ static void cp210x_break_ctl(struct tty_struct *tty, int break_state)
cp210x_write_u16_reg(port, CP210X_SET_BREAK, state);
}
+#ifdef CONFIG_GPIOLIB
+static int cp210x_gpio_request(struct gpio_chip *gc, unsigned int offset)
+{
+ struct cp210x_serial_private *priv = gpiochip_get_data(gc);
+ u8 intf_num = cp210x_interface_num(priv->serial);
+
+ if (intf_num == 0) {
+ switch (offset) {
+ case 0:
+ if (priv->config & CP2105_GPIO0_TXLED_MODE)
+ return -ENODEV;
+ break;
+ case 1:
+ if (priv->config & (CP2105_GPIO1_RXLED_MODE |
+ CP2105_GPIO1_RS485_MODE))
+ return -ENODEV;
+ break;
+ }
+ } else if (intf_num == 1) {
+ switch (offset) {
+ case 0:
+ if (priv->config & CP2105_GPIO0_TXLED_MODE)
+ return -ENODEV;
+ case 1:
+ if (priv->config & CP2105_GPIO1_RXLED_MODE)
+ return -ENODEV;
+ break;
+ }
+ } else {
+ return -ENODEV;
+ }
+
+ return 0;
+}
+
+static int cp210x_gpio_get(struct gpio_chip *gc, unsigned int gpio)
+{
+ struct cp210x_serial_private *priv = gpiochip_get_data(gc);
+ struct usb_serial *serial = priv->serial;
+ int result;
+ u8 buf;
+
+ result = cp210x_read_vendor_block(serial, REQTYPE_INTERFACE_TO_HOST,
+ CP210X_READ_LATCH, &buf, sizeof(buf));
+ if (result < 0)
+ return result;
+
+ return !!(buf & BIT(gpio));
+}
+
+static void cp210x_gpio_set(struct gpio_chip *gc, unsigned int gpio, int value)
+{
+ struct cp210x_serial_private *priv = gpiochip_get_data(gc);
+ struct usb_serial *serial = priv->serial;
+ struct cp210x_gpio_write buf;
+
+ if (value == 1)
+ buf.state = BIT(gpio);
+ else
+ buf.state = 0;
+
+ buf.mask = BIT(gpio);
+
+ cp210x_write_vendor_block(serial, REQTYPE_HOST_TO_INTERFACE,
+ CP210X_WRITE_LATCH, &buf, sizeof(buf));
+}
+
+static int cp210x_gpio_direction_get(struct gpio_chip *gc, unsigned int gpio)
+{
+ /* Hardware does not support an input mode */
+ return 0;
+}
+
+static int cp210x_gpio_direction_input(struct gpio_chip *gc, unsigned int gpio)
+{
+ /* Hardware does not support an input mode */
+ return -ENOTSUPP;
+}
+
+static int cp210x_gpio_direction_output(struct gpio_chip *gc, unsigned int gpio,
+ int value)
+{
+ return 0;
+}
+
+static int cp210x_gpio_set_single_ended(struct gpio_chip *gc, unsigned int gpio,
+ enum single_ended_mode mode)
+{
+ struct cp210x_serial_private *priv = gpiochip_get_data(gc);
+
+ /* Succeed only if in correct mode (this can't be set at runtime) */
+ if ((mode == LINE_MODE_PUSH_PULL) && (priv->gpio_mode & BIT(gpio)))
+ return 0;
+
+ if ((mode == LINE_MODE_OPEN_DRAIN) && !(priv->gpio_mode & BIT(gpio)))
+ return 0;
+
+ return -ENOTSUPP;
+}
+
+/*
+ * This function is for configuring GPIO using shared pins, where other signals
+ * are made unavailable by configuring the use of GPIO. This is believed to be
+ * only applicable to the cp2105 at this point, the other devices supported by
+ * this driver that provide GPIO do so in a way that does not impact other
+ * signals and are thus expected to have very different initialisation.
+ */
+static int cp2105_shared_gpio_init(struct usb_serial *serial)
+{
+ struct cp210x_serial_private *priv;
+ struct cp210x_pin_mode mode;
+ struct cp210x_config config;
+ u8 intf_num = cp210x_interface_num(serial);
+ int result;
+
+ priv = kzalloc(sizeof(*priv), GFP_KERNEL);
+ if (!priv)
+ return -ENOMEM;
+
+ result = cp210x_read_vendor_block(serial, REQTYPE_DEVICE_TO_HOST,
+ CP210X_GET_DEVICEMODE, &mode,
+ sizeof(mode));
+ if (result < 0)
+ goto err_free_priv;
+
+ result = cp210x_read_vendor_block(serial, REQTYPE_DEVICE_TO_HOST,
+ CP210X_GET_PORTCONFIG, &config,
+ sizeof(config));
+ if (result < 0)
+ goto err_free_priv;
+
+ /* 2 banks of GPIO - One for the pins taken from each serial port */
+ if (intf_num == 0) {
+ if (mode.eci == 0)
+ return 0;
+
+ priv->config = config.eci_cfg;
+ priv->gpio_mode = (u8)((le16_to_cpu(config.gpio_mode) &
+ CP210X_ECI_GPIO_MODE_MASK) >>
+ CP210X_ECI_GPIO_MODE_OFFSET);
+ priv->gc.ngpio = 2;
+ } else if (intf_num == 1) {
+ if (mode.sci == 0)
+ return 0;
+
+ priv->config = config.sci_cfg;
+ priv->gpio_mode = (u8)((le16_to_cpu(config.gpio_mode) &
+ CP210X_SCI_GPIO_MODE_MASK) >>
+ CP210X_SCI_GPIO_MODE_OFFSET);
+ priv->gc.ngpio = 3;
+ } else {
+ result = -ENODEV;
+ goto err_free_priv;
+ }
+
+ priv->gc.label = "cp210x";
+ priv->gc.request = cp210x_gpio_request;
+ priv->gc.get_direction = cp210x_gpio_direction_get;
+ priv->gc.direction_input = cp210x_gpio_direction_input;
+ priv->gc.direction_output = cp210x_gpio_direction_output;
+ priv->gc.get = cp210x_gpio_get;
+ priv->gc.set = cp210x_gpio_set;
+ priv->gc.set_single_ended = cp210x_gpio_set_single_ended;
+ priv->gc.owner = THIS_MODULE;
+ priv->gc.parent = &serial->interface->dev;
+ priv->gc.base = -1;
+ priv->gc.can_sleep = true;
+
+ priv->serial = serial;
+
+ result = gpiochip_add_data(&priv->gc, priv);
+ if (result < 0)
+ goto err_free_priv;
+
+ usb_set_serial_data(serial, (void *)priv);
+
+ return 0;
+
+err_free_priv:
+ kfree(priv);
+
+ return result;
+}
+
+static void cp210x_gpio_remove(struct usb_serial *serial)
+{
+ struct cp210x_serial_private *priv = usb_get_serial_data(serial);
+
+ if (priv)
+ gpiochip_remove(&priv->gc);
+}
+
+static void cp210x_gpio_release(struct usb_serial *serial)
+{
+ struct cp210x_serial_private *priv = usb_get_serial_data(serial);
+
+ kfree(priv);
+}
+
+#else
+
+static int cp2105_shared_gpio_init(struct usb_serial *serial)
+{
+ return 0;
+}
+
+static void cp210x_gpio_remove(struct usb_serial *serial)
+{
+ /* Nothing to do */
+}
+
+static void cp210x_gpio_release(struct usb_serial *serial)
+{
+ /* Nothing to do */
+}
+
+#endif
+
static int cp210x_port_probe(struct usb_serial_port *port)
{
struct usb_serial *serial = port->serial;
- struct usb_host_interface *cur_altsetting;
struct cp210x_port_private *port_priv;
int ret;
@@ -1115,8 +1487,7 @@ static int cp210x_port_probe(struct usb_serial_port *port)
if (!port_priv)
return -ENOMEM;
- cur_altsetting = serial->interface->cur_altsetting;
- port_priv->bInterfaceNumber = cur_altsetting->desc.bInterfaceNumber;
+ port_priv->bInterfaceNumber = cp210x_interface_num(serial);
usb_set_serial_port_data(port, port_priv);
@@ -1139,6 +1510,37 @@ static int cp210x_port_remove(struct usb_serial_port *port)
return 0;
}
+static int cp210x_attach(struct usb_serial *serial)
+{
+ int result;
+ u8 partnum;
+
+ result = cp210x_read_vendor_block(serial, REQTYPE_DEVICE_TO_HOST,
+ CP210X_GET_PARTNUM, &partnum,
+ sizeof(partnum));
+ if (result < 0)
+ return result;
+
+ if (partnum == CP210X_PARTNUM_CP2105) {
+ result = cp2105_shared_gpio_init(serial);
+ if (result < 0)
+ dev_err(&serial->interface->dev,
+ "GPIO initialisation failed, continuing without GPIO support\n");
+ }
+
+ return 0;
+}
+
+static void cp210x_disconnect(struct usb_serial *serial)
+{
+ cp210x_gpio_remove(serial);
+}
+
+static void cp210x_release(struct usb_serial *serial)
+{
+ cp210x_gpio_release(serial);
+}
+
module_usb_serial_driver(serial_drivers, id_table);
MODULE_DESCRIPTION(DRIVER_DESC);
--
1.8.3.1
--
To unsubscribe from this list: send the line "unsubscribe linux-usb" in
the body of a message to majordomo-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply related [flat|nested] 8+ messages in thread
* Re: [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
[not found] ` <33cb529dad5c28a135e9e21460582c3cc4e6d4b5.1476950450.git.martyn.welch-ZGY8ohtN/8pPYcu2f3hruQ@public.gmane.org>
@ 2016-10-20 8:49 ` Johan Hovold
2016-10-20 13:31 ` Martyn Welch
0 siblings, 1 reply; 8+ messages in thread
From: Johan Hovold @ 2016-10-20 8:49 UTC (permalink / raw)
To: Martyn Welch
Cc: Johan Hovold, Linus Walleij, Alexandre Courbot,
Greg Kroah-Hartman, linux-usb-u79uwXL29TY76Z2rM5mHXA,
linux-gpio-u79uwXL29TY76Z2rM5mHXA, Karl Palsson,
Konstantin Shkolnyy, Peter Senna Tschudin
On Thu, Oct 20, 2016 at 09:13:41AM +0100, Martyn Welch wrote:
> This patch adds support for the GPIO found on the CP2105. Unlike the GPIO
> provided by some of the other devices supported by the cp210x driver, the
> GPIO on the CP2015 is muxed on pins otherwise used for serial control
> lines. The GPIO have been configured in 2 separate banks as the choice to
> configure the pins for GPIO is made separately for pins shared with each
> of the 2 serial ports this device provides, though the choice is made for
> all pins associated with that port in one go. The choice of whether to use
> the pins for GPIO or serial is made by adding configuration to a one-time
> programable PROM in the chip and can not be changed at runtime. The device
> defaults to GPIO.
>
> This device supports either push-pull or open-drain modes, it doesn't
> provide an explicit input mode, though the state of the GPIO can be read
> when used in open-drain mode. Like with pin use, the mode is configured in
> the one-time programable PROM and can't be changed at runtime.
>
> Signed-off-by: Martyn Welch <martyn.welch-ZGY8ohtN/8pPYcu2f3hruQ@public.gmane.org>
> ---
>
> V2: - Doesn't break build when gpiolib isn't selected.
>
> V3: - Tracking GPIO state so pins no longer get their state changed should
> the pin be in open-drain mode and be pulled down externally whilst
> another pin is set.
> - Reworked buffers and moved to byte accesses to remove the
> questionable buffer size logic and byte swapping.
> - Added error reporting.
> - Removed incorrect/pointless comments.
> - Renamed tmp variable to make use clearer.
>
> V4: - Fixed memory leak in cp210x_gpio_get error path.
>
> V5: - Determining shared GPIO based on device type.
> - Reordered vendor specific values by value.
> - Use interface device for gpio messages.
> - Remove unnecessary empty lines.
> - Using kzalloc rather than kcalloc.
> - Added locking to port_priv->output_state.
> - Added dummy cp2105_shared_gpio_init for !CONFIG_GPIOLIB.
> - Removed unnecessary masking on u8.
> - Added support for use of GPIO pin as RS485 traffic indication or
> activity LEDs.
> - Use correct dev for GPIO device.
> - Set can_sleep.
> - Roll in initial configuration state support.
> - Print error message & continue if GPIO fails.
> - Simplified ifdef'ing.
>
> V6: - Remove unused define.
> - Renamed cp210x_dev_private, cp210x_serial_private.
> - Moved GPIO variables to cp210x_serial_private.
> - Renamed PARTNUM defines.
> - Switched to using bitops for GPIO mode bits.
> - Moved vendor-specific defiles to end of defines.
> - Added helpers for vendor requests.
> - Using structs rather than byte arrays for sent and recieved values.
> - Exposing total number of GPIOs and refusing requests for pins not
> configured as GPIO, removing gpio_map in process.
> - Added checks for allocation failures.
> - Using same label for both banks of GPIO.
> - Moved GPIO into to attach function.
>
> V7: - Using GPIO private data for GPIO bits.
> - Adding limited .set_single_ended() and direction support.
> - Simplifying attach() and removing release() as it's no longer required.
>
> V8: - Re-fix for when gpiolib isn't selected.
>
> V9: - Reverted to using cp210x_serial_private.
> - Use gpiochip_add_data rather than devm_gpiochip_add_data.
> - Tweak struct padding.
> - Use common GPIO Mode defines.
> - Use USB_CTRL_GET_TIMEOUT rather than USB_CTRL_SET_TIMEOUT when performing USB reads.
> - Tweak error messages and return values.
> - Add free'ing of priv.
> - Add disconnect and release functions (for correctly removing and releasing gpio).
>
> v10:- Remove extraneous "u" in non-GLIOLIB path.
>
> drivers/usb/serial/cp210x.c | 408 +++++++++++++++++++++++++++++++++++++++++++-
> 1 file changed, 405 insertions(+), 3 deletions(-)
>
> diff --git a/drivers/usb/serial/cp210x.c b/drivers/usb/serial/cp210x.c
> index 4d6a5c6..e0573bf 100644
> --- a/drivers/usb/serial/cp210x.c
> +++ b/drivers/usb/serial/cp210x.c
> @@ -23,6 +23,9 @@
> #include <linux/usb.h>
> #include <linux/uaccess.h>
> #include <linux/usb/serial.h>
> +#include <linux/gpio/driver.h>
> +#include <linux/bitops.h>
> +#include <linux/mutex.h>
>
> #define DRIVER_DESC "Silicon Labs CP210x RS232 serial adaptor driver"
>
> @@ -44,6 +47,9 @@ static int cp210x_tiocmset(struct tty_struct *, unsigned int, unsigned int);
> static int cp210x_tiocmset_port(struct usb_serial_port *port,
> unsigned int, unsigned int);
> static void cp210x_break_ctl(struct tty_struct *, int);
> +static int cp210x_attach(struct usb_serial *);
> +static void cp210x_disconnect(struct usb_serial *);
> +static void cp210x_release(struct usb_serial *);
> static int cp210x_port_probe(struct usb_serial_port *);
> static int cp210x_port_remove(struct usb_serial_port *);
> static void cp210x_dtr_rts(struct usb_serial_port *p, int on);
> @@ -207,6 +213,15 @@ static const struct usb_device_id id_table[] = {
>
> MODULE_DEVICE_TABLE(usb, id_table);
>
> +#ifdef CONFIG_GPIOLIB
> +struct cp210x_serial_private {
> + struct usb_serial *serial;
This should not be needed. Pass the usb_serial struct to gpiolib as
private data instead.
> + struct gpio_chip gc;
> + u8 config;
> + u8 gpio_mode;
> +};
> +#endif
> +#ifdef CONFIG_GPIOLIB
> +static int cp210x_gpio_request(struct gpio_chip *gc, unsigned int offset)
> +{
> + struct cp210x_serial_private *priv = gpiochip_get_data(gc);
> + u8 intf_num = cp210x_interface_num(priv->serial);
> +
> + if (intf_num == 0) {
> + switch (offset) {
> + case 0:
> + if (priv->config & CP2105_GPIO0_TXLED_MODE)
> + return -ENODEV;
> + break;
> + case 1:
> + if (priv->config & (CP2105_GPIO1_RXLED_MODE |
> + CP2105_GPIO1_RS485_MODE))
> + return -ENODEV;
> + break;
> + }
> + } else if (intf_num == 1) {
> + switch (offset) {
> + case 0:
> + if (priv->config & CP2105_GPIO0_TXLED_MODE)
> + return -ENODEV;
Odd indentation.
> + case 1:
> + if (priv->config & CP2105_GPIO1_RXLED_MODE)
> + return -ENODEV;
> + break;
> + }
Now that you use common defines, aren't you able to just use a single
common switch construct for this (even if rs485-mode will never be set
for interface 1) as I suggested earlier?
> + } else {
> + return -ENODEV;
> + }
> +
> + return 0;
> +}
> +/*
> + * This function is for configuring GPIO using shared pins, where other signals
> + * are made unavailable by configuring the use of GPIO. This is believed to be
> + * only applicable to the cp2105 at this point, the other devices supported by
> + * this driver that provide GPIO do so in a way that does not impact other
> + * signals and are thus expected to have very different initialisation.
> + */
> +static int cp2105_shared_gpio_init(struct usb_serial *serial)
> +{
> + struct cp210x_serial_private *priv;
> + struct cp210x_pin_mode mode;
> + struct cp210x_config config;
> + u8 intf_num = cp210x_interface_num(serial);
> + int result;
> +
> + priv = kzalloc(sizeof(*priv), GFP_KERNEL);
> + if (!priv)
> + return -ENOMEM;
> +
> + result = cp210x_read_vendor_block(serial, REQTYPE_DEVICE_TO_HOST,
> + CP210X_GET_DEVICEMODE, &mode,
> + sizeof(mode));
> + if (result < 0)
> + goto err_free_priv;
> +
> + result = cp210x_read_vendor_block(serial, REQTYPE_DEVICE_TO_HOST,
> + CP210X_GET_PORTCONFIG, &config,
> + sizeof(config));
> + if (result < 0)
> + goto err_free_priv;
> +
> + /* 2 banks of GPIO - One for the pins taken from each serial port */
> + if (intf_num == 0) {
> + if (mode.eci == 0)
Would you mind explaining how mode is used as I asked in my comments to
v8?
> + return 0;
> +
> + priv->config = config.eci_cfg;
> + priv->gpio_mode = (u8)((le16_to_cpu(config.gpio_mode) &
> + CP210X_ECI_GPIO_MODE_MASK) >>
> + CP210X_ECI_GPIO_MODE_OFFSET);
> + priv->gc.ngpio = 2;
> + } else if (intf_num == 1) {
> + if (mode.sci == 0)
> + return 0;
> +
> + priv->config = config.sci_cfg;
> + priv->gpio_mode = (u8)((le16_to_cpu(config.gpio_mode) &
> + CP210X_SCI_GPIO_MODE_MASK) >>
> + CP210X_SCI_GPIO_MODE_OFFSET);
> + priv->gc.ngpio = 3;
> + } else {
> + result = -ENODEV;
> + goto err_free_priv;
> + }
> +
> + priv->gc.label = "cp210x";
> + priv->gc.request = cp210x_gpio_request;
> + priv->gc.get_direction = cp210x_gpio_direction_get;
> + priv->gc.direction_input = cp210x_gpio_direction_input;
> + priv->gc.direction_output = cp210x_gpio_direction_output;
> + priv->gc.get = cp210x_gpio_get;
> + priv->gc.set = cp210x_gpio_set;
> + priv->gc.set_single_ended = cp210x_gpio_set_single_ended;
> + priv->gc.owner = THIS_MODULE;
> + priv->gc.parent = &serial->interface->dev;
> + priv->gc.base = -1;
> + priv->gc.can_sleep = true;
> +
> + priv->serial = serial;
> +
> + result = gpiochip_add_data(&priv->gc, priv);
So set the serial data first and then pass struct usb_serial here
instead.
> + if (result < 0)
> + goto err_free_priv;
> +
> + usb_set_serial_data(serial, (void *)priv);
Cast not needed.
> +
> + return 0;
> +
> +err_free_priv:
> + kfree(priv);
> +
> + return result;
> +}
> +
> +static void cp210x_gpio_remove(struct usb_serial *serial)
> +{
> + struct cp210x_serial_private *priv = usb_get_serial_data(serial);
> +
> + if (priv)
You should not rely on the private data as a flag for the gpio
implementation (see below).
> + gpiochip_remove(&priv->gc);
> +}
> +
> +static void cp210x_gpio_release(struct usb_serial *serial)
> +{
> + struct cp210x_serial_private *priv = usb_get_serial_data(serial);
> +
> + kfree(priv);
Hmm. This looks odd, but I think I understand why you did it this way.
The interface (serial) private data should be allocated in attach and
freed in release. Now it happens that you currently only use it for gpio
fields, but you should still follow that expected pattern.
Perhaps always store the device type (we'll surely need it at some
point) in the private data, and move the compile guards inside the
struct again. Allocate in attach, free in release. And initialise the
gpio fields above, before registering the gpio chip when needed.
> +}
> +
> +#else
> +static int cp210x_attach(struct usb_serial *serial)
> +{
> + int result;
> + u8 partnum;
> +
> + result = cp210x_read_vendor_block(serial, REQTYPE_DEVICE_TO_HOST,
> + CP210X_GET_PARTNUM, &partnum,
> + sizeof(partnum));
> + if (result < 0)
> + return result;
> +
> + if (partnum == CP210X_PARTNUM_CP2105) {
> + result = cp2105_shared_gpio_init(serial);
> + if (result < 0)
> + dev_err(&serial->interface->dev,
> + "GPIO initialisation failed, continuing without GPIO support\n");
> + }
> +
> + return 0;
> +}
> +
> +static void cp210x_disconnect(struct usb_serial *serial)
> +{
> + cp210x_gpio_remove(serial);
> +}
> +
> +static void cp210x_release(struct usb_serial *serial)
> +{
There's another complication here. In the unlikely event of a late probe
error, disconnect will never be called, but release will be if attach
succeeded. Then you need to deregister the gpio chip here as well.
> + cp210x_gpio_release(serial);
> +}
> +
> module_usb_serial_driver(serial_drivers, id_table);
>
> MODULE_DESCRIPTION(DRIVER_DESC);
Thanks,
Johan
--
To unsubscribe from this list: send the line "unsubscribe linux-usb" in
the body of a message to majordomo-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 8+ messages in thread
* Re: [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
2016-10-20 8:49 ` Johan Hovold
@ 2016-10-20 13:31 ` Martyn Welch
0 siblings, 0 replies; 8+ messages in thread
From: Martyn Welch @ 2016-10-20 13:31 UTC (permalink / raw)
To: Johan Hovold
Cc: Linus Walleij, Alexandre Courbot, Greg Kroah-Hartman,
linux-usb-u79uwXL29TY76Z2rM5mHXA,
linux-gpio-u79uwXL29TY76Z2rM5mHXA, Karl Palsson,
Konstantin Shkolnyy, Peter Senna Tschudin
On Thu, Oct 20, 2016 at 10:49:24AM +0200, Johan Hovold wrote:
> On Thu, Oct 20, 2016 at 09:13:41AM +0100, Martyn Welch wrote:
> > + /* 2 banks of GPIO - One for the pins taken from each serial port */
> > + if (intf_num == 0) {
> > + if (mode.eci == 0)
>
> Would you mind explaining how mode is used as I asked in my comments to
> v8?
>
These are set to 0 if in "modem mode" or 1 if in "gpio mode". I will add
these as defines to make this clear.
Martyn
--
To unsubscribe from this list: send the line "unsubscribe linux-usb" in
the body of a message to majordomo-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 8+ messages in thread
* Re: [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
2016-10-20 8:13 [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105 Martyn Welch
[not found] ` <33cb529dad5c28a135e9e21460582c3cc4e6d4b5.1476950450.git.martyn.welch-ZGY8ohtN/8pPYcu2f3hruQ@public.gmane.org>
@ 2016-10-25 9:34 ` Linus Walleij
[not found] ` <CACRpkdab5d71TgrTD-4U95R6MvWdFcaqRcGpPS0D8sExKi=b3g-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
2016-10-31 10:17 ` Martyn Welch
1 sibling, 2 replies; 8+ messages in thread
From: Linus Walleij @ 2016-10-25 9:34 UTC (permalink / raw)
To: Martyn Welch
Cc: Johan Hovold, Alexandre Courbot, Greg Kroah-Hartman,
linux-usb@vger.kernel.org, linux-gpio@vger.kernel.org,
Karl Palsson, Konstantin Shkolnyy, Peter Senna Tschudin
Good work on this patch, nice that it got merged.
I was just thinking that as an add-on, you may want to name
the gpio lines so they have meaningful names in userspace
when you use this with the chardev (I have reasons to believe
these GPIOs will be used from userspace, tell me if that
is wrong).
We currently support naming lines for devicetree and
ACPI (in -next).
I was thinking on either reusing the .names field of the
struct gpiochip to name the lines for the userspace
chardev. With the sideeffect of the names getting reflected
also to sysfs if using that.
We could otherwise add a special function to name the
lines from drivers like this that hang off a pluggable bus.
Johan/Martyn what is your idea?
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 8+ messages in thread
* Re: [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
[not found] ` <CACRpkdab5d71TgrTD-4U95R6MvWdFcaqRcGpPS0D8sExKi=b3g-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
@ 2016-10-26 9:09 ` Johan Hovold
2016-10-26 11:50 ` Linus Walleij
0 siblings, 1 reply; 8+ messages in thread
From: Johan Hovold @ 2016-10-26 9:09 UTC (permalink / raw)
To: Linus Walleij
Cc: Martyn Welch, Johan Hovold, Alexandre Courbot, Greg Kroah-Hartman,
linux-usb-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
linux-gpio-u79uwXL29TY76Z2rM5mHXA@public.gmane.org, Karl Palsson,
Konstantin Shkolnyy, Peter Senna Tschudin
On Tue, Oct 25, 2016 at 11:34:40AM +0200, Linus Walleij wrote:
> Good work on this patch, nice that it got merged.
>
> I was just thinking that as an add-on, you may want to name
> the gpio lines so they have meaningful names in userspace
> when you use this with the chardev (I have reasons to believe
> these GPIOs will be used from userspace, tell me if that
> is wrong).
>
> We currently support naming lines for devicetree and
> ACPI (in -next).
>
> I was thinking on either reusing the .names field of the
> struct gpiochip to name the lines for the userspace
> chardev. With the sideeffect of the names getting reflected
> also to sysfs if using that.
Simply reusing .names would cause problems since the old sysfs name
space is flat, so you would be unable to use more than one pluggable
expander (unless also encoding the topology in the name).
> We could otherwise add a special function to name the
> lines from drivers like this that hang off a pluggable bus.
>
> Johan/Martyn what is your idea?
Providing default names from the driver could perhaps be useful at
times. For this particular chip the names would still be GPIO_0, GPIO_1
and GPIO_2 (possibly with a suffix depending on which of the two
controllers they hang off of) however, which may not be much better than
using chip->base + offset. I'd assume this to be the common case.
Device-tree overlays is what I see a real use for where different
overlays can be applied based on topology data to describe what is
actually connected to a pin in a specific setup. And that seems like
something that could be useful for normal (static) DT systems as well
(e.g. describe what's actually connected to those Beaglebone pins).
Johan
--
To unsubscribe from this list: send the line "unsubscribe linux-usb" in
the body of a message to majordomo-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
More majordomo info at http://vger.kernel.org/majordomo-info.html
^ permalink raw reply [flat|nested] 8+ messages in thread
* Re: [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
2016-10-26 9:09 ` Johan Hovold
@ 2016-10-26 11:50 ` Linus Walleij
2016-10-26 12:16 ` Johan Hovold
0 siblings, 1 reply; 8+ messages in thread
From: Linus Walleij @ 2016-10-26 11:50 UTC (permalink / raw)
To: Johan Hovold
Cc: Martyn Welch, Alexandre Courbot, Greg Kroah-Hartman,
linux-usb@vger.kernel.org, linux-gpio@vger.kernel.org,
Karl Palsson, Konstantin Shkolnyy, Peter Senna Tschudin
On Wed, Oct 26, 2016 at 11:09 AM, Johan Hovold <johan@kernel.org> wrote:
> On Tue, Oct 25, 2016 at 11:34:40AM +0200, Linus Walleij wrote:
>> I was thinking on either reusing the .names field of the
>> struct gpiochip to name the lines for the userspace
>> chardev. With the sideeffect of the names getting reflected
>> also to sysfs if using that.
>
> Simply reusing .names would cause problems since the old sysfs name
> space is flat, so you would be unable to use more than one pluggable
> expander (unless also encoding the topology in the name).
Hm it seems we should actually #ifdef that field for sysfs then,
it has no applicability outside the legacy sysfs.
> Providing default names from the driver could perhaps be useful at
> times. For this particular chip the names would still be GPIO_0, GPIO_1
> and GPIO_2 (possibly with a suffix depending on which of the two
> controllers they hang off of) however, which may not be much better than
> using chip->base + offset. I'd assume this to be the common case.
The chardev names are pertaining to a certain device like
"gpiochip1" already so the names only need to be unique
per-instance.
If we made them globally unique we could just use the .names
in gpiochip anyways, but that seems ugly.
What about suppling
gpiochip_set_names(struct gpio_chip *gc,
char **names);
As the size of the array is implicit from ngpios and the function
would be kernel-internal anyways.
> Device-tree overlays is what I see a real use for where different
> overlays can be applied based on topology data to describe what is
> actually connected to a pin in a specific setup. And that seems like
> something that could be useful for normal (static) DT systems as well
> (e.g. describe what's actually connected to those Beaglebone pins).
Yeah these overlays ... discussed that a lot recently.
It fits the Beaglebone indeed.
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 8+ messages in thread
* Re: [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
2016-10-26 11:50 ` Linus Walleij
@ 2016-10-26 12:16 ` Johan Hovold
0 siblings, 0 replies; 8+ messages in thread
From: Johan Hovold @ 2016-10-26 12:16 UTC (permalink / raw)
To: Linus Walleij
Cc: Johan Hovold, Martyn Welch, Alexandre Courbot, Greg Kroah-Hartman,
linux-usb@vger.kernel.org, linux-gpio@vger.kernel.org,
Karl Palsson, Konstantin Shkolnyy, Peter Senna Tschudin
On Wed, Oct 26, 2016 at 01:50:14PM +0200, Linus Walleij wrote:
> On Wed, Oct 26, 2016 at 11:09 AM, Johan Hovold <johan@kernel.org> wrote:
> > On Tue, Oct 25, 2016 at 11:34:40AM +0200, Linus Walleij wrote:
>
> >> I was thinking on either reusing the .names field of the
> >> struct gpiochip to name the lines for the userspace
> >> chardev. With the sideeffect of the names getting reflected
> >> also to sysfs if using that.
> >
> > Simply reusing .names would cause problems since the old sysfs name
> > space is flat, so you would be unable to use more than one pluggable
> > expander (unless also encoding the topology in the name).
>
> Hm it seems we should actually #ifdef that field for sysfs then,
> it has no applicability outside the legacy sysfs.
Might make sense. If I remember correctly, this isn't the first time
we've had this discussion. ;)
> > Providing default names from the driver could perhaps be useful at
> > times. For this particular chip the names would still be GPIO_0, GPIO_1
> > and GPIO_2 (possibly with a suffix depending on which of the two
> > controllers they hang off of) however, which may not be much better than
> > using chip->base + offset. I'd assume this to be the common case.
>
> The chardev names are pertaining to a certain device like
> "gpiochip1" already so the names only need to be unique
> per-instance.
Yeah, I was referring to the legacy sysfs interface above.
> If we made them globally unique we could just use the .names
> in gpiochip anyways, but that seems ugly.
Agreed.
> What about suppling
>
> gpiochip_set_names(struct gpio_chip *gc,
> char **names);
>
> As the size of the array is implicit from ngpios and the function
> would be kernel-internal anyways.
You'd at least want to provide a way to set these names before the
gpiochip is registered if you go down this path.
But the point I was trying to make above was whether it was at all worth
it. If the pins are truly general purpose, you would typically not be
providing any more information than the pin chip-offset (e.g. GPIO_1).
But sure, some device might use "a", "b", "c, or whatever...
> > Device-tree overlays is what I see a real use for where different
> > overlays can be applied based on topology data to describe what is
> > actually connected to a pin in a specific setup. And that seems like
> > something that could be useful for normal (static) DT systems as well
> > (e.g. describe what's actually connected to those Beaglebone pins).
>
> Yeah these overlays ... discussed that a lot recently.
> It fits the Beaglebone indeed.
Not just Beaglebone. It would be generally useful for anything
hotpluggable (e.g. we intended to use this for Greybus) where you need
to describe something non-discoverable (e.g. i2c, spi, gpio) that's
sitting behind a controller on a discoverable bus (e.g. greybus or usb).
Thanks,
Johan
^ permalink raw reply [flat|nested] 8+ messages in thread
* Re: [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105
2016-10-25 9:34 ` Linus Walleij
[not found] ` <CACRpkdab5d71TgrTD-4U95R6MvWdFcaqRcGpPS0D8sExKi=b3g-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
@ 2016-10-31 10:17 ` Martyn Welch
1 sibling, 0 replies; 8+ messages in thread
From: Martyn Welch @ 2016-10-31 10:17 UTC (permalink / raw)
To: Linus Walleij
Cc: Johan Hovold, Alexandre Courbot, Greg Kroah-Hartman,
linux-usb@vger.kernel.org, linux-gpio@vger.kernel.org,
Karl Palsson, Konstantin Shkolnyy, Peter Senna Tschudin
On Tue, Oct 25, 2016 at 11:34:40AM +0200, Linus Walleij wrote:
> Good work on this patch, nice that it got merged.
>
> I was just thinking that as an add-on, you may want to name
> the gpio lines so they have meaningful names in userspace
> when you use this with the chardev (I have reasons to believe
> these GPIOs will be used from userspace, tell me if that
> is wrong).
>
Yeah, they are.
> We currently support naming lines for devicetree and
> ACPI (in -next).
>
I'm not sure this would be a good fit for the current use case I've been
working on, as I understand there might be an arbitary number of devices
plugged in. The same chip may also get used in more than one way (in the
current use case, the Vendor/Product IDs actually get get to determine the
use case.
Originally I did name the GPIO as either SCI or ECI, in the case of the
CP2105, being able to distinguish between the two banks can be helpful
during debug (but isn't essential and didn't actually seem to help when
trying to programatically parse though the available banks of GPIO in user
space to find the ones that were interesting). However this doesn't
translate so well to the other chips in the CP210x family as the GPIO is
implemented differently for the majority of those (they don't mux pins from
the serial ports).
I have seen such chips actually used inside of units, so being able to name
the GPIO would be quite useful there, though that naming would need to only
be applied to specific devices and not to other devices plugged in
externally.
Martyn
^ permalink raw reply [flat|nested] 8+ messages in thread
end of thread, other threads:[~2016-10-31 10:17 UTC | newest]
Thread overview: 8+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2016-10-20 8:13 [PATCH v10 1/1] USB: serial: cp210x: Adding GPIO support for CP2105 Martyn Welch
[not found] ` <33cb529dad5c28a135e9e21460582c3cc4e6d4b5.1476950450.git.martyn.welch-ZGY8ohtN/8pPYcu2f3hruQ@public.gmane.org>
2016-10-20 8:49 ` Johan Hovold
2016-10-20 13:31 ` Martyn Welch
2016-10-25 9:34 ` Linus Walleij
[not found] ` <CACRpkdab5d71TgrTD-4U95R6MvWdFcaqRcGpPS0D8sExKi=b3g-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
2016-10-26 9:09 ` Johan Hovold
2016-10-26 11:50 ` Linus Walleij
2016-10-26 12:16 ` Johan Hovold
2016-10-31 10:17 ` Martyn Welch
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).