2012-10-12 14:36:31

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v2 1/4] mfd: add viperboard driver

From: Lars Poeschel <[email protected]>

Add mfd driver for Nano River Technologies viperboard.

Signed-off-by: Lars Poeschel <[email protected]>
---
drivers/mfd/Kconfig | 14 ++++
drivers/mfd/Makefile | 1 +
drivers/mfd/viperboard.c | 149 ++++++++++++++++++++++++++++++++++++++++
include/linux/mfd/viperboard.h | 99 ++++++++++++++++++++++++++
4 files changed, 263 insertions(+)
create mode 100644 drivers/mfd/viperboard.c
create mode 100644 include/linux/mfd/viperboard.h

diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
index b1a1462..98d9fa3 100644
--- a/drivers/mfd/Kconfig
+++ b/drivers/mfd/Kconfig
@@ -1003,6 +1003,20 @@ config MFD_PALMAS
If you say yes here you get support for the Palmas
series of PMIC chips from Texas Instruments.

+config MFD_VIPERBOARD
+ tristate "Support for Nano River Technologies Viperboard"
+ select MFD_CORE
+ depends on USB && IIO
+ default n
+ help
+ Say yes here if you want support for Nano River Technologies
+ Viperboard.
+ There are mfd cell drivers available for i2c master, adc and
+ both gpios found on the board. The spi part does not yet
+ have a driver.
+ You need to select the mfd cell drivers seperatly.
+ The drivers do not support all features the board exposes.
+
endmenu
endif

diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
index 79dd22d..6ab6b64 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -128,6 +128,7 @@ obj-$(CONFIG_MFD_TPS65090) += tps65090.o
obj-$(CONFIG_MFD_AAT2870_CORE) += aat2870-core.o
obj-$(CONFIG_MFD_INTEL_MSIC) += intel_msic.o
obj-$(CONFIG_MFD_PALMAS) += palmas.o
+obj-$(CONFIG_MFD_VIPERBOARD) += viperboard.o
obj-$(CONFIG_MFD_RC5T583) += rc5t583.o rc5t583-irq.o
obj-$(CONFIG_MFD_SEC_CORE) += sec-core.o sec-irq.o
obj-$(CONFIG_MFD_ANATOP) += anatop-mfd.o
diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
new file mode 100644
index 0000000..8095ea2
--- /dev/null
+++ b/drivers/mfd/viperboard.c
@@ -0,0 +1,149 @@
+/*
+ * Nano River Technologies viperboard driver
+ *
+ * This is the core driver for the viperboard. There are cell drivers
+ * available for I2C, ADC and both GPIOs. SPI is not yet supported
+ * The drivers do not support all features the board exposes. See user
+ * manual of the viperboard.
+ *
+ * (C) 2012 by Lemonage GmbH
+ * Author: Lars Poeschel <[email protected]>
+ * All rights reserved.
+ *
+ * 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/errno.h>
+#include <linux/module.h>
+#include <linux/slab.h>
+#include <linux/types.h>
+#include <linux/mutex.h>
+
+#include <linux/mfd/core.h>
+#include <linux/mfd/viperboard.h>
+
+#include <linux/usb.h>
+
+
+static const struct usb_device_id vprbrd_table[] = {
+ { USB_DEVICE(0x2058, 0x1005) }, /* Nano River Technologies */
+ { } /* Terminating entry */
+};
+
+MODULE_DEVICE_TABLE(usb, vprbrd_table);
+
+static void vprbrd_dev_release(struct device *dev)
+{
+ return;
+}
+
+static void vprbrd_free(struct vprbrd *dev)
+{
+ usb_put_dev(dev->usb_dev);
+ kfree(dev);
+}
+
+static struct mfd_cell vprbrd_devs[] = {
+};
+
+static int vprbrd_probe(struct usb_interface *interface,
+ const struct usb_device_id *id)
+{
+ struct vprbrd *vb;
+
+ u16 version = 0;
+ int pipe, ret;
+ unsigned char buf[1];
+
+ /* allocate memory for our device state and initialize it */
+ vb = kzalloc(sizeof(*vb), GFP_KERNEL);
+ if (vb == NULL) {
+ dev_err(&interface->dev, "Out of memory\n");
+ return -ENOMEM;
+ }
+
+ device_initialize(&vb->pdev.dev);
+ vb->pdev.dev.parent = &interface->dev;
+ vb->pdev.dev.release = vprbrd_dev_release;
+ dev_set_name(&vb->pdev.dev, "%s-%s-mfd-holder",
+ dev_driver_string(&interface->dev), dev_name(&interface->dev));
+ ret = device_add(&vb->pdev.dev);
+ if (ret) {
+ dev_err(&interface->dev, "Failed to add mfd holder device.");
+ goto error;
+ }
+
+ mutex_init(&vb->lock);
+
+ vb->usb_dev = usb_get_dev(interface_to_usbdev(interface));
+
+ /* save our data pointer in this interface device */
+ usb_set_intfdata(interface, vb);
+ dev_set_drvdata(&vb->pdev.dev, vb);
+
+ /* get version information, major first, minor then */
+ pipe = usb_rcvctrlpipe(vb->usb_dev, 0);
+ ret = usb_control_msg(vb->usb_dev, pipe, 0xea, 0xc0, 0x0000,
+ 0x0000, buf, 1, 100);
+ if (ret == 1)
+ version = buf[0];
+
+ ret = usb_control_msg(vb->usb_dev, pipe, 0xeb, 0xc0, 0x0000,
+ 0x0000, buf, 1, 100);
+ if (ret == 1) {
+ version <<= 8;
+ version = version | buf[0];
+ }
+
+ dev_info(&interface->dev,
+ "version %x.%02x found at bus %03d address %03d\n",
+ version >> 8, version & 0xff,
+ vb->usb_dev->bus->busnum, vb->usb_dev->devnum);
+
+ ret = mfd_add_devices(&vb->pdev.dev, -1, vprbrd_devs,
+ ARRAY_SIZE(vprbrd_devs), NULL, 0, NULL);
+ if (ret != 0) {
+ dev_err(&interface->dev, "Failed to add mfd devices to core.");
+ goto error;
+ }
+
+ return 0;
+
+error:
+ put_device(&vb->pdev.dev);
+ if (vb)
+ vprbrd_free(vb);
+
+ return ret;
+}
+
+static void vprbrd_disconnect(struct usb_interface *interface)
+{
+ struct vprbrd *vb = usb_get_intfdata(interface);
+
+ mfd_remove_devices(&vb->pdev.dev);
+ usb_set_intfdata(interface, NULL);
+ device_unregister(&vb->pdev.dev);
+ vprbrd_free(vb);
+
+ dev_dbg(&interface->dev, "disconnected\n");
+}
+
+static struct usb_driver vprbrd_driver = {
+ .name = "viperboard",
+ .probe = vprbrd_probe,
+ .disconnect = vprbrd_disconnect,
+ .id_table = vprbrd_table,
+};
+
+module_usb_driver(vprbrd_driver);
+
+MODULE_DESCRIPTION("Nano River Technologies viperboard mfd core driver");
+MODULE_AUTHOR("Lars Poeschel <[email protected]>");
+MODULE_LICENSE("GPL");
+
diff --git a/include/linux/mfd/viperboard.h b/include/linux/mfd/viperboard.h
new file mode 100644
index 0000000..3f3f777
--- /dev/null
+++ b/include/linux/mfd/viperboard.h
@@ -0,0 +1,99 @@
+/*
+ * include/linux/mfd/viperboard.h
+ *
+ * Nano River Technologies viperboard definitions
+ *
+ * (C) 2012 by Lemonage GmbH
+ * Author: Lars Poeschel <[email protected]>
+ * All rights reserved.
+ *
+ * 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.
+ *
+ */
+
+#ifndef __MFD_VIPERBOARD_H__
+#define __MFD_VIPERBOARD_H__
+
+#include <linux/types.h>
+#include <linux/usb.h>
+
+#define VPRBRD_EP_OUT 0x02
+#define VPRBRD_EP_IN 0x86
+
+#define VPRBRD_I2C_MSG_LEN 512 /* max length of a msg on USB level */
+
+#define VPRBRD_I2C_FREQ_6MHZ 1 /* 6 MBit/s */
+#define VPRBRD_I2C_FREQ_3MHZ 2 /* 3 MBit/s */
+#define VPRBRD_I2C_FREQ_1MHZ 3 /* 1 MBit/s */
+#define VPRBRD_I2C_FREQ_FAST 4 /* 400 kbit/s */
+#define VPRBRD_I2C_FREQ_400KHZ VPRBRD_I2C_FREQ_FAST
+#define VPRBRD_I2C_FREQ_200KHZ 5 /* 200 kbit/s */
+#define VPRBRD_I2C_FREQ_STD 6 /* 100 kbit/s */
+#define VPRBRD_I2C_FREQ_100KHZ VPRBRD_I2C_FREQ_STD
+#define VPRBRD_I2C_FREQ_10KHZ 7 /* 10 kbit/s */
+
+#define VPRBRD_I2C_CMD_WRITE 0x00
+#define VPRBRD_I2C_CMD_READ 0x01
+#define VPRBRD_I2C_CMD_ADDR 0x02
+
+struct __packed vprbrd_i2c_write_hdr {
+ u8 cmd;
+ u16 addr;
+ u8 len1;
+ u8 len2;
+ u8 last;
+ u8 chan;
+ u16 spi;
+};
+
+struct __packed vprbrd_i2c_read_hdr {
+ u8 cmd;
+ u16 addr;
+ u8 len0;
+ u8 len1;
+ u8 len2;
+ u8 len3;
+ u8 len4;
+ u8 len5;
+ u16 tf1; /* transfer 1 length */
+ u16 tf2; /* transfer 2 length */
+};
+
+struct __packed vprbrd_i2c_status {
+ u8 unknown[11];
+ u8 status;
+};
+
+struct __packed vprbrd_i2c_write_msg {
+ struct vprbrd_i2c_write_hdr header;
+ u8 data[VPRBRD_I2C_MSG_LEN
+ - sizeof(struct vprbrd_i2c_write_hdr)];
+};
+
+struct __packed vprbrd_i2c_read_msg {
+ struct vprbrd_i2c_read_hdr header;
+ u8 data[VPRBRD_I2C_MSG_LEN
+ - sizeof(struct vprbrd_i2c_read_hdr)];
+};
+
+struct __packed vprbrd_i2c_addr_msg {
+ u8 cmd;
+ u8 addr;
+ u8 unknown1;
+ u16 len;
+ u8 unknown2;
+ u8 unknown3;
+};
+
+/* Structure to hold all device specific stuff */
+struct vprbrd {
+ struct usb_device *usb_dev; /* the usb device for this device */
+ struct mutex lock;
+ u8 buf[sizeof(struct vprbrd_i2c_write_msg)];
+ struct platform_device pdev;
+};
+
+#endif /* __MFD_VIPERBOARD_H__ */
--
1.7.10.4


2012-10-12 14:36:33

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v2 2/4] gpio: add viperboard gpio driver

From: Lars Poeschel <[email protected]>

This adds the mfd cell to use the gpio a and gpio b part
of the Nano River Technologies viperboard.

Signed-off-by: Lars Poeschel <[email protected]>
---
drivers/gpio/Kconfig | 13 ++
drivers/gpio/Makefile | 1 +
drivers/gpio/gpio-viperboard.c | 482 ++++++++++++++++++++++++++++++++++++++++
drivers/mfd/viperboard.c | 3 +
4 files changed, 499 insertions(+)
create mode 100644 drivers/gpio/gpio-viperboard.c

diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index 8382dc8..48be4ba 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -636,4 +636,17 @@ config GPIO_MSIC
Enable support for GPIO on intel MSIC controllers found in
intel MID devices

+comment "USB GPIO expanders:"
+
+config GPIO_VIPERBOARD
+ tristate "Viperboard GPIO a & b support"
+ depends on MFD_VIPERBOARD && USB
+ help
+ Say yes here to access the GPIO signals of Nano River
+ Technologies Viperboard. There are two GPIO chips on the
+ board: gpioa and gpiob.
+ See viperboard API specification and Nano
+ River Tech's viperboard.h for detailed meaning
+ of the module parameters.
+
endif
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index 0ffaa84..71cc896 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -69,6 +69,7 @@ obj-$(CONFIG_GPIO_TPS65910) += gpio-tps65910.o
obj-$(CONFIG_GPIO_TPS65912) += gpio-tps65912.o
obj-$(CONFIG_GPIO_TWL4030) += gpio-twl4030.o
obj-$(CONFIG_GPIO_UCB1400) += gpio-ucb1400.o
+obj-$(CONFIG_GPIO_VIPERBOARD) += gpio-viperboard.o
obj-$(CONFIG_GPIO_VR41XX) += gpio-vr41xx.o
obj-$(CONFIG_GPIO_VT8500) += gpio-vt8500.o
obj-$(CONFIG_GPIO_VX855) += gpio-vx855.o
diff --git a/drivers/gpio/gpio-viperboard.c b/drivers/gpio/gpio-viperboard.c
new file mode 100644
index 0000000..dcc0b2c
--- /dev/null
+++ b/drivers/gpio/gpio-viperboard.c
@@ -0,0 +1,482 @@
+/*
+ * Nano River Technologies viperboard GPIO lib driver
+ *
+ * (C) 2012 by Lemonage GmbH
+ * Author: Lars Poeschel <[email protected]>
+ * All rights reserved.
+ *
+ * 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/errno.h>
+#include <linux/module.h>
+#include <linux/slab.h>
+#include <linux/types.h>
+#include <linux/mutex.h>
+#include <linux/platform_device.h>
+
+#include <linux/usb.h>
+#include <linux/gpio.h>
+
+#include <linux/mfd/viperboard.h>
+
+#define VPRBRD_GPIOA_CLK_1 0 /* (1us = 1MHz) */
+#define VPRBRD_GPIOA_CLK_10 1 /* (10us = 100kHz) */
+#define VPRBRD_GPIOA_CLK_100 2 /* (100us = 10kHz) */
+#define VPRBRD_GPIOA_CLK_1000 3 /* (1ms = 1kHz) */
+#define VPRBRD_GPIOA_CLK_10000 4 /* (10ms = 100Hz) */
+#define VPRBRD_GPIOA_CLK_100000 5 /* (100ms = 10Hz) */
+
+#define VPRBRD_GPIOA_CMD_CONT 0x00
+#define VPRBRD_GPIOA_CMD_PULSE 0x01
+#define VPRBRD_GPIOA_CMD_PWM 0x02
+#define VPRBRD_GPIOA_CMD_SETOUT 0x03
+#define VPRBRD_GPIOA_CMD_SETIN 0x04
+#define VPRBRD_GPIOA_CMD_SETINT 0x05
+#define VPRBRD_GPIOA_CMD_GETIN 0x06
+
+#define VPRBRD_GPIOB_CMD_SETDIR 0x00
+#define VPRBRD_GPIOB_CMD_SETVAL 0x01
+
+struct __packed vprbrd_gpioa_msg {
+ u8 cmd;
+ u8 clk;
+ u8 offset;
+ u8 t1;
+ u8 t2;
+ u8 invert;
+ u8 pwmlevel;
+ u8 outval;
+ u8 risefall;
+ u8 answer;
+ u8 __fill;
+};
+
+struct __packed vprbrd_gpiob_msg {
+ u8 cmd;
+ u16 val;
+ u16 mask;
+};
+
+struct vprbrd_gpio {
+ struct gpio_chip gpioa; /* gpio a related things */
+ u32 gpioa_out;
+ u32 gpioa_val;
+ struct gpio_chip gpiob; /* gpio b related things */
+ u32 gpiob_out;
+ u32 gpiob_val;
+ struct vprbrd *vb;
+};
+
+/* gpioa sampling clock module parameter */
+static unsigned char gpioa_clk = 3;
+module_param(gpioa_clk, byte, 0);
+MODULE_PARM_DESC(gpioa_clk, "gpio a sampling clk (default is 3 for 1 kHz)");
+
+/* ----- begin of gipo a chip -------------------------------------------- */
+
+static int vprbrd_gpioa_get(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret, answer, error = 0;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
+
+ /* if io is set to output, just return the saved value */
+ if (gpio->gpioa_out & (1 << offset))
+ return gpio->gpioa_val & (1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ gamsg->cmd = VPRBRD_GPIOA_CMD_GETIN;
+ gamsg->clk = 0x00;
+ gamsg->offset = offset;
+ gamsg->t1 = 0x00;
+ gamsg->t2 = 0x00;
+ gamsg->invert = 0x00;
+ gamsg->pwmlevel = 0x00;
+ gamsg->outval = 0x00;
+ gamsg->risefall = 0x00;
+ gamsg->answer = 0x00;
+ gamsg->__fill = 0x00;
+
+ ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
+ 0xed, 0x40, 0x0000, 0x0000, gamsg,
+ sizeof(struct vprbrd_gpioa_msg), 100);
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ error = -EREMOTEIO;
+
+ ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
+ 0xed, 0xc0, 0x0000, 0x0000, gamsg,
+ sizeof(struct vprbrd_gpioa_msg), 100);
+ answer = gamsg->answer & 0x01;
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ error = -EREMOTEIO;
+
+ if (error)
+ return error;
+
+ return answer;
+}
+
+static void vprbrd_gpioa_set(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
+
+ if (gpio->gpioa_out & (1 << offset)) {
+ if (value)
+ gpio->gpioa_val |= (1 << offset);
+ else
+ gpio->gpioa_val &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ gamsg->cmd = VPRBRD_GPIOA_CMD_SETOUT;
+ gamsg->clk = 0x00;
+ gamsg->offset = offset;
+ gamsg->t1 = 0x00;
+ gamsg->t2 = 0x00;
+ gamsg->invert = 0x00;
+ gamsg->pwmlevel = 0x00;
+ gamsg->outval = value;
+ gamsg->risefall = 0x00;
+ gamsg->answer = 0x00;
+ gamsg->__fill = 0x00;
+
+ ret = usb_control_msg(vb->usb_dev,
+ usb_sndctrlpipe(vb->usb_dev, 0), 0xed, 0x40, 0x0000,
+ 0x0000, gamsg, sizeof(struct vprbrd_gpioa_msg), 100);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ dev_err(chip->dev, "usb error setting pin value\n");
+ }
+}
+
+static int vprbrd_gpioa_direction_input(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
+
+ gpio->gpioa_out &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ gamsg->cmd = VPRBRD_GPIOA_CMD_SETIN;
+ gamsg->clk = gpioa_clk;
+ gamsg->offset = offset;
+ gamsg->t1 = 0x00;
+ gamsg->t2 = 0x00;
+ gamsg->invert = 0x00;
+ gamsg->pwmlevel = 0x00;
+ gamsg->outval = 0x00;
+ gamsg->risefall = 0x00;
+ gamsg->answer = 0x00;
+ gamsg->__fill = 0x00;
+
+ ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
+ 0xed, 0x40, 0x0000, 0x0000, gamsg,
+ sizeof(struct vprbrd_gpioa_msg), 100);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ return -EREMOTEIO;
+
+ return 0;
+}
+
+static int vprbrd_gpioa_direction_output(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
+
+ gpio->gpioa_out |= (1 << offset);
+ if (value)
+ gpio->gpioa_val |= (1 << offset);
+ else
+ gpio->gpioa_val &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ gamsg->cmd = VPRBRD_GPIOA_CMD_SETOUT;
+ gamsg->clk = 0x00;
+ gamsg->offset = offset;
+ gamsg->t1 = 0x00;
+ gamsg->t2 = 0x00;
+ gamsg->invert = 0x00;
+ gamsg->pwmlevel = 0x00;
+ gamsg->outval = value;
+ gamsg->risefall = 0x00;
+ gamsg->answer = 0x00;
+ gamsg->__fill = 0x00;
+
+ ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
+ 0xed, 0x40, 0x0000, 0x0000, gamsg,
+ sizeof(struct vprbrd_gpioa_msg), 100);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ return -EREMOTEIO;
+
+ return 0;
+}
+
+/* ----- end of gpio a chip ---------------------------------------------- */
+
+/* ----- begin of gipo b chip -------------------------------------------- */
+
+static int vprbrd_gpiob_setdir(struct vprbrd *vb, unsigned offset,
+ unsigned dir)
+{
+ struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
+ int ret;
+
+ gbmsg->cmd = VPRBRD_GPIOB_CMD_SETDIR;
+ gbmsg->val = cpu_to_be16(dir << offset);
+ gbmsg->mask = cpu_to_be16(0x0001 << offset);
+
+ ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
+ 0xdd, 0x40, 0x0000, 0x0000, gbmsg,
+ sizeof(struct vprbrd_gpiob_msg), 100);
+
+ if (ret != sizeof(struct vprbrd_gpiob_msg))
+ return -EREMOTEIO;
+
+ return 0;
+}
+
+static int vprbrd_gpiob_get(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret;
+ u16 val;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
+
+ /* if io is set to output, just return the saved value */
+ if (gpio->gpiob_out & (1 << offset))
+ return gpio->gpiob_val & (1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
+ 0xdd, 0xc0, 0x0000, 0x0000, gbmsg,
+ sizeof(struct vprbrd_gpiob_msg), 100);
+ val = gbmsg->val;
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpiob_msg))
+ return ret;
+
+ /* cache the read values */
+ gpio->gpiob_val = be16_to_cpu(val);
+
+ return (gpio->gpiob_val >> offset) & 0x1;
+}
+
+static void vprbrd_gpiob_set(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
+
+ if (gpio->gpiob_out & (1 << offset)) {
+ if (value)
+ gpio->gpiob_val |= (1 << offset);
+ else
+ gpio->gpiob_val &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ gbmsg->cmd = VPRBRD_GPIOB_CMD_SETVAL;
+ gbmsg->val = cpu_to_be16(value << offset);
+ gbmsg->mask = cpu_to_be16(0x0001 << offset);
+
+ ret = usb_control_msg(vb->usb_dev,
+ usb_sndctrlpipe(vb->usb_dev, 0), 0xdd, 0x40, 0x0000,
+ 0x0000, gbmsg, sizeof(struct vprbrd_gpiob_msg), 100);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpiob_msg))
+ dev_err(chip->dev, "usb error setting pin value\n");
+ }
+}
+
+static int vprbrd_gpiob_direction_input(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+
+ gpio->gpiob_out &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ ret = vprbrd_gpiob_setdir(vb, offset, 0);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret)
+ dev_err(chip->dev, "usb error setting pin to input\n");
+
+ return ret;
+}
+
+static int vprbrd_gpiob_direction_output(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+
+ gpio->gpiob_out |= (1 << offset);
+ if (value)
+ gpio->gpiob_val |= (1 << offset);
+ else
+ gpio->gpiob_val &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ ret = vprbrd_gpiob_setdir(vb, offset, 1);
+ if (ret)
+ dev_err(chip->dev, "usb error setting pin to output\n");
+
+ mutex_unlock(&vb->lock);
+
+ vprbrd_gpiob_set(chip, offset, value);
+
+ return ret;
+}
+
+/* ----- end of gpio b chip ---------------------------------------------- */
+
+static int __devinit vprbrd_gpio_probe(struct platform_device *pdev)
+{
+ struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
+ struct vprbrd_gpio *vb_gpio;
+ int ret;
+
+ vb_gpio = kzalloc(sizeof(*vb_gpio), GFP_KERNEL);
+ if (vb_gpio == NULL)
+ return -ENOMEM;
+
+ vb_gpio->vb = vb;
+ /* registering gpio a */
+ vb_gpio->gpioa.label = "viperboard gpio a";
+ vb_gpio->gpioa.dev = &pdev->dev;
+ vb_gpio->gpioa.owner = THIS_MODULE;
+ vb_gpio->gpioa.base = -1;
+ vb_gpio->gpioa.ngpio = 16;
+ vb_gpio->gpioa.can_sleep = 1;
+ vb_gpio->gpioa.set = vprbrd_gpioa_set;
+ vb_gpio->gpioa.get = vprbrd_gpioa_get;
+ vb_gpio->gpioa.direction_input = vprbrd_gpioa_direction_input;
+ vb_gpio->gpioa.direction_output = vprbrd_gpioa_direction_output;
+ ret = gpiochip_add(&vb_gpio->gpioa);
+ if (ret < 0) {
+ dev_err(vb_gpio->gpioa.dev, "could not add gpio a");
+ goto err_gpioa;
+ }
+
+ /* registering gpio b */
+ vb_gpio->gpiob.label = "viperboard gpio b";
+ vb_gpio->gpiob.dev = &pdev->dev;
+ vb_gpio->gpiob.owner = THIS_MODULE;
+ vb_gpio->gpiob.base = -1;
+ vb_gpio->gpiob.ngpio = 16;
+ vb_gpio->gpiob.can_sleep = 1;
+ vb_gpio->gpiob.set = vprbrd_gpiob_set;
+ vb_gpio->gpiob.get = vprbrd_gpiob_get;
+ vb_gpio->gpiob.direction_input = vprbrd_gpiob_direction_input;
+ vb_gpio->gpiob.direction_output = vprbrd_gpiob_direction_output;
+ ret = gpiochip_add(&vb_gpio->gpiob);
+ if (ret < 0) {
+ dev_err(vb_gpio->gpiob.dev, "could not add gpio b");
+ goto err_gpiob;
+ }
+
+ platform_set_drvdata(pdev, vb_gpio);
+
+ return ret;
+
+err_gpiob:
+ ret = gpiochip_remove(&vb_gpio->gpioa);
+
+err_gpioa:
+ kfree(vb_gpio);
+ return ret;
+}
+
+static int __devexit vprbrd_gpio_remove(struct platform_device *pdev)
+{
+ struct vprbrd_gpio *vb_gpio = platform_get_drvdata(pdev);
+ int ret;
+
+ ret = gpiochip_remove(&vb_gpio->gpiob);
+ if (ret == 0)
+ ret = gpiochip_remove(&vb_gpio->gpioa);
+ if (ret == 0)
+ kfree(vb_gpio);
+
+ return ret;
+}
+
+static struct platform_driver vprbrd_gpio_driver = {
+ .driver.name = "viperboard-gpio",
+ .driver.owner = THIS_MODULE,
+ .probe = vprbrd_gpio_probe,
+ .remove = __devexit_p(vprbrd_gpio_remove),
+};
+
+static int __init vprbrd_gpio_init(void)
+{
+ return platform_driver_register(&vprbrd_gpio_driver);
+}
+subsys_initcall(vprbrd_gpio_init);
+
+static void __exit vprbrd_gpio_exit(void)
+{
+ platform_driver_unregister(&vprbrd_gpio_driver);
+}
+module_exit(vprbrd_gpio_exit);
+
+MODULE_AUTHOR("Lars Poeschel <[email protected]>");
+MODULE_DESCRIPTION("GPIO driver for Nano River Techs Viperboard");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:viperboard-gpio");
diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
index 8095ea2..09558e7 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -49,6 +49,9 @@ static void vprbrd_free(struct vprbrd *dev)
}

static struct mfd_cell vprbrd_devs[] = {
+ {
+ .name = "viperboard-gpio",
+ },
};

static int vprbrd_probe(struct usb_interface *interface,
--
1.7.10.4

2012-10-12 14:36:39

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v2 3/4] i2c: add viperboard i2c master driver

From: Lars Poeschel <[email protected]>

This adds the mfd cell to use the i2c part of the Nano River Technologies
viperboard as i2c master.

Signed-off-by: Lars Poeschel <[email protected]>
---
drivers/i2c/busses/Kconfig | 10 +
drivers/i2c/busses/Makefile | 1 +
drivers/i2c/busses/i2c-viperboard.c | 442 +++++++++++++++++++++++++++++++++++
drivers/mfd/viperboard.c | 3 +
4 files changed, 456 insertions(+)
create mode 100644 drivers/i2c/busses/i2c-viperboard.c

diff --git a/drivers/i2c/busses/Kconfig b/drivers/i2c/busses/Kconfig
index 42d9fdd..48344cb 100644
--- a/drivers/i2c/busses/Kconfig
+++ b/drivers/i2c/busses/Kconfig
@@ -803,6 +803,16 @@ config I2C_TINY_USB
This driver can also be built as a module. If so, the module
will be called i2c-tiny-usb.

+config I2C_VIPERBOARD
+ tristate "Viperboard I2C master support"
+ depends on MFD_VIPERBOARD && USB
+ help
+ Say yes here to access the I2C part of the Nano River
+ Technologies Viperboard as I2C master.
+ See viperboard API specification and Nano
+ River Tech's viperboard.h for detailed meaning
+ of the module parameters.
+
comment "Other I2C/SMBus bus drivers"

config I2C_ACORN
diff --git a/drivers/i2c/busses/Makefile b/drivers/i2c/busses/Makefile
index 37c4182..cc3a376 100644
--- a/drivers/i2c/busses/Makefile
+++ b/drivers/i2c/busses/Makefile
@@ -78,6 +78,7 @@ obj-$(CONFIG_I2C_PARPORT) += i2c-parport.o
obj-$(CONFIG_I2C_PARPORT_LIGHT) += i2c-parport-light.o
obj-$(CONFIG_I2C_TAOS_EVM) += i2c-taos-evm.o
obj-$(CONFIG_I2C_TINY_USB) += i2c-tiny-usb.o
+obj-$(CONFIG_I2C_VIPERBOARD) += i2c-viperboard.o

# Other I2C/SMBus bus drivers
obj-$(CONFIG_I2C_ACORN) += i2c-acorn.o
diff --git a/drivers/i2c/busses/i2c-viperboard.c b/drivers/i2c/busses/i2c-viperboard.c
new file mode 100644
index 0000000..c8da2a7
--- /dev/null
+++ b/drivers/i2c/busses/i2c-viperboard.c
@@ -0,0 +1,442 @@
+/*
+ * Nano River Technologies viperboard i2c master driver
+ *
+ * (C) 2012 by Lemonage GmbH
+ * Author: Lars Poeschel <[email protected]>
+ * All rights reserved.
+ *
+ * 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/errno.h>
+#include <linux/module.h>
+#include <linux/slab.h>
+#include <linux/types.h>
+#include <linux/mutex.h>
+#include <linux/platform_device.h>
+
+#include <linux/usb.h>
+#include <linux/i2c.h>
+
+#include <linux/mfd/viperboard.h>
+
+struct vprbrd_i2c {
+ struct i2c_adapter i2c;
+};
+
+/* i2c bus frequency module parameter */
+static unsigned char i2c_bus_freq = 6;
+module_param(i2c_bus_freq, byte, 0);
+MODULE_PARM_DESC(i2c_bus_freq, "i2c bus frequency (default is 6 for 100kHz)");
+
+static int vprbrd_i2c_status(struct i2c_adapter *i2c,
+ struct vprbrd_i2c_status *status, bool prev_error)
+{
+ u16 bytes_xfer;
+ int ret;
+ struct vprbrd *vb = (struct vprbrd *)i2c->algo_data;
+
+ /* check for protocol error */
+ bytes_xfer = sizeof(struct vprbrd_i2c_status);
+
+ ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
+ 0xe9, 0xc0, 0x0000, 0x0000, status, bytes_xfer, 100);
+
+ if (ret != bytes_xfer)
+ prev_error = true;
+
+ if (prev_error) {
+ dev_err(&i2c->dev, "failure in usb communication\n");
+ return -EREMOTEIO;
+ }
+
+ dev_dbg(&i2c->dev, " status = %d\n", status->status);
+ if (status->status != 0x00) {
+ dev_err(&i2c->dev, "failure: i2c protocol error\n");
+ return -EPROTO;
+ }
+ return 0;
+}
+
+static int vprbrd_i2c_receive(struct usb_device *usb_dev,
+ struct vprbrd_i2c_read_msg *rmsg, int bytes_xfer)
+{
+ int ret, bytes_actual;
+ int error = 0;
+
+ /* send the read request */
+ ret = usb_bulk_msg(usb_dev,
+ usb_sndbulkpipe(usb_dev, VPRBRD_EP_OUT), rmsg,
+ sizeof(struct vprbrd_i2c_read_hdr), &bytes_actual, 100);
+
+ if ((ret < 0)
+ || (bytes_actual != sizeof(struct vprbrd_i2c_read_hdr))) {
+ dev_err(&usb_dev->dev, "failure transmitting usb\n");
+ error = -EREMOTEIO;
+ }
+
+ /* read the actual data */
+ ret = usb_bulk_msg(usb_dev,
+ usb_rcvbulkpipe(usb_dev, VPRBRD_EP_IN), rmsg,
+ bytes_xfer, &bytes_actual, 100);
+
+ if ((ret < 0) || (bytes_xfer != bytes_actual)) {
+ dev_err(&usb_dev->dev, "failure receiving usb\n");
+ error = -EREMOTEIO;
+ }
+ return error;
+}
+
+static int vprbrd_i2c_addr(struct usb_device *usb_dev,
+ struct vprbrd_i2c_addr_msg *amsg)
+{
+ int ret, bytes_actual;
+
+ ret = usb_bulk_msg(usb_dev,
+ usb_sndbulkpipe(usb_dev, VPRBRD_EP_OUT), amsg,
+ sizeof(struct vprbrd_i2c_addr_msg), &bytes_actual, 100);
+
+ if ((ret < 0) ||
+ (sizeof(struct vprbrd_i2c_addr_msg) != bytes_actual)) {
+ dev_err(&usb_dev->dev, "failure transmitting usb\n");
+ return -EREMOTEIO;
+ }
+ return 0;
+}
+
+static int vprbrd_i2c_read(struct vprbrd *vb, struct i2c_msg *msg)
+{
+ int ret;
+ u16 remain_len, bytes_xfer, len1, len2,
+ start = 0x0000;
+ struct vprbrd_i2c_read_msg *rmsg =
+ (struct vprbrd_i2c_read_msg *)vb->buf;
+
+ remain_len = msg->len;
+ rmsg->header.cmd = VPRBRD_I2C_CMD_READ;
+ while (remain_len > 0) {
+ rmsg->header.addr = cpu_to_le16(start + 0x4000);
+ if (remain_len <= 255) {
+ len1 = remain_len;
+ len2 = 0x00;
+ rmsg->header.len0 = remain_len;
+ rmsg->header.len1 = 0x00;
+ rmsg->header.len2 = 0x00;
+ rmsg->header.len3 = 0x00;
+ rmsg->header.len4 = 0x00;
+ rmsg->header.len5 = 0x00;
+ remain_len = 0;
+ } else if (remain_len <= 510) {
+ len1 = remain_len;
+ len2 = 0x00;
+ rmsg->header.len0 = remain_len - 255;
+ rmsg->header.len1 = 0xff;
+ rmsg->header.len2 = 0x00;
+ rmsg->header.len3 = 0x00;
+ rmsg->header.len4 = 0x00;
+ rmsg->header.len5 = 0x00;
+ remain_len = 0;
+ } else if (remain_len <= 512) {
+ len1 = remain_len;
+ len2 = 0x00;
+ rmsg->header.len0 = remain_len - 510;
+ rmsg->header.len1 = 0xff;
+ rmsg->header.len2 = 0xff;
+ rmsg->header.len3 = 0x00;
+ rmsg->header.len4 = 0x00;
+ rmsg->header.len5 = 0x00;
+ remain_len = 0;
+ } else if (remain_len <= 767) {
+ len1 = 512;
+ len2 = remain_len - 512;
+ rmsg->header.len0 = 0x02;
+ rmsg->header.len1 = 0xff;
+ rmsg->header.len2 = 0xff;
+ rmsg->header.len3 = remain_len - 512;
+ rmsg->header.len4 = 0x00;
+ rmsg->header.len5 = 0x00;
+ bytes_xfer = remain_len;
+ remain_len = 0;
+ } else if (remain_len <= 1022) {
+ len1 = 512;
+ len2 = remain_len - 512;
+ rmsg->header.len0 = 0x02;
+ rmsg->header.len1 = 0xff;
+ rmsg->header.len2 = 0xff;
+ rmsg->header.len3 = remain_len - 767;
+ rmsg->header.len4 = 0xff;
+ rmsg->header.len5 = 0x00;
+ remain_len = 0;
+ } else if (remain_len <= 1024) {
+ len1 = 512;
+ len2 = remain_len - 512;
+ rmsg->header.len0 = 0x02;
+ rmsg->header.len1 = 0xff;
+ rmsg->header.len2 = 0xff;
+ rmsg->header.len3 = remain_len - 1022;
+ rmsg->header.len4 = 0xff;
+ rmsg->header.len5 = 0xff;
+ remain_len = 0;
+ } else {
+ len1 = 512;
+ len2 = 512;
+ rmsg->header.len0 = 0x02;
+ rmsg->header.len1 = 0xff;
+ rmsg->header.len2 = 0xff;
+ rmsg->header.len3 = 0x02;
+ rmsg->header.len4 = 0xff;
+ rmsg->header.len5 = 0xff;
+ remain_len -= 1024;
+ start += 1024;
+ }
+ rmsg->header.tf1 = cpu_to_le16(len1);
+ rmsg->header.tf2 = cpu_to_le16(len2);
+
+ /* first read transfer */
+ ret = vprbrd_i2c_receive(vb->usb_dev, rmsg, len1);
+ if (ret < 0)
+ return ret;
+ /* copy the received data */
+ memcpy(msg->buf + start, rmsg, len1);
+
+ /* second read transfer if neccessary */
+ if (len2 > 0) {
+ ret = vprbrd_i2c_receive(vb->usb_dev, rmsg, len2);
+ if (ret < 0)
+ return ret;
+ /* copy the received data */
+ memcpy(msg->buf + start + 512, rmsg, len2);
+ }
+ }
+ return 0;
+}
+
+static int vprbrd_i2c_write(struct vprbrd *vb, struct i2c_msg *msg)
+{
+ int ret, bytes_actual;
+ u16 remain_len, bytes_xfer,
+ start = 0x0000;
+ struct vprbrd_i2c_write_msg *wmsg =
+ (struct vprbrd_i2c_write_msg *)vb->buf;
+
+ remain_len = msg->len;
+ wmsg->header.cmd = VPRBRD_I2C_CMD_WRITE;
+ wmsg->header.last = 0x00;
+ wmsg->header.chan = 0x00;
+ wmsg->header.spi = 0x0000;
+ while (remain_len > 0) {
+ wmsg->header.addr = cpu_to_le16(start + 0x4000);
+ if (remain_len > 503) {
+ wmsg->header.len1 = 0xff;
+ wmsg->header.len2 = 0xf8;
+ remain_len -= 503;
+ bytes_xfer = 503 + sizeof(struct vprbrd_i2c_write_hdr);
+ start += 503;
+ } else if (remain_len > 255) {
+ wmsg->header.len1 = 0xff;
+ wmsg->header.len2 = (remain_len - 255);
+ bytes_xfer = remain_len +
+ sizeof(struct vprbrd_i2c_write_hdr);
+ remain_len = 0;
+ } else {
+ wmsg->header.len1 = remain_len;
+ wmsg->header.len2 = 0x00;
+ bytes_xfer = remain_len +
+ sizeof(struct vprbrd_i2c_write_hdr);
+ remain_len = 0;
+ }
+ memcpy(wmsg->data, msg->buf + start,
+ bytes_xfer - sizeof(struct vprbrd_i2c_write_hdr));
+
+ ret = usb_bulk_msg(vb->usb_dev,
+ usb_sndbulkpipe(vb->usb_dev,
+ VPRBRD_EP_OUT), wmsg,
+ bytes_xfer, &bytes_actual, 100);
+ if ((ret < 0) || (bytes_xfer != bytes_actual))
+ return -EREMOTEIO;
+ }
+ return 0;
+}
+
+static int vprbrd_i2c_xfer(struct i2c_adapter *i2c, struct i2c_msg *msgs,
+ int num)
+{
+ struct i2c_msg *pmsg;
+ int i, ret,
+ error = 0;
+ struct vprbrd *vb = (struct vprbrd *)i2c->algo_data;
+ struct vprbrd_i2c_addr_msg *amsg =
+ (struct vprbrd_i2c_addr_msg *)vb->buf;
+ struct vprbrd_i2c_status *smsg = (struct vprbrd_i2c_status *)vb->buf;
+
+ dev_dbg(&i2c->dev, "master xfer %d messages:\n", num);
+
+ for (i = 0 ; i < num ; i++) {
+ pmsg = &msgs[i];
+
+ dev_dbg(&i2c->dev,
+ " %d: %s (flags %d) %d bytes to 0x%02x\n",
+ i, pmsg->flags & I2C_M_RD ? "read" : "write",
+ pmsg->flags, pmsg->len, pmsg->addr);
+
+ /* msgs longer than 2048 bytes are not supported by adapter */
+ if (pmsg->len > 2048)
+ return -EINVAL;
+
+ mutex_lock(&vb->lock);
+ /* directly send the message */
+ if (pmsg->flags & I2C_M_RD) {
+ /* read data */
+ amsg->cmd = VPRBRD_I2C_CMD_ADDR;
+ amsg->unknown2 = 0x00;
+ amsg->unknown3 = 0x00;
+ amsg->addr = pmsg->addr;
+ amsg->unknown1 = 0x01;
+ amsg->len = cpu_to_le16(pmsg->len);
+ /* send the addr and len, we're interested to board */
+ ret = vprbrd_i2c_addr(vb->usb_dev, amsg);
+ if (ret < 0)
+ error = ret;
+
+ ret = vprbrd_i2c_read(vb, pmsg);
+ if (ret < 0)
+ error = ret;
+
+ ret = vprbrd_i2c_status(i2c, smsg, error);
+ if (ret < 0)
+ error = ret;
+ /* in case of protocol error, return the error */
+ if (error < 0)
+ goto error;
+ } else {
+ /* write data */
+ ret = vprbrd_i2c_write(vb, pmsg);
+
+ amsg->cmd = VPRBRD_I2C_CMD_ADDR;
+ amsg->unknown2 = 0x00;
+ amsg->unknown3 = 0x00;
+ amsg->addr = pmsg->addr;
+ amsg->unknown1 = 0x00;
+ amsg->len = cpu_to_le16(pmsg->len);
+ /* send the addr, the data goes to to board */
+ ret = vprbrd_i2c_addr(vb->usb_dev, amsg);
+ if (ret < 0)
+ error = ret;
+
+ ret = vprbrd_i2c_status(i2c, smsg, error);
+ if (ret < 0)
+ error = ret;
+
+ if (error < 0)
+ goto error;
+ }
+ mutex_unlock(&vb->lock);
+ }
+ return 0;
+error:
+ mutex_unlock(&vb->lock);
+ return error;
+}
+
+static u32 vprbrd_i2c_func(struct i2c_adapter *i2c)
+{
+ return I2C_FUNC_I2C | I2C_FUNC_SMBUS_EMUL;
+}
+
+/* This is the actual algorithm we define */
+static const struct i2c_algorithm vprbrd_algorithm = {
+ .master_xfer = vprbrd_i2c_xfer,
+ .functionality = vprbrd_i2c_func,
+};
+
+static int __devinit vprbrd_i2c_probe(struct platform_device *pdev)
+{
+ struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
+ struct vprbrd_i2c *vb_i2c;
+ int ret;
+ int pipe;
+
+ vb_i2c = kzalloc(sizeof(*vb_i2c), GFP_KERNEL);
+ if (vb_i2c == NULL)
+ return -ENOMEM;
+
+ /* setup i2c adapter description */
+ vb_i2c->i2c.owner = THIS_MODULE;
+ vb_i2c->i2c.class = I2C_CLASS_HWMON;
+ vb_i2c->i2c.algo = &vprbrd_algorithm;
+ vb_i2c->i2c.algo_data = vb;
+ snprintf(vb_i2c->i2c.name, sizeof(vb_i2c->i2c.name),
+ "viperboard at bus %03d device %03d",
+ vb->usb_dev->bus->busnum, vb->usb_dev->devnum);
+
+ /* setting the bus frequency */
+ if ((i2c_bus_freq <= VPRBRD_I2C_FREQ_10KHZ)
+ && (i2c_bus_freq >= VPRBRD_I2C_FREQ_6MHZ)) {
+ pipe = usb_sndctrlpipe(vb->usb_dev, 0);
+ ret = usb_control_msg(vb->usb_dev, pipe, 0xe6, 0x40,
+ 0x0000, 0x0000, &i2c_bus_freq, 1, 100);
+ if (ret != 1) {
+ dev_err(&vb_i2c->i2c.dev,
+ "failure setting i2c_bus_freq to %d\n", i2c_bus_freq);
+ ret = -EIO;
+ goto error;
+ }
+ } else {
+ dev_err(&vb_i2c->i2c.dev,
+ "invalid i2c_bus_freq setting:%d\n", i2c_bus_freq);
+ ret = -EIO;
+ goto error;
+ }
+
+ vb_i2c->i2c.dev.parent = &pdev->dev;
+
+ /* attach to i2c layer */
+ i2c_add_adapter(&vb_i2c->i2c);
+
+ platform_set_drvdata(pdev, vb_i2c);
+
+ return 0;
+
+error:
+ kfree(vb_i2c);
+ return ret;
+}
+
+static int __devexit vprbrd_i2c_remove(struct platform_device *pdev)
+{
+ struct vprbrd_i2c *vb_i2c = platform_get_drvdata(pdev);
+ int ret;
+
+ ret = i2c_del_adapter(&vb_i2c->i2c);
+
+ return ret;
+}
+
+static struct platform_driver vprbrd_i2c_driver = {
+ .driver.name = "viperboard-i2c",
+ .driver.owner = THIS_MODULE,
+ .probe = vprbrd_i2c_probe,
+ .remove = __devexit_p(vprbrd_i2c_remove),
+};
+
+static int __init vprbrd_i2c_init(void)
+{
+ return platform_driver_register(&vprbrd_i2c_driver);
+}
+subsys_initcall(vprbrd_i2c_init);
+
+static void __exit vprbrd_i2c_exit(void)
+{
+ platform_driver_unregister(&vprbrd_i2c_driver);
+}
+module_exit(vprbrd_i2c_exit);
+
+MODULE_AUTHOR("Lars Poeschel <[email protected]>");
+MODULE_DESCRIPTION("I2C master driver for Nano River Techs Viperboard");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:viperboard-i2c");
diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
index 09558e7..a25e07e 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -52,6 +52,9 @@ static struct mfd_cell vprbrd_devs[] = {
{
.name = "viperboard-gpio",
},
+ {
+ .name = "viperboard-i2c",
+ },
};

static int vprbrd_probe(struct usb_interface *interface,
--
1.7.10.4

2012-10-12 14:36:52

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v2 4/4] iio: adc: add viperboard adc driver

From: Lars Poeschel <[email protected]>

This adds the mfd cell to use the adc part of the Nano River Technologies
viperboard.

Signed-off-by: Lars Poeschel <[email protected]>
---
drivers/iio/adc/Kconfig | 7 ++
drivers/iio/adc/Makefile | 1 +
drivers/iio/adc/viperboard_adc.c | 185 ++++++++++++++++++++++++++++++++++++++
drivers/mfd/viperboard.c | 3 +
4 files changed, 196 insertions(+)
create mode 100644 drivers/iio/adc/viperboard_adc.c

diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
index 4927581..35ad77d 100644
--- a/drivers/iio/adc/Kconfig
+++ b/drivers/iio/adc/Kconfig
@@ -60,4 +60,11 @@ config LP8788_ADC
help
Say yes here to build support for TI LP8788 ADC.

+config VIPERBOARD_ADC
+ tristate "Viperboard ADC support"
+ depends on MFD_VIPERBOARD && USB
+ help
+ Say yes here to access the ADC part of the Nano River
+ Technologies Viperboard.
+
endmenu
diff --git a/drivers/iio/adc/Makefile b/drivers/iio/adc/Makefile
index 900995d..4852c2e 100644
--- a/drivers/iio/adc/Makefile
+++ b/drivers/iio/adc/Makefile
@@ -8,3 +8,4 @@ obj-$(CONFIG_AD7476) += ad7476.o
obj-$(CONFIG_AD7791) += ad7791.o
obj-$(CONFIG_AT91_ADC) += at91_adc.o
obj-$(CONFIG_LP8788_ADC) += lp8788_adc.o
+obj-$(CONFIG_VIPERBOARD_ADC) += viperboard_adc.o
diff --git a/drivers/iio/adc/viperboard_adc.c b/drivers/iio/adc/viperboard_adc.c
new file mode 100644
index 0000000..8ae6634
--- /dev/null
+++ b/drivers/iio/adc/viperboard_adc.c
@@ -0,0 +1,185 @@
+/*
+ * Nano River Technologies viperboard iio ADC driver
+ *
+ * (C) 2012 by Lemonage GmbH
+ * Author: Lars Poeschel <[email protected]>
+ * All rights reserved.
+ *
+ * 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/errno.h>
+#include <linux/module.h>
+#include <linux/slab.h>
+#include <linux/types.h>
+#include <linux/mutex.h>
+#include <linux/platform_device.h>
+
+#include <linux/usb.h>
+#include <linux/iio/iio.h>
+
+#include <linux/mfd/viperboard.h>
+
+#define VPRBRD_ADC_CMD_GET 0x00
+
+struct __packed vprbrd_adc_msg {
+ u8 cmd;
+ u8 chan;
+ u8 val;
+};
+
+struct vprbrd_adc {
+ struct vprbrd *vb;
+};
+
+#define VPRBRD_ADC_CHANNEL(_index) { \
+ .type = IIO_VOLTAGE, \
+ .indexed = 1, \
+ .channel = _index, \
+ .info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT, \
+ .scan_index = _index, \
+ .scan_type.sign = 'u', \
+ .scan_type.realbits = 8, \
+ .scan_type.storagebits = 8, \
+}
+
+static struct iio_chan_spec vprbrd_adc_iio_channels[] = {
+ VPRBRD_ADC_CHANNEL(0),
+ VPRBRD_ADC_CHANNEL(1),
+ VPRBRD_ADC_CHANNEL(2),
+ VPRBRD_ADC_CHANNEL(3),
+};
+
+static int vprbrd_iio_read_raw(struct iio_dev *iio_dev,
+ struct iio_chan_spec const *chan,
+ int *val,
+ int *val2,
+ long mask)
+{
+ int ret, error = 0;
+ struct vprbrd_adc *adc = iio_priv(iio_dev);
+ struct vprbrd *vb = adc->vb;
+ struct vprbrd_adc_msg *admsg = (struct vprbrd_adc_msg *)vb->buf;
+
+ if (mask == IIO_CHAN_INFO_RAW) {
+
+ mutex_lock(&vb->lock);
+
+ admsg->cmd = VPRBRD_ADC_CMD_GET;
+ admsg->chan = chan->scan_index;
+ admsg->val = 0x00;
+
+ ret = usb_control_msg(vb->usb_dev,
+ usb_sndctrlpipe(vb->usb_dev, 0), 0xec, 0x40,
+ 0x0000, 0x0000, admsg,
+ sizeof(struct vprbrd_adc_msg), 100);
+ if (ret != sizeof(struct vprbrd_adc_msg)) {
+ dev_err(&iio_dev->dev, "usb send error on adc read\n");
+ error = -EREMOTEIO;
+ }
+
+ ret = usb_control_msg(vb->usb_dev,
+ usb_rcvctrlpipe(vb->usb_dev, 0), 0xec, 0xc0,
+ 0x0000, 0x0000, admsg,
+ sizeof(struct vprbrd_adc_msg), 100);
+
+ *val = admsg->val;
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_adc_msg)) {
+ dev_err(&iio_dev->dev, "usb recv error on adc read\n");
+ error = -EREMOTEIO;
+ }
+
+ if (error)
+ goto error;
+
+ return IIO_VAL_INT;
+ }
+ error = -EINVAL;
+error:
+ return error;
+}
+
+static const struct iio_info vprbrd_adc_iio_info = {
+ .read_raw = &vprbrd_iio_read_raw,
+ .driver_module = THIS_MODULE,
+};
+
+static int __devinit vprbrd_adc_probe(struct platform_device *pdev)
+{
+ struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
+ struct vprbrd_adc *adc;
+ struct iio_dev *iodev;
+ int ret;
+
+ /* registering iio */
+ iodev = iio_device_alloc(sizeof(struct vprbrd_adc));
+ if (!iodev) {
+ dev_err(&pdev->dev, "failed allocating iio device\n");
+ return -ENOMEM;
+ }
+
+ adc = iio_priv(iodev);
+ adc->vb = vb;
+ iodev->name = "viperboard adc";
+ iodev->dev.parent = &pdev->dev;
+ iodev->info = &vprbrd_adc_iio_info;
+ iodev->modes = INDIO_DIRECT_MODE;
+ iodev->channels = vprbrd_adc_iio_channels;
+ iodev->num_channels = ARRAY_SIZE(vprbrd_adc_iio_channels);
+
+ ret = iio_device_register(iodev);
+ if (ret) {
+ dev_err(&pdev->dev, "could not register iio (adc)");
+ goto error;
+ }
+
+ platform_set_drvdata(pdev, iodev);
+
+ return 0;
+
+error:
+ iio_device_free(iodev);
+ return ret;
+}
+
+static int __devexit vprbrd_adc_remove(struct platform_device *pdev)
+{
+ struct iio_dev *iodev = platform_get_drvdata(pdev);
+
+ iio_device_unregister(iodev);
+ iio_device_free(iodev);
+
+ return 0;
+}
+
+static struct platform_driver vprbrd_adc_driver = {
+ .driver.name = "viperboard-adc",
+ .driver.owner = THIS_MODULE,
+ .probe = vprbrd_adc_probe,
+ .remove = __devexit_p(vprbrd_adc_remove),
+};
+
+static int __init vprbrd_adc_init(void)
+{
+ return platform_driver_register(&vprbrd_adc_driver);
+}
+subsys_initcall(vprbrd_adc_init);
+
+static void __exit vprbrd_adc_exit(void)
+{
+ platform_driver_unregister(&vprbrd_adc_driver);
+}
+module_exit(vprbrd_adc_exit);
+
+MODULE_AUTHOR("Lars Poeschel <[email protected]>");
+MODULE_DESCRIPTION("IIO ADC driver for Nano River Techs Viperboard");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:viperboard-adc");
diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
index a25e07e..eb1cf89 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -55,6 +55,9 @@ static struct mfd_cell vprbrd_devs[] = {
{
.name = "viperboard-i2c",
},
+ {
+ .name = "viperboard-adc",
+ },
};

static int vprbrd_probe(struct usb_interface *interface,
--
1.7.10.4

2012-10-15 13:00:15

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Fri, Oct 12, 2012 at 4:34 PM, Lars Poeschel <[email protected]> wrote:

> From: Lars Poeschel <[email protected]>
>
> This adds the mfd cell to use the gpio a and gpio b part
> of the Nano River Technologies viperboard.
>
> Signed-off-by: Lars Poeschel <[email protected]>

OK...
(...)
> diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
(...)

> +#define VPRBRD_GPIOA_CLK_1 0 /* (1us = 1MHz) */
> +#define VPRBRD_GPIOA_CLK_10 1 /* (10us = 100kHz) */
> +#define VPRBRD_GPIOA_CLK_100 2 /* (100us = 10kHz) */
> +#define VPRBRD_GPIOA_CLK_1000 3 /* (1ms = 1kHz) */
> +#define VPRBRD_GPIOA_CLK_10000 4 /* (10ms = 100Hz) */
> +#define VPRBRD_GPIOA_CLK_100000 5 /* (100ms = 10Hz) */

So instead of #defining something noone understands and
then writing in the comment what it actually means, why
don't you just:

#define VPRBRD_GPIOA_CLK_1MHZ 0
#define VPRBRD_GPIOA_CLK_100KHZ 1

or maybe:

#define VPRBRD_GPIOA_CLK_PERIOD_1US 0
#define VPRBRD_GPIOA_CLK_PERIOD_10US 1

or something else you will understand immediately when reading the
code?

(...)
> +struct __packed vprbrd_gpioa_msg {

__packed always goes *after* the struct does it not?

> + u8 cmd;
> + u8 clk;
> + u8 offset;
> + u8 t1;
> + u8 t2;
> + u8 invert;
> + u8 pwmlevel;
> + u8 outval;
> + u8 risefall;
> + u8 answer;
> + u8 __fill;
> +}; <- i.e. here, before the semicolon.

> +/* gpioa sampling clock module parameter */
> +static unsigned char gpioa_clk = 3;

Isn't this actually

static unsigned char gpioa_clk = VPRBRD_GPIOA_CLK_1000

> +module_param(gpioa_clk, byte, 0);
> +MODULE_PARM_DESC(gpioa_clk, "gpio a sampling clk (default is 3 for 1 kHz)");

So if you're adding very magic module parameters maybe
this magic number isn't such a good idea. Oh well, there
are stranger things in the world so OK...

(...)
> +static int vprbrd_gpioa_get(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + int ret, answer, error = 0;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpioa);
> + struct vprbrd *vb = gpio->vb;
> + struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
> +
> + /* if io is set to output, just return the saved value */
> + if (gpio->gpioa_out & (1 << offset))
> + return gpio->gpioa_val & (1 << offset);

That's not going to work if the hardware changes state
behind the back of the driver right? Oh well, maybe
it doesn't matter.

The rest does some clever USB marshalling that I trust
is doing what it should :-)

> + ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
> + 0xed, 0x40, 0x0000, 0x0000, gamsg,
> + sizeof(struct vprbrd_gpioa_msg), 100);

0xed? 0x40? 100?

Can you #define the magic constants, or are they already available
in some existing header file?

(The zeros are OK.)

> + if (ret != sizeof(struct vprbrd_gpioa_msg))
> + error = -EREMOTEIO;
> +
> + ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
> + 0xed, 0xc0, 0x0000, 0x0000, gamsg,
> + sizeof(struct vprbrd_gpioa_msg), 100);

Dito...

Same comment for *set, *direction_input, *direction_output,
*setdir,

(...)
> +static int __devinit vprbrd_gpio_probe(struct platform_device *pdev)
> +{
> + struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
> + struct vprbrd_gpio *vb_gpio;
> + int ret;
> +
> + vb_gpio = kzalloc(sizeof(*vb_gpio), GFP_KERNEL);

Can you use devm_kzalloc(&pdev->dev, ...)?

> + if (vb_gpio == NULL)
> + return -ENOMEM;
> +
> + vb_gpio->vb = vb;
> + /* registering gpio a */
> + vb_gpio->gpioa.label = "viperboard gpio a";
> + vb_gpio->gpioa.dev = &pdev->dev;
> + vb_gpio->gpioa.owner = THIS_MODULE;
> + vb_gpio->gpioa.base = -1;
> + vb_gpio->gpioa.ngpio = 16;
> + vb_gpio->gpioa.can_sleep = 1;
> + vb_gpio->gpioa.set = vprbrd_gpioa_set;
> + vb_gpio->gpioa.get = vprbrd_gpioa_get;
> + vb_gpio->gpioa.direction_input = vprbrd_gpioa_direction_input;
> + vb_gpio->gpioa.direction_output = vprbrd_gpioa_direction_output;
> + ret = gpiochip_add(&vb_gpio->gpioa);
> + if (ret < 0) {
> + dev_err(vb_gpio->gpioa.dev, "could not add gpio a");
> + goto err_gpioa;
> + }
> +
> + /* registering gpio b */
> + vb_gpio->gpiob.label = "viperboard gpio b";
> + vb_gpio->gpiob.dev = &pdev->dev;
> + vb_gpio->gpiob.owner = THIS_MODULE;
> + vb_gpio->gpiob.base = -1;
> + vb_gpio->gpiob.ngpio = 16;
> + vb_gpio->gpiob.can_sleep = 1;
> + vb_gpio->gpiob.set = vprbrd_gpiob_set;
> + vb_gpio->gpiob.get = vprbrd_gpiob_get;
> + vb_gpio->gpiob.direction_input = vprbrd_gpiob_direction_input;
> + vb_gpio->gpiob.direction_output = vprbrd_gpiob_direction_output;
> + ret = gpiochip_add(&vb_gpio->gpiob);
> + if (ret < 0) {
> + dev_err(vb_gpio->gpiob.dev, "could not add gpio b");
> + goto err_gpiob;
> + }
> +
> + platform_set_drvdata(pdev, vb_gpio);
> +
> + return ret;
> +
> +err_gpiob:
> + ret = gpiochip_remove(&vb_gpio->gpioa);
> +
> +err_gpioa:
> + kfree(vb_gpio);

With devm_kzalloc you don't need this free.

(...)
> +static int __devexit vprbrd_gpio_remove(struct platform_device *pdev)
> +{
> + struct vprbrd_gpio *vb_gpio = platform_get_drvdata(pdev);
> + int ret;
> +
> + ret = gpiochip_remove(&vb_gpio->gpiob);
> + if (ret == 0)
> + ret = gpiochip_remove(&vb_gpio->gpioa);
> + if (ret == 0)
> + kfree(vb_gpio);

Nor this.

Apart from this the driver is looking nice!

Yours,
Linus Walleij

2012-10-15 14:25:26

by Lars-Peter Clausen

[permalink] [raw]
Subject: Re: [PATCH v2 4/4] iio: adc: add viperboard adc driver

Added [email protected] to Cc.

On 10/12/2012 04:34 PM, Lars Poeschel wrote:
> From: Lars Poeschel <[email protected]>
>
> This adds the mfd cell to use the adc part of the Nano River Technologies
> viperboard.
>
> Signed-off-by: Lars Poeschel <[email protected]>

Looks good in general, just some minor code style issues.

> ---
> drivers/iio/adc/Kconfig | 7 ++
> drivers/iio/adc/Makefile | 1 +
> drivers/iio/adc/viperboard_adc.c | 185 ++++++++++++++++++++++++++++++++++++++
> drivers/mfd/viperboard.c | 3 +
> 4 files changed, 196 insertions(+)
> create mode 100644 drivers/iio/adc/viperboard_adc.c
>
[...]
> diff --git a/drivers/iio/adc/viperboard_adc.c b/drivers/iio/adc/viperboard_adc.c
> new file mode 100644
> index 0000000..8ae6634
> --- /dev/null
> +++ b/drivers/iio/adc/viperboard_adc.c
> @@ -0,0 +1,185 @@
> +/*
> + * Nano River Technologies viperboard iio ADC driver
> + *
> + * (C) 2012 by Lemonage GmbH
> + * Author: Lars Poeschel <[email protected]>
> + * All rights reserved.
> + *
> + * 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/errno.h>
> +#include <linux/module.h>
> +#include <linux/slab.h>
> +#include <linux/types.h>
> +#include <linux/mutex.h>
> +#include <linux/platform_device.h>
> +
> +#include <linux/usb.h>
> +#include <linux/iio/iio.h>
> +
> +#include <linux/mfd/viperboard.h>
> +
> +#define VPRBRD_ADC_CMD_GET 0x00
> +
> +struct __packed vprbrd_adc_msg {
> + u8 cmd;
> + u8 chan;
> + u8 val;
> +};

put the __packed between } and ;

> +
> +struct vprbrd_adc {
> + struct vprbrd *vb;
> +};
> +
> +#define VPRBRD_ADC_CHANNEL(_index) { \
> + .type = IIO_VOLTAGE, \
> + .indexed = 1, \
> + .channel = _index, \
> + .info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT, \

It would be good if you could also report the channel scale.

> + .scan_index = _index, \
> + .scan_type.sign = 'u', \
> + .scan_type.realbits = 8, \
> + .scan_type.storagebits = 8, \

Usually this is written as
.scan_type = {
.sign = 'u',
....
},

> +}
> +
> +static struct iio_chan_spec vprbrd_adc_iio_channels[] = {
const

> + VPRBRD_ADC_CHANNEL(0),
> + VPRBRD_ADC_CHANNEL(1),
> + VPRBRD_ADC_CHANNEL(2),
> + VPRBRD_ADC_CHANNEL(3),
> +};
> +
> +static int vprbrd_iio_read_raw(struct iio_dev *iio_dev,
> + struct iio_chan_spec const *chan,
> + int *val,
> + int *val2,
> + long mask)

'mask' used to be a mask and that's why it is still called 'mask' in older
drivers. For new drivers we should use 'info'.

> +{
> + int ret, error = 0;
> + struct vprbrd_adc *adc = iio_priv(iio_dev);
> + struct vprbrd *vb = adc->vb;
> + struct vprbrd_adc_msg *admsg = (struct vprbrd_adc_msg *)vb->buf;
> +
> + if (mask == IIO_CHAN_INFO_RAW) {
> +

Use switch instead of if. Otherwise you'd end up with if(mask == ...) else
if(mask == ...) else if (mask == ...) if you add support for more channel
attributes.

> + mutex_lock(&vb->lock);
> +
> + admsg->cmd = VPRBRD_ADC_CMD_GET;
> + admsg->chan = chan->scan_index;
> + admsg->val = 0x00;
> +
> + ret = usb_control_msg(vb->usb_dev,
> + usb_sndctrlpipe(vb->usb_dev, 0), 0xec, 0x40,
> + 0x0000, 0x0000, admsg,
> + sizeof(struct vprbrd_adc_msg), 100);
> + if (ret != sizeof(struct vprbrd_adc_msg)) {
> + dev_err(&iio_dev->dev, "usb send error on adc read\n");
> + error = -EREMOTEIO;
> + }

Does it make sense to send out the second msg if the first one failed?

> +
> + ret = usb_control_msg(vb->usb_dev,
> + usb_rcvctrlpipe(vb->usb_dev, 0), 0xec, 0xc0,
> + 0x0000, 0x0000, admsg,
> + sizeof(struct vprbrd_adc_msg), 100);
> +

It would be good to have some defines for the magic constants used for
request and request_type.

> + *val = admsg->val;
> +
> + mutex_unlock(&vb->lock);
> +
> + if (ret != sizeof(struct vprbrd_adc_msg)) {
> + dev_err(&iio_dev->dev, "usb recv error on adc read\n");
> + error = -EREMOTEIO;
> + }
> +
> + if (error)
> + goto error;
> +
> + return IIO_VAL_INT;
> + }
> + error = -EINVAL;
> +error:
> + return error;
> +}
> +
> +static const struct iio_info vprbrd_adc_iio_info = {
> + .read_raw = &vprbrd_iio_read_raw,
> + .driver_module = THIS_MODULE,
> +};
> +
> +static int __devinit vprbrd_adc_probe(struct platform_device *pdev)
> +{
> + struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
> + struct vprbrd_adc *adc;
> + struct iio_dev *iodev;

Usually this is called indio_dev, would be good for consistency if you'd do
this as well.

> + int ret;
> +
> + /* registering iio */
> + iodev = iio_device_alloc(sizeof(struct vprbrd_adc));
> + if (!iodev) {
> + dev_err(&pdev->dev, "failed allocating iio device\n");
> + return -ENOMEM;
> + }
> +
> + adc = iio_priv(iodev);
> + adc->vb = vb;
> + iodev->name = "viperboard adc";
> + iodev->dev.parent = &pdev->dev;
> + iodev->info = &vprbrd_adc_iio_info;
> + iodev->modes = INDIO_DIRECT_MODE;
> + iodev->channels = vprbrd_adc_iio_channels;
> + iodev->num_channels = ARRAY_SIZE(vprbrd_adc_iio_channels);
> +
> + ret = iio_device_register(iodev);
> + if (ret) {
> + dev_err(&pdev->dev, "could not register iio (adc)");
> + goto error;
> + }
> +
> + platform_set_drvdata(pdev, iodev);
> +
> + return 0;
> +
> +error:
> + iio_device_free(iodev);
> + return ret;
> +}
> +
> +static int __devexit vprbrd_adc_remove(struct platform_device *pdev)
> +{
> + struct iio_dev *iodev = platform_get_drvdata(pdev);
> +
> + iio_device_unregister(iodev);
> + iio_device_free(iodev);
> +
> + return 0;
> +}
> +
> +static struct platform_driver vprbrd_adc_driver = {
> + .driver.name = "viperboard-adc",
> + .driver.owner = THIS_MODULE,

Same as with scan_type, usually this is written as

.driver = {
.name = ...
....
},

> + .probe = vprbrd_adc_probe,
> + .remove = __devexit_p(vprbrd_adc_remove),
> +};
> +
> +static int __init vprbrd_adc_init(void)
> +{
> + return platform_driver_register(&vprbrd_adc_driver);
> +}
> +subsys_initcall(vprbrd_adc_init);
> +
> +static void __exit vprbrd_adc_exit(void)
> +{
> + platform_driver_unregister(&vprbrd_adc_driver);
> +}
> +module_exit(vprbrd_adc_exit);

module_platform_driver(vprbrd_adc_driver);

> +
> +MODULE_AUTHOR("Lars Poeschel <[email protected]>");
> +MODULE_DESCRIPTION("IIO ADC driver for Nano River Techs Viperboard");
> +MODULE_LICENSE("GPL");
> +MODULE_ALIAS("platform:viperboard-adc");
> diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
> index a25e07e..eb1cf89 100644
> --- a/drivers/mfd/viperboard.c
> +++ b/drivers/mfd/viperboard.c
> @@ -55,6 +55,9 @@ static struct mfd_cell vprbrd_devs[] = {
> {
> .name = "viperboard-i2c",
> },
> + {
> + .name = "viperboard-adc",
> + },
> };
>
> static int vprbrd_probe(struct usb_interface *interface,

2012-10-15 17:09:57

by Peter Meerwald-Stadler

[permalink] [raw]
Subject: Re: [PATCH v2 1/4] mfd: add viperboard driver


minor nitpicking below

> From: Lars Poeschel <[email protected]>
>
> Add mfd driver for Nano River Technologies viperboard.
>
> Signed-off-by: Lars Poeschel <[email protected]>
> ---
> drivers/mfd/Kconfig | 14 ++++
> drivers/mfd/Makefile | 1 +
> drivers/mfd/viperboard.c | 149 ++++++++++++++++++++++++++++++++++++++++
> include/linux/mfd/viperboard.h | 99 ++++++++++++++++++++++++++
> 4 files changed, 263 insertions(+)
> create mode 100644 drivers/mfd/viperboard.c
> create mode 100644 include/linux/mfd/viperboard.h
>
> diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
> index b1a1462..98d9fa3 100644
> --- a/drivers/mfd/Kconfig
> +++ b/drivers/mfd/Kconfig
> @@ -1003,6 +1003,20 @@ config MFD_PALMAS
> If you say yes here you get support for the Palmas
> series of PMIC chips from Texas Instruments.
>
> +config MFD_VIPERBOARD
> + tristate "Support for Nano River Technologies Viperboard"

probably wrong indentation (space vs. tab)?

> + select MFD_CORE
> + depends on USB && IIO
> + default n
> + help
> + Say yes here if you want support for Nano River Technologies
> + Viperboard.
> + There are mfd cell drivers available for i2c master, adc and
> + both gpios found on the board. The spi part does not yet
> + have a driver.
> + You need to select the mfd cell drivers seperatly.

separately

> + The drivers do not support all features the board exposes.
> +
> endmenu
> endif
>
> diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
> index 79dd22d..6ab6b64 100644
> --- a/drivers/mfd/Makefile
> +++ b/drivers/mfd/Makefile
> @@ -128,6 +128,7 @@ obj-$(CONFIG_MFD_TPS65090) += tps65090.o
> obj-$(CONFIG_MFD_AAT2870_CORE) += aat2870-core.o
> obj-$(CONFIG_MFD_INTEL_MSIC) += intel_msic.o
> obj-$(CONFIG_MFD_PALMAS) += palmas.o
> +obj-$(CONFIG_MFD_VIPERBOARD) += viperboard.o
> obj-$(CONFIG_MFD_RC5T583) += rc5t583.o rc5t583-irq.o
> obj-$(CONFIG_MFD_SEC_CORE) += sec-core.o sec-irq.o
> obj-$(CONFIG_MFD_ANATOP) += anatop-mfd.o
> diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
> new file mode 100644
> index 0000000..8095ea2
> --- /dev/null
> +++ b/drivers/mfd/viperboard.c
> @@ -0,0 +1,149 @@
> +/*
> + * Nano River Technologies viperboard driver
> + *
> + * This is the core driver for the viperboard. There are cell drivers
> + * available for I2C, ADC and both GPIOs. SPI is not yet supported

full stop (.) missing

> + * The drivers do not support all features the board exposes. See user
> + * manual of the viperboard.
> + *
> + * (C) 2012 by Lemonage GmbH
> + * Author: Lars Poeschel <[email protected]>
> + * All rights reserved.
> + *
> + * 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/errno.h>
> +#include <linux/module.h>
> +#include <linux/slab.h>
> +#include <linux/types.h>
> +#include <linux/mutex.h>
> +
> +#include <linux/mfd/core.h>
> +#include <linux/mfd/viperboard.h>
> +
> +#include <linux/usb.h>
> +
> +
> +static const struct usb_device_id vprbrd_table[] = {
> + { USB_DEVICE(0x2058, 0x1005) }, /* Nano River Technologies */
> + { } /* Terminating entry */
> +};
> +
> +MODULE_DEVICE_TABLE(usb, vprbrd_table);
> +
> +static void vprbrd_dev_release(struct device *dev)
> +{
> + return;

return not needed

> +}
> +
> +static void vprbrd_free(struct vprbrd *dev)
> +{
> + usb_put_dev(dev->usb_dev);
> + kfree(dev);
> +}


--

Peter Meerwald
+43-664-2444418 (mobile)

2012-10-16 06:51:45

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Monday 15 October 2012 at 15:00:12, Linus Walleij wrote:

> > +#define VPRBRD_GPIOA_CLK_1 0 /* (1us = 1MHz)
> > */ +#define VPRBRD_GPIOA_CLK_10 1 /* (10us =
> > 100kHz) */ +#define VPRBRD_GPIOA_CLK_100 2 /* (100us
> > = 10kHz) */ +#define VPRBRD_GPIOA_CLK_1000 3 /* (1ms
> > = 1kHz) */ +#define VPRBRD_GPIOA_CLK_10000 4 /*
> > (10ms = 100Hz) */ +#define VPRBRD_GPIOA_CLK_100000 5
> > /* (100ms = 10Hz) */
>
> So instead of #defining something noone understands and
> then writing in the comment what it actually means, why
> don't you just:
>
> #define VPRBRD_GPIOA_CLK_1MHZ 0
> #define VPRBRD_GPIOA_CLK_100KHZ 1
>
> or maybe:
>
> #define VPRBRD_GPIOA_CLK_PERIOD_1US 0
> #define VPRBRD_GPIOA_CLK_PERIOD_10US 1
>
> or something else you will understand immediately when reading the
> code?

Yes, you are right. I was too involved with my hardware to see this. I will
change this.

> > +struct __packed vprbrd_gpioa_msg {
>
> __packed always goes *after* the struct does it not?
>
> > + u8 cmd;
> > + u8 clk;
> > + u8 offset;
> > + u8 t1;
> > + u8 t2;
> > + u8 invert;
> > + u8 pwmlevel;
> > + u8 outval;
> > + u8 risefall;
> > + u8 answer;
> > + u8 __fill;
> > +}; <- i.e. here, before the semicolon.

GCC does allow both alternatives. See description of packed attribute under:

http://gcc.gnu.org/onlinedocs/gcc/Type-Attributes.html#Type-Attributes

But since most kernel code does it right before the semicolon, I will change
that too.

> > +/* gpioa sampling clock module parameter */
> > +static unsigned char gpioa_clk = 3;
>
> Isn't this actually
>
> static unsigned char gpioa_clk = VPRBRD_GPIOA_CLK_1000
>
> > +module_param(gpioa_clk, byte, 0);
> > +MODULE_PARM_DESC(gpioa_clk, "gpio a sampling clk (default is 3 for 1
> > kHz)");
>
> So if you're adding very magic module parameters maybe
> this magic number isn't such a good idea. Oh well, there
> are stranger things in the world so OK...

Also I will change this to be more descriptive.

> > +static int vprbrd_gpioa_get(struct gpio_chip *chip,
> > + unsigned offset)
> > +{
> > + int ret, answer, error = 0;
> > + struct vprbrd_gpio *gpio =
> > + container_of(chip, struct vprbrd_gpio, gpioa);
> > + struct vprbrd *vb = gpio->vb;
> > + struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg
> > *)vb->buf; +
> > + /* if io is set to output, just return the saved value */
> > + if (gpio->gpioa_out & (1 << offset))
> > + return gpio->gpioa_val & (1 << offset);
>
> That's not going to work if the hardware changes state
> behind the back of the driver right? Oh well, maybe
> it doesn't matter.

I thought about that and then did this "cache" only in case the gpio is a
output to save to usb ping-pong that is needed otherwise. I thought that
nothing can change to state of the output but the driver itself.

> The rest does some clever USB marshalling that I trust
> is doing what it should :-)
>
> > + ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev,
> > 0), + 0xed, 0x40, 0x0000, 0x0000, gamsg,
> > + sizeof(struct vprbrd_gpioa_msg), 100);
>
> 0xed? 0x40? 100?
>
> Can you #define the magic constants, or are they already available
> in some existing header file?
>
> (The zeros are OK.)

No there are no constants in some existing file. I will introduce them.

> > + if (ret != sizeof(struct vprbrd_gpioa_msg))
> > + error = -EREMOTEIO;
> > +
> > + ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev,
> > 0), + 0xed, 0xc0, 0x0000, 0x0000, gamsg,
> > + sizeof(struct vprbrd_gpioa_msg), 100);
>
> Dito...
>
> Same comment for *set, *direction_input, *direction_output,
> *setdir,
>
> (...)
>
> > +static int __devinit vprbrd_gpio_probe(struct platform_device *pdev)
> > +{
> > + struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
> > + struct vprbrd_gpio *vb_gpio;
> > + int ret;
> > +
> > + vb_gpio = kzalloc(sizeof(*vb_gpio), GFP_KERNEL);
>
> Can you use devm_kzalloc(&pdev->dev, ...)?

Ofcourse. Thanks for the hint. I did not knew this function.

> > + if (vb_gpio == NULL)
> > + return -ENOMEM;
> > +
> > + vb_gpio->vb = vb;
> > + /* registering gpio a */
> > + vb_gpio->gpioa.label = "viperboard gpio a";
> > + vb_gpio->gpioa.dev = &pdev->dev;
> > + vb_gpio->gpioa.owner = THIS_MODULE;
> > + vb_gpio->gpioa.base = -1;
> > + vb_gpio->gpioa.ngpio = 16;
> > + vb_gpio->gpioa.can_sleep = 1;
> > + vb_gpio->gpioa.set = vprbrd_gpioa_set;
> > + vb_gpio->gpioa.get = vprbrd_gpioa_get;
> > + vb_gpio->gpioa.direction_input = vprbrd_gpioa_direction_input;
> > + vb_gpio->gpioa.direction_output = vprbrd_gpioa_direction_output;
> > + ret = gpiochip_add(&vb_gpio->gpioa);
> > + if (ret < 0) {
> > + dev_err(vb_gpio->gpioa.dev, "could not add gpio a");
> > + goto err_gpioa;
> > + }
> > +
> > + /* registering gpio b */
> > + vb_gpio->gpiob.label = "viperboard gpio b";
> > + vb_gpio->gpiob.dev = &pdev->dev;
> > + vb_gpio->gpiob.owner = THIS_MODULE;
> > + vb_gpio->gpiob.base = -1;
> > + vb_gpio->gpiob.ngpio = 16;
> > + vb_gpio->gpiob.can_sleep = 1;
> > + vb_gpio->gpiob.set = vprbrd_gpiob_set;
> > + vb_gpio->gpiob.get = vprbrd_gpiob_get;
> > + vb_gpio->gpiob.direction_input = vprbrd_gpiob_direction_input;
> > + vb_gpio->gpiob.direction_output = vprbrd_gpiob_direction_output;
> > + ret = gpiochip_add(&vb_gpio->gpiob);
> > + if (ret < 0) {
> > + dev_err(vb_gpio->gpiob.dev, "could not add gpio b");
> > + goto err_gpiob;
> > + }
> > +
> > + platform_set_drvdata(pdev, vb_gpio);
> > +
> > + return ret;
> > +
> > +err_gpiob:
> > + ret = gpiochip_remove(&vb_gpio->gpioa);
> > +
> > +err_gpioa:
> > + kfree(vb_gpio);
>
> With devm_kzalloc you don't need this free.
>
> (...)
>
> > +static int __devexit vprbrd_gpio_remove(struct platform_device *pdev)
> > +{
> > + struct vprbrd_gpio *vb_gpio = platform_get_drvdata(pdev);
> > + int ret;
> > +
> > + ret = gpiochip_remove(&vb_gpio->gpiob);
> > + if (ret == 0)
> > + ret = gpiochip_remove(&vb_gpio->gpioa);
> > + if (ret == 0)
> > + kfree(vb_gpio);
>
> Nor this.
>
> Apart from this the driver is looking nice!

Thank you for your feedback. I will wait some time for responses of the other
maintainers and then do a version 3 of the whole patchset.

Regards,
Lars

2012-10-16 07:11:57

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 4/4] iio: adc: add viperboard adc driver

On Monday 15 October 2012 at 16:26:36, Lars-Peter Clausen wrote:
> Added [email protected] to Cc.
>
> On 10/12/2012 04:34 PM, Lars Poeschel wrote:
> > From: Lars Poeschel <[email protected]>
> >
> > This adds the mfd cell to use the adc part of the Nano River Technologies
> > viperboard.
> >
> > Signed-off-by: Lars Poeschel <[email protected]>
>
> Looks good in general, just some minor code style issues.
>
> > ---
> >
> > drivers/iio/adc/Kconfig | 7 ++
> > drivers/iio/adc/Makefile | 1 +
> > drivers/iio/adc/viperboard_adc.c | 185
> > ++++++++++++++++++++++++++++++++++++++ drivers/mfd/viperboard.c
> > | 3 +
> > 4 files changed, 196 insertions(+)
> > create mode 100644 drivers/iio/adc/viperboard_adc.c
>
> [...]
>
> > diff --git a/drivers/iio/adc/viperboard_adc.c
> > b/drivers/iio/adc/viperboard_adc.c new file mode 100644
> > index 0000000..8ae6634
> > --- /dev/null
> > +++ b/drivers/iio/adc/viperboard_adc.c
> > @@ -0,0 +1,185 @@
> > +/*
> > + * Nano River Technologies viperboard iio ADC driver
> > + *
> > + * (C) 2012 by Lemonage GmbH
> > + * Author: Lars Poeschel <[email protected]>
> > + * All rights reserved.
> > + *
> > + * 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/errno.h>
> > +#include <linux/module.h>
> > +#include <linux/slab.h>
> > +#include <linux/types.h>
> > +#include <linux/mutex.h>
> > +#include <linux/platform_device.h>
> > +
> > +#include <linux/usb.h>
> > +#include <linux/iio/iio.h>
> > +
> > +#include <linux/mfd/viperboard.h>
> > +
> > +#define VPRBRD_ADC_CMD_GET 0x00
> > +
> > +struct __packed vprbrd_adc_msg {
> > + u8 cmd;
> > + u8 chan;
> > + u8 val;
> > +};
>
> put the __packed between } and ;

GCC allows both alternatives, but you are right: Most kernel code is doing it
between } and ; so I will change this.

> > +
> > +struct vprbrd_adc {
> > + struct vprbrd *vb;
> > +};
> > +
> > +#define VPRBRD_ADC_CHANNEL(_index) { \
> > + .type = IIO_VOLTAGE, \
> > + .indexed = 1, \
> > + .channel = _index, \
> > + .info_mask = IIO_CHAN_INFO_RAW_SEPARATE_BIT, \
>
> It would be good if you could also report the channel scale.

I saw that there is the possibility to supply a channel scale, which is way
cool. :-) The doc of the viperboard says nothing about the scale of the ADC.
At the moment I do not have the right measuring equipment here to measure a
scale myself. I would do another tiny patch if I have the oppotunity to
measure somewhere.

> > + .scan_index = _index, \
> > + .scan_type.sign = 'u', \
> > + .scan_type.realbits = 8, \
> > + .scan_type.storagebits = 8, \
>
> Usually this is written as
> .scan_type = {
> .sign = 'u',
> ....
> },
>
> > +}
> > +
> > +static struct iio_chan_spec vprbrd_adc_iio_channels[] = {
>
> const
>
> > + VPRBRD_ADC_CHANNEL(0),
> > + VPRBRD_ADC_CHANNEL(1),
> > + VPRBRD_ADC_CHANNEL(2),
> > + VPRBRD_ADC_CHANNEL(3),
> > +};
> > +
> > +static int vprbrd_iio_read_raw(struct iio_dev *iio_dev,
> > + struct iio_chan_spec const *chan,
> > + int *val,
> > + int *val2,
> > + long mask)
>
> 'mask' used to be a mask and that's why it is still called 'mask' in older
> drivers. For new drivers we should use 'info'.
>
> > +{
> > + int ret, error = 0;
> > + struct vprbrd_adc *adc = iio_priv(iio_dev);
> > + struct vprbrd *vb = adc->vb;
> > + struct vprbrd_adc_msg *admsg = (struct vprbrd_adc_msg *)vb->buf;
> > +
> > + if (mask == IIO_CHAN_INFO_RAW) {
> > +
>
> Use switch instead of if. Otherwise you'd end up with if(mask == ...) else
> if(mask == ...) else if (mask == ...) if you add support for more channel
> attributes.
>
> > + mutex_lock(&vb->lock);
> > +
> > + admsg->cmd = VPRBRD_ADC_CMD_GET;
> > + admsg->chan = chan->scan_index;
> > + admsg->val = 0x00;
> > +
> > + ret = usb_control_msg(vb->usb_dev,
> > + usb_sndctrlpipe(vb->usb_dev, 0), 0xec, 0x40,
> > + 0x0000, 0x0000, admsg,
> > + sizeof(struct vprbrd_adc_msg), 100);
> > + if (ret != sizeof(struct vprbrd_adc_msg)) {
> > + dev_err(&iio_dev->dev, "usb send error on adc read\n");
> > + error = -EREMOTEIO;
> > + }
>
> Does it make sense to send out the second msg if the first one failed?

This is a good question. I can not fully answer it, because I did not build
the hardware. I thought it is better to try send the second message, because
there is some chance it reaches the device. I would opt for trying it.

> > +
> > + ret = usb_control_msg(vb->usb_dev,
> > + usb_rcvctrlpipe(vb->usb_dev, 0), 0xec, 0xc0,
> > + 0x0000, 0x0000, admsg,
> > + sizeof(struct vprbrd_adc_msg), 100);
> > +
>
> It would be good to have some defines for the magic constants used for
> request and request_type.
>
> > + *val = admsg->val;
> > +
> > + mutex_unlock(&vb->lock);
> > +
> > + if (ret != sizeof(struct vprbrd_adc_msg)) {
> > + dev_err(&iio_dev->dev, "usb recv error on adc read\n");
> > + error = -EREMOTEIO;
> > + }
> > +
> > + if (error)
> > + goto error;
> > +
> > + return IIO_VAL_INT;
> > + }
> > + error = -EINVAL;
> > +error:
> > + return error;
> > +}
> > +
> > +static const struct iio_info vprbrd_adc_iio_info = {
> > + .read_raw = &vprbrd_iio_read_raw,
> > + .driver_module = THIS_MODULE,
> > +};
> > +
> > +static int __devinit vprbrd_adc_probe(struct platform_device *pdev)
> > +{
> > + struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
> > + struct vprbrd_adc *adc;
> > + struct iio_dev *iodev;
>
> Usually this is called indio_dev, would be good for consistency if you'd do
> this as well.
>
> > + int ret;
> > +
> > + /* registering iio */
> > + iodev = iio_device_alloc(sizeof(struct vprbrd_adc));
> > + if (!iodev) {
> > + dev_err(&pdev->dev, "failed allocating iio device\n");
> > + return -ENOMEM;
> > + }
> > +
> > + adc = iio_priv(iodev);
> > + adc->vb = vb;
> > + iodev->name = "viperboard adc";
> > + iodev->dev.parent = &pdev->dev;
> > + iodev->info = &vprbrd_adc_iio_info;
> > + iodev->modes = INDIO_DIRECT_MODE;
> > + iodev->channels = vprbrd_adc_iio_channels;
> > + iodev->num_channels = ARRAY_SIZE(vprbrd_adc_iio_channels);
> > +
> > + ret = iio_device_register(iodev);
> > + if (ret) {
> > + dev_err(&pdev->dev, "could not register iio (adc)");
> > + goto error;
> > + }
> > +
> > + platform_set_drvdata(pdev, iodev);
> > +
> > + return 0;
> > +
> > +error:
> > + iio_device_free(iodev);
> > + return ret;
> > +}
> > +
> > +static int __devexit vprbrd_adc_remove(struct platform_device *pdev)
> > +{
> > + struct iio_dev *iodev = platform_get_drvdata(pdev);
> > +
> > + iio_device_unregister(iodev);
> > + iio_device_free(iodev);
> > +
> > + return 0;
> > +}
> > +
> > +static struct platform_driver vprbrd_adc_driver = {
> > + .driver.name = "viperboard-adc",
> > + .driver.owner = THIS_MODULE,
>
> Same as with scan_type, usually this is written as
>
> .driver = {
> .name = ...
> ....
> },
>
> > + .probe = vprbrd_adc_probe,
> > + .remove = __devexit_p(vprbrd_adc_remove),
> > +};
> > +
> > +static int __init vprbrd_adc_init(void)
> > +{
> > + return platform_driver_register(&vprbrd_adc_driver);
> > +}
> > +subsys_initcall(vprbrd_adc_init);
> > +
> > +static void __exit vprbrd_adc_exit(void)
> > +{
> > + platform_driver_unregister(&vprbrd_adc_driver);
> > +}
> > +module_exit(vprbrd_adc_exit);
>
> module_platform_driver(vprbrd_adc_driver);
>
> > +
> > +MODULE_AUTHOR("Lars Poeschel <[email protected]>");
> > +MODULE_DESCRIPTION("IIO ADC driver for Nano River Techs Viperboard");
> > +MODULE_LICENSE("GPL");
> > +MODULE_ALIAS("platform:viperboard-adc");
> > diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
> > index a25e07e..eb1cf89 100644
> > --- a/drivers/mfd/viperboard.c
> > +++ b/drivers/mfd/viperboard.c
> > @@ -55,6 +55,9 @@ static struct mfd_cell vprbrd_devs[] = {
> >
> > {
> >
> > .name = "viperboard-i2c",
> >
> > },
> >
> > + {
> > + .name = "viperboard-adc",
> > + },
> >
> > };
> >
> > static int vprbrd_probe(struct usb_interface *interface,

Thank you for your review. The other things you mention are clear. I will
change them. I will wait some time for some feedback from the other
maintainers and then do a version 3 of the whole patchset.

Regards,
Lars

2012-10-16 07:15:37

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 1/4] mfd: add viperboard driver

On Monday 15 October 2012 at 19:09:53, Peter Meerwald wrote:
> minor nitpicking below
>
> > From: Lars Poeschel <[email protected]>
> >
> > Add mfd driver for Nano River Technologies viperboard.
> >
> > Signed-off-by: Lars Poeschel <[email protected]>
> > ---
> >
> > drivers/mfd/Kconfig | 14 ++++
> > drivers/mfd/Makefile | 1 +
> > drivers/mfd/viperboard.c | 149
> > ++++++++++++++++++++++++++++++++++++++++ include/linux/mfd/viperboard.h
> > | 99 ++++++++++++++++++++++++++ 4 files changed, 263 insertions(+)
> > create mode 100644 drivers/mfd/viperboard.c
> > create mode 100644 include/linux/mfd/viperboard.h
> >
> > diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig
> > index b1a1462..98d9fa3 100644
> > --- a/drivers/mfd/Kconfig
> > +++ b/drivers/mfd/Kconfig
> > @@ -1003,6 +1003,20 @@ config MFD_PALMAS
> >
> > If you say yes here you get support for the Palmas
> > series of PMIC chips from Texas Instruments.
> >
> > +config MFD_VIPERBOARD
> > + tristate "Support for Nano River Technologies Viperboard"
>
> probably wrong indentation (space vs. tab)?
>
> > + select MFD_CORE
> > + depends on USB && IIO
> > + default n
> > + help
> > + Say yes here if you want support for Nano River Technologies
> > + Viperboard.
> > + There are mfd cell drivers available for i2c master, adc and
> > + both gpios found on the board. The spi part does not yet
> > + have a driver.
> > + You need to select the mfd cell drivers seperatly.
>
> separately
>
> > + The drivers do not support all features the board exposes.
> > +
> >
> > endmenu
> > endif
> >
> > diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
> > index 79dd22d..6ab6b64 100644
> > --- a/drivers/mfd/Makefile
> > +++ b/drivers/mfd/Makefile
> > @@ -128,6 +128,7 @@ obj-$(CONFIG_MFD_TPS65090) += tps65090.o
> >
> > obj-$(CONFIG_MFD_AAT2870_CORE) += aat2870-core.o
> > obj-$(CONFIG_MFD_INTEL_MSIC) += intel_msic.o
> > obj-$(CONFIG_MFD_PALMAS) += palmas.o
> >
> > +obj-$(CONFIG_MFD_VIPERBOARD) += viperboard.o
> >
> > obj-$(CONFIG_MFD_RC5T583) += rc5t583.o rc5t583-irq.o
> > obj-$(CONFIG_MFD_SEC_CORE) += sec-core.o sec-irq.o
> > obj-$(CONFIG_MFD_ANATOP) += anatop-mfd.o
> >
> > diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
> > new file mode 100644
> > index 0000000..8095ea2
> > --- /dev/null
> > +++ b/drivers/mfd/viperboard.c
> > @@ -0,0 +1,149 @@
> > +/*
> > + * Nano River Technologies viperboard driver
> > + *
> > + * This is the core driver for the viperboard. There are cell drivers
> > + * available for I2C, ADC and both GPIOs. SPI is not yet supported
>
> full stop (.) missing
>
> > + * The drivers do not support all features the board exposes. See user
> > + * manual of the viperboard.
> > + *
> > + * (C) 2012 by Lemonage GmbH
> > + * Author: Lars Poeschel <[email protected]>
> > + * All rights reserved.
> > + *
> > + * 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/errno.h>
> > +#include <linux/module.h>
> > +#include <linux/slab.h>
> > +#include <linux/types.h>
> > +#include <linux/mutex.h>
> > +
> > +#include <linux/mfd/core.h>
> > +#include <linux/mfd/viperboard.h>
> > +
> > +#include <linux/usb.h>
> > +
> > +
> > +static const struct usb_device_id vprbrd_table[] = {
> > + { USB_DEVICE(0x2058, 0x1005) }, /* Nano River Technologies */
> > + { } /* Terminating entry */
> > +};
> > +
> > +MODULE_DEVICE_TABLE(usb, vprbrd_table);
> > +
> > +static void vprbrd_dev_release(struct device *dev)
> > +{
> > + return;
>
> return not needed
>
> > +}
> > +
> > +static void vprbrd_free(struct vprbrd *dev)
> > +{
> > + usb_put_dev(dev->usb_dev);
> > + kfree(dev);
> > +}

Thanks for your review. I will change this and after waiting some time for
additional comments, I will do a version 3 of the whole patchset.

Regards,
Lars

2012-10-16 08:39:13

by Lars-Peter Clausen

[permalink] [raw]
Subject: Re: [PATCH v2 1/4] mfd: add viperboard driver

On 10/12/2012 04:34 PM, Lars Poeschel wrote:
> [...]
> +static void vprbrd_dev_release(struct device *dev)
> +{
> + return;

A empty release callback is usually a good indicator that something is
wrong. The release callback will be called once the last reference to the
device has been called, so the memory associated with the device should not
be freed before the release callback has been called, otherwise the memory
might be accessed after it has been freed...

> +}
> +
> +static void vprbrd_free(struct vprbrd *dev)
> +{
> + usb_put_dev(dev->usb_dev);
> + kfree(dev);

..., so this kfree should be moved from here to the release callback.

Btw. I'm wondering why is the extra platform device required? Can't you not
just use the usb device as the parent device for the mfd cells?

> +}
> [...][

2012-10-16 09:43:32

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 1/4] mfd: add viperboard driver

On Tuesday 16 October 2012 at 10:40:26, Lars-Peter Clausen wrote:
> On 10/12/2012 04:34 PM, Lars Poeschel wrote:
> > [...]
> > +static void vprbrd_dev_release(struct device *dev)
> > +{
> > + return;
>
> A empty release callback is usually a good indicator that something is
> wrong. The release callback will be called once the last reference to the
> device has been called, so the memory associated with the device should not
> be freed before the release callback has been called, otherwise the memory
> might be accessed after it has been freed...
>
> > +}
> > +
> > +static void vprbrd_free(struct vprbrd *dev)
> > +{
> > + usb_put_dev(dev->usb_dev);
> > + kfree(dev);
>
> ..., so this kfree should be moved from here to the release callback.

Thank you for catching that one!

> Btw. I'm wondering why is the extra platform device required? Can't you not
> just use the usb device as the parent device for the mfd cells?

This is what I first did, but this does not work. You can read about my first
thoughts why this is not working here: (To sum it up: The device is housed in
an usb_device, not a platform_device and This usb_device has no mfd_cell
member.)

https://lkml.org/lkml/2012/9/28/327

As I got a bit more deeper I also noticed, that mfd_add_devices (obviously)
adds the devices "as childs" to the parent device. mfd_remove_devices then
removes ALL "child" devices from the parent, not only those added by
mfd_add_devices before. This does not work in the case of the usb parent
device, because it has other childs that the usb layer added before (some
endpoints and stuff). So I had to construct an "empty" (in sense of childs)
mock platform_device between the usb and mfd.

2012-10-16 10:00:17

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Tue, Oct 16, 2012 at 8:51 AM, Lars Poeschel <[email protected]> wrote:
> On Monday 15 October 2012 at 15:00:12, Linus Walleij wrote:
>> > + /* if io is set to output, just return the saved value */
>> > + if (gpio->gpioa_out & (1 << offset))
>> > + return gpio->gpioa_val & (1 << offset);
>>
>> That's not going to work if the hardware changes state
>> behind the back of the driver right? Oh well, maybe
>> it doesn't matter.
>
> I thought about that and then did this "cache" only in case the gpio is a
> output to save to usb ping-pong that is needed otherwise. I thought that
> nothing can change to state of the output but the driver itself.

On a second note there is already a standard mechanism for caching
registers in the kernel, and that is regmap. Sadly it's a bit
undocumented but there are several examples and the code
lives in drivers/base/regmap and include/linux/regmap.h

Yours,
Linus Walleij

2012-10-16 10:57:38

by Lars-Peter Clausen

[permalink] [raw]
Subject: Re: [PATCH v2 1/4] mfd: add viperboard driver

On 10/16/2012 11:43 AM, Lars Poeschel wrote:
> On Tuesday 16 October 2012 at 10:40:26, Lars-Peter Clausen wrote:
>> On 10/12/2012 04:34 PM, Lars Poeschel wrote:
>>> [...]
>>> +static void vprbrd_dev_release(struct device *dev)
>>> +{
>>> + return;
>>
>> A empty release callback is usually a good indicator that something is
>> wrong. The release callback will be called once the last reference to the
>> device has been called, so the memory associated with the device should not
>> be freed before the release callback has been called, otherwise the memory
>> might be accessed after it has been freed...
>>
>>> +}
>>> +
>>> +static void vprbrd_free(struct vprbrd *dev)
>>> +{
>>> + usb_put_dev(dev->usb_dev);
>>> + kfree(dev);
>>
>> ..., so this kfree should be moved from here to the release callback.
>
> Thank you for catching that one!
>
>> Btw. I'm wondering why is the extra platform device required? Can't you not
>> just use the usb device as the parent device for the mfd cells?
>
> This is what I first did, but this does not work. You can read about my first
> thoughts why this is not working here: (To sum it up: The device is housed in
> an usb_device, not a platform_device and This usb_device has no mfd_cell
> member.)
>
> https://lkml.org/lkml/2012/9/28/327
>
> As I got a bit more deeper I also noticed, that mfd_add_devices (obviously)
> adds the devices "as childs" to the parent device. mfd_remove_devices then
> removes ALL "child" devices from the parent, not only those added by
> mfd_add_devices before. This does not work in the case of the usb parent
> device, because it has other childs that the usb layer added before (some
> endpoints and stuff). So I had to construct an "empty" (in sense of childs)
> mock platform_device between the usb and mfd.

Ah, ok that makes sense. I was a bit confused, because there are other mfd
drivers with for example i2c or spi devices as parents and these work fine,
but I guess this is because non of them registers any additional child
devices. I guess it makes sense to create a mfd cell device type and assign
this type to newly created mfd cells and only unregister a device in
mfd_remove_devices if it has the correct device type.

E.g. something along the lines of:


--- a/drivers/mfd/mfd-core.c
+++ b/drivers/mfd/mfd-core.c
@@ -21,6 +21,10 @@
#include <linux/irqdomain.h>
#include <linux/of.h>

+static struct device_type mfd_device_type = {
+ .name = "mfd-cell",
+};
+
int mfd_cell_enable(struct platform_device *pdev)
{
const struct mfd_cell *cell = mfd_get_cell(pdev);
@@ -91,6 +95,7 @@ static int mfd_add_device(struct device *parent, int id,
goto fail_device;

pdev->dev.parent = parent;
+ pdev->dev.type = &mfd_device_type;

if (parent->of_node && cell->of_compatible) {
for_each_child_of_node(parent->of_node, np) {
@@ -204,10 +209,16 @@ EXPORT_SYMBOL(mfd_add_devices);

static int mfd_remove_devices_fn(struct device *dev, void *c)
{
- struct platform_device *pdev = to_platform_device(dev);
- const struct mfd_cell *cell = mfd_get_cell(pdev);
+ struct platform_device *pdev;
+ const struct mfd_cell *cell;
atomic_t **usage_count = c;

+ if (dev->type != &mfd_device_type)
+ return 0;
+
+ pdev = to_platform_device(dev);
+ cell = mfd_get_cell(pdev);
+
/* find the base address of usage_count pointers (for freeing) */
if (!*usage_count || (cell->usage_count < *usage_count))
*usage_count = cell->usage_count;

2012-10-16 13:38:39

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Tuesday 16 October 2012 at 12:00:13, Linus Walleij wrote:
> On Tue, Oct 16, 2012 at 8:51 AM, Lars Poeschel <[email protected]> wrote:
> > On Monday 15 October 2012 at 15:00:12, Linus Walleij wrote:
> >> > + /* if io is set to output, just return the saved value */
> >> > + if (gpio->gpioa_out & (1 << offset))
> >> > + return gpio->gpioa_val & (1 << offset);
> >>
> >> That's not going to work if the hardware changes state
> >> behind the back of the driver right? Oh well, maybe
> >> it doesn't matter.
> >
> > I thought about that and then did this "cache" only in case the gpio is a
> > output to save to usb ping-pong that is needed otherwise. I thought that
> > nothing can change to state of the output but the driver itself.
>
> On a second note there is already a standard mechanism for caching
> registers in the kernel, and that is regmap. Sadly it's a bit
> undocumented but there are several examples and the code
> lives in drivers/base/regmap and include/linux/regmap.h

I had a look at regmap. This is interesting. But there is no regmap_bus
implementation for usb. Are you pointing me in this direction ? ;-) I don't
think you want me as a kernel newbie write this code.
And another thing: I don't think this can be implemented in such a general way
as it is done already for i2c or mmio. As you see in the example of my
(viperboard-)adapter, there is a bunch bytes sent, just to set the direction
bit in a register. And it is not guaranteed, that this "address" and "value"
are at the same position for other usb adapters. And this is getting even
worse, if I think of reading values out of the viperboard...
I would stay at the "cache" implementation I presented in the patch - this is
too special.

Lars

2012-10-16 17:11:13

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Tue, Oct 16, 2012 at 3:38 PM, Lars Poeschel <[email protected]> wrote:

> I had a look at regmap. This is interesting. But there is no regmap_bus
> implementation for usb. Are you pointing me in this direction ? ;-)

I was more thinking about whether it would be useful to use for this
MFD hub. So that for this MFD and it's children, you would use
regmap to:

1) Cache registers
2) Marshall the register read/writes across USB

I don't think it would be applicable for USB, as reading & writing registers
across USB is a pretty odd usecase. (IIRC using control transfers
right?)

> And it is not guaranteed, that this "address" and "value"
> are at the same position for other usb adapters. And this is getting even
> worse, if I think of reading values out of the viperboard...

I was mainly thinking about the Viperboard MFD complex.

> I would stay at the "cache" implementation I presented in the patch - this is
> too special.

You're special just like everybody else ;-)

But to be honest I haven't seen another USB device like this.
Which probably means that next week there will be dozens of them...

Yours,
Linus Walleij

2012-10-18 07:29:18

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 1/4] mfd: add viperboard driver

On Tuesday 16 October 2012 at 12:58:48, Lars-Peter Clausen wrote:
> On 10/16/2012 11:43 AM, Lars Poeschel wrote:
> > On Tuesday 16 October 2012 at 10:40:26, Lars-Peter Clausen wrote:
> >> On 10/12/2012 04:34 PM, Lars Poeschel wrote:
> >> Btw. I'm wondering why is the extra platform device required? Can't you
> >> not just use the usb device as the parent device for the mfd cells?
> >
> > This is what I first did, but this does not work. You can read about my
> > first thoughts why this is not working here: (To sum it up: The device
> > is housed in an usb_device, not a platform_device and This usb_device
> > has no mfd_cell member.)
> >
> > https://lkml.org/lkml/2012/9/28/327
> >
> > As I got a bit more deeper I also noticed, that mfd_add_devices
> > (obviously) adds the devices "as childs" to the parent device.
> > mfd_remove_devices then removes ALL "child" devices from the parent, not
> > only those added by mfd_add_devices before. This does not work in the
> > case of the usb parent device, because it has other childs that the usb
> > layer added before (some endpoints and stuff). So I had to construct an
> > "empty" (in sense of childs) mock platform_device between the usb and
> > mfd.
>
> Ah, ok that makes sense. I was a bit confused, because there are other mfd
> drivers with for example i2c or spi devices as parents and these work fine,
> but I guess this is because non of them registers any additional child
> devices. I guess it makes sense to create a mfd cell device type and assign
> this type to newly created mfd cells and only unregister a device in
> mfd_remove_devices if it has the correct device type.
>
> E.g. something along the lines of:
>
>
> --- a/drivers/mfd/mfd-core.c
> +++ b/drivers/mfd/mfd-core.c
> @@ -21,6 +21,10 @@
> #include <linux/irqdomain.h>
> #include <linux/of.h>
>
> +static struct device_type mfd_device_type = {
> + .name = "mfd-cell",
> +};
> +
> int mfd_cell_enable(struct platform_device *pdev)
> {
> const struct mfd_cell *cell = mfd_get_cell(pdev);
> @@ -91,6 +95,7 @@ static int mfd_add_device(struct device *parent, int id,
> goto fail_device;
>
> pdev->dev.parent = parent;
> + pdev->dev.type = &mfd_device_type;
>
> if (parent->of_node && cell->of_compatible) {
> for_each_child_of_node(parent->of_node, np) {
> @@ -204,10 +209,16 @@ EXPORT_SYMBOL(mfd_add_devices);
>
> static int mfd_remove_devices_fn(struct device *dev, void *c)
> {
> - struct platform_device *pdev = to_platform_device(dev);
> - const struct mfd_cell *cell = mfd_get_cell(pdev);
> + struct platform_device *pdev;
> + const struct mfd_cell *cell;
> atomic_t **usage_count = c;
>
> + if (dev->type != &mfd_device_type)
> + return 0;
> +
> + pdev = to_platform_device(dev);
> + cell = mfd_get_cell(pdev);
> +
> /* find the base address of usage_count pointers (for freeing) */
> if (!*usage_count || (cell->usage_count < *usage_count))
> *usage_count = cell->usage_count;

I thought about this and I am not fully happy with it:
If we add the mfd devices to the usb_interface parent they are at the same
level in the device tree as the usb endpoints and stuff. I would consider this
logically wrong.
Is this something we should take care of ?

2012-10-18 14:12:12

by Lars-Peter Clausen

[permalink] [raw]
Subject: Re: [PATCH v2 1/4] mfd: add viperboard driver

On 10/18/2012 09:29 AM, Lars Poeschel wrote:
> On Tuesday 16 October 2012 at 12:58:48, Lars-Peter Clausen wrote:
>> On 10/16/2012 11:43 AM, Lars Poeschel wrote:
>>> On Tuesday 16 October 2012 at 10:40:26, Lars-Peter Clausen wrote:
>>>> On 10/12/2012 04:34 PM, Lars Poeschel wrote:
>>>> Btw. I'm wondering why is the extra platform device required? Can't you
>>>> not just use the usb device as the parent device for the mfd cells?
>>>
>>> This is what I first did, but this does not work. You can read about my
>>> first thoughts why this is not working here: (To sum it up: The device
>>> is housed in an usb_device, not a platform_device and This usb_device
>>> has no mfd_cell member.)
>>>
>>> https://lkml.org/lkml/2012/9/28/327
>>>
>>> As I got a bit more deeper I also noticed, that mfd_add_devices
>>> (obviously) adds the devices "as childs" to the parent device.
>>> mfd_remove_devices then removes ALL "child" devices from the parent, not
>>> only those added by mfd_add_devices before. This does not work in the
>>> case of the usb parent device, because it has other childs that the usb
>>> layer added before (some endpoints and stuff). So I had to construct an
>>> "empty" (in sense of childs) mock platform_device between the usb and
>>> mfd.
>>
>> Ah, ok that makes sense. I was a bit confused, because there are other mfd
>> drivers with for example i2c or spi devices as parents and these work fine,
>> but I guess this is because non of them registers any additional child
>> devices. I guess it makes sense to create a mfd cell device type and assign
>> this type to newly created mfd cells and only unregister a device in
>> mfd_remove_devices if it has the correct device type.
>>
>> E.g. something along the lines of:
>>
>>
>> --- a/drivers/mfd/mfd-core.c
>> +++ b/drivers/mfd/mfd-core.c
>> @@ -21,6 +21,10 @@
>> #include <linux/irqdomain.h>
>> #include <linux/of.h>
>>
>> +static struct device_type mfd_device_type = {
>> + .name = "mfd-cell",
>> +};
>> +
>> int mfd_cell_enable(struct platform_device *pdev)
>> {
>> const struct mfd_cell *cell = mfd_get_cell(pdev);
>> @@ -91,6 +95,7 @@ static int mfd_add_device(struct device *parent, int id,
>> goto fail_device;
>>
>> pdev->dev.parent = parent;
>> + pdev->dev.type = &mfd_device_type;
>>
>> if (parent->of_node && cell->of_compatible) {
>> for_each_child_of_node(parent->of_node, np) {
>> @@ -204,10 +209,16 @@ EXPORT_SYMBOL(mfd_add_devices);
>>
>> static int mfd_remove_devices_fn(struct device *dev, void *c)
>> {
>> - struct platform_device *pdev = to_platform_device(dev);
>> - const struct mfd_cell *cell = mfd_get_cell(pdev);
>> + struct platform_device *pdev;
>> + const struct mfd_cell *cell;
>> atomic_t **usage_count = c;
>>
>> + if (dev->type != &mfd_device_type)
>> + return 0;
>> +
>> + pdev = to_platform_device(dev);
>> + cell = mfd_get_cell(pdev);
>> +
>> /* find the base address of usage_count pointers (for freeing) */
>> if (!*usage_count || (cell->usage_count < *usage_count))
>> *usage_count = cell->usage_count;
>
> I thought about this and I am not fully happy with it:
> If we add the mfd devices to the usb_interface parent they are at the same
> level in the device tree as the usb endpoints and stuff. I would consider this
> logically wrong.
> Is this something we should take care of ?

I wouldn't worry to much about it. If you use the the container platform
device the container platform device would be at the same level as the usb
endpoints. I did a quick search and it seams that other subsystems also
register the child devices directly on the usb interface device. E.g. the
media subsystem uses this a lot.

- Lars

2012-10-23 15:24:37

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Tuesday 16 October 2012 at 19:11:10, Linus Walleij wrote:
> On Tue, Oct 16, 2012 at 3:38 PM, Lars Poeschel <[email protected]> wrote:
> > I had a look at regmap. This is interesting. But there is no regmap_bus
> > implementation for usb. Are you pointing me in this direction ? ;-)
>
> I was more thinking about whether it would be useful to use for this
> MFD hub. So that for this MFD and it's children, you would use
> regmap to:
>
> 1) Cache registers
> 2) Marshall the register read/writes across USB
>
> I don't think it would be applicable for USB, as reading & writing
> registers across USB is a pretty odd usecase. (IIRC using control
> transfers
> right?)

Yes, right.

> > And it is not guaranteed, that this "address" and "value"
> > are at the same position for other usb adapters. And this is getting even
> > worse, if I think of reading values out of the viperboard...
>
> I was mainly thinking about the Viperboard MFD complex.

Ok, I tried to implement it (at least for the gpioa part of the driver).
It does not work. I got stuck. There are three problems I could not solve:

To be able to use the caching, I have to implement a volatile_reg function. I
have to do this, because caching can only happen, when the gpio pin is an
output. If it is an input, I want to read the pin - caching has to be turned
off. So in my vprbrd_volatile_reg function I have to check if a pin is set to
output and return false or true. I can not query a regmap register inside that
function if a pin is an output or not, this would deadlock, because there is
a mutex lock inside regmap, so I have to cache this outside of regmap.
This is a bit strange, to use the cache, setup another own cache. (1st
problem)
I chose my per device structure struct vprbrd_gpio to hold this cache, but I
can not reach it. You see in the patch, I try to container_of up to my
structure. This does not work, because struct regmap is not public available.
(2nd problem)
Setting the direction to output is an atomic set direction and set value.
The register number is different from setting the value only. So after a
successful call, I want to update the cache of output value using
regcache_write. This is also not publicy available api. The only thing I could
do is invalidate the whole cache using regcache_mark_dirty. (3rd problem)

I attach my current working state here. This is NOT WORKING and only as
reference.

Regards,
Lars
---
diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index 8382dc8..48be4ba 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -636,4 +636,17 @@ config GPIO_MSIC
Enable support for GPIO on intel MSIC controllers found in
intel MID devices

+comment "USB GPIO expanders:"
+
+config GPIO_VIPERBOARD
+ tristate "Viperboard GPIO a & b support"
+ depends on MFD_VIPERBOARD && USB
+ help
+ Say yes here to access the GPIO signals of Nano River
+ Technologies Viperboard. There are two GPIO chips on the
+ board: gpioa and gpiob.
+ See viperboard API specification and Nano
+ River Tech's viperboard.h for detailed meaning
+ of the module parameters.
+
endif
diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
index 0ffaa84..71cc896 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -69,6 +69,7 @@ obj-$(CONFIG_GPIO_TPS65910) += gpio-tps65910.o
obj-$(CONFIG_GPIO_TPS65912) += gpio-tps65912.o
obj-$(CONFIG_GPIO_TWL4030) += gpio-twl4030.o
obj-$(CONFIG_GPIO_UCB1400) += gpio-ucb1400.o
+obj-$(CONFIG_GPIO_VIPERBOARD) += gpio-viperboard.o
obj-$(CONFIG_GPIO_VR41XX) += gpio-vr41xx.o
obj-$(CONFIG_GPIO_VT8500) += gpio-vt8500.o
obj-$(CONFIG_GPIO_VX855) += gpio-vx855.o
diff --git a/drivers/gpio/gpio-viperboard.c b/drivers/gpio/gpio-viperboard.c
new file mode 100644
index 0000000..2dc6c9f
--- /dev/null
+++ b/drivers/gpio/gpio-viperboard.c
@@ -0,0 +1,618 @@
+/*
+ * Nano River Technologies viperboard GPIO lib driver
+ *
+ * (C) 2012 by Lemonage GmbH
+ * Author: Lars Poeschel <[email protected]>
+ * All rights reserved.
+ *
+ * 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/errno.h>
+#include <linux/module.h>
+#include <linux/slab.h>
+#include <linux/types.h>
+#include <linux/mutex.h>
+#include <linux/platform_device.h>
+#include <linux/regmap.h>
+
+#include <linux/usb.h>
+#include <linux/gpio.h>
+
+#include <linux/mfd/viperboard.h>
+
+#define VPRBRD_GPIOA_CLK_1MHZ 0
+#define VPRBRD_GPIOA_CLK_100KHZ 1
+#define VPRBRD_GPIOA_CLK_10KHZ 2
+#define VPRBRD_GPIOA_CLK_1KHZ 3
+#define VPRBRD_GPIOA_CLK_100HZ 4
+#define VPRBRD_GPIOA_CLK_10HZ 5
+
+#define VPRBRD_GPIOA_FREQ_DEFAULT 1000
+
+#define VPRBRD_GPIOA_CMD_CONT 0x00
+#define VPRBRD_GPIOA_CMD_PULSE 0x01
+#define VPRBRD_GPIOA_CMD_PWM 0x02
+#define VPRBRD_GPIOA_CMD_SETOUT 0x03
+#define VPRBRD_GPIOA_CMD_SETIN 0x04
+#define VPRBRD_GPIOA_CMD_SETINT 0x05
+#define VPRBRD_GPIOA_CMD_GETIN 0x06
+
+#define VPRBRD_GPIOB_CMD_SETDIR 0x00
+#define VPRBRD_GPIOB_CMD_SETVAL 0x01
+
+#define VPRBRD_GPIOA_NUM_PINS 16
+#define VPRBRD_GPIOA_REG_VAL_BASE 0
+#define VPRBRD_GPIOA_REG_VAL_MAX (1 * VPRBRD_GPIOA_NUM_PINS - 1)
+#define VPRBRD_GPIOA_REG_DIR_BASE (VPRBRD_GPIOA_REG_VAL_MAX + 1)
+#define VPRBRD_GPIOA_REG_DIR_MAX (2 * VPRBRD_GPIOA_NUM_PINS - 1)
+#define VPRBRD_GPIOA_NUM_REGS (VPRBRD_GPIOA_REG_DIR_MAX + 1)
+
+struct vprbrd_gpioa_msg {
+ u8 cmd;
+ u8 clk;
+ u8 offset;
+ u8 t1;
+ u8 t2;
+ u8 invert;
+ u8 pwmlevel;
+ u8 outval;
+ u8 risefall;
+ u8 answer;
+ u8 __fill;
+} __packed;
+
+struct vprbrd_gpiob_msg {
+ u8 cmd;
+ u16 val;
+ u16 mask;
+} __packed;
+
+struct vprbrd_gpio {
+ struct gpio_chip gpioa; /* gpio a related things */
+ u32 gpioa_out;
+ u32 gpioa_val;
+ struct gpio_chip gpiob; /* gpio b related things */
+ u32 gpiob_out;
+ u32 gpiob_val;
+ struct vprbrd *vb;
+ struct regmap *regmap;
+};
+
+/* gpioa sampling clock module parameter */
+static unsigned char gpioa_clk;
+static unsigned int gpioa_freq = VPRBRD_GPIOA_FREQ_DEFAULT;
+module_param(gpioa_freq, uint, 0);
+MODULE_PARM_DESC(gpioa_freq, "gpio a sampling freq in Hz (default is 1000Hz)"
+ "valid values: 10, 100, 1000, 10000, 100000, 1000000");
+
+/* ----- begin of gipo a chip -------------------------------------------- */
+
+static int regmap_vb_gpio_write(void *context, const void *data, size_t count)
+{
+ struct vprbrd *vb = (struct vprbrd *)context;
+ struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
+ int ret;
+ const u8 reg = ((const u8 *)data)[0];
+ const u8 val = ((const u8 *)data)[1];
+
+ dev_dbg(&vb->pdev.dev, "%s count:%i reg:%i, val:%i\n", __FUNCTION__, count, reg, val);
+
+ if (count != 2)
+ return -ENOTSUPP;
+
+ mutex_lock(&vb->lock);
+
+ gamsg->clk = 0x00;
+ gamsg->t1 = 0x00;
+ gamsg->t2 = 0x00;
+ gamsg->invert = 0x00;
+ gamsg->pwmlevel = 0x00;
+ gamsg->outval = val;
+ gamsg->risefall = 0x00;
+ gamsg->answer = 0x00;
+ gamsg->__fill = 0x00;
+
+ if (reg >= VPRBRD_GPIOA_REG_VAL_BASE &&
+ reg <= VPRBRD_GPIOA_REG_VAL_MAX) {
+ gamsg->cmd = VPRBRD_GPIOA_CMD_SETOUT;
+ gamsg->offset = reg;
+ gamsg->outval = val;
+ } else if (reg >= VPRBRD_GPIOA_REG_DIR_BASE &&
+ reg <= VPRBRD_GPIOA_REG_DIR_MAX) {
+ gamsg->offset = reg - VPRBRD_GPIOA_REG_DIR_BASE;
+ if (val > 0) {
+ gamsg->cmd = VPRBRD_GPIOA_CMD_SETIN;
+ gamsg->clk = gpioa_clk;
+ } else {
+ gamsg->cmd = VPRBRD_GPIOA_CMD_SETOUT;
+ }
+ }
+ ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
+ VPRBRD_USB_REQUEST_GPIOA, VPRBRD_USB_TYPE_OUT, 0x0000,
+ 0x0000, gamsg, sizeof(struct vprbrd_gpioa_msg),
+ VPRBRD_USB_TIMEOUT_MS);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ return -EREMOTEIO;
+
+ return 0;
+}
+
+static int regmap_vb_gpio_read(void *context, const void *reg_buf,
+ size_t reg_size, void *val_buf, size_t val_size)
+{
+ struct vprbrd *vb = (struct vprbrd *)context;
+ struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
+ int ret, error = 0;
+ const u8 *reg8 = reg_buf;
+
+ dev_dbg(&vb->pdev.dev, "%s reg_size:%i val_size:%i\n", __FUNCTION__, reg_size, val_size);
+
+ if (val_size != 1 || reg_size != 1)
+ return -ENOTSUPP;
+
+ mutex_lock(&vb->lock);
+
+ gamsg->cmd = VPRBRD_GPIOA_CMD_GETIN;
+ gamsg->clk = 0x00;
+ gamsg->offset = reg8[0];
+ gamsg->t1 = 0x00;
+ gamsg->t2 = 0x00;
+ gamsg->invert = 0x00;
+ gamsg->pwmlevel = 0x00;
+ gamsg->outval = 0x00;
+ gamsg->risefall = 0x00;
+ gamsg->answer = 0x00;
+ gamsg->__fill = 0x00;
+
+ ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
+ VPRBRD_USB_REQUEST_GPIOA, VPRBRD_USB_TYPE_OUT, 0x0000,
+ 0x0000, gamsg, sizeof(struct vprbrd_gpioa_msg),
+ VPRBRD_USB_TIMEOUT_MS);
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ error = -EREMOTEIO;
+
+ ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
+ VPRBRD_USB_REQUEST_GPIOA, VPRBRD_USB_TYPE_IN, 0x0000,
+ 0x0000, gamsg, sizeof(struct vprbrd_gpioa_msg),
+ VPRBRD_USB_TIMEOUT_MS);
+ *(u8 *)val_buf = gamsg->answer & 0x01;
+
+ dev_dbg(&vb->pdev.dev, "%s gamsg->answer:%i val:%i\n", __FUNCTION__, gamsg->answer, *(u8 *)val_buf);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpioa_msg))
+ error = -EREMOTEIO;
+
+ if (error)
+ return error;
+
+ return 0;
+}
+
+static const struct regmap_bus regmap_vb_gpio = {
+ .write = regmap_vb_gpio_write,
+ .read = regmap_vb_gpio_read,
+};
+
+static bool vprbrd_volatile_reg(struct device *device, unsigned int reg)
+{
+ struct regmap *regmap = container_of(device, struct regmap, dev);
+ struct vprbrd_gpio *gpio =
+ container_of(regmap, struct vprbrd_gpio, regmap);
+
+ dev_dbg(device, "%s reg:%i\n", __FUNCTION__, reg);
+
+ /* if the pin is an output, we are not volatile and can cache */
+ if (gpio->gpioa_out & (1 << reg))
+ return false;
+
+ return true;
+}
+
+static struct reg_default vprbrd_regdefaults[] = {
+ {0x00, 0x00}, /* 0x00 - 0x0f pin values */
+ {0x01, 0x00},
+ {0x02, 0x00},
+ {0x03, 0x00},
+ {0x04, 0x00},
+ {0x05, 0x00},
+ {0x06, 0x00},
+ {0x07, 0x00},
+ {0x08, 0x00},
+ {0x09, 0x00},
+ {0x0a, 0x00},
+ {0x0b, 0x00},
+ {0x0c, 0x00},
+ {0x0d, 0x00},
+ {0x0e, 0x00},
+ {0x0f, 0x00},
+ {0x10, 0x00}, /* 0x10 - 0x1f pin direction */
+ {0x11, 0x00},
+ {0x12, 0x00},
+ {0x13, 0x00},
+ {0x14, 0x00},
+ {0x15, 0x00},
+ {0x16, 0x00},
+ {0x17, 0x00},
+ {0x18, 0x00},
+ {0x19, 0x00},
+ {0x1a, 0x00},
+ {0x1b, 0x00},
+ {0x1c, 0x00},
+ {0x1d, 0x00},
+ {0x1e, 0x00},
+ {0x1f, 0x00},
+};
+
+static const struct regmap_config vprbrd_regmap_config = {
+ .name = "gpio_regmap",
+ .reg_bits = 8,
+ .val_bits = 8,
+ .volatile_reg = vprbrd_volatile_reg,
+ .max_register = VPRBRD_GPIOA_NUM_REGS,
+ .reg_defaults = vprbrd_regdefaults,
+ .num_reg_defaults = ARRAY_SIZE(vprbrd_regdefaults),
+ .cache_type = REGCACHE_RBTREE,
+};
+
+static int vprbrd_gpioa_get(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+ unsigned int val;
+
+ ret = regmap_read(gpio->regmap, offset, &val);
+
+ dev_dbg(chip->dev, "%s offset:%i val:%x ret:%i\n", __FUNCTION__, offset, val, ret);
+
+ if (ret < 0)
+ return ret;
+ else
+ return val;
+}
+
+static void vprbrd_gpioa_set(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+
+ dev_dbg(chip->dev, "%s offset:%i, value:%i\n", __FUNCTION__, offset, value);
+
+ ret = regmap_write(gpio->regmap, offset, value);
+ if (ret < 0)
+ dev_err(chip->dev, "usb error setting pin value\n");
+}
+
+static int vprbrd_gpioa_direction_input(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+
+ dev_dbg(chip->dev, "%s offset:%i\n", __FUNCTION__, offset);
+
+ ret = regmap_write(gpio->regmap,
+ offset + VPRBRD_GPIOA_REG_DIR_BASE, 0);
+
+ if (ret < 0) {
+ dev_err(chip->dev, "usb error setting pin to output\n");
+ return ret;
+ }
+
+ gpio->gpioa_out &= ~(1 << offset);
+
+ return 0;
+}
+
+static int vprbrd_gpioa_direction_output(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpioa);
+
+ dev_dbg(chip->dev, "%s offset:%i, value:%i\n", __FUNCTION__, offset, value);
+
+ ret = regmap_write(gpio->regmap,
+ offset + VPRBRD_GPIOA_REG_DIR_BASE, value);
+
+ if (ret < 0) {
+ dev_err(chip->dev, "usb error setting pin to output\n");
+ return ret;
+ }
+
+ gpio->gpioa_out |= (1 << offset);
+ ret = regcache_write(gpio->regmap, offset, value);
+
+ return 0;
+}
+
+/* ----- end of gpio a chip ---------------------------------------------- */
+
+/* ----- begin of gipo b chip -------------------------------------------- */
+
+static int vprbrd_gpiob_setdir(struct vprbrd *vb, unsigned offset,
+ unsigned dir)
+{
+ struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
+ int ret;
+
+ gbmsg->cmd = VPRBRD_GPIOB_CMD_SETDIR;
+ gbmsg->val = cpu_to_be16(dir << offset);
+ gbmsg->mask = cpu_to_be16(0x0001 << offset);
+
+ ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
+ VPRBRD_USB_REQUEST_GPIOB, VPRBRD_USB_TYPE_OUT, 0x0000,
+ 0x0000, gbmsg, sizeof(struct vprbrd_gpiob_msg),
+ VPRBRD_USB_TIMEOUT_MS);
+
+ if (ret != sizeof(struct vprbrd_gpiob_msg))
+ return -EREMOTEIO;
+
+ return 0;
+}
+
+static int vprbrd_gpiob_get(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret;
+ u16 val;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
+
+ /* if io is set to output, just return the saved value */
+ if (gpio->gpiob_out & (1 << offset))
+ return gpio->gpiob_val & (1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
+ VPRBRD_USB_REQUEST_GPIOB, VPRBRD_USB_TYPE_IN, 0x0000,
+ 0x0000, gbmsg, sizeof(struct vprbrd_gpiob_msg),
+ VPRBRD_USB_TIMEOUT_MS);
+ val = gbmsg->val;
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpiob_msg))
+ return ret;
+
+ /* cache the read values */
+ gpio->gpiob_val = be16_to_cpu(val);
+
+ return (gpio->gpiob_val >> offset) & 0x1;
+}
+
+static void vprbrd_gpiob_set(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+ struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
+
+ if (gpio->gpiob_out & (1 << offset)) {
+ if (value)
+ gpio->gpiob_val |= (1 << offset);
+ else
+ gpio->gpiob_val &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ gbmsg->cmd = VPRBRD_GPIOB_CMD_SETVAL;
+ gbmsg->val = cpu_to_be16(value << offset);
+ gbmsg->mask = cpu_to_be16(0x0001 << offset);
+
+ ret = usb_control_msg(vb->usb_dev,
+ usb_sndctrlpipe(vb->usb_dev, 0),
+ VPRBRD_USB_REQUEST_GPIOB, VPRBRD_USB_TYPE_OUT,
+ 0x0000, 0x0000, gbmsg,
+ sizeof(struct vprbrd_gpiob_msg), VPRBRD_USB_TIMEOUT_MS);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret != sizeof(struct vprbrd_gpiob_msg))
+ dev_err(chip->dev, "usb error setting pin value\n");
+ }
+}
+
+static int vprbrd_gpiob_direction_input(struct gpio_chip *chip,
+ unsigned offset)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+
+ gpio->gpiob_out &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ ret = vprbrd_gpiob_setdir(vb, offset, 0);
+
+ mutex_unlock(&vb->lock);
+
+ if (ret)
+ dev_err(chip->dev, "usb error setting pin to input\n");
+
+ return ret;
+}
+
+static int vprbrd_gpiob_direction_output(struct gpio_chip *chip,
+ unsigned offset, int value)
+{
+ int ret;
+ struct vprbrd_gpio *gpio =
+ container_of(chip, struct vprbrd_gpio, gpiob);
+ struct vprbrd *vb = gpio->vb;
+
+ gpio->gpiob_out |= (1 << offset);
+ if (value)
+ gpio->gpiob_val |= (1 << offset);
+ else
+ gpio->gpiob_val &= ~(1 << offset);
+
+ mutex_lock(&vb->lock);
+
+ ret = vprbrd_gpiob_setdir(vb, offset, 1);
+ if (ret)
+ dev_err(chip->dev, "usb error setting pin to output\n");
+
+ mutex_unlock(&vb->lock);
+
+ vprbrd_gpiob_set(chip, offset, value);
+
+ return ret;
+}
+
+/* ----- end of gpio b chip ---------------------------------------------- */
+
+static int __devinit vprbrd_gpio_probe(struct platform_device *pdev)
+{
+ struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
+ struct vprbrd_gpio *vb_gpio;
+ int ret, ret_err;
+
+ vb_gpio = kzalloc(sizeof(*vb_gpio), GFP_KERNEL);
+ if (vb_gpio == NULL)
+ return -ENOMEM;
+
+ vb_gpio->vb = vb;
+ /* registering gpio a */
+ vb_gpio->gpioa.label = "viperboard gpio a";
+ vb_gpio->gpioa.dev = &pdev->dev;
+ vb_gpio->gpioa.owner = THIS_MODULE;
+ vb_gpio->gpioa.base = -1;
+ vb_gpio->gpioa.ngpio = 16;
+ vb_gpio->gpioa.can_sleep = 1;
+ vb_gpio->gpioa.set = vprbrd_gpioa_set;
+ vb_gpio->gpioa.get = vprbrd_gpioa_get;
+ vb_gpio->gpioa.direction_input = vprbrd_gpioa_direction_input;
+ vb_gpio->gpioa.direction_output = vprbrd_gpioa_direction_output;
+ ret = gpiochip_add(&vb_gpio->gpioa);
+ if (ret < 0) {
+ dev_err(vb_gpio->gpioa.dev, "could not add gpio a");
+ goto err_gpioa;
+ }
+
+ /* registering gpio b */
+ vb_gpio->gpiob.label = "viperboard gpio b";
+ vb_gpio->gpiob.dev = &pdev->dev;
+ vb_gpio->gpiob.owner = THIS_MODULE;
+ vb_gpio->gpiob.base = -1;
+ vb_gpio->gpiob.ngpio = 16;
+ vb_gpio->gpiob.can_sleep = 1;
+ vb_gpio->gpiob.set = vprbrd_gpiob_set;
+ vb_gpio->gpiob.get = vprbrd_gpiob_get;
+ vb_gpio->gpiob.direction_input = vprbrd_gpiob_direction_input;
+ vb_gpio->gpiob.direction_output = vprbrd_gpiob_direction_output;
+ ret = gpiochip_add(&vb_gpio->gpiob);
+ if (ret < 0) {
+ dev_err(vb_gpio->gpiob.dev, "could not add gpio b");
+ goto err_gpiob;
+ }
+
+ platform_set_drvdata(pdev, vb_gpio);
+
+ vb_gpio->regmap = devm_regmap_init(vb_gpio->gpioa.dev,
+ &regmap_vb_gpio, vb, &vprbrd_regmap_config);
+ if (IS_ERR(vb_gpio->regmap)) {
+ ret = PTR_ERR(vb_gpio->regmap);
+ dev_err(vb_gpio->gpioa.dev,
+ "regmap_init failed with err: %d\n", ret);
+ goto err_gpiob;
+ }
+
+ return ret;
+
+err_gpiob:
+ ret_err = gpiochip_remove(&vb_gpio->gpioa);
+
+err_gpioa:
+ kfree(vb_gpio);
+ return ret;
+}
+
+static int __devexit vprbrd_gpio_remove(struct platform_device *pdev)
+{
+ struct vprbrd_gpio *vb_gpio = platform_get_drvdata(pdev);
+ int ret;
+
+/*
+ ret = regmap_exit(vbgpio->regmap);
+ if (ret == 0)
+*/
+ ret = gpiochip_remove(&vb_gpio->gpiob);
+ if (ret == 0)
+ ret = gpiochip_remove(&vb_gpio->gpioa);
+ if (ret == 0)
+ kfree(vb_gpio);
+
+ return ret;
+}
+
+static struct platform_driver vprbrd_gpio_driver = {
+ .driver.name = "viperboard-gpio",
+ .driver.owner = THIS_MODULE,
+ .probe = vprbrd_gpio_probe,
+ .remove = __devexit_p(vprbrd_gpio_remove),
+};
+
+static int __init vprbrd_gpio_init(void)
+{
+ switch (gpioa_freq) {
+ case 1000000:
+ gpioa_clk = VPRBRD_GPIOA_CLK_1MHZ;
+ break;
+ case 100000:
+ gpioa_clk = VPRBRD_GPIOA_CLK_100KHZ;
+ break;
+ case 10000:
+ gpioa_clk = VPRBRD_GPIOA_CLK_10KHZ;
+ break;
+ case 1000:
+ gpioa_clk = VPRBRD_GPIOA_CLK_1KHZ;
+ break;
+ case 100:
+ gpioa_clk = VPRBRD_GPIOA_CLK_100HZ;
+ break;
+ case 10:
+ gpioa_clk = VPRBRD_GPIOA_CLK_10HZ;
+ break;
+ default:
+ pr_warn("invalid gpioa_freq (%d)\n", gpioa_freq);
+ gpioa_clk = VPRBRD_GPIOA_CLK_1KHZ;
+ }
+
+ return platform_driver_register(&vprbrd_gpio_driver);
+}
+subsys_initcall(vprbrd_gpio_init);
+
+static void __exit vprbrd_gpio_exit(void)
+{
+ platform_driver_unregister(&vprbrd_gpio_driver);
+}
+module_exit(vprbrd_gpio_exit);
+
+MODULE_AUTHOR("Lars Poeschel <[email protected]>");
+MODULE_DESCRIPTION("GPIO driver for Nano River Techs Viperboard");
+MODULE_LICENSE("GPL");
+MODULE_ALIAS("platform:viperboard-gpio");
diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
index de368b7..9ad06cd 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -49,6 +49,9 @@ static void vprbrd_free(struct vprbrd *dev)
}

static struct mfd_cell vprbrd_devs[] = {
+ {
+ .name = "viperboard-gpio",
+ },
};

static int vprbrd_probe(struct usb_interface *interface,
diff --git a/include/linux/mfd/viperboard.h b/include/linux/mfd/viperboard.h
index 1c23c79..d3c9ad2 100644
--- a/include/linux/mfd/viperboard.h
+++ b/include/linux/mfd/viperboard.h
@@ -44,6 +44,8 @@
#define VPRBRD_USB_TIMEOUT_MS 100
#define VPRBRD_USB_REQUEST_MAJOR 0xea
#define VPRBRD_USB_REQUEST_MINOR 0xeb
+#define VPRBRD_USB_REQUEST_GPIOA 0xed
+#define VPRBRD_USB_REQUEST_GPIOB 0xdd

struct __packed vprbrd_i2c_write_hdr {
u8 cmd;

2012-10-24 07:53:11

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Tue, Oct 23, 2012 at 5:24 PM, Lars Poeschel <[email protected]> wrote:
> On Tuesday 16 October 2012 at 19:11:10, Linus Walleij wrote:
>> On Tue, Oct 16, 2012 at 3:38 PM, Lars Poeschel <[email protected]> wrote:
>> > I had a look at regmap. This is interesting. But there is no regmap_bus
>> > implementation for usb. Are you pointing me in this direction ? ;-)
>>
>> I was more thinking about whether it would be useful to use for this
>> MFD hub. So that for this MFD and it's children, you would use
>> regmap to:
>>
>> 1) Cache registers
>> 2) Marshall the register read/writes across USB
>>
>> I don't think it would be applicable for USB, as reading & writing
>> registers across USB is a pretty odd usecase. (IIRC using control
>> transfers
>> right?)
>
> Yes, right.
>
>> > And it is not guaranteed, that this "address" and "value"
>> > are at the same position for other usb adapters. And this is getting even
>> > worse, if I think of reading values out of the viperboard...
>>
>> I was mainly thinking about the Viperboard MFD complex.
>
> Ok, I tried to implement it (at least for the gpioa part of the driver).
> It does not work. I got stuck. There are three problems I could not solve:

So I'm looping in Mark Brown to get some hints whether the following
can be resolved easily or needs to be given up on...

> To be able to use the caching, I have to implement a volatile_reg function. I
> have to do this, because caching can only happen, when the gpio pin is an
> output. If it is an input, I want to read the pin - caching has to be turned
> off. So in my vprbrd_volatile_reg function I have to check if a pin is set to
> output and return false or true. I can not query a regmap register inside that
> function if a pin is an output or not, this would deadlock, because there is
> a mutex lock inside regmap, so I have to cache this outside of regmap.
> This is a bit strange, to use the cache, setup another own cache. (1st
> problem)
> I chose my per device structure struct vprbrd_gpio to hold this cache, but I
> can not reach it. You see in the patch, I try to container_of up to my
> structure. This does not work, because struct regmap is not public available.
> (2nd problem)

The idea is that regmap is self-contained. If you need to change
it's semantics the place to patch is in regmap itself.

> Setting the direction to output is an atomic set direction and set value.
> The register number is different from setting the value only. So after a
> successful call, I want to update the cache of output value using
> regcache_write. This is also not publicy available api. The only thing I could
> do is invalidate the whole cache using regcache_mark_dirty. (3rd problem)

Same thing.

> I attach my current working state here. This is NOT WORKING and only as
> reference.

So if you want to do this with regmap, I suggest the way forward would
be to go solve it at the root by implementing something like
drivers/base/regmap/regmap-usb-ctrl.c with your desired semantics
and using that.

However I *do* understand that requesting this may be a bit thick,
so I'm happy to accept the older patch with custom caching
now.

> Regards,
> Lars
> ---
> diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
> index 8382dc8..48be4ba 100644
> --- a/drivers/gpio/Kconfig
> +++ b/drivers/gpio/Kconfig
> @@ -636,4 +636,17 @@ config GPIO_MSIC
> Enable support for GPIO on intel MSIC controllers found in
> intel MID devices
>
> +comment "USB GPIO expanders:"
> +
> +config GPIO_VIPERBOARD
> + tristate "Viperboard GPIO a & b support"
> + depends on MFD_VIPERBOARD && USB
> + help
> + Say yes here to access the GPIO signals of Nano River
> + Technologies Viperboard. There are two GPIO chips on the
> + board: gpioa and gpiob.
> + See viperboard API specification and Nano
> + River Tech's viperboard.h for detailed meaning
> + of the module parameters.
> +
> endif
> diff --git a/drivers/gpio/Makefile b/drivers/gpio/Makefile
> index 0ffaa84..71cc896 100644
> --- a/drivers/gpio/Makefile
> +++ b/drivers/gpio/Makefile
> @@ -69,6 +69,7 @@ obj-$(CONFIG_GPIO_TPS65910) += gpio-tps65910.o
> obj-$(CONFIG_GPIO_TPS65912) += gpio-tps65912.o
> obj-$(CONFIG_GPIO_TWL4030) += gpio-twl4030.o
> obj-$(CONFIG_GPIO_UCB1400) += gpio-ucb1400.o
> +obj-$(CONFIG_GPIO_VIPERBOARD) += gpio-viperboard.o
> obj-$(CONFIG_GPIO_VR41XX) += gpio-vr41xx.o
> obj-$(CONFIG_GPIO_VT8500) += gpio-vt8500.o
> obj-$(CONFIG_GPIO_VX855) += gpio-vx855.o
> diff --git a/drivers/gpio/gpio-viperboard.c b/drivers/gpio/gpio-viperboard.c
> new file mode 100644
> index 0000000..2dc6c9f
> --- /dev/null
> +++ b/drivers/gpio/gpio-viperboard.c
> @@ -0,0 +1,618 @@
> +/*
> + * Nano River Technologies viperboard GPIO lib driver
> + *
> + * (C) 2012 by Lemonage GmbH
> + * Author: Lars Poeschel <[email protected]>
> + * All rights reserved.
> + *
> + * 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/errno.h>
> +#include <linux/module.h>
> +#include <linux/slab.h>
> +#include <linux/types.h>
> +#include <linux/mutex.h>
> +#include <linux/platform_device.h>
> +#include <linux/regmap.h>
> +
> +#include <linux/usb.h>
> +#include <linux/gpio.h>
> +
> +#include <linux/mfd/viperboard.h>
> +
> +#define VPRBRD_GPIOA_CLK_1MHZ 0
> +#define VPRBRD_GPIOA_CLK_100KHZ 1
> +#define VPRBRD_GPIOA_CLK_10KHZ 2
> +#define VPRBRD_GPIOA_CLK_1KHZ 3
> +#define VPRBRD_GPIOA_CLK_100HZ 4
> +#define VPRBRD_GPIOA_CLK_10HZ 5
> +
> +#define VPRBRD_GPIOA_FREQ_DEFAULT 1000
> +
> +#define VPRBRD_GPIOA_CMD_CONT 0x00
> +#define VPRBRD_GPIOA_CMD_PULSE 0x01
> +#define VPRBRD_GPIOA_CMD_PWM 0x02
> +#define VPRBRD_GPIOA_CMD_SETOUT 0x03
> +#define VPRBRD_GPIOA_CMD_SETIN 0x04
> +#define VPRBRD_GPIOA_CMD_SETINT 0x05
> +#define VPRBRD_GPIOA_CMD_GETIN 0x06
> +
> +#define VPRBRD_GPIOB_CMD_SETDIR 0x00
> +#define VPRBRD_GPIOB_CMD_SETVAL 0x01
> +
> +#define VPRBRD_GPIOA_NUM_PINS 16
> +#define VPRBRD_GPIOA_REG_VAL_BASE 0
> +#define VPRBRD_GPIOA_REG_VAL_MAX (1 * VPRBRD_GPIOA_NUM_PINS - 1)
> +#define VPRBRD_GPIOA_REG_DIR_BASE (VPRBRD_GPIOA_REG_VAL_MAX + 1)
> +#define VPRBRD_GPIOA_REG_DIR_MAX (2 * VPRBRD_GPIOA_NUM_PINS - 1)
> +#define VPRBRD_GPIOA_NUM_REGS (VPRBRD_GPIOA_REG_DIR_MAX + 1)
> +
> +struct vprbrd_gpioa_msg {
> + u8 cmd;
> + u8 clk;
> + u8 offset;
> + u8 t1;
> + u8 t2;
> + u8 invert;
> + u8 pwmlevel;
> + u8 outval;
> + u8 risefall;
> + u8 answer;
> + u8 __fill;
> +} __packed;
> +
> +struct vprbrd_gpiob_msg {
> + u8 cmd;
> + u16 val;
> + u16 mask;
> +} __packed;
> +
> +struct vprbrd_gpio {
> + struct gpio_chip gpioa; /* gpio a related things */
> + u32 gpioa_out;
> + u32 gpioa_val;
> + struct gpio_chip gpiob; /* gpio b related things */
> + u32 gpiob_out;
> + u32 gpiob_val;
> + struct vprbrd *vb;
> + struct regmap *regmap;
> +};
> +
> +/* gpioa sampling clock module parameter */
> +static unsigned char gpioa_clk;
> +static unsigned int gpioa_freq = VPRBRD_GPIOA_FREQ_DEFAULT;
> +module_param(gpioa_freq, uint, 0);
> +MODULE_PARM_DESC(gpioa_freq, "gpio a sampling freq in Hz (default is 1000Hz)"
> + "valid values: 10, 100, 1000, 10000, 100000, 1000000");
> +
> +/* ----- begin of gipo a chip -------------------------------------------- */
> +
> +static int regmap_vb_gpio_write(void *context, const void *data, size_t count)
> +{
> + struct vprbrd *vb = (struct vprbrd *)context;
> + struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
> + int ret;
> + const u8 reg = ((const u8 *)data)[0];
> + const u8 val = ((const u8 *)data)[1];
> +
> + dev_dbg(&vb->pdev.dev, "%s count:%i reg:%i, val:%i\n", __FUNCTION__, count, reg, val);
> +
> + if (count != 2)
> + return -ENOTSUPP;
> +
> + mutex_lock(&vb->lock);
> +
> + gamsg->clk = 0x00;
> + gamsg->t1 = 0x00;
> + gamsg->t2 = 0x00;
> + gamsg->invert = 0x00;
> + gamsg->pwmlevel = 0x00;
> + gamsg->outval = val;
> + gamsg->risefall = 0x00;
> + gamsg->answer = 0x00;
> + gamsg->__fill = 0x00;
> +
> + if (reg >= VPRBRD_GPIOA_REG_VAL_BASE &&
> + reg <= VPRBRD_GPIOA_REG_VAL_MAX) {
> + gamsg->cmd = VPRBRD_GPIOA_CMD_SETOUT;
> + gamsg->offset = reg;
> + gamsg->outval = val;
> + } else if (reg >= VPRBRD_GPIOA_REG_DIR_BASE &&
> + reg <= VPRBRD_GPIOA_REG_DIR_MAX) {
> + gamsg->offset = reg - VPRBRD_GPIOA_REG_DIR_BASE;
> + if (val > 0) {
> + gamsg->cmd = VPRBRD_GPIOA_CMD_SETIN;
> + gamsg->clk = gpioa_clk;
> + } else {
> + gamsg->cmd = VPRBRD_GPIOA_CMD_SETOUT;
> + }
> + }
> + ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
> + VPRBRD_USB_REQUEST_GPIOA, VPRBRD_USB_TYPE_OUT, 0x0000,
> + 0x0000, gamsg, sizeof(struct vprbrd_gpioa_msg),
> + VPRBRD_USB_TIMEOUT_MS);
> +
> + mutex_unlock(&vb->lock);
> +
> + if (ret != sizeof(struct vprbrd_gpioa_msg))
> + return -EREMOTEIO;
> +
> + return 0;
> +}
> +
> +static int regmap_vb_gpio_read(void *context, const void *reg_buf,
> + size_t reg_size, void *val_buf, size_t val_size)
> +{
> + struct vprbrd *vb = (struct vprbrd *)context;
> + struct vprbrd_gpioa_msg *gamsg = (struct vprbrd_gpioa_msg *)vb->buf;
> + int ret, error = 0;
> + const u8 *reg8 = reg_buf;
> +
> + dev_dbg(&vb->pdev.dev, "%s reg_size:%i val_size:%i\n", __FUNCTION__, reg_size, val_size);
> +
> + if (val_size != 1 || reg_size != 1)
> + return -ENOTSUPP;
> +
> + mutex_lock(&vb->lock);
> +
> + gamsg->cmd = VPRBRD_GPIOA_CMD_GETIN;
> + gamsg->clk = 0x00;
> + gamsg->offset = reg8[0];
> + gamsg->t1 = 0x00;
> + gamsg->t2 = 0x00;
> + gamsg->invert = 0x00;
> + gamsg->pwmlevel = 0x00;
> + gamsg->outval = 0x00;
> + gamsg->risefall = 0x00;
> + gamsg->answer = 0x00;
> + gamsg->__fill = 0x00;
> +
> + ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
> + VPRBRD_USB_REQUEST_GPIOA, VPRBRD_USB_TYPE_OUT, 0x0000,
> + 0x0000, gamsg, sizeof(struct vprbrd_gpioa_msg),
> + VPRBRD_USB_TIMEOUT_MS);
> + if (ret != sizeof(struct vprbrd_gpioa_msg))
> + error = -EREMOTEIO;
> +
> + ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
> + VPRBRD_USB_REQUEST_GPIOA, VPRBRD_USB_TYPE_IN, 0x0000,
> + 0x0000, gamsg, sizeof(struct vprbrd_gpioa_msg),
> + VPRBRD_USB_TIMEOUT_MS);
> + *(u8 *)val_buf = gamsg->answer & 0x01;
> +
> + dev_dbg(&vb->pdev.dev, "%s gamsg->answer:%i val:%i\n", __FUNCTION__, gamsg->answer, *(u8 *)val_buf);
> +
> + mutex_unlock(&vb->lock);
> +
> + if (ret != sizeof(struct vprbrd_gpioa_msg))
> + error = -EREMOTEIO;
> +
> + if (error)
> + return error;
> +
> + return 0;
> +}
> +
> +static const struct regmap_bus regmap_vb_gpio = {
> + .write = regmap_vb_gpio_write,
> + .read = regmap_vb_gpio_read,
> +};
> +
> +static bool vprbrd_volatile_reg(struct device *device, unsigned int reg)
> +{
> + struct regmap *regmap = container_of(device, struct regmap, dev);
> + struct vprbrd_gpio *gpio =
> + container_of(regmap, struct vprbrd_gpio, regmap);
> +
> + dev_dbg(device, "%s reg:%i\n", __FUNCTION__, reg);
> +
> + /* if the pin is an output, we are not volatile and can cache */
> + if (gpio->gpioa_out & (1 << reg))
> + return false;
> +
> + return true;
> +}
> +
> +static struct reg_default vprbrd_regdefaults[] = {
> + {0x00, 0x00}, /* 0x00 - 0x0f pin values */
> + {0x01, 0x00},
> + {0x02, 0x00},
> + {0x03, 0x00},
> + {0x04, 0x00},
> + {0x05, 0x00},
> + {0x06, 0x00},
> + {0x07, 0x00},
> + {0x08, 0x00},
> + {0x09, 0x00},
> + {0x0a, 0x00},
> + {0x0b, 0x00},
> + {0x0c, 0x00},
> + {0x0d, 0x00},
> + {0x0e, 0x00},
> + {0x0f, 0x00},
> + {0x10, 0x00}, /* 0x10 - 0x1f pin direction */
> + {0x11, 0x00},
> + {0x12, 0x00},
> + {0x13, 0x00},
> + {0x14, 0x00},
> + {0x15, 0x00},
> + {0x16, 0x00},
> + {0x17, 0x00},
> + {0x18, 0x00},
> + {0x19, 0x00},
> + {0x1a, 0x00},
> + {0x1b, 0x00},
> + {0x1c, 0x00},
> + {0x1d, 0x00},
> + {0x1e, 0x00},
> + {0x1f, 0x00},
> +};
> +
> +static const struct regmap_config vprbrd_regmap_config = {
> + .name = "gpio_regmap",
> + .reg_bits = 8,
> + .val_bits = 8,
> + .volatile_reg = vprbrd_volatile_reg,
> + .max_register = VPRBRD_GPIOA_NUM_REGS,
> + .reg_defaults = vprbrd_regdefaults,
> + .num_reg_defaults = ARRAY_SIZE(vprbrd_regdefaults),
> + .cache_type = REGCACHE_RBTREE,
> +};
> +
> +static int vprbrd_gpioa_get(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + int ret;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpioa);
> + unsigned int val;
> +
> + ret = regmap_read(gpio->regmap, offset, &val);
> +
> + dev_dbg(chip->dev, "%s offset:%i val:%x ret:%i\n", __FUNCTION__, offset, val, ret);
> +
> + if (ret < 0)
> + return ret;
> + else
> + return val;
> +}
> +
> +static void vprbrd_gpioa_set(struct gpio_chip *chip,
> + unsigned offset, int value)
> +{
> + int ret;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpioa);
> +
> + dev_dbg(chip->dev, "%s offset:%i, value:%i\n", __FUNCTION__, offset, value);
> +
> + ret = regmap_write(gpio->regmap, offset, value);
> + if (ret < 0)
> + dev_err(chip->dev, "usb error setting pin value\n");
> +}
> +
> +static int vprbrd_gpioa_direction_input(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + int ret;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpioa);
> +
> + dev_dbg(chip->dev, "%s offset:%i\n", __FUNCTION__, offset);
> +
> + ret = regmap_write(gpio->regmap,
> + offset + VPRBRD_GPIOA_REG_DIR_BASE, 0);
> +
> + if (ret < 0) {
> + dev_err(chip->dev, "usb error setting pin to output\n");
> + return ret;
> + }
> +
> + gpio->gpioa_out &= ~(1 << offset);
> +
> + return 0;
> +}
> +
> +static int vprbrd_gpioa_direction_output(struct gpio_chip *chip,
> + unsigned offset, int value)
> +{
> + int ret;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpioa);
> +
> + dev_dbg(chip->dev, "%s offset:%i, value:%i\n", __FUNCTION__, offset, value);
> +
> + ret = regmap_write(gpio->regmap,
> + offset + VPRBRD_GPIOA_REG_DIR_BASE, value);
> +
> + if (ret < 0) {
> + dev_err(chip->dev, "usb error setting pin to output\n");
> + return ret;
> + }
> +
> + gpio->gpioa_out |= (1 << offset);
> + ret = regcache_write(gpio->regmap, offset, value);
> +
> + return 0;
> +}
> +
> +/* ----- end of gpio a chip ---------------------------------------------- */
> +
> +/* ----- begin of gipo b chip -------------------------------------------- */
> +
> +static int vprbrd_gpiob_setdir(struct vprbrd *vb, unsigned offset,
> + unsigned dir)
> +{
> + struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
> + int ret;
> +
> + gbmsg->cmd = VPRBRD_GPIOB_CMD_SETDIR;
> + gbmsg->val = cpu_to_be16(dir << offset);
> + gbmsg->mask = cpu_to_be16(0x0001 << offset);
> +
> + ret = usb_control_msg(vb->usb_dev, usb_sndctrlpipe(vb->usb_dev, 0),
> + VPRBRD_USB_REQUEST_GPIOB, VPRBRD_USB_TYPE_OUT, 0x0000,
> + 0x0000, gbmsg, sizeof(struct vprbrd_gpiob_msg),
> + VPRBRD_USB_TIMEOUT_MS);
> +
> + if (ret != sizeof(struct vprbrd_gpiob_msg))
> + return -EREMOTEIO;
> +
> + return 0;
> +}
> +
> +static int vprbrd_gpiob_get(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + int ret;
> + u16 val;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpiob);
> + struct vprbrd *vb = gpio->vb;
> + struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
> +
> + /* if io is set to output, just return the saved value */
> + if (gpio->gpiob_out & (1 << offset))
> + return gpio->gpiob_val & (1 << offset);
> +
> + mutex_lock(&vb->lock);
> +
> + ret = usb_control_msg(vb->usb_dev, usb_rcvctrlpipe(vb->usb_dev, 0),
> + VPRBRD_USB_REQUEST_GPIOB, VPRBRD_USB_TYPE_IN, 0x0000,
> + 0x0000, gbmsg, sizeof(struct vprbrd_gpiob_msg),
> + VPRBRD_USB_TIMEOUT_MS);
> + val = gbmsg->val;
> +
> + mutex_unlock(&vb->lock);
> +
> + if (ret != sizeof(struct vprbrd_gpiob_msg))
> + return ret;
> +
> + /* cache the read values */
> + gpio->gpiob_val = be16_to_cpu(val);
> +
> + return (gpio->gpiob_val >> offset) & 0x1;
> +}
> +
> +static void vprbrd_gpiob_set(struct gpio_chip *chip,
> + unsigned offset, int value)
> +{
> + int ret;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpiob);
> + struct vprbrd *vb = gpio->vb;
> + struct vprbrd_gpiob_msg *gbmsg = (struct vprbrd_gpiob_msg *)vb->buf;
> +
> + if (gpio->gpiob_out & (1 << offset)) {
> + if (value)
> + gpio->gpiob_val |= (1 << offset);
> + else
> + gpio->gpiob_val &= ~(1 << offset);
> +
> + mutex_lock(&vb->lock);
> +
> + gbmsg->cmd = VPRBRD_GPIOB_CMD_SETVAL;
> + gbmsg->val = cpu_to_be16(value << offset);
> + gbmsg->mask = cpu_to_be16(0x0001 << offset);
> +
> + ret = usb_control_msg(vb->usb_dev,
> + usb_sndctrlpipe(vb->usb_dev, 0),
> + VPRBRD_USB_REQUEST_GPIOB, VPRBRD_USB_TYPE_OUT,
> + 0x0000, 0x0000, gbmsg,
> + sizeof(struct vprbrd_gpiob_msg), VPRBRD_USB_TIMEOUT_MS);
> +
> + mutex_unlock(&vb->lock);
> +
> + if (ret != sizeof(struct vprbrd_gpiob_msg))
> + dev_err(chip->dev, "usb error setting pin value\n");
> + }
> +}
> +
> +static int vprbrd_gpiob_direction_input(struct gpio_chip *chip,
> + unsigned offset)
> +{
> + int ret;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpiob);
> + struct vprbrd *vb = gpio->vb;
> +
> + gpio->gpiob_out &= ~(1 << offset);
> +
> + mutex_lock(&vb->lock);
> +
> + ret = vprbrd_gpiob_setdir(vb, offset, 0);
> +
> + mutex_unlock(&vb->lock);
> +
> + if (ret)
> + dev_err(chip->dev, "usb error setting pin to input\n");
> +
> + return ret;
> +}
> +
> +static int vprbrd_gpiob_direction_output(struct gpio_chip *chip,
> + unsigned offset, int value)
> +{
> + int ret;
> + struct vprbrd_gpio *gpio =
> + container_of(chip, struct vprbrd_gpio, gpiob);
> + struct vprbrd *vb = gpio->vb;
> +
> + gpio->gpiob_out |= (1 << offset);
> + if (value)
> + gpio->gpiob_val |= (1 << offset);
> + else
> + gpio->gpiob_val &= ~(1 << offset);
> +
> + mutex_lock(&vb->lock);
> +
> + ret = vprbrd_gpiob_setdir(vb, offset, 1);
> + if (ret)
> + dev_err(chip->dev, "usb error setting pin to output\n");
> +
> + mutex_unlock(&vb->lock);
> +
> + vprbrd_gpiob_set(chip, offset, value);
> +
> + return ret;
> +}
> +
> +/* ----- end of gpio b chip ---------------------------------------------- */
> +
> +static int __devinit vprbrd_gpio_probe(struct platform_device *pdev)
> +{
> + struct vprbrd *vb = dev_get_drvdata(pdev->dev.parent);
> + struct vprbrd_gpio *vb_gpio;
> + int ret, ret_err;
> +
> + vb_gpio = kzalloc(sizeof(*vb_gpio), GFP_KERNEL);
> + if (vb_gpio == NULL)
> + return -ENOMEM;
> +
> + vb_gpio->vb = vb;
> + /* registering gpio a */
> + vb_gpio->gpioa.label = "viperboard gpio a";
> + vb_gpio->gpioa.dev = &pdev->dev;
> + vb_gpio->gpioa.owner = THIS_MODULE;
> + vb_gpio->gpioa.base = -1;
> + vb_gpio->gpioa.ngpio = 16;
> + vb_gpio->gpioa.can_sleep = 1;
> + vb_gpio->gpioa.set = vprbrd_gpioa_set;
> + vb_gpio->gpioa.get = vprbrd_gpioa_get;
> + vb_gpio->gpioa.direction_input = vprbrd_gpioa_direction_input;
> + vb_gpio->gpioa.direction_output = vprbrd_gpioa_direction_output;
> + ret = gpiochip_add(&vb_gpio->gpioa);
> + if (ret < 0) {
> + dev_err(vb_gpio->gpioa.dev, "could not add gpio a");
> + goto err_gpioa;
> + }
> +
> + /* registering gpio b */
> + vb_gpio->gpiob.label = "viperboard gpio b";
> + vb_gpio->gpiob.dev = &pdev->dev;
> + vb_gpio->gpiob.owner = THIS_MODULE;
> + vb_gpio->gpiob.base = -1;
> + vb_gpio->gpiob.ngpio = 16;
> + vb_gpio->gpiob.can_sleep = 1;
> + vb_gpio->gpiob.set = vprbrd_gpiob_set;
> + vb_gpio->gpiob.get = vprbrd_gpiob_get;
> + vb_gpio->gpiob.direction_input = vprbrd_gpiob_direction_input;
> + vb_gpio->gpiob.direction_output = vprbrd_gpiob_direction_output;
> + ret = gpiochip_add(&vb_gpio->gpiob);
> + if (ret < 0) {
> + dev_err(vb_gpio->gpiob.dev, "could not add gpio b");
> + goto err_gpiob;
> + }
> +
> + platform_set_drvdata(pdev, vb_gpio);
> +
> + vb_gpio->regmap = devm_regmap_init(vb_gpio->gpioa.dev,
> + &regmap_vb_gpio, vb, &vprbrd_regmap_config);
> + if (IS_ERR(vb_gpio->regmap)) {
> + ret = PTR_ERR(vb_gpio->regmap);
> + dev_err(vb_gpio->gpioa.dev,
> + "regmap_init failed with err: %d\n", ret);
> + goto err_gpiob;
> + }
> +
> + return ret;
> +
> +err_gpiob:
> + ret_err = gpiochip_remove(&vb_gpio->gpioa);
> +
> +err_gpioa:
> + kfree(vb_gpio);
> + return ret;
> +}
> +
> +static int __devexit vprbrd_gpio_remove(struct platform_device *pdev)
> +{
> + struct vprbrd_gpio *vb_gpio = platform_get_drvdata(pdev);
> + int ret;
> +
> +/*
> + ret = regmap_exit(vbgpio->regmap);
> + if (ret == 0)
> +*/
> + ret = gpiochip_remove(&vb_gpio->gpiob);
> + if (ret == 0)
> + ret = gpiochip_remove(&vb_gpio->gpioa);
> + if (ret == 0)
> + kfree(vb_gpio);
> +
> + return ret;
> +}
> +
> +static struct platform_driver vprbrd_gpio_driver = {
> + .driver.name = "viperboard-gpio",
> + .driver.owner = THIS_MODULE,
> + .probe = vprbrd_gpio_probe,
> + .remove = __devexit_p(vprbrd_gpio_remove),
> +};
> +
> +static int __init vprbrd_gpio_init(void)
> +{
> + switch (gpioa_freq) {
> + case 1000000:
> + gpioa_clk = VPRBRD_GPIOA_CLK_1MHZ;
> + break;
> + case 100000:
> + gpioa_clk = VPRBRD_GPIOA_CLK_100KHZ;
> + break;
> + case 10000:
> + gpioa_clk = VPRBRD_GPIOA_CLK_10KHZ;
> + break;
> + case 1000:
> + gpioa_clk = VPRBRD_GPIOA_CLK_1KHZ;
> + break;
> + case 100:
> + gpioa_clk = VPRBRD_GPIOA_CLK_100HZ;
> + break;
> + case 10:
> + gpioa_clk = VPRBRD_GPIOA_CLK_10HZ;
> + break;
> + default:
> + pr_warn("invalid gpioa_freq (%d)\n", gpioa_freq);
> + gpioa_clk = VPRBRD_GPIOA_CLK_1KHZ;
> + }
> +
> + return platform_driver_register(&vprbrd_gpio_driver);
> +}
> +subsys_initcall(vprbrd_gpio_init);
> +
> +static void __exit vprbrd_gpio_exit(void)
> +{
> + platform_driver_unregister(&vprbrd_gpio_driver);
> +}
> +module_exit(vprbrd_gpio_exit);
> +
> +MODULE_AUTHOR("Lars Poeschel <[email protected]>");
> +MODULE_DESCRIPTION("GPIO driver for Nano River Techs Viperboard");
> +MODULE_LICENSE("GPL");
> +MODULE_ALIAS("platform:viperboard-gpio");
> diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
> index de368b7..9ad06cd 100644
> --- a/drivers/mfd/viperboard.c
> +++ b/drivers/mfd/viperboard.c
> @@ -49,6 +49,9 @@ static void vprbrd_free(struct vprbrd *dev)
> }
>
> static struct mfd_cell vprbrd_devs[] = {
> + {
> + .name = "viperboard-gpio",
> + },
> };
>
> static int vprbrd_probe(struct usb_interface *interface,
> diff --git a/include/linux/mfd/viperboard.h b/include/linux/mfd/viperboard.h
> index 1c23c79..d3c9ad2 100644
> --- a/include/linux/mfd/viperboard.h
> +++ b/include/linux/mfd/viperboard.h
> @@ -44,6 +44,8 @@
> #define VPRBRD_USB_TIMEOUT_MS 100
> #define VPRBRD_USB_REQUEST_MAJOR 0xea
> #define VPRBRD_USB_REQUEST_MINOR 0xeb
> +#define VPRBRD_USB_REQUEST_GPIOA 0xed
> +#define VPRBRD_USB_REQUEST_GPIOB 0xdd
>
> struct __packed vprbrd_i2c_write_hdr {
> u8 cmd;


Yours,
Linus Walleij

2012-10-24 16:31:59

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Wed, Oct 24, 2012 at 09:53:06AM +0200, Linus Walleij wrote:
> On Tue, Oct 23, 2012 at 5:24 PM, Lars Poeschel <[email protected]> wrote:

> > Ok, I tried to implement it (at least for the gpioa part of the driver).
> > It does not work. I got stuck. There are three problems I could not solve:

> So I'm looping in Mark Brown to get some hints whether the following
> can be resolved easily or needs to be given up on...

Some context would've been enormously useful for working out what the
discussion is all about... this is *very* verbose and not at all clear.

> > Setting the direction to output is an atomic set direction and set value.
> > The register number is different from setting the value only. So after a
> > successful call, I want to update the cache of output value using
> > regcache_write. This is also not publicy available api. The only thing I could
> > do is invalidate the whole cache using regcache_mark_dirty. (3rd problem)

> Same thing.

The above doesn't sound like marking the register as dirty is going to
be helpful... at most you'd want to discard the cache which is already
supported per register. Marking the register as dirty would leave the
existing (presumably wrong if there's a problem) value in place in the
cache. It's not at all clear to me that a cache is even useful for
these registers.

> > I attach my current working state here. This is NOT WORKING and only as
> > reference.

> So if you want to do this with regmap, I suggest the way forward would
> be to go solve it at the root by implementing something like
> drivers/base/regmap/regmap-usb-ctrl.c with your desired semantics
> and using that.

So the issue is that we're trying to use regmap for some USB device?


Attachments:
(No filename) (1.69 kB)
signature.asc (836.00 B)
Digital signature
Download all attachments

2012-10-25 10:02:32

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Wednesday 24 October 2012 at 18:31:55, Mark Brown wrote:
> On Wed, Oct 24, 2012 at 09:53:06AM +0200, Linus Walleij wrote:
> > On Tue, Oct 23, 2012 at 5:24 PM, Lars Poeschel <[email protected]>
wrote:
> > > Ok, I tried to implement it (at least for the gpioa part of the
> > > driver).
> >
> > > It does not work. I got stuck. There are three problems I could not
solve:
> > So I'm looping in Mark Brown to get some hints whether the following
> > can be resolved easily or needs to be given up on...
>
> Some context would've been enormously useful for working out what the
> discussion is all about... this is *very* verbose and not at all clear.

You can reread our conversation before Linus Walleij brought you in starting
with my first patch submission here:

https://lkml.org/lkml/2012/10/12/218

I'll try to sum up, what happend so far:
I'd submit a driver some strange device (called "viperboard") that besides
some other functionality is a USB interface that has 2x16 GPIO at the other
side. Some USB to GPIO converter.
In my driver I had two 16 bit variables that cache the values of the GPIO and
two 16 bit variables holding the direction of the GPIO pin (input or output).
The idea is that in case a pin is an output and there is a read on that pin,
that I wanted to save the USB ping pong for reading the value of the pin.
Linus Walleij pointed out that there is already a framework for marshalling
and caching register read/writes called regmap.
I gave it a try and used it for my driver but I had problems and this is where
you came in.
As there is no general regmap_bus for reading/writing registers over USB (and
probably will never be). I had to implement it in my driver for the special
case of this device. I also have a regmap_config, that provides a volatile_reg
function. I need this to decide if the pin the value is queried is an output
or an input. In the latter case I obviously can't use the cache, in the former
case I want to use it. Here the first problem arises. In the volatile_reg
function I can not do a read of a regmap register since regmap internally uses
a mutex lock. Thus I have my own cache in a device private variable. This is a
bit strange. To use the cache to have to implement my own cache ;-)
The other problem is, that the volatile_reg function is called with struct
device and I can not container_of up to my device vprbrd_gpio struct, since
the struct regmap seems to be regmap private - not for use in drivers.
The last problem is that I have 16 registers for setting/reading the first 16
pins value. And there is another 16 registers for setting the pins direction
(input/output). Setting the pin to output is an atomic operation of setting
the pins direction AND setting it's value. So if there is a set pin direction
to output operation in my driver I want to update the value of the
corresponding value register, since regmap does not know of this change. But
the regcache_write I would use for this seems also not intended for use by
drivers. It is not exported.
You can have a look at my current development code of the driver in question
in this mail:
https://lkml.org/lkml/2012/10/23/374

> > > Setting the direction to output is an atomic set direction and set
> > > value. The register number is different from setting the value only.
> > > So after a successful call, I want to update the cache of output value
> > > using regcache_write. This is also not publicy available api. The only
> > > thing I could do is invalidate the whole cache using
> > > regcache_mark_dirty. (3rd problem)
> >
> > Same thing.
>
> The above doesn't sound like marking the register as dirty is going to
> be helpful... at most you'd want to discard the cache which is already
> supported per register. Marking the register as dirty would leave the
> existing (presumably wrong if there's a problem) value in place in the
> cache. It's not at all clear to me that a cache is even useful for
> these registers.
>
> > > I attach my current working state here. This is NOT WORKING and only as
> > > reference.
> >
> > So if you want to do this with regmap, I suggest the way forward would
> > be to go solve it at the root by implementing something like
> > drivers/base/regmap/regmap-usb-ctrl.c with your desired semantics
> > and using that.
>
> So the issue is that we're trying to use regmap for some USB device?

This is not an issue, since I can implement my regmap_bus for this inside my
driver.

Thanks for your help!

Lars

2012-10-25 14:00:19

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Thu, Oct 25, 2012 at 12:02:36PM +0200, Lars Poeschel wrote:

> You can reread our conversation before Linus Walleij brought you in starting
> with my first patch submission here:

> https://lkml.org/lkml/2012/10/12/218

This has all the problems of this and your previous mail - here we've
got about 40 lines of unbroken text (with very wide lines too, notice
how things start to wrap when I quote them) none of which is easy to
read.

> As there is no general regmap_bus for reading/writing registers over USB (and
> probably will never be). I had to implement it in my driver for the special
> case of this device. I also have a regmap_config, that provides a volatile_reg
> function. I need this to decide if the pin the value is queried is an output
> or an input. In the latter case I obviously can't use the cache, in the former
Why would you want to implement this as a bus? If you're not actually
rendering things down into a register and value on the bus then you
should be hooking in at the level before we do the marshalling since
that's totally irrelevant. This should be done by making the
marashalling pluggable.

> case I want to use it. Here the first problem arises. In the volatile_reg
> function I can not do a read of a regmap register since regmap internally uses
> a mutex lock. Thus I have my own cache in a device private variable. This is a
> bit strange. To use the cache to have to implement my own cache ;-)

What do you actually need to read back here?

> The other problem is, that the volatile_reg function is called with struct
> device and I can not container_of up to my device vprbrd_gpio struct, since

Why on earth can't you do that? That sounds like something that should
be fixed for whatever bus you're using if it's an issue but normally
this is simply a case of setting and reading some driver data.

> The last problem is that I have 16 registers for setting/reading the first 16
> pins value. And there is another 16 registers for setting the pins direction
> (input/output). Setting the pin to output is an atomic operation of setting
> the pins direction AND setting it's value. So if there is a set pin direction
> to output operation in my driver I want to update the value of the
> corresponding value register, since regmap does not know of this change. But
> the regcache_write I would use for this seems also not intended for use by
> drivers. It is not exported.

So just invalidate the cache and it'll get restored next time we look at
the register.


Attachments:
(No filename) (2.47 kB)
signature.asc (836.00 B)
Digital signature
Download all attachments

2012-10-25 16:02:40

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

I am not sure if I did something fundamentally wrong or if you did not
understand, what I am trying to do. I am sorry, I am not a native english
writer, maybe I did a bad explanation.

On Thursday 25 October 2012 at 16:00:13, Mark Brown wrote:
> On Thu, Oct 25, 2012 at 12:02:36PM +0200, Lars Poeschel wrote:
> > As there is no general regmap_bus for reading/writing registers over USB
> > (and probably will never be). I had to implement it in my driver for the
> > special case of this device. I also have a regmap_config, that provides
> > a volatile_reg function. I need this to decide if the pin the value is
> > queried is an output or an input. In the latter case I obviously can't
> > use the cache, in the former
>
> Why would you want to implement this as a bus? If you're not actually
> rendering things down into a register and value on the bus then you
> should be hooking in at the level before we do the marshalling since
> that's totally irrelevant. This should be done by making the
> marashalling pluggable.

Did you have a look at the code ? I want to render things down to registers
and values on the bus! In the one and only case a pin is set to be an output
and someone reads it's value, I don't want the bus to become active and
instead read the value from the regmap cache.
There is no ready-to-use remap-usb-something, so I have to implement this bus
on my own. regmap_init needs some regmap_bus. This is what I've done for this
usb device inside my driver.

> > case I want to use it. Here the first problem arises. In the volatile_reg
> > function I can not do a read of a regmap register since regmap internally
> > uses a mutex lock. Thus I have my own cache in a device private
> > variable. This is a bit strange. To use the cache to have to implement
> > my own cache ;-)
>
> What do you actually need to read back here?

Someone reads a gpio value register. To be able to decide if I really have to
do the read on the usb bus or if I can use a cached value, I have to know if
the pin in question is an output or an input. To get this information I have
to do another register read. If it's an output I give back the cached value,
if it's an input I do the register read.

> > The other problem is, that the volatile_reg function is called with
> > struct device and I can not container_of up to my device vprbrd_gpio
> > struct, since
>
> Why on earth can't you do that? That sounds like something that should
> be fixed for whatever bus you're using if it's an issue but normally
> this is simply a case of setting and reading some driver data.

Sorry, I did not see this. I was confused by the regmap_bus functions get
called with a void *context pointer and the volatile_reg function with the
struct device *device. But those are different. Thanks for the hint.

> > The last problem is that I have 16 registers for setting/reading the
> > first 16 pins value. And there is another 16 registers for setting the
> > pins direction (input/output). Setting the pin to output is an atomic
> > operation of setting the pins direction AND setting it's value. So if
> > there is a set pin direction to output operation in my driver I want to
> > update the value of the corresponding value register, since regmap does
> > not know of this change. But the regcache_write I would use for this
> > seems also not intended for use by drivers. It is not exported.
>
> So just invalidate the cache and it'll get restored next time we look at
> the register.

Yes, this is exactly what I gave as an alternative in my second to last mail.
But this invalidates the whole register map although I just want to update
one register value.

2012-10-25 16:06:55

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Thu, Oct 25, 2012 at 06:02:42PM +0200, Lars Poeschel wrote:

> On Thursday 25 October 2012 at 16:00:13, Mark Brown wrote:

> > Why would you want to implement this as a bus? If you're not actually
> > rendering things down into a register and value on the bus then you
> > should be hooking in at the level before we do the marshalling since
> > that's totally irrelevant. This should be done by making the
> > marashalling pluggable.

> Did you have a look at the code ? I want to render things down to registers

No.

> and values on the bus! In the one and only case a pin is set to be an output
> and someone reads it's value, I don't want the bus to become active and
> instead read the value from the regmap cache.

Are you saying that whoever designed this USB device has done it so that
it takes a byte stream with something like RRVV where RR is the register
and VV is the value? That's the marshalling, as you'll have seen that's
done before the buses see the data.

> > What do you actually need to read back here?

> Someone reads a gpio value register. To be able to decide if I really have to
> do the read on the usb bus or if I can use a cached value, I have to know if
> the pin in question is an output or an input. To get this information I have
> to do another register read. If it's an output I give back the cached value,
> if it's an input I do the register read.

Is the I/O selection per GPIO or per device?

> > So just invalidate the cache and it'll get restored next time we look at
> > the register.

> Yes, this is exactly what I gave as an alternative in my second to last mail.
> But this invalidates the whole register map although I just want to update
> one register value.

So add that functionality to the core if it's not there.


Attachments:
(No filename) (1.74 kB)
signature.asc (836.00 B)
Digital signature
Download all attachments

2012-10-26 09:15:58

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Thursday 25 October 2012 at 18:06:51, Mark Brown wrote:
> Are you saying that whoever designed this USB device has done it so that
> it takes a byte stream with something like RRVV where RR is the register
> and VV is the value? That's the marshalling, as you'll have seen that's
> done before the buses see the data.

Aaah, I understand! Now your hint that the marshalling should be made
pluggable makes sense to me.
The device is more complicated and worse. For the first 16 gpio pins it is
something like 01RR0000FD00VV for setting the value and 03RR00FF00FEVV00 for
setting the direction. For the second 16 gpio pins it is completly different.
And yes, for this I completely remarshal what I get marshalled from regmap in
my bus implementation. This is bad. Thank you for your clarification. This
was not that clear to me as I began to use regmap and I think it also was not
to Linus Walleji, as he asked me to change the driver to use regmap. This is
why he brought you into our discussion.

I am a bit unsure what to do now. Since Linus said he would take my driver
without regmap, this will be my way for the driver.
I had a look at the regmap code in sense of making the marshalling pluggable.
It seems that the current assumption is that the register is always the first
value in the buffer after the marshalling happend which would not fit for my
device. Changing that is a bit hard. This marshalling is not the only issue.
For reading values I would need a split buffer or two seperate buffers.
Reading the device means doing a usb write using the first buffer telling the
device which register I am interested in and then doing a usb read into the
second buffer which then contains the actual value of the register. (Both
transfers marshalled different of course.)

> Is the I/O selection per GPIO or per device?

The I/O selection is per GPIO.

> > > So just invalidate the cache and it'll get restored next time we look
> > > at the register.
> >
> > Yes, this is exactly what I gave as an alternative in my second to last
> > mail. But this invalidates the whole register map although I just want
> > to update one register value.
>
> So add that functionality to the core if it's not there.

If I reach the limitations of some api/framework/something it is not my first
idea to change that api but if I did something wrong. But this word from a
maintainer is clear!

2012-10-27 16:14:18

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Fri, Oct 26, 2012 at 11:16 AM, Lars Poeschel <[email protected]> wrote:

> I am a bit unsure what to do now. Since Linus said he would take my driver
> without regmap, this will be my way for the driver.

Please submit the code in the shape you want me to merge it.

I think you've done an honest effort (more than most would do for sure)
to explore the ways of the regmap. If it doesn't fit, it doesn't fit and
that's it.

Yours,
Linus Walleij

2012-10-27 21:35:13

by Mark Brown

[permalink] [raw]
Subject: Re: [PATCH v2 2/4] gpio: add viperboard gpio driver

On Sat, Oct 27, 2012 at 06:14:16PM +0200, Linus Walleij wrote:

> I think you've done an honest effort (more than most would do for sure)
> to explore the ways of the regmap. If it doesn't fit, it doesn't fit and
> that's it.

The bus stuff is needed by a bunch of other drivers - there's a similar
thing with SI476x for example. We should have support for providing I/O
functions as part of the regmap config for drivers that don't need the
data formatting down into a byte stream.


Attachments:
(No filename) (484.00 B)
signature.asc (836.00 B)
Digital signature
Download all attachments