2012-10-17 12:37:40

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 00/15 v5] gpio: Add block GPIO

This set of patches adds:

* Block GPIO API to gpiolib
* Sysfs support for GPIO API, to provide userland access
* Devicetree support to instantiate GPIO blocks via DT
* Example implementations in several gpio drivers since they need
special accessor functions for block wise GPIO access
* Fix for race condition in gpiolib on device creation

Signed-off-by: Roland Stigge <[email protected]>
--

Changes since v4:
* Documented word width
* Bugfix: export/unexport on register/unregister
* Using default dev_attrs for gpio_block_class
* Fix gpiolib: race condition on device creation
* Added driver support for ucb14500, vt8500, xilinx

Changes since v3:
* Added driver support for pca953x, em, pl061, max732x, pcf857x
* Coding style improvements
* Fixed krealloc memory leak in error case
* sysfs: values in hex
* Register blocks in a list
* Narrowing lock scope
* Use S_IWUSR and S_IRUGO instead of direct octal values
* Use for_each_set_bit()
* Change from unsigned to unsigned long for masks and values

Changes since v2:
* Added sysfs support
* Added devicetree support
* Added support for lpc32xx, generic
* Added functions for GPIO block registration
* Added more error checking
* Bit remapping bugfix

Changes since v1:
* API change to 32/64 bit word, bit masks

Thanks to Ryan Mallon, Linus Walleij, Stijn Devriendt, Jean-Christophe
Plagniol-Villard, Mark Brown and Greg Kroah-Hartman for reviewing!

Roland Stigge (15):
gpio: Add a block GPIO API to gpiolib
gpio: Add sysfs support to block GPIO API
gpiolib: Fix default attributes for class
gpio: Add device tree support to block GPIO API
gpio-max730x: Add block GPIO API
gpio-lpc32xx: Add block GPIO API
gpio-generic: Add block GPIO API
gpio-pca953x: Add block GPIO API
gpio-em: Add block GPIO API
gpio-pl061: Add block GPIO API
gpio-max732x: Add block GPIO API
gpio-pcf857x: Add block GPIO API
gpio-xilinx: Add block GPIO API
gpio-vt8500: Add block GPIO API
gpio-ucb1400: Add block GPIO API

Documentation/ABI/testing/sysfs-gpio | 6
Documentation/devicetree/bindings/gpio/gpio-block.txt | 36 +
Documentation/gpio.txt | 47 +
drivers/gpio/Makefile | 1
drivers/gpio/gpio-em.c | 23
drivers/gpio/gpio-generic.c | 56 +
drivers/gpio/gpio-lpc32xx.c | 82 ++
drivers/gpio/gpio-max730x.c | 61 ++
drivers/gpio/gpio-max732x.c | 59 ++
drivers/gpio/gpio-pca953x.c | 64 ++
drivers/gpio/gpio-pcf857x.c | 24
drivers/gpio/gpio-pl061.c | 17
drivers/gpio/gpio-ucb1400.c | 23
drivers/gpio/gpio-vt8500.c | 24
drivers/gpio/gpio-xilinx.c | 44 +
drivers/gpio/gpioblock-of.c | 84 ++
drivers/gpio/gpiolib.c | 510 ++++++++++++++++--
include/asm-generic/gpio.h | 26
include/linux/gpio.h | 87 +++
19 files changed, 1228 insertions(+), 46 deletions(-)


2012-10-17 12:37:49

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 10/15 v5] gpio-pl061: Add block GPIO API

This patch adds block GPIO API support to the gpio-pl061 driver.

Signed-off-by: Roland Stigge <[email protected]>
---
drivers/gpio/gpio-pl061.c | 17 +++++++++++++++++
1 file changed, 17 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-pl061.c
+++ linux-2.6/drivers/gpio/gpio-pl061.c
@@ -123,6 +123,21 @@ static void pl061_set_value(struct gpio_
writeb(!!value << offset, chip->base + (1 << (offset + 2)));
}

+static unsigned long pl061_get_block(struct gpio_chip *gc, unsigned long mask)
+{
+ struct pl061_gpio *chip = container_of(gc, struct pl061_gpio, gc);
+
+ return !!readb(chip->base + (mask << 2));
+}
+
+static void pl061_set_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ struct pl061_gpio *chip = container_of(gc, struct pl061_gpio, gc);
+
+ writeb(values & mask, chip->base + (mask << 2));
+}
+
static int pl061_to_irq(struct gpio_chip *gc, unsigned offset)
{
struct pl061_gpio *chip = container_of(gc, struct pl061_gpio, gc);
@@ -256,6 +271,8 @@ static int pl061_probe(struct amba_devic
chip->gc.direction_output = pl061_direction_output;
chip->gc.get = pl061_get_value;
chip->gc.set = pl061_set_value;
+ chip->gc.get_block = pl061_get_block;
+ chip->gc.set_block = pl061_set_block;
chip->gc.to_irq = pl061_to_irq;
chip->gc.ngpio = PL061_GPIO_NR;
chip->gc.label = dev_name(&dev->dev);

2012-10-17 12:37:52

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 13/15 v5] gpio-xilinx: Add block GPIO API

This patch adds block GPIO API support to the gpio-xilinx driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-xilinx.c | 44 ++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 44 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-xilinx.c
+++ linux-2.6/drivers/gpio/gpio-xilinx.c
@@ -49,6 +49,21 @@ static int xgpio_get(struct gpio_chip *g
}

/**
+ * xgpio_get_block - Read a block of specified signals of the GPIO device.
+ * @gc: Pointer to gpio_chip device structure.
+ * @mask: Bit mask (bit 0 == 0th GPIO) for GPIOs to get
+ *
+ * This function reads a block of specified signal of the GPIO device, returned
+ * as a bit mask, each bit representing a GPIO
+ */
+static unsigned long xgpio_get_block(struct gpio_chip *gc, unsigned long mask)
+{
+ struct of_mm_gpio_chip *mm_gc = to_of_mm_gpio_chip(gc);
+
+ return in_be32(mm_gc->regs + XGPIO_DATA_OFFSET) & mask;
+}
+
+/**
* xgpio_set - Write the specified signal of the GPIO device.
* @gc: Pointer to gpio_chip device structure.
* @gpio: GPIO signal number.
@@ -77,6 +92,33 @@ static void xgpio_set(struct gpio_chip *
}

/**
+ * xgpio_set_block - Write a block of specified signals of the GPIO device.
+ * @gc: Pointer to gpio_chip device structure.
+ * @mask: Bit mask (bit 0 == 0th GPIO) for GPIOs to set
+ * @values: Bit mapped values
+ *
+ * This function writes the specified values in to the specified signals of the
+ * GPIO device.
+ */
+static void xgpio_set_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ unsigned long flags;
+ struct of_mm_gpio_chip *mm_gc = to_of_mm_gpio_chip(gc);
+ struct xgpio_instance *chip =
+ container_of(mm_gc, struct xgpio_instance, mmchip);
+
+ spin_lock_irqsave(&chip->gpio_lock, flags);
+
+ chip->gpio_state &= ~mask;
+ chip->gpio_state |= mask & values;
+
+ out_be32(mm_gc->regs + XGPIO_DATA_OFFSET, chip->gpio_state);
+
+ spin_unlock_irqrestore(&chip->gpio_lock, flags);
+}
+
+/**
* xgpio_dir_in - Set the direction of the specified GPIO signal as input.
* @gc: Pointer to gpio_chip device structure.
* @gpio: GPIO signal number.
@@ -195,6 +237,8 @@ static int __devinit xgpio_of_probe(stru
chip->mmchip.gc.direction_output = xgpio_dir_out;
chip->mmchip.gc.get = xgpio_get;
chip->mmchip.gc.set = xgpio_set;
+ chip->mmchip.gc.get_block = xgpio_get_block;
+ chip->mmchip.gc.set_block = xgpio_set_block;

chip->mmchip.save_regs = xgpio_save_regs;

2012-10-17 12:37:58

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 14/15 v5] gpio-vt8500: Add block GPIO API

This patch adds block GPIO API support to the gpio-vt8500 driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-vt8500.c | 24 ++++++++++++++++++++++++
1 file changed, 24 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-vt8500.c
+++ linux-2.6/drivers/gpio/gpio-vt8500.c
@@ -209,6 +209,28 @@ static void vt8500_gpio_set_value(struct
writel_relaxed(val, vt8500_chip->base + vt8500_chip->regs->data_out);
}

+static unsigned long vt8500_gpio_get_block(struct gpio_chip *chip,
+ unsigned long mask)
+{
+ struct vt8500_gpio_chip *vt8500_chip = to_vt8500(chip);
+
+ return readl_relaxed(vt8500_chip->base + vt8500_chip->regs->data_in) &
+ mask;
+}
+
+static void vt8500_gpio_set_block(struct gpio_chip *chip, unsigned long mask,
+ unsigned long values)
+{
+ struct vt8500_gpio_chip *vt8500_chip = to_vt8500(chip);
+
+ u32 val = readl_relaxed(vt8500_chip->base +
+ vt8500_chip->regs->data_out);
+ val &= ~mask;
+ val |= values & mask;
+
+ writel_relaxed(val, vt8500_chip->base + vt8500_chip->regs->data_out);
+}
+
static int vt8500_of_xlate(struct gpio_chip *gc,
const struct of_phandle_args *gpiospec, u32 *flags)
{
@@ -251,6 +273,8 @@ static int vt8500_add_chips(struct platf
chip->direction_output = vt8500_gpio_direction_output;
chip->get = vt8500_gpio_get_value;
chip->set = vt8500_gpio_set_value;
+ chip->get_block = vt8500_gpio_get_block;
+ chip->set_block = vt8500_gpio_set_block;
chip->can_sleep = 0;
chip->base = pin_cnt;
chip->ngpio = data->banks[i].ngpio;

2012-10-17 12:38:05

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 04/15 v5] gpio: Add device tree support to block GPIO API

This patch adds device tree support to the block GPIO API.

Signed-off-by: Roland Stigge <[email protected]>

---
Documentation/devicetree/bindings/gpio/gpio-block.txt | 36 +++++++
drivers/gpio/Makefile | 1
drivers/gpio/gpioblock-of.c | 84 ++++++++++++++++++
3 files changed, 121 insertions(+)

--- /dev/null
+++ linux-2.6/Documentation/devicetree/bindings/gpio/gpio-block.txt
@@ -0,0 +1,36 @@
+Block GPIO definition
+=====================
+
+This binding specifies arbitrary blocks of gpios, combining gpios from one or
+more GPIO controllers together, to form a word for r/w access.
+
+Required property:
+- compatible: must be "linux,gpio-block"
+
+Required subnodes:
+- the name will be the registered name of the block
+- property "gpios" is a list of gpios for the respective block
+
+Example:
+
+ blockgpio {
+ compatible = "linux,gpio-block";
+
+ block0 {
+ gpios = <&gpio 3 0 0>,
+ <&gpio 3 1 0>;
+ };
+ block1 {
+ gpios = <&gpio 4 1 0>,
+ <&gpio 4 3 0>,
+ <&gpio 4 2 0>,
+ <&gpio 4 4 0>,
+ <&gpio 4 5 0>,
+ <&gpio 4 6 0>,
+ <&gpio 4 7 0>,
+ <&gpio 4 8 0>,
+ <&gpio 4 9 0>,
+ <&gpio 4 10 0>,
+ <&gpio 4 19 0>;
+ };
+ };
--- linux-2.6.orig/drivers/gpio/Makefile
+++ linux-2.6/drivers/gpio/Makefile
@@ -4,6 +4,7 @@ ccflags-$(CONFIG_DEBUG_GPIO) += -DDEBUG

obj-$(CONFIG_GPIOLIB) += gpiolib.o devres.o
obj-$(CONFIG_OF_GPIO) += gpiolib-of.o
+obj-$(CONFIG_OF_GPIO) += gpioblock-of.o

# Device drivers. Generally keep list sorted alphabetically
obj-$(CONFIG_GPIO_GENERIC) += gpio-generic.o
--- /dev/null
+++ linux-2.6/drivers/gpio/gpioblock-of.c
@@ -0,0 +1,84 @@
+/*
+ * OF implementation for Block GPIO
+ *
+ * Copyright (C) 2012 Roland Stigge <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ */
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/platform_device.h>
+#include <linux/gpio.h>
+#include <linux/of.h>
+#include <linux/of_gpio.h>
+#include <linux/module.h>
+#include <linux/slab.h>
+#include <linux/err.h>
+
+static int __devinit gpioblock_of_probe(struct platform_device *pdev)
+{
+ struct device_node *block;
+ unsigned *gpios;
+ int ngpio;
+ int ret;
+ struct gpio_block *gb;
+
+ for_each_available_child_of_node(pdev->dev.of_node, block) {
+ int i;
+
+ ngpio = of_gpio_count(block);
+ gpios = kzalloc(ngpio * sizeof(*gpios), GFP_KERNEL);
+ if (!gpios)
+ return -ENOMEM;
+ for (i = 0; i < ngpio; i++) {
+ ret = of_get_gpio(block, i);
+ if (ret < 0)
+ return ret; /* expect -EPROBE_DEFER */
+ gpios[i] = ret;
+ }
+ gb = gpio_block_create(gpios, ngpio, block->name);
+ if (IS_ERR(gb)) {
+ dev_err(&pdev->dev,
+ "Error creating GPIO block from device tree\n");
+ return PTR_ERR(gb);
+ }
+ ret = gpio_block_register(gb);
+ if (ret < 0) {
+ gpio_block_free(gb);
+ return ret;
+ }
+ kfree(gpios);
+ dev_info(&pdev->dev, "Registered gpio block %s: %d gpios\n",
+ block->name, ngpio);
+ }
+ return 0;
+}
+
+#ifdef CONFIG_OF
+static struct of_device_id gpioblock_of_match[] __devinitdata = {
+ { .compatible = "linux,gpio-block", },
+ { },
+};
+MODULE_DEVICE_TABLE(of, gpioblock_of_match);
+#endif
+
+static struct platform_driver gpioblock_of_driver = {
+ .driver = {
+ .name = "gpio-block",
+ .owner = THIS_MODULE,
+ .of_match_table = of_match_ptr(gpioblock_of_match),
+
+ },
+ .probe = gpioblock_of_probe,
+};
+
+module_platform_driver(gpioblock_of_driver);
+
+MODULE_DESCRIPTION("GPIO Block driver");
+MODULE_AUTHOR("Roland Stigge <[email protected]>");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:gpioblock-of");

2012-10-17 12:38:31

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 15/15 v5] gpio-ucb1400: Add block GPIO API

This patch adds block GPIO API support to the gpio-ucb1400 driver.

Signed-off-by: Roland Stigge <[email protected]>
---
drivers/gpio/gpio-ucb1400.c | 23 +++++++++++++++++++++++
1 file changed, 23 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-ucb1400.c
+++ linux-2.6/drivers/gpio/gpio-ucb1400.c
@@ -45,6 +45,27 @@ static void ucb1400_gpio_set(struct gpio
ucb1400_gpio_set_value(gpio->ac97, off, val);
}

+static unsigned long ucb1400_gpio_get_block(struct gpio_chip *gc,
+ unsigned long mask)
+{
+ struct ucb1400_gpio *gpio;
+ gpio = container_of(gc, struct ucb1400_gpio, gc);
+ return ucb1400_reg_read(gpio->ac97, UCB_IO_DATA) & mask;
+}
+
+static void ucb1400_gpio_set_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ struct ucb1400_gpio *gpio;
+ u16 tmp;
+ gpio = container_of(gc, struct ucb1400_gpio, gc);
+
+ tmp = ucb1400_reg_read(gpio->ac97, UCB_IO_DATA) & ~mask;
+ tmp |= values & mask;
+
+ ucb1400_reg_write(gpio->ac97, UCB_IO_DATA, tmp);
+}
+
static int ucb1400_gpio_probe(struct platform_device *dev)
{
struct ucb1400_gpio *ucb = dev->dev.platform_data;
@@ -66,6 +87,8 @@ static int ucb1400_gpio_probe(struct pla
ucb->gc.direction_output = ucb1400_gpio_dir_out;
ucb->gc.get = ucb1400_gpio_get;
ucb->gc.set = ucb1400_gpio_set;
+ ucb->gc.get_block = ucb1400_gpio_get_block;
+ ucb->gc.set_block = ucb1400_gpio_set_block;
ucb->gc.can_sleep = 1;

err = gpiochip_add(&ucb->gc);

2012-10-17 12:38:48

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 12/15 v5] gpio-pcf857x: Add block GPIO API

This patch adds block GPIO API support to the gpio-pcf857x driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-pcf857x.c | 24 ++++++++++++++++++++++++
1 file changed, 24 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-pcf857x.c
+++ linux-2.6/drivers/gpio/gpio-pcf857x.c
@@ -158,6 +158,28 @@ static void pcf857x_set(struct gpio_chip
pcf857x_output(chip, offset, value);
}

+static unsigned long pcf857x_get_block(struct gpio_chip *chip,
+ unsigned long mask)
+{
+ struct pcf857x *gpio = container_of(chip, struct pcf857x, chip);
+ int value;
+
+ value = gpio->read(gpio->client);
+ return (value < 0) ? 0 : (value & mask);
+}
+
+static void pcf857x_set_block(struct gpio_chip *chip, unsigned long mask,
+ unsigned long values)
+{
+ struct pcf857x *gpio = container_of(chip, struct pcf857x, chip);
+
+ mutex_lock(&gpio->lock);
+ gpio->out &= ~mask;
+ gpio->out |= values & mask;
+ gpio->write(gpio->client, gpio->out);
+ mutex_unlock(&gpio->lock);
+}
+
/*-------------------------------------------------------------------------*/

static int pcf857x_to_irq(struct gpio_chip *chip, unsigned offset)
@@ -280,6 +302,8 @@ static int pcf857x_probe(struct i2c_clie
gpio->chip.owner = THIS_MODULE;
gpio->chip.get = pcf857x_get;
gpio->chip.set = pcf857x_set;
+ gpio->chip.get_block = pcf857x_get_block;
+ gpio->chip.set_block = pcf857x_set_block;
gpio->chip.direction_input = pcf857x_input;
gpio->chip.direction_output = pcf857x_output;
gpio->chip.ngpio = id->driver_data;

2012-10-17 12:39:09

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 11/15 v5] gpio-max732x: Add block GPIO API

This patch adds block GPIO API support to the gpio-max732x driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-max732x.c | 59 ++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 59 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-max732x.c
+++ linux-2.6/drivers/gpio/gpio-max732x.c
@@ -219,6 +219,63 @@ out:
mutex_unlock(&chip->lock);
}

+static unsigned long max732x_gpio_get_block(struct gpio_chip *gc,
+ unsigned long mask)
+{
+ struct max732x_chip *chip;
+ uint8_t lo = 0;
+ uint8_t hi = 0;
+ int ret;
+
+ chip = container_of(gc, struct max732x_chip, gpio_chip);
+
+ if (mask & 0xFF) {
+ ret = max732x_readb(chip, is_group_a(chip, 0), &lo);
+ if (ret < 0)
+ return 0;
+ }
+ if (mask & 0xFF00) {
+ ret = max732x_readb(chip, is_group_a(chip, 8), &hi);
+ if (ret < 0)
+ return 0;
+ }
+
+ return (((unsigned long)hi << 8) | lo) & mask;
+}
+
+static void max732x_gpio_set_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ struct max732x_chip *chip;
+ uint8_t reg_out;
+ uint8_t lo_mask = mask & 0xFF;
+ uint8_t hi_mask = (mask >> 8) & 0xFF;
+ int ret;
+
+ chip = container_of(gc, struct max732x_chip, gpio_chip);
+
+ mutex_lock(&chip->lock);
+
+ if (lo_mask) {
+ reg_out = (chip->reg_out[0] & ~lo_mask) | (values & lo_mask);
+ ret = max732x_writeb(chip, is_group_a(chip, 0), reg_out);
+ if (ret < 0)
+ goto out;
+ chip->reg_out[0] = reg_out;
+ }
+ if (hi_mask) {
+ reg_out = (chip->reg_out[1] & ~hi_mask) |
+ ((values >> 8) & hi_mask);
+ ret = max732x_writeb(chip, is_group_a(chip, 8), reg_out);
+ if (ret < 0)
+ goto out;
+ chip->reg_out[1] = reg_out;
+ }
+
+out:
+ mutex_unlock(&chip->lock);
+}
+
static int max732x_gpio_direction_input(struct gpio_chip *gc, unsigned off)
{
struct max732x_chip *chip;
@@ -562,8 +619,10 @@ static int __devinit max732x_setup_gpio(
if (chip->dir_output) {
gc->direction_output = max732x_gpio_direction_output;
gc->set = max732x_gpio_set_value;
+ gc->set_block = max732x_gpio_set_block;
}
gc->get = max732x_gpio_get_value;
+ gc->get_block = max732x_gpio_get_block;
gc->can_sleep = 1;

gc->base = gpio_start;

2012-10-17 12:37:47

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 03/15 v5] gpiolib: Fix default attributes for class

There is a race condition between creating a gpio or gpiochip device and adding
default attribues. This patch fixes this by defining the default attributes as
dev_attrs of the class. For this, it was necessary to create a separate
gpiochip_class besides gpio_class.

Signed-off-by: Roland Stigge <[email protected]>
---
drivers/gpio/gpiolib.c | 79 +++++++++++++++++++++----------------------------
1 file changed, 34 insertions(+), 45 deletions(-)

--- linux-2.6.orig/drivers/gpio/gpiolib.c
+++ linux-2.6/drivers/gpio/gpiolib.c
@@ -321,9 +321,6 @@ static ssize_t gpio_value_store(struct d
return status;
}

-static const DEVICE_ATTR(value, 0644,
- gpio_value_show, gpio_value_store);
-
static irqreturn_t gpio_sysfs_irq(int irq, void *priv)
{
struct sysfs_dirent *value_sd = priv;
@@ -544,19 +541,6 @@ static ssize_t gpio_active_low_store(str
return status ? : size;
}

-static const DEVICE_ATTR(active_low, 0644,
- gpio_active_low_show, gpio_active_low_store);
-
-static const struct attribute *gpio_attrs[] = {
- &dev_attr_value.attr,
- &dev_attr_active_low.attr,
- NULL,
-};
-
-static const struct attribute_group gpio_attr_group = {
- .attrs = (struct attribute **) gpio_attrs,
-};
-
/*
* /sys/class/gpio/gpiochipN/
* /base ... matching gpio_chip.base (N)
@@ -571,7 +555,6 @@ static ssize_t chip_base_show(struct dev

return sprintf(buf, "%d\n", chip->base);
}
-static DEVICE_ATTR(base, 0444, chip_base_show, NULL);

static ssize_t chip_label_show(struct device *dev,
struct device_attribute *attr, char *buf)
@@ -580,7 +563,6 @@ static ssize_t chip_label_show(struct de

return sprintf(buf, "%s\n", chip->label ? : "");
}
-static DEVICE_ATTR(label, 0444, chip_label_show, NULL);

static ssize_t chip_ngpio_show(struct device *dev,
struct device_attribute *attr, char *buf)
@@ -589,18 +571,6 @@ static ssize_t chip_ngpio_show(struct de

return sprintf(buf, "%u\n", chip->ngpio);
}
-static DEVICE_ATTR(ngpio, 0444, chip_ngpio_show, NULL);
-
-static const struct attribute *gpiochip_attrs[] = {
- &dev_attr_base.attr,
- &dev_attr_label.attr,
- &dev_attr_ngpio.attr,
- NULL,
-};
-
-static const struct attribute_group gpiochip_attr_group = {
- .attrs = (struct attribute **) gpiochip_attrs,
-};

/*
* /sys/class/gpio/export ... write-only
@@ -677,11 +647,32 @@ static struct class_attribute gpio_class
__ATTR_NULL,
};

+static struct device_attribute gpio_attrs[] = {
+ __ATTR(active_low, 0644, gpio_active_low_show, gpio_active_low_store),
+ __ATTR(value, 0644, gpio_value_show, gpio_value_store),
+ __ATTR_NULL,
+};
+
static struct class gpio_class = {
.name = "gpio",
.owner = THIS_MODULE,

- .class_attrs = gpio_class_attrs,
+ .class_attrs = gpio_class_attrs,
+ .dev_attrs = gpio_attrs,
+};
+
+static struct device_attribute gpiochip_attrs[] = {
+ __ATTR(label, 0444, chip_label_show, NULL),
+ __ATTR(base, 0444, chip_base_show, NULL),
+ __ATTR(ngpio, 0444, chip_ngpio_show, NULL),
+ __ATTR_NULL,
+};
+
+static struct class gpiochip_class = {
+ .name = "gpiochip",
+ .owner = THIS_MODULE,
+
+ .dev_attrs = gpiochip_attrs,
};


@@ -738,10 +729,7 @@ int gpio_export(unsigned gpio, bool dire
dev = device_create(&gpio_class, desc->chip->dev, MKDEV(0, 0),
desc, ioname ? ioname : "gpio%u", gpio);
if (!IS_ERR(dev)) {
- status = sysfs_create_group(&dev->kobj,
- &gpio_attr_group);
-
- if (!status && direction_may_change)
+ if (direction_may_change)
status = device_create_file(dev,
&dev_attr_direction);

@@ -911,25 +899,22 @@ EXPORT_SYMBOL_GPL(gpio_unexport);

static int gpiochip_export(struct gpio_chip *chip)
{
- int status;
+ int status = 0;
struct device *dev;

/* Many systems register gpio chips for SOC support very early,
* before driver model support is available. In those cases we
* export this later, in gpiolib_sysfs_init() ... here we just
- * verify that _some_ field of gpio_class got initialized.
+ * verify that _some_ field of gpiochip_class got initialized.
*/
- if (!gpio_class.p)
+ if (!gpiochip_class.p)
return 0;

/* use chip->base for the ID; it's already known to be unique */
mutex_lock(&sysfs_lock);
- dev = device_create(&gpio_class, chip->dev, MKDEV(0, 0), chip,
- "gpiochip%d", chip->base);
- if (!IS_ERR(dev)) {
- status = sysfs_create_group(&dev->kobj,
- &gpiochip_attr_group);
- } else
+ dev = device_create(&gpiochip_class, chip->dev, MKDEV(0, 0), chip,
+ "gpiochip%d", chip->base);
+ if (IS_ERR(dev))
status = PTR_ERR(dev);
chip->exported = (status == 0);
mutex_unlock(&sysfs_lock);
@@ -957,7 +942,7 @@ static void gpiochip_unexport(struct gpi
struct device *dev;

mutex_lock(&sysfs_lock);
- dev = class_find_device(&gpio_class, NULL, chip, match_export);
+ dev = class_find_device(&gpiochip_class, NULL, chip, match_export);
if (dev) {
put_device(dev);
device_unregister(dev);
@@ -1190,6 +1175,10 @@ static int __init gpiolib_sysfs_init(voi
if (status < 0)
return status;

+ status = class_register(&gpiochip_class);
+ if (status < 0)
+ return status;
+
status = class_register(&gpio_block_class);
if (status < 0)
return status;

2012-10-17 12:39:36

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 09/15 v5] gpio-em: Add block GPIO API

This patch adds block GPIO API support to the gpio-em driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-em.c | 23 +++++++++++++++++++++++
1 file changed, 23 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-em.c
+++ linux-2.6/drivers/gpio/gpio-em.c
@@ -203,6 +203,27 @@ static void em_gio_set(struct gpio_chip
__em_gio_set(chip, GIO_OH, offset - 16, value);
}

+static unsigned long em_gio_get_block(struct gpio_chip *chip,
+ unsigned long mask)
+{
+ return (int)(em_gio_read(gpio_to_priv(chip), GIO_I) & mask);
+}
+
+static void em_gio_set_block(struct gpio_chip *chip, unsigned long mask,
+ unsigned long values)
+{
+ unsigned long mask_ol = mask & 0xFFFF;
+ unsigned long mask_oh = mask >> 16;
+
+ unsigned long values_ol = values & mask_ol;
+ unsigned long values_oh = (values >> 16) & mask_oh;
+
+ em_gio_write(gpio_to_priv(chip), GIO_OL,
+ mask_ol << 16 | values_ol);
+ em_gio_write(gpio_to_priv(chip), GIO_OH,
+ mask_oh << 16 | values_oh);
+}
+
static int em_gio_direction_output(struct gpio_chip *chip, unsigned offset,
int value)
{
@@ -317,8 +338,10 @@ static int __devinit em_gio_probe(struct
gpio_chip = &p->gpio_chip;
gpio_chip->direction_input = em_gio_direction_input;
gpio_chip->get = em_gio_get;
+ gpio_chip->get_block = em_gio_get_block;
gpio_chip->direction_output = em_gio_direction_output;
gpio_chip->set = em_gio_set;
+ gpio_chip->set_block = em_gio_set_block;
gpio_chip->to_irq = em_gio_to_irq;
gpio_chip->label = name;
gpio_chip->owner = THIS_MODULE;

2012-10-17 12:40:08

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 06/15 v5] gpio-lpc32xx: Add block GPIO API

This patch adds block GPIO API support to the LPC32xx driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-lpc32xx.c | 82 ++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 82 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-lpc32xx.c
+++ linux-2.6/drivers/gpio/gpio-lpc32xx.c
@@ -297,6 +297,22 @@ static int lpc32xx_gpio_get_value_p3(str
return __get_gpio_state_p3(group, pin);
}

+static unsigned long lpc32xx_gpio_get_block_p3(struct gpio_chip *chip,
+ unsigned long mask)
+{
+ struct lpc32xx_gpio_chip *group = to_lpc32xx_gpio(chip);
+ u32 bits = __raw_readl(group->gpio_grp->inp_state);
+
+ /* In P3_INP_STATE, the 6 GPIOs are scattered over the register,
+ * rearranging to bits 0-5
+ */
+ bits >>= 10;
+ bits &= 0x401F;
+ bits |= (bits & 0x4000) >> 9;
+
+ return bits & mask & 0x3F;
+}
+
static int lpc32xx_gpi_get_value(struct gpio_chip *chip, unsigned pin)
{
struct lpc32xx_gpio_chip *group = to_lpc32xx_gpio(chip);
@@ -304,6 +320,15 @@ static int lpc32xx_gpi_get_value(struct
return __get_gpi_state_p3(group, pin);
}

+static unsigned long lpc32xx_gpi_get_block(struct gpio_chip *chip,
+ unsigned long mask)
+{
+ struct lpc32xx_gpio_chip *group = to_lpc32xx_gpio(chip);
+ u32 bits = __raw_readl(group->gpio_grp->inp_state);
+
+ return bits & mask;
+}
+
static int lpc32xx_gpio_dir_output_p012(struct gpio_chip *chip, unsigned pin,
int value)
{
@@ -351,6 +376,27 @@ static void lpc32xx_gpio_set_value_p3(st
__set_gpio_level_p3(group, pin, value);
}

+static void lpc32xx_gpio_set_block_p3(struct gpio_chip *chip,
+ unsigned long mask,
+ unsigned long values)
+{
+ struct lpc32xx_gpio_chip *group = to_lpc32xx_gpio(chip);
+ u32 set_bits = values & mask;
+ u32 clr_bits = ~values & mask;
+
+ /* States of GPIO 0-5 start at bit 25 */
+ set_bits <<= 25;
+ clr_bits <<= 25;
+
+ /* Note: On LPC32xx, GPOs can only be set at once or cleared at once,
+ * but not set and cleared at once
+ */
+ if (set_bits)
+ __raw_writel(set_bits, group->gpio_grp->outp_set);
+ if (clr_bits)
+ __raw_writel(clr_bits, group->gpio_grp->outp_clr);
+}
+
static void lpc32xx_gpo_set_value(struct gpio_chip *chip, unsigned pin,
int value)
{
@@ -366,6 +412,31 @@ static int lpc32xx_gpo_get_value(struct
return __get_gpo_state_p3(group, pin);
}

+static void lpc32xx_gpo_set_block(struct gpio_chip *chip, unsigned long mask,
+ unsigned long values)
+{
+ struct lpc32xx_gpio_chip *group = to_lpc32xx_gpio(chip);
+ u32 set_bits = values & mask;
+ u32 clr_bits = ~values & mask;
+
+ /* Note: On LPC32xx, GPOs can only be set at once or cleared at once,
+ * but not set and cleared at once
+ */
+ if (set_bits)
+ __raw_writel(set_bits, group->gpio_grp->outp_set);
+ if (clr_bits)
+ __raw_writel(clr_bits, group->gpio_grp->outp_clr);
+}
+
+static unsigned long lpc32xx_gpo_get_block(struct gpio_chip *chip,
+ unsigned long mask)
+{
+ struct lpc32xx_gpio_chip *group = to_lpc32xx_gpio(chip);
+ u32 bits = __raw_readl(group->gpio_grp->outp_state);
+
+ return bits & mask;
+}
+
static int lpc32xx_gpio_request(struct gpio_chip *chip, unsigned pin)
{
if (pin < chip->ngpio)
@@ -440,8 +511,10 @@ static struct lpc32xx_gpio_chip lpc32xx_
.label = "gpio_p0",
.direction_input = lpc32xx_gpio_dir_input_p012,
.get = lpc32xx_gpio_get_value_p012,
+ .get_block = lpc32xx_gpi_get_block,
.direction_output = lpc32xx_gpio_dir_output_p012,
.set = lpc32xx_gpio_set_value_p012,
+ .set_block = lpc32xx_gpo_set_block,
.request = lpc32xx_gpio_request,
.to_irq = lpc32xx_gpio_to_irq_p01,
.base = LPC32XX_GPIO_P0_GRP,
@@ -456,8 +529,10 @@ static struct lpc32xx_gpio_chip lpc32xx_
.label = "gpio_p1",
.direction_input = lpc32xx_gpio_dir_input_p012,
.get = lpc32xx_gpio_get_value_p012,
+ .get_block = lpc32xx_gpi_get_block,
.direction_output = lpc32xx_gpio_dir_output_p012,
.set = lpc32xx_gpio_set_value_p012,
+ .set_block = lpc32xx_gpo_set_block,
.request = lpc32xx_gpio_request,
.to_irq = lpc32xx_gpio_to_irq_p01,
.base = LPC32XX_GPIO_P1_GRP,
@@ -472,8 +547,10 @@ static struct lpc32xx_gpio_chip lpc32xx_
.label = "gpio_p2",
.direction_input = lpc32xx_gpio_dir_input_p012,
.get = lpc32xx_gpio_get_value_p012,
+ .get_block = lpc32xx_gpi_get_block,
.direction_output = lpc32xx_gpio_dir_output_p012,
.set = lpc32xx_gpio_set_value_p012,
+ .set_block = lpc32xx_gpo_set_block,
.request = lpc32xx_gpio_request,
.base = LPC32XX_GPIO_P2_GRP,
.ngpio = LPC32XX_GPIO_P2_MAX,
@@ -487,8 +564,10 @@ static struct lpc32xx_gpio_chip lpc32xx_
.label = "gpio_p3",
.direction_input = lpc32xx_gpio_dir_input_p3,
.get = lpc32xx_gpio_get_value_p3,
+ .get_block = lpc32xx_gpio_get_block_p3,
.direction_output = lpc32xx_gpio_dir_output_p3,
.set = lpc32xx_gpio_set_value_p3,
+ .set_block = lpc32xx_gpio_set_block_p3,
.request = lpc32xx_gpio_request,
.to_irq = lpc32xx_gpio_to_irq_gpio_p3,
.base = LPC32XX_GPIO_P3_GRP,
@@ -503,6 +582,7 @@ static struct lpc32xx_gpio_chip lpc32xx_
.label = "gpi_p3",
.direction_input = lpc32xx_gpio_dir_in_always,
.get = lpc32xx_gpi_get_value,
+ .get_block = lpc32xx_gpi_get_block,
.request = lpc32xx_gpio_request,
.to_irq = lpc32xx_gpio_to_irq_gpi_p3,
.base = LPC32XX_GPI_P3_GRP,
@@ -517,7 +597,9 @@ static struct lpc32xx_gpio_chip lpc32xx_
.label = "gpo_p3",
.direction_output = lpc32xx_gpio_dir_out_always,
.set = lpc32xx_gpo_set_value,
+ .set_block = lpc32xx_gpo_set_block,
.get = lpc32xx_gpo_get_value,
+ .get_block = lpc32xx_gpo_get_block,
.request = lpc32xx_gpio_request,
.base = LPC32XX_GPO_P3_GRP,
.ngpio = LPC32XX_GPO_P3_MAX,

2012-10-17 12:37:45

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 07/15 v5] gpio-generic: Add block GPIO API

This patch adds block GPIO API support to the gpio-generic driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-generic.c | 56 ++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 56 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-generic.c
+++ linux-2.6/drivers/gpio/gpio-generic.c
@@ -122,6 +122,13 @@ static int bgpio_get(struct gpio_chip *g
return bgc->read_reg(bgc->reg_dat) & bgc->pin2mask(bgc, gpio);
}

+static unsigned long bgpio_get_block(struct gpio_chip *gc, unsigned long mask)
+{
+ struct bgpio_chip *bgc = to_bgpio_chip(gc);
+
+ return bgc->read_reg(bgc->reg_dat) & mask;
+}
+
static void bgpio_set(struct gpio_chip *gc, unsigned int gpio, int val)
{
struct bgpio_chip *bgc = to_bgpio_chip(gc);
@@ -170,6 +177,51 @@ static void bgpio_set_set(struct gpio_ch
spin_unlock_irqrestore(&bgc->lock, flags);
}

+static void bgpio_set_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ struct bgpio_chip *bgc = to_bgpio_chip(gc);
+ unsigned long flags;
+
+ spin_lock_irqsave(&bgc->lock, flags);
+
+ bgc->data &= ~mask;
+ bgc->data |= values & mask;
+
+ bgc->write_reg(bgc->reg_dat, bgc->data);
+
+ spin_unlock_irqrestore(&bgc->lock, flags);
+}
+
+static void bgpio_set_with_clear_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ struct bgpio_chip *bgc = to_bgpio_chip(gc);
+ unsigned long set_bits = values & mask;
+ unsigned long clr_bits = ~values & mask;
+
+ if (set_bits)
+ bgc->write_reg(bgc->reg_set, set_bits);
+ if (clr_bits)
+ bgc->write_reg(bgc->reg_set, clr_bits);
+}
+
+static void bgpio_set_set_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ struct bgpio_chip *bgc = to_bgpio_chip(gc);
+ unsigned long flags;
+
+ spin_lock_irqsave(&bgc->lock, flags);
+
+ bgc->data &= ~mask;
+ bgc->data |= values & mask;
+
+ bgc->write_reg(bgc->reg_set, bgc->data);
+
+ spin_unlock_irqrestore(&bgc->lock, flags);
+}
+
static int bgpio_simple_dir_in(struct gpio_chip *gc, unsigned int gpio)
{
return 0;
@@ -317,14 +369,18 @@ static int bgpio_setup_io(struct bgpio_c
bgc->reg_set = set;
bgc->reg_clr = clr;
bgc->gc.set = bgpio_set_with_clear;
+ bgc->gc.set_block = bgpio_set_with_clear_block;
} else if (set && !clr) {
bgc->reg_set = set;
bgc->gc.set = bgpio_set_set;
+ bgc->gc.set_block = bgpio_set_set_block;
} else {
bgc->gc.set = bgpio_set;
+ bgc->gc.set_block = bgpio_set_block;
}

bgc->gc.get = bgpio_get;
+ bgc->gc.get_block = bgpio_get_block;

return 0;
}

2012-10-17 12:40:49

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 08/15 v5] gpio-pca953x: Add block GPIO API

This patch adds block GPIO API support to the gpio-pca953x driver.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-pca953x.c | 64 ++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 64 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-pca953x.c
+++ linux-2.6/drivers/gpio/gpio-pca953x.c
@@ -300,6 +300,68 @@ exit:
mutex_unlock(&chip->i2c_lock);
}

+static unsigned long pca953x_gpio_get_block(struct gpio_chip *gc,
+ unsigned long mask)
+{
+ struct pca953x_chip *chip;
+ u32 reg_val;
+ int ret, offset = 0;
+
+ chip = container_of(gc, struct pca953x_chip, gpio_chip);
+
+ mutex_lock(&chip->i2c_lock);
+ switch (chip->chip_type) {
+ case PCA953X_TYPE:
+ offset = PCA953X_INPUT;
+ break;
+ case PCA957X_TYPE:
+ offset = PCA957X_IN;
+ break;
+ }
+ ret = pca953x_read_reg(chip, offset, &reg_val);
+ mutex_unlock(&chip->i2c_lock);
+ if (ret < 0) {
+ /* NOTE: diagnostic already emitted; that's all we should
+ * do unless gpio_*_value_cansleep() calls become different
+ * from their nonsleeping siblings (and report faults).
+ */
+ return 0;
+ }
+
+ return reg_val & mask;
+}
+
+static void pca953x_gpio_set_block(struct gpio_chip *gc, unsigned long mask,
+ unsigned long values)
+{
+ struct pca953x_chip *chip;
+ u32 reg_val;
+ int ret, offset = 0;
+
+ chip = container_of(gc, struct pca953x_chip, gpio_chip);
+
+ mutex_lock(&chip->i2c_lock);
+
+ reg_val = chip->reg_output & ~mask;
+ reg_val |= values & mask;
+
+ switch (chip->chip_type) {
+ case PCA953X_TYPE:
+ offset = PCA953X_OUTPUT;
+ break;
+ case PCA957X_TYPE:
+ offset = PCA957X_OUT;
+ break;
+ }
+ ret = pca953x_write_reg(chip, offset, reg_val);
+ if (ret)
+ goto exit;
+
+ chip->reg_output = reg_val;
+exit:
+ mutex_unlock(&chip->i2c_lock);
+}
+
static void pca953x_setup_gpio(struct pca953x_chip *chip, int gpios)
{
struct gpio_chip *gc;
@@ -310,6 +372,8 @@ static void pca953x_setup_gpio(struct pc
gc->direction_output = pca953x_gpio_direction_output;
gc->get = pca953x_gpio_get_value;
gc->set = pca953x_gpio_set_value;
+ gc->get_block = pca953x_gpio_get_block;
+ gc->set_block = pca953x_gpio_set_block;
gc->can_sleep = 1;

gc->base = chip->gpio_start;

2012-10-17 12:41:04

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 01/15 v5] gpio: Add a block GPIO API to gpiolib

The recurring task of providing simultaneous access to GPIO lines (especially
for bit banging protocols) needs an appropriate API.

This patch adds a kernel internal "Block GPIO" API that enables simultaneous
access to several GPIOs. This is done by abstracting GPIOs to an n-bit word:
Once requested, it provides access to a group of GPIOs which can range over
multiple GPIO chips.

Signed-off-by: Roland Stigge <[email protected]>
---

Documentation/gpio.txt | 47 +++++++++
drivers/gpio/gpiolib.c | 217 +++++++++++++++++++++++++++++++++++++++++++++
include/asm-generic/gpio.h | 15 +++
include/linux/gpio.h | 74 +++++++++++++++
4 files changed, 353 insertions(+)

--- linux-2.6.orig/Documentation/gpio.txt
+++ linux-2.6/Documentation/gpio.txt
@@ -439,6 +439,53 @@ slower clock delays the rising edge of S
signaling rate accordingly.


+Block GPIO
+----------
+
+The above described interface concentrates on handling single GPIOs. However,
+in applications where it is critical to set several GPIOs at once, this
+interface doesn't work well, e.g. bit-banging protocols via grouped GPIO lines.
+Consider a GPIO controller that is connected via a slow I2C line. When
+switching two or more GPIOs one after another, there can be considerable time
+between those events. This is solved by an interface called Block GPIO:
+
+struct gpio_block *gpio_block_create(unsigned int *gpios, size_t size);
+
+This creates a new block of GPIOs as a list of GPIO numbers with the specified
+size which are accessible via the returned struct gpio_block and the accessor
+functions described below. Please note that you need to request the GPIOs
+separately via gpio_request(). An arbitrary list of globally valid GPIOs can be
+specified, even ranging over several gpio_chips. Actual handling of I/O
+operations will be done on a best effort base, i.e. simultaneous I/O only where
+possible by hardware and implemented in the respective GPIO driver. The number
+of GPIOs in one block is limited to the number of bits in an unsigned long, or
+BITS_PER_LONG, of the respective platform, i.e. typically at least 32 on a 32
+bit system, and at least 64 on a 64 bit system. However, several blocks can be
+defined at once.
+
+unsigned gpio_block_get(struct gpio_block *block);
+void gpio_block_set(struct gpio_block *block, unsigned value);
+
+With those accessor functions, setting and getting the GPIO values is possible,
+analogous to gpio_get_value() and gpio_set_value(). Each bit in the return
+value of gpio_block_get() and in the value argument of gpio_block_set()
+corresponds to a bit specified on gpio_block_create(). Block operations in
+hardware are only possible where the respective GPIO driver implements it,
+falling back to using single GPIO operations where the driver only implements
+single GPIO access.
+
+void gpio_block_free(struct gpio_block *block);
+
+After the GPIO block isn't used anymore, it should be free'd via
+gpio_block_free().
+
+int gpio_block_register(struct gpio_block *block);
+void gpio_block_unregister(struct gpio_block *block);
+
+These functions can be used to register a GPIO block. Blocks registered this
+way will be available via sysfs.
+
+
What do these conventions omit?
===============================
One of the biggest things these conventions omit is pin multiplexing, since
--- linux-2.6.orig/drivers/gpio/gpiolib.c
+++ linux-2.6/drivers/gpio/gpiolib.c
@@ -83,6 +83,8 @@ static inline void desc_set_label(struct
#endif
}

+static LIST_HEAD(gpio_block_list);
+
/* Warn when drivers omit gpio_request() calls -- legal but ill-advised
* when setting direction, and otherwise illegal. Until board setup code
* and drivers use explicit requests everywhere (which won't happen when
@@ -1676,6 +1678,221 @@ void __gpio_set_value(unsigned gpio, int
}
EXPORT_SYMBOL_GPL(__gpio_set_value);

+static int gpio_block_chip_index(struct gpio_block *block, struct gpio_chip *gc)
+{
+ int i;
+
+ for (i = 0; i < block->nchip; i++) {
+ if (block->gbc[i].gc == gc)
+ return i;
+ }
+ return -1;
+}
+
+struct gpio_block *gpio_block_create(unsigned *gpios, size_t size,
+ const char *name)
+{
+ struct gpio_block *block;
+ struct gpio_block_chip *gbc;
+ struct gpio_remap *remap;
+ void *tmp;
+ int i;
+
+ if (size < 1 || size > sizeof(unsigned long) * 8)
+ return ERR_PTR(-EINVAL);
+
+ for (i = 0; i < size; i++)
+ if (!gpio_is_valid(gpios[i]))
+ return ERR_PTR(-EINVAL);
+
+ block = kzalloc(sizeof(struct gpio_block), GFP_KERNEL);
+ if (!block)
+ return ERR_PTR(-ENOMEM);
+
+ block->name = name;
+ block->ngpio = size;
+ block->gpio = kzalloc(sizeof(*block->gpio) * size, GFP_KERNEL);
+ if (!block->gpio)
+ goto err1;
+
+ memcpy(block->gpio, gpios, sizeof(*block->gpio) * size);
+
+ for (i = 0; i < size; i++) {
+ struct gpio_chip *gc = gpio_to_chip(gpios[i]);
+ int bit = gpios[i] - gc->base;
+ int index = gpio_block_chip_index(block, gc);
+
+ if (index < 0) {
+ block->nchip++;
+ tmp = krealloc(block->gbc,
+ sizeof(struct gpio_block_chip) *
+ block->nchip, GFP_KERNEL);
+ if (!tmp) {
+ kfree(block->gbc);
+ goto err2;
+ }
+ block->gbc = tmp;
+ gbc = &block->gbc[block->nchip - 1];
+ gbc->gc = gc;
+ gbc->remap = NULL;
+ gbc->nremap = 0;
+ gbc->mask = 0;
+ } else {
+ gbc = &block->gbc[index];
+ }
+ /* represents the mask necessary on calls to the driver's
+ * .get_block() and .set_block()
+ */
+ gbc->mask |= BIT(bit);
+
+ /* collect gpios that are specified together, represented by
+ * neighboring bits
+ *
+ * Note that even though in setting remap is given a negative
+ * index, the next lines guard that the potential out-of-bounds
+ * pointer is not dereferenced when out of bounds.
+ */
+ remap = &gbc->remap[gbc->nremap - 1];
+ if (!gbc->nremap || (bit - i != remap->offset)) {
+ gbc->nremap++;
+ tmp = krealloc(gbc->remap,
+ sizeof(struct gpio_remap) *
+ gbc->nremap, GFP_KERNEL);
+ if (!tmp) {
+ kfree(gbc->remap);
+ goto err3;
+ }
+ gbc->remap = tmp;
+ remap = &gbc->remap[gbc->nremap - 1];
+ remap->offset = bit - i;
+ remap->mask = 0;
+ }
+
+ /* represents the mask necessary for bit reordering between
+ * gpio_block (i.e. as specified on gpio_block_get() and
+ * gpio_block_set()) and gpio_chip domain (i.e. as specified on
+ * the driver's .set_block() and .get_block())
+ */
+ remap->mask |= BIT(i);
+ }
+
+ return block;
+err3:
+ for (i = 0; i < block->nchip - 1; i++)
+ kfree(block->gbc[i].remap);
+ kfree(block->gbc);
+err2:
+ kfree(block->gpio);
+err1:
+ kfree(block);
+ return ERR_PTR(-ENOMEM);
+}
+EXPORT_SYMBOL_GPL(gpio_block_create);
+
+void gpio_block_free(struct gpio_block *block)
+{
+ int i;
+
+ for (i = 0; i < block->nchip; i++)
+ kfree(block->gbc[i].remap);
+ kfree(block->gpio);
+ kfree(block->gbc);
+ kfree(block);
+}
+EXPORT_SYMBOL_GPL(gpio_block_free);
+
+unsigned long gpio_block_get(const struct gpio_block *block)
+{
+ struct gpio_block_chip *gbc;
+ int i, j;
+ unsigned long values = 0;
+
+ for (i = 0; i < block->nchip; i++) {
+ unsigned long remapped = 0;
+
+ gbc = &block->gbc[i];
+
+ if (gbc->gc->get_block) {
+ remapped = gbc->gc->get_block(gbc->gc, gbc->mask);
+ } else {
+ /* emulate */
+ for_each_set_bit(j, &gbc->mask, BITS_PER_LONG)
+ remapped |= gbc->gc->get(gbc->gc,
+ gbc->gc->base + j) << j;
+ }
+
+ for (j = 0; j < gbc->nremap; j++) {
+ struct gpio_remap *gr = &gbc->remap[j];
+
+ values |= (remapped >> gr->offset) & gr->mask;
+ }
+ }
+
+ return values;
+}
+EXPORT_SYMBOL_GPL(gpio_block_get);
+
+void gpio_block_set(struct gpio_block *block, unsigned long values)
+{
+ struct gpio_block_chip *gbc;
+ int i, j;
+
+ for (i = 0; i < block->nchip; i++) {
+ unsigned long remapped = 0;
+
+ gbc = &block->gbc[i];
+
+ for (j = 0; j < gbc->nremap; j++) {
+ struct gpio_remap *gr = &gbc->remap[j];
+
+ remapped |= (values & gr->mask) << gr->offset;
+ }
+ if (gbc->gc->set_block) {
+ gbc->gc->set_block(gbc->gc, gbc->mask, remapped);
+ } else {
+ /* emulate */
+ for_each_set_bit(j, &gbc->mask, BITS_PER_LONG)
+ gbc->gc->set(gbc->gc, gbc->gc->base + j,
+ (remapped >> j) & 1);
+ }
+ }
+}
+EXPORT_SYMBOL_GPL(gpio_block_set);
+
+struct gpio_block *gpio_block_find_by_name(const char *name)
+{
+ struct gpio_block *i;
+
+ list_for_each_entry(i, &gpio_block_list, list)
+ if (!strcmp(i->name, name))
+ return i;
+ return NULL;
+}
+EXPORT_SYMBOL_GPL(gpio_block_find_by_name);
+
+int gpio_block_register(struct gpio_block *block)
+{
+ if (gpio_block_find_by_name(block->name))
+ return -EBUSY;
+
+ list_add(&block->list, &gpio_block_list);
+
+ return 0;
+}
+EXPORT_SYMBOL_GPL(gpio_block_register);
+
+void gpio_block_unregister(struct gpio_block *block)
+{
+ struct gpio_block *i;
+
+ list_for_each_entry(i, &gpio_block_list, list)
+ if (i == block) {
+ list_del(&i->list);
+ break;
+ }
+}
+EXPORT_SYMBOL_GPL(gpio_block_unregister);
+
/**
* __gpio_cansleep() - report whether gpio value access will sleep
* @gpio: gpio in question
--- linux-2.6.orig/include/asm-generic/gpio.h
+++ linux-2.6/include/asm-generic/gpio.h
@@ -43,6 +43,7 @@ static inline bool gpio_is_valid(int num

struct device;
struct gpio;
+struct gpio_block;
struct seq_file;
struct module;
struct device_node;
@@ -105,6 +106,8 @@ struct gpio_chip {
unsigned offset);
int (*get)(struct gpio_chip *chip,
unsigned offset);
+ unsigned long (*get_block)(struct gpio_chip *chip,
+ unsigned long mask);
int (*direction_output)(struct gpio_chip *chip,
unsigned offset, int value);
int (*set_debounce)(struct gpio_chip *chip,
@@ -112,6 +115,9 @@ struct gpio_chip {

void (*set)(struct gpio_chip *chip,
unsigned offset, int value);
+ void (*set_block)(struct gpio_chip *chip,
+ unsigned long mask,
+ unsigned long values);

int (*to_irq)(struct gpio_chip *chip,
unsigned offset);
@@ -171,6 +177,15 @@ extern void gpio_set_value_cansleep(unsi
extern int __gpio_get_value(unsigned gpio);
extern void __gpio_set_value(unsigned gpio, int value);

+extern struct gpio_block *gpio_block_create(unsigned *gpio, size_t size,
+ const char *name);
+extern void gpio_block_free(struct gpio_block *block);
+extern unsigned long gpio_block_get(const struct gpio_block *block);
+extern void gpio_block_set(struct gpio_block *block, unsigned long values);
+extern struct gpio_block *gpio_block_find_by_name(const char *name);
+extern int gpio_block_register(struct gpio_block *block);
+extern void gpio_block_unregister(struct gpio_block *block);
+
extern int __gpio_cansleep(unsigned gpio);

extern int __gpio_to_irq(unsigned gpio);
--- linux-2.6.orig/include/linux/gpio.h
+++ linux-2.6/include/linux/gpio.h
@@ -2,6 +2,8 @@
#define __LINUX_GPIO_H

#include <linux/errno.h>
+#include <linux/types.h>
+#include <linux/list.h>

/* see Documentation/gpio.txt */

@@ -39,6 +41,43 @@ struct gpio {
const char *label;
};

+/*
+ * struct gpio_remap - a structure for describing a bit mapping
+ * @mask: a bit mask
+ * @offset: how many bits to shift to the left (negative: to the right)
+ *
+ * When we are mapping bit values from one word to another (here: from GPIO
+ * block domain to GPIO driver domain) we first mask them out with mask and
+ * shift them as specified with offset. More complicated mappings are done by
+ * grouping several of those structs and adding the results together.
+ */
+struct gpio_remap {
+ unsigned long mask;
+ int offset;
+};
+
+struct gpio_block_chip {
+ struct gpio_chip *gc;
+ struct gpio_remap *remap;
+ int nremap;
+ unsigned long mask;
+};
+
+/**
+ * struct gpio_block - a structure describing a list of GPIOs for simultaneous
+ * operations
+ */
+struct gpio_block {
+ struct gpio_block_chip *gbc;
+ size_t nchip;
+ const char *name;
+
+ int ngpio;
+ unsigned *gpio;
+
+ struct list_head list;
+};
+
#ifdef CONFIG_GENERIC_GPIO

#ifdef CONFIG_ARCH_HAVE_CUSTOM_GPIO_H
@@ -169,6 +208,41 @@ static inline void gpio_set_value(unsign
WARN_ON(1);
}

+static inline
+struct gpio_block *gpio_block_create(unsigned *gpios, size_t size,
+ const char *name)
+{
+ WARN_ON(1);
+ return NULL;
+}
+
+static inline void gpio_block_free(struct gpio_block *block)
+{
+ WARN_ON(1);
+}
+
+static inline unsigned long gpio_block_get(const struct gpio_block *block)
+{
+ WARN_ON(1);
+ return 0;
+}
+
+static inline void gpio_block_set(struct gpio_block *block, unsigned long value)
+{
+ WARN_ON(1);
+}
+
+static inline int gpio_block_register(struct gpio_block *block)
+{
+ WARN_ON(1);
+ return 0;
+}
+
+static inline void gpio_block_unregister(struct gpio_block *block)
+{
+ WARN_ON(1);
+}
+
static inline int gpio_cansleep(unsigned gpio)
{
/* GPIO can never have been requested or set as {in,out}put */

2012-10-17 12:37:39

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

This patch adds sysfs support to the block GPIO API.

Signed-off-by: Roland Stigge <[email protected]>

---
Documentation/ABI/testing/sysfs-gpio | 6
drivers/gpio/gpiolib.c | 214 +++++++++++++++++++++++++++++++++++
include/asm-generic/gpio.h | 11 +
include/linux/gpio.h | 13 ++
4 files changed, 243 insertions(+), 1 deletion(-)

--- linux-2.6.orig/Documentation/ABI/testing/sysfs-gpio
+++ linux-2.6/Documentation/ABI/testing/sysfs-gpio
@@ -24,4 +24,8 @@ Description:
/base ... (r/o) same as N
/label ... (r/o) descriptive, not necessarily unique
/ngpio ... (r/o) number of GPIOs; numbered N to N + (ngpio - 1)
-
+ /blockN ... for each GPIO block #N
+ /ngpio ... (r/o) number of GPIOs in this group
+ /exported ... sysfs export state of this group (0, 1)
+ /value ... current value as 32 or 64 bit integer in decimal
+ (only available if /exported is 1)
--- linux-2.6.orig/drivers/gpio/gpiolib.c
+++ linux-2.6/drivers/gpio/gpiolib.c
@@ -972,6 +972,214 @@ static void gpiochip_unexport(struct gpi
chip->label, status);
}

+static ssize_t gpio_block_ngpio_show(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ const struct gpio_block *block = dev_get_drvdata(dev);
+
+ return sprintf(buf, "%u\n", block->ngpio);
+}
+
+static ssize_t gpio_block_value_show(struct device *dev,
+ struct device_attribute *attr, char *buf)
+{
+ const struct gpio_block *block = dev_get_drvdata(dev);
+
+ return sprintf(buf, sizeof(unsigned long) == 4 ? "0x%08lx\n" :
+ "0x%016lx\n", gpio_block_get(block));
+}
+
+static bool gpio_block_is_output(struct gpio_block *block)
+{
+ int i;
+
+ for (i = 0; i < block->ngpio; i++)
+ if (!test_bit(FLAG_IS_OUT, &gpio_desc[block->gpio[i]].flags))
+ return false;
+ return true;
+}
+
+static ssize_t gpio_block_value_store(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t size)
+{
+ ssize_t status;
+ struct gpio_block *block = dev_get_drvdata(dev);
+ unsigned long value;
+
+ status = kstrtoul(buf, 0, &value);
+ if (status == 0) {
+ mutex_lock(&sysfs_lock);
+ if (gpio_block_is_output(block)) {
+ gpio_block_set(block, value);
+ status = size;
+ } else {
+ status = -EPERM;
+ }
+ mutex_unlock(&sysfs_lock);
+ }
+ return status;
+}
+
+static struct device_attribute
+dev_attr_block_value = __ATTR(value, S_IWUSR | S_IRUGO, gpio_block_value_show,
+ gpio_block_value_store);
+
+static struct class gpio_block_class;
+
+static int gpio_block_value_is_exported(struct gpio_block *block)
+{
+ struct device *dev;
+ struct sysfs_dirent *sd = NULL;
+
+ mutex_lock(&sysfs_lock);
+ dev = class_find_device(&gpio_block_class, NULL, block, match_export);
+ if (!dev)
+ goto out;
+
+ sd = sysfs_get_dirent(dev->kobj.sd, NULL, "value");
+
+out:
+ mutex_unlock(&sysfs_lock);
+ return !!sd;
+}
+
+static ssize_t gpio_block_exported_show(struct device *dev,
+ struct device_attribute *attr,
+ char *buf)
+{
+ struct gpio_block *block = dev_get_drvdata(dev);
+
+ return sprintf(buf, "%u\n", gpio_block_value_is_exported(block));
+}
+
+static int gpio_block_value_export(struct gpio_block *block)
+{
+ struct device *dev;
+ int status;
+ int i;
+
+ mutex_lock(&sysfs_lock);
+
+ for (i = 0; i < block->ngpio; i++) {
+ status = gpio_request(block->gpio[i], "sysfs");
+ if (status)
+ goto out;
+ }
+
+ dev = class_find_device(&gpio_block_class, NULL, block, match_export);
+ if (!dev) {
+ status = -ENODEV;
+ goto out;
+ }
+
+ status = device_create_file(dev, &dev_attr_block_value);
+ if (status)
+ goto out;
+
+ mutex_unlock(&sysfs_lock);
+ return 0;
+
+out:
+ while (--i >= 0)
+ gpio_free(block->gpio[i]);
+
+ mutex_unlock(&sysfs_lock);
+ return status;
+}
+
+static int gpio_block_value_unexport(struct gpio_block *block)
+{
+ struct device *dev;
+ int i;
+
+ dev = class_find_device(&gpio_block_class, NULL, block, match_export);
+ if (!dev)
+ return -ENODEV;
+
+ for (i = 0; i < block->ngpio; i++)
+ gpio_free(block->gpio[i]);
+
+ device_remove_file(dev, &dev_attr_block_value);
+
+ return 0;
+}
+
+static ssize_t gpio_block_exported_store(struct device *dev,
+ struct device_attribute *attr,
+ const char *buf, size_t size)
+{
+ long value;
+ int status;
+ struct gpio_block *block = dev_get_drvdata(dev);
+ int exported = gpio_block_value_is_exported(block);
+
+ status = kstrtoul(buf, 0, &value);
+ if (status < 0)
+ goto err;
+
+ if (value != exported) {
+ if (value)
+ status = gpio_block_value_export(block);
+ else
+ status = gpio_block_value_unexport(block);
+ if (!status)
+ status = size;
+ } else {
+ status = size;
+ }
+err:
+ return status;
+}
+
+static struct device_attribute gpio_block_attrs[] = {
+ __ATTR(exported, S_IWUSR | S_IRUGO, gpio_block_exported_show,
+ gpio_block_exported_store),
+ __ATTR(ngpio, S_IRUGO, gpio_block_ngpio_show, NULL),
+ __ATTR_NULL,
+};
+
+static struct class gpio_block_class = {
+ .name = "gpioblock",
+ .owner = THIS_MODULE,
+
+ .dev_attrs = gpio_block_attrs,
+};
+
+int gpio_block_export(struct gpio_block *block)
+{
+ int status = 0;
+ struct device *dev;
+
+ /* can't export until sysfs is available ... */
+ if (!gpio_block_class.p) {
+ pr_debug("%s: called too early!\n", __func__);
+ return -ENOENT;
+ }
+
+ mutex_lock(&sysfs_lock);
+ dev = device_create(&gpio_block_class, NULL, MKDEV(0, 0), block,
+ block->name);
+ if (IS_ERR(dev))
+ status = PTR_ERR(dev);
+ mutex_unlock(&sysfs_lock);
+
+ return status;
+}
+EXPORT_SYMBOL_GPL(gpio_block_export);
+
+void gpio_block_unexport(struct gpio_block *block)
+{
+ struct device *dev;
+
+ mutex_lock(&sysfs_lock);
+ dev = class_find_device(&gpio_block_class, NULL, block, match_export);
+ if (dev)
+ device_unregister(dev);
+ mutex_unlock(&sysfs_lock);
+}
+EXPORT_SYMBOL_GPL(gpio_block_unexport);
+
static int __init gpiolib_sysfs_init(void)
{
int status;
@@ -982,6 +1190,10 @@ static int __init gpiolib_sysfs_init(voi
if (status < 0)
return status;

+ status = class_register(&gpio_block_class);
+ if (status < 0)
+ return status;
+
/* Scan and register the gpio_chips which registered very
* early (e.g. before the class_register above was called).
*
@@ -1876,6 +2088,7 @@ int gpio_block_register(struct gpio_bloc
return -EBUSY;

list_add(&block->list, &gpio_block_list);
+ gpio_block_export(block);

return 0;
}
@@ -1888,6 +2101,7 @@ void gpio_block_unregister(struct gpio_b
list_for_each_entry(i, &gpio_block_list, list)
if (i == block) {
list_del(&i->list);
+ gpio_block_unexport(block);
break;
}
}
--- linux-2.6.orig/include/asm-generic/gpio.h
+++ linux-2.6/include/asm-generic/gpio.h
@@ -211,6 +211,8 @@ extern int gpio_export_link(struct devic
unsigned gpio);
extern int gpio_sysfs_set_active_low(unsigned gpio, int value);
extern void gpio_unexport(unsigned gpio);
+extern int gpio_block_export(struct gpio_block *block);
+extern void gpio_block_unexport(struct gpio_block *block);

#endif /* CONFIG_GPIO_SYSFS */

@@ -270,6 +272,15 @@ static inline int gpio_sysfs_set_active_
static inline void gpio_unexport(unsigned gpio)
{
}
+
+static inline int gpio_block_export(struct gpio_block *block)
+{
+ return -ENOSYS;
+}
+
+static inline void gpio_block_unexport(struct gpio_block *block)
+{
+}
#endif /* CONFIG_GPIO_SYSFS */

#endif /* _ASM_GENERIC_GPIO_H */
--- linux-2.6.orig/include/linux/gpio.h
+++ linux-2.6/include/linux/gpio.h
@@ -291,6 +291,19 @@ static inline void gpio_unexport(unsigne
WARN_ON(1);
}

+static inline int gpio_block_export(struct gpio_block *block)
+{
+ /* GPIO block can never have been requested or set as {in,out}put */
+ WARN_ON(1);
+ return -EINVAL;
+}
+
+static inline void gpio_block_unexport(struct gpio_block *block)
+{
+ /* GPIO block can never have been exported */
+ WARN_ON(1);
+}
+
static inline int gpio_to_irq(unsigned gpio)
{
/* GPIO can never have been requested or set as input */

2012-10-17 12:41:31

by Roland Stigge

[permalink] [raw]
Subject: [PATCH RFC 05/15 v5] gpio-max730x: Add block GPIO API

This patch adds block GPIO API support to the MAX730x driver.

Due to hardware constraints in this chip, simultaneous access to GPIO lines can
only be done in groups of 8: GPIOs 0-7, 8-15, 16-23, 24-27. However, setting
and clearing will be done at once.

Signed-off-by: Roland Stigge <[email protected]>

---
drivers/gpio/gpio-max730x.c | 61 ++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 61 insertions(+)

--- linux-2.6.orig/drivers/gpio/gpio-max730x.c
+++ linux-2.6/drivers/gpio/gpio-max730x.c
@@ -146,6 +146,44 @@ static int max7301_get(struct gpio_chip
return level;
}

+static unsigned long max7301_get_block(struct gpio_chip *chip,
+ unsigned long mask)
+{
+ struct max7301 *ts = container_of(chip, struct max7301, chip);
+ int i, j;
+ unsigned long result = 0;
+
+ for (i = 0; i < 4; i++) {
+ if ((mask >> (i * 8)) & 0xFF) { /* i/o only if necessary */
+ u8 in_level = ts->read(ts->dev, 0x44 + i * 8);
+ u8 in_mask = 0;
+ u8 out_level = (ts->out_level >> (i * 8 + 4)) & 0xFF;
+ u8 out_mask = 0;
+
+ for (j = 0; j < 8; j++) {
+ int offset = 4 + i * 8 + j;
+ int config = (ts->port_config[offset >> 2] >>
+ ((offset & 3) << 1)) &
+ PIN_CONFIG_MASK;
+
+ switch (config) {
+ case PIN_CONFIG_OUT:
+ out_mask |= BIT(j);
+ break;
+ case PIN_CONFIG_IN_WO_PULLUP:
+ case PIN_CONFIG_IN_PULLUP:
+ in_mask |= BIT(j);
+ }
+ }
+
+ result |= ((unsigned long)(in_level & in_mask) |
+ (out_level & out_mask)) << (i * 8);
+ }
+ }
+
+ return result & mask;
+}
+
static void max7301_set(struct gpio_chip *chip, unsigned offset, int value)
{
struct max7301 *ts = container_of(chip, struct max7301, chip);
@@ -160,6 +198,27 @@ static void max7301_set(struct gpio_chip
mutex_unlock(&ts->lock);
}

+static void max7301_set_block(struct gpio_chip *chip, unsigned long mask,
+ unsigned long values)
+{
+ struct max7301 *ts = container_of(chip, struct max7301, chip);
+ unsigned long changes;
+ int i;
+
+ mutex_lock(&ts->lock);
+
+ changes = (ts->out_level ^ (values << 4)) & (mask << 4);
+ ts->out_level ^= changes;
+
+ for (i = 0; i < 4; i++) {
+ if ((changes >> (i * 8 + 4)) & 0xFF) /* i/o only on change */
+ ts->write(ts->dev, 0x44 + i * 8,
+ (ts->out_level >> (i * 8 + 4)) & 0xFF);
+ }
+
+ mutex_unlock(&ts->lock);
+}
+
int __devinit __max730x_probe(struct max7301 *ts)
{
struct device *dev = ts->dev;
@@ -183,8 +242,10 @@ int __devinit __max730x_probe(struct max

ts->chip.direction_input = max7301_direction_input;
ts->chip.get = max7301_get;
+ ts->chip.get_block = max7301_get_block;
ts->chip.direction_output = max7301_direction_output;
ts->chip.set = max7301_set;
+ ts->chip.set_block = max7301_set_block;

ts->chip.base = pdata->base;
ts->chip.ngpio = PIN_NUMBER;

2012-10-17 19:05:26

by Greg Kroah-Hartman

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On Wed, Oct 17, 2012 at 02:31:34PM +0200, Roland Stigge wrote:
> This patch adds sysfs support to the block GPIO API.
>
> Signed-off-by: Roland Stigge <[email protected]>
>
> ---
> Documentation/ABI/testing/sysfs-gpio | 6
> drivers/gpio/gpiolib.c | 214 +++++++++++++++++++++++++++++++++++
> include/asm-generic/gpio.h | 11 +
> include/linux/gpio.h | 13 ++
> 4 files changed, 243 insertions(+), 1 deletion(-)
>
> --- linux-2.6.orig/Documentation/ABI/testing/sysfs-gpio
> +++ linux-2.6/Documentation/ABI/testing/sysfs-gpio
> @@ -24,4 +24,8 @@ Description:
> /base ... (r/o) same as N
> /label ... (r/o) descriptive, not necessarily unique
> /ngpio ... (r/o) number of GPIOs; numbered N to N + (ngpio - 1)
> -
> + /blockN ... for each GPIO block #N
> + /ngpio ... (r/o) number of GPIOs in this group
> + /exported ... sysfs export state of this group (0, 1)
> + /value ... current value as 32 or 64 bit integer in decimal
> + (only available if /exported is 1)

I think you need some more documentation here, as I just noticed
something "odd":

> +static int gpio_block_value_unexport(struct gpio_block *block)
> +{
> + struct device *dev;
> + int i;
> +
> + dev = class_find_device(&gpio_block_class, NULL, block, match_export);
> + if (!dev)
> + return -ENODEV;
> +
> + for (i = 0; i < block->ngpio; i++)
> + gpio_free(block->gpio[i]);
> +
> + device_remove_file(dev, &dev_attr_block_value);
> +
> + return 0;
> +}

Wait, what? You are removing a sysfs file in this function, from within
a sysfs write:

> +static ssize_t gpio_block_exported_store(struct device *dev,
> + struct device_attribute *attr,
> + const char *buf, size_t size)
> +{
> + long value;
> + int status;
> + struct gpio_block *block = dev_get_drvdata(dev);
> + int exported = gpio_block_value_is_exported(block);
> +
> + status = kstrtoul(buf, 0, &value);
> + if (status < 0)
> + goto err;
> +
> + if (value != exported) {
> + if (value)
> + status = gpio_block_value_export(block);
> + else
> + status = gpio_block_value_unexport(block);

That looks like a recipie for disaster. Why do you allow userspace to
do this?

Anyway, the other fixups for how you create/destroy the attribute files
looks great, thanks for making those changes.

greg k-h

2012-10-18 10:07:47

by Roland Stigge

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On 10/17/2012 09:05 PM, Greg KH wrote:
>> +static int gpio_block_value_unexport(struct gpio_block *block)
>> +{
>> + struct device *dev;
>> + int i;
>> +
>> + dev = class_find_device(&gpio_block_class, NULL, block, match_export);
>> + if (!dev)
>> + return -ENODEV;
>> +
>> + for (i = 0; i < block->ngpio; i++)
>> + gpio_free(block->gpio[i]);
>> +
>> + device_remove_file(dev, &dev_attr_block_value);
>> +
>> + return 0;
>> +}
>
> Wait, what? You are removing a sysfs file in this function, from within
> a sysfs write:

Yes, exactly:

>> +static ssize_t gpio_block_exported_store(struct device *dev,
>> + struct device_attribute *attr,
>> + const char *buf, size_t size)
>> +{
>> + long value;
>> + int status;
>> + struct gpio_block *block = dev_get_drvdata(dev);
>> + int exported = gpio_block_value_is_exported(block);
>> +
>> + status = kstrtoul(buf, 0, &value);
>> + if (status < 0)
>> + goto err;
>> +
>> + if (value != exported) {
>> + if (value)
>> + status = gpio_block_value_export(block);
>> + else
>> + status = gpio_block_value_unexport(block);
>
> That looks like a recipie for disaster. Why do you allow userspace to
> do this?

Exporting for gpio blocks is done as follows: writing "1" to the
"exported" _device_ attribute of the gpio block creates the "values"
attribute and at the same time requests the whole block (including all
of its gpios) as "sysfs".

This admittedly deviates from the exporting of gpios (with the "export"
and "unexport" _class_ attributes) because blocks are not numbered. In
contrast, they are registered in a list (as was requested). Now, I
already had the idea of also having an "export" and "unexport" _class_
attribute for blocks also, but from a userspace perspective you only see
the presence and name of the gpio block if it is already being in sysfs
(even if not exported yet). If it wouldn't be this way, a user couldn't
guess how the required gpio block is called (or numbered), wouldn't even
know about its presence.

Just for understanding your strong desire for the device attribute
("value") being always present (in contrast to being created and removed
dynamically) - can you please give me any hint how the dynamic approach
would lead to disaster?

One possibility would be to always have "value" as a default device
attribute, but then it wouldn't be so obvious that it's useless until
"exported" is "1".

What do you think?

For now, I would elaborate about my terse "only available if /exported
is 1" like this:

"
Block GPIO devices are visible in sysfs as soon as they are registered
(e.g. via devicetree definition). For actual I/O use, their "exported"
boolean attribute must be set to "1". Then, the attribute "values" is
created and at the same time, the GPIOs in the block are requested for
exclusive use by sysfs.
"

Thanks in advance,

Roland

2012-10-19 10:35:34

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On Thu, Oct 18, 2012 at 12:07 PM, Roland Stigge <[email protected]> wrote:
> On 10/17/2012 09:05 PM, Greg KH wrote:
>>>
>>> + if (value != exported) {
>>> + if (value)
>>> + status = gpio_block_value_export(block);
>>> + else
>>> + status = gpio_block_value_unexport(block);
>>
>> That looks like a recipie for disaster. Why do you allow userspace to
>> do this?
>
> Exporting for gpio blocks is done as follows: writing "1" to the
> "exported" _device_ attribute of the gpio block creates the "values"
> attribute and at the same time requests the whole block (including all
> of its gpios) as "sysfs".

To me it reads like Greg's comment is basically pinpointing a flaw
in Brownell's initial design of gpio sysfs: that new sysfs files are
created and destroyed by writing into sysfs */export files from
userspace?

See commit: d8f388d8dc8d4f36539dd37c1fff62cc404ea0fc

The block GPIO stuff is just following that design pattern.

Yours,
Linus Walleij

2012-10-19 11:51:17

by Roland Stigge

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On 10/19/2012 12:35 PM, Linus Walleij wrote:
> On Thu, Oct 18, 2012 at 12:07 PM, Roland Stigge <[email protected]> wrote:
>> On 10/17/2012 09:05 PM, Greg KH wrote:
>>>>
>>>> + if (value != exported) {
>>>> + if (value)
>>>> + status = gpio_block_value_export(block);
>>>> + else
>>>> + status = gpio_block_value_unexport(block);
>>>
>>> That looks like a recipie for disaster. Why do you allow userspace to
>>> do this?
>>
>> Exporting for gpio blocks is done as follows: writing "1" to the
>> "exported" _device_ attribute of the gpio block creates the "values"
>> attribute and at the same time requests the whole block (including all
>> of its gpios) as "sysfs".
>
> To me it reads like Greg's comment is basically pinpointing a flaw
> in Brownell's initial design of gpio sysfs: that new sysfs files are
> created and destroyed by writing into sysfs */export files from
> userspace?
>
> See commit: d8f388d8dc8d4f36539dd37c1fff62cc404ea0fc
>
> The block GPIO stuff is just following that design pattern.

So what do you think about my just proposed idea of always having the
"value" argument present, but only useable when "exported" is "1"? Now
only talking about the block gpios, but later maybe also for gpios?

But I would only do this if you and Greg consider it reasonable.

Thanks in advance,

Roland

2012-10-19 18:02:38

by Greg Kroah-Hartman

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On Thu, Oct 18, 2012 at 12:07:39PM +0200, Roland Stigge wrote:
> On 10/17/2012 09:05 PM, Greg KH wrote:
> >> +static int gpio_block_value_unexport(struct gpio_block *block)
> >> +{
> >> + struct device *dev;
> >> + int i;
> >> +
> >> + dev = class_find_device(&gpio_block_class, NULL, block, match_export);
> >> + if (!dev)
> >> + return -ENODEV;
> >> +
> >> + for (i = 0; i < block->ngpio; i++)
> >> + gpio_free(block->gpio[i]);
> >> +
> >> + device_remove_file(dev, &dev_attr_block_value);
> >> +
> >> + return 0;
> >> +}
> >
> > Wait, what? You are removing a sysfs file in this function, from within
> > a sysfs write:
>
> Yes, exactly:
>
> >> +static ssize_t gpio_block_exported_store(struct device *dev,
> >> + struct device_attribute *attr,
> >> + const char *buf, size_t size)
> >> +{
> >> + long value;
> >> + int status;
> >> + struct gpio_block *block = dev_get_drvdata(dev);
> >> + int exported = gpio_block_value_is_exported(block);
> >> +
> >> + status = kstrtoul(buf, 0, &value);
> >> + if (status < 0)
> >> + goto err;
> >> +
> >> + if (value != exported) {
> >> + if (value)
> >> + status = gpio_block_value_export(block);
> >> + else
> >> + status = gpio_block_value_unexport(block);
> >
> > That looks like a recipie for disaster. Why do you allow userspace to
> > do this?
>
> Exporting for gpio blocks is done as follows: writing "1" to the
> "exported" _device_ attribute of the gpio block creates the "values"
> attribute and at the same time requests the whole block (including all
> of its gpios) as "sysfs".
>
> This admittedly deviates from the exporting of gpios (with the "export"
> and "unexport" _class_ attributes) because blocks are not numbered. In
> contrast, they are registered in a list (as was requested). Now, I
> already had the idea of also having an "export" and "unexport" _class_
> attribute for blocks also, but from a userspace perspective you only see
> the presence and name of the gpio block if it is already being in sysfs
> (even if not exported yet). If it wouldn't be this way, a user couldn't
> guess how the required gpio block is called (or numbered), wouldn't even
> know about its presence.
>
> Just for understanding your strong desire for the device attribute
> ("value") being always present (in contrast to being created and removed
> dynamically) - can you please give me any hint how the dynamic approach
> would lead to disaster?
>
> One possibility would be to always have "value" as a default device
> attribute, but then it wouldn't be so obvious that it's useless until
> "exported" is "1".
>
> What do you think?
>
> For now, I would elaborate about my terse "only available if /exported
> is 1" like this:
>
> "
> Block GPIO devices are visible in sysfs as soon as they are registered
> (e.g. via devicetree definition). For actual I/O use, their "exported"
> boolean attribute must be set to "1". Then, the attribute "values" is
> created and at the same time, the GPIOs in the block are requested for
> exclusive use by sysfs.
> "

Yes, that explanation makes it more obvious as to what is going on, it
caught me by supprise.

We used to have problems with attributes removing/adding devices or
attributes from their callbacks, but that has been fixed up now, and the
fact that the other gpio code works this way is good enough precedence
to keep me from objecting to it.

thanks,

greg k-h

2012-10-22 08:54:36

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On Fri, Oct 19, 2012 at 8:02 PM, Greg KH <[email protected]> wrote:

> We used to have problems with attributes removing/adding devices or
> attributes from their callbacks, but that has been fixed up now, and the
> fact that the other gpio code works this way is good enough precedence
> to keep me from objecting to it.

OK thanks I get this now too...

Yours,
Linus Walleij

2012-10-22 08:55:51

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On Fri, Oct 19, 2012 at 1:51 PM, Roland Stigge <[email protected]> wrote:

> [Me]
>> The block GPIO stuff is just following that design pattern.
>
> So what do you think about my just proposed idea of always having the
> "value" argument present, but only useable when "exported" is "1"? Now
> only talking about the block gpios, but later maybe also for gpios?

We should atleast be consistent and do it the same way for
blocks as individual gpios.

> But I would only do this if you and Greg consider it reasonable.

I'm still afraid of this whole thing and would seek Grant's consent.

Yours,
Linus Walleij

2012-10-22 09:05:56

by Roland Stigge

[permalink] [raw]
Subject: Re: [PATCH RFC 02/15 v5] gpio: Add sysfs support to block GPIO API

On 10/22/2012 10:55 AM, Linus Walleij wrote:
> On Fri, Oct 19, 2012 at 1:51 PM, Roland Stigge <[email protected]> wrote:
>> So what do you think about my just proposed idea of always having the
>> "value" argument present, but only useable when "exported" is "1"? Now
>> only talking about the block gpios, but later maybe also for gpios?
>
> We should atleast be consistent and do it the same way for
> blocks as individual gpios.

OK, I'll leave it as creating-attribute-on-export.

>> But I would only do this if you and Greg consider it reasonable.
>
> I'm still afraid of this whole thing and would seek Grant's consent.

Yes, he acked. :-)

Thanks,

Roland