2012-11-05 13:48:31

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v3 1/5] mfd: set device type of mfd platform devices to a mfd type

From: Lars Poeschel <[email protected]>

This sets the type of the platform devices that are added
to the mfd core to some mfd-cell type. This enables us
to add mfd cells to platform devices, that are in use by
other cores (e.g. the usb core).
Otherwise by removing the mfd cell from a platform device
that already has some "childs" would remove all childs,
not only the mfd ones.
Thanks to Lars-Peter Clausen for proposing this.

Signed-off-by: Lars Poeschel <[email protected]>
---
drivers/mfd/mfd-core.c | 15 +++++++++++++--
1 file changed, 13 insertions(+), 2 deletions(-)

diff --git a/drivers/mfd/mfd-core.c b/drivers/mfd/mfd-core.c
index f8b7771..d317b50 100644
--- 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 const 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;
--
1.7.10.4


2012-11-05 13:48:42

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v3 2/5] 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 | 130 ++++++++++++++++++++++++++++++++++++++++
include/linux/mfd/viperboard.h | 105 ++++++++++++++++++++++++++++++++
4 files changed, 250 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 acab3ef..0c2e6bb 100644
--- a/drivers/mfd/Kconfig
+++ b/drivers/mfd/Kconfig
@@ -1044,6 +1044,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
+ 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 separately.
+ The drivers do not support all features the board exposes.
+
endmenu
endif

diff --git a/drivers/mfd/Makefile b/drivers/mfd/Makefile
index d8ccb63..eb85ab2 100644
--- a/drivers/mfd/Makefile
+++ b/drivers/mfd/Makefile
@@ -134,6 +134,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_SYSCON) += syscon.o
diff --git a/drivers/mfd/viperboard.c b/drivers/mfd/viperboard.c
new file mode 100644
index 0000000..34bc372
--- /dev/null
+++ b/drivers/mfd/viperboard.c
@@ -0,0 +1,130 @@
+/*
+ * 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 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;
+ }
+
+ 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, VPRBRD_USB_REQUEST_MAJOR,
+ VPRBRD_USB_TYPE_IN, 0x0000, 0x0000, buf, 1,
+ VPRBRD_USB_TIMEOUT_MS);
+ if (ret == 1)
+ version = buf[0];
+
+ ret = usb_control_msg(vb->usb_dev, pipe, VPRBRD_USB_REQUEST_MINOR,
+ VPRBRD_USB_TYPE_IN, 0x0000, 0x0000, buf, 1,
+ VPRBRD_USB_TIMEOUT_MS);
+ 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(&interface->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:
+ if (vb) {
+ usb_put_dev(vb->usb_dev);
+ kfree(vb);
+ }
+
+ return ret;
+}
+
+static void vprbrd_disconnect(struct usb_interface *interface)
+{
+ struct vprbrd *vb = usb_get_intfdata(interface);
+
+ mfd_remove_devices(&interface->dev);
+ usb_set_intfdata(interface, NULL);
+ usb_put_dev(vb->usb_dev);
+ kfree(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..0d13424
--- /dev/null
+++ b/include/linux/mfd/viperboard.h
@@ -0,0 +1,105 @@
+/*
+ * 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
+
+#define VPRBRD_USB_TYPE_OUT 0x40
+#define VPRBRD_USB_TYPE_IN 0xc0
+#define VPRBRD_USB_TIMEOUT_MS 100
+#define VPRBRD_USB_REQUEST_MAJOR 0xea
+#define VPRBRD_USB_REQUEST_MINOR 0xeb
+
+struct vprbrd_i2c_write_hdr {
+ u8 cmd;
+ u16 addr;
+ u8 len1;
+ u8 len2;
+ u8 last;
+ u8 chan;
+ u16 spi;
+} __packed;
+
+struct 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 */
+} __packed;
+
+struct vprbrd_i2c_status {
+ u8 unknown[11];
+ u8 status;
+} __packed;
+
+struct vprbrd_i2c_write_msg {
+ struct vprbrd_i2c_write_hdr header;
+ u8 data[VPRBRD_I2C_MSG_LEN
+ - sizeof(struct vprbrd_i2c_write_hdr)];
+} __packed;
+
+struct vprbrd_i2c_read_msg {
+ struct vprbrd_i2c_read_hdr header;
+ u8 data[VPRBRD_I2C_MSG_LEN
+ - sizeof(struct vprbrd_i2c_read_hdr)];
+} __packed;
+
+struct vprbrd_i2c_addr_msg {
+ u8 cmd;
+ u8 addr;
+ u8 unknown1;
+ u16 len;
+ u8 unknown2;
+ u8 unknown3;
+} __packed;
+
+/* 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-11-05 13:48:46

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v3 3/5] 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 | 517 ++++++++++++++++++++++++++++++++++++++++
drivers/mfd/viperboard.c | 3 +
include/linux/mfd/viperboard.h | 2 +
5 files changed, 536 insertions(+)
create mode 100644 drivers/gpio/gpio-viperboard.c

diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig
index d055cee..c3bbd08 100644
--- a/drivers/gpio/Kconfig
+++ b/drivers/gpio/Kconfig
@@ -649,4 +649,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 9aeed67..16a1385 100644
--- a/drivers/gpio/Makefile
+++ b/drivers/gpio/Makefile
@@ -71,6 +71,7 @@ obj-$(CONFIG_GPIO_TPS65912) += gpio-tps65912.o
obj-$(CONFIG_GPIO_TWL4030) += gpio-twl4030.o
obj-$(CONFIG_GPIO_TWL6040) += gpio-twl6040.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..1377299
--- /dev/null
+++ b/drivers/gpio/gpio-viperboard.c
@@ -0,0 +1,517 @@
+/*
+ * 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_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
+
+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;
+};
+
+/* 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 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),
+ 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);
+ 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),
+ 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))
+ 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),
+ 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 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),
+ 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;
+}
+
+/* ----- 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;
+
+ vb_gpio = devm_kzalloc(&pdev->dev, 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:
+ 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);
+
+ 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 34bc372..4b2ffbf 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -38,6 +38,9 @@ static const struct usb_device_id vprbrd_table[] = {
MODULE_DEVICE_TABLE(usb, vprbrd_table);

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 0d13424..42d339f 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 vprbrd_i2c_write_hdr {
u8 cmd;
--
1.7.10.4

2012-11-05 13:48:51

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v3 5/5] 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 | 181 ++++++++++++++++++++++++++++++++++++++
drivers/mfd/viperboard.c | 3 +
include/linux/mfd/viperboard.h | 1 +
5 files changed, 193 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..58345c7
--- /dev/null
+++ b/drivers/iio/adc/viperboard_adc.c
@@ -0,0 +1,181 @@
+/*
+ * 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 vprbrd_adc_msg {
+ u8 cmd;
+ u8 chan;
+ u8 val;
+} __packed;
+
+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', \
+ .realbits = 8, \
+ .storagebits = 8, \
+ }, \
+}
+
+static struct iio_chan_spec const 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 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;
+
+ switch (info) {
+ case 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), VPRBRD_USB_REQUEST_ADC,
+ VPRBRD_USB_TYPE_OUT, 0x0000, 0x0000, admsg,
+ sizeof(struct vprbrd_adc_msg), VPRBRD_USB_TIMEOUT_MS);
+ 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), VPRBRD_USB_REQUEST_ADC,
+ VPRBRD_USB_TYPE_IN, 0x0000, 0x0000, admsg,
+ sizeof(struct vprbrd_adc_msg), VPRBRD_USB_TIMEOUT_MS);
+
+ *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;
+ default:
+ error = -EINVAL;
+ break;
+ }
+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 *indio_dev;
+ int ret;
+
+ /* registering iio */
+ indio_dev = iio_device_alloc(sizeof(struct vprbrd_adc));
+ if (!indio_dev) {
+ dev_err(&pdev->dev, "failed allocating iio device\n");
+ return -ENOMEM;
+ }
+
+ adc = iio_priv(indio_dev);
+ adc->vb = vb;
+ indio_dev->name = "viperboard adc";
+ indio_dev->dev.parent = &pdev->dev;
+ indio_dev->info = &vprbrd_adc_iio_info;
+ indio_dev->modes = INDIO_DIRECT_MODE;
+ indio_dev->channels = vprbrd_adc_iio_channels;
+ indio_dev->num_channels = ARRAY_SIZE(vprbrd_adc_iio_channels);
+
+ ret = iio_device_register(indio_dev);
+ if (ret) {
+ dev_err(&pdev->dev, "could not register iio (adc)");
+ goto error;
+ }
+
+ platform_set_drvdata(pdev, indio_dev);
+
+ return 0;
+
+error:
+ iio_device_free(indio_dev);
+ return ret;
+}
+
+static int __devexit vprbrd_adc_remove(struct platform_device *pdev)
+{
+ struct iio_dev *indio_dev = platform_get_drvdata(pdev);
+
+ iio_device_unregister(indio_dev);
+ iio_device_free(indio_dev);
+
+ return 0;
+}
+
+static struct platform_driver vprbrd_adc_driver = {
+ .driver = {
+ .name = "viperboard-adc",
+ .owner = THIS_MODULE,
+ },
+ .probe = vprbrd_adc_probe,
+ .remove = __devexit_p(vprbrd_adc_remove),
+};
+
+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 a7b5b34..dacb3b7 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -44,6 +44,9 @@ static struct mfd_cell vprbrd_devs[] = {
{
.name = "viperboard-i2c",
},
+ {
+ .name = "viperboard-adc",
+ },
};

static int vprbrd_probe(struct usb_interface *interface,
diff --git a/include/linux/mfd/viperboard.h b/include/linux/mfd/viperboard.h
index ef78514..1934528 100644
--- a/include/linux/mfd/viperboard.h
+++ b/include/linux/mfd/viperboard.h
@@ -46,6 +46,7 @@
#define VPRBRD_USB_REQUEST_I2C 0xe9
#define VPRBRD_USB_REQUEST_MAJOR 0xea
#define VPRBRD_USB_REQUEST_MINOR 0xeb
+#define VPRBRD_USB_REQUEST_ADC 0xec
#define VPRBRD_USB_REQUEST_GPIOA 0xed
#define VPRBRD_USB_REQUEST_GPIOB 0xdd

--
1.7.10.4

2012-11-05 13:49:11

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v3 4/5] 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 | 476 +++++++++++++++++++++++++++++++++++
drivers/mfd/viperboard.c | 3 +
include/linux/mfd/viperboard.h | 2 +
5 files changed, 492 insertions(+)
create mode 100644 drivers/i2c/busses/i2c-viperboard.c

diff --git a/drivers/i2c/busses/Kconfig b/drivers/i2c/busses/Kconfig
index 65dd599..405a0fb 100644
--- a/drivers/i2c/busses/Kconfig
+++ b/drivers/i2c/busses/Kconfig
@@ -819,6 +819,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 2d33d62..7e8befd 100644
--- a/drivers/i2c/busses/Makefile
+++ b/drivers/i2c/busses/Makefile
@@ -79,6 +79,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..6688d51
--- /dev/null
+++ b/drivers/i2c/busses/i2c-viperboard.c
@@ -0,0 +1,476 @@
+/*
+ * 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_param;
+static unsigned int i2c_bus_freq = 100;
+module_param(i2c_bus_freq, byte, 0);
+MODULE_PARM_DESC(i2c_bus_freq,
+ "i2c bus frequency in khz (default is 100) valid values: 10, 100, 200, 400, 1000, 3000, 6000");
+
+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),
+ VPRBRD_USB_REQUEST_I2C, VPRBRD_USB_TYPE_IN, 0x0000, 0x0000,
+ status, bytes_xfer, VPRBRD_USB_TIMEOUT_MS);
+
+ 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,
+ VPRBRD_USB_TIMEOUT_MS);
+
+ 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, VPRBRD_USB_TIMEOUT_MS);
+
+ 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,
+ VPRBRD_USB_TIMEOUT_MS);
+
+ 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, VPRBRD_USB_TIMEOUT_MS);
+ 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_param <= VPRBRD_I2C_FREQ_10KHZ)
+ && (i2c_bus_param >= VPRBRD_I2C_FREQ_6MHZ)) {
+ pipe = usb_sndctrlpipe(vb->usb_dev, 0);
+ ret = usb_control_msg(vb->usb_dev, pipe,
+ VPRBRD_USB_REQUEST_I2C_FREQ, VPRBRD_USB_TYPE_OUT,
+ 0x0000, 0x0000, &i2c_bus_param, 1,
+ VPRBRD_USB_TIMEOUT_MS);
+ 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)
+{
+ switch (i2c_bus_freq) {
+ case 6000:
+ i2c_bus_param = VPRBRD_I2C_FREQ_6MHZ;
+ break;
+ case 3000:
+ i2c_bus_param = VPRBRD_I2C_FREQ_3MHZ;
+ break;
+ case 1000:
+ i2c_bus_param = VPRBRD_I2C_FREQ_1MHZ;
+ break;
+ case 400:
+ i2c_bus_param = VPRBRD_I2C_FREQ_400KHZ;
+ break;
+ case 200:
+ i2c_bus_param = VPRBRD_I2C_FREQ_200KHZ;
+ break;
+ case 100:
+ i2c_bus_param = VPRBRD_I2C_FREQ_100KHZ;
+ break;
+ case 10:
+ i2c_bus_param = VPRBRD_I2C_FREQ_10KHZ;
+ break;
+ default:
+ pr_warn("invalid i2c_bus_freq (%d)\n", i2c_bus_freq);
+ i2c_bus_param = VPRBRD_I2C_FREQ_100KHZ;
+ }
+
+ 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 4b2ffbf..a7b5b34 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -41,6 +41,9 @@ static struct mfd_cell vprbrd_devs[] = {
{
.name = "viperboard-gpio",
},
+ {
+ .name = "viperboard-i2c",
+ },
};

static int vprbrd_probe(struct usb_interface *interface,
diff --git a/include/linux/mfd/viperboard.h b/include/linux/mfd/viperboard.h
index 42d339f..ef78514 100644
--- a/include/linux/mfd/viperboard.h
+++ b/include/linux/mfd/viperboard.h
@@ -42,6 +42,8 @@
#define VPRBRD_USB_TYPE_OUT 0x40
#define VPRBRD_USB_TYPE_IN 0xc0
#define VPRBRD_USB_TIMEOUT_MS 100
+#define VPRBRD_USB_REQUEST_I2C_FREQ 0xe6
+#define VPRBRD_USB_REQUEST_I2C 0xe9
#define VPRBRD_USB_REQUEST_MAJOR 0xea
#define VPRBRD_USB_REQUEST_MINOR 0xeb
#define VPRBRD_USB_REQUEST_GPIOA 0xed
--
1.7.10.4

2012-11-05 15:57:54

by Lars-Peter Clausen

[permalink] [raw]
Subject: Re: [PATCH v3 5/5] iio: adc: add viperboard adc driver

On 11/05/2012 03:48 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 to me.

Reviewed-by: Lars-Peter Clausen <[email protected]>

If you happen to resend the series there is one tiny bit that could be
changed, but no need to resend the series just for this.

> ---
> drivers/iio/adc/Kconfig | 7 ++
> drivers/iio/adc/Makefile | 1 +
> drivers/iio/adc/viperboard_adc.c | 181 ++++++++++++++++++++++++++++++++++++++
> drivers/mfd/viperboard.c | 3 +
> include/linux/mfd/viperboard.h | 1 +
> 5 files changed, 193 insertions(+)
> create mode 100644 drivers/iio/adc/viperboard_adc.c
>

> +
> +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 *indio_dev;
> + int ret;
> +
> + /* registering iio */
> + indio_dev = iio_device_alloc(sizeof(struct vprbrd_adc));

sizeof(*adc)

> + if (!indio_dev) {
> + dev_err(&pdev->dev, "failed allocating iio device\n");
> + return -ENOMEM;
> + }

2012-11-05 20:52:44

by Jonathan Cameron

[permalink] [raw]
Subject: Re: [PATCH v3 5/5] iio: adc: add viperboard adc driver

On 11/05/2012 02:48 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.
>
One utter nitpick inline (nice to clean up but totally trivial)

> Signed-off-by: Lars Poeschel <[email protected]>
Acked-by: Jonathan Cameron <[email protected]>

As there is a clear dependence on the mfd elements here this should
probably go though Samuel's tree once people are happy with the other elements.
> ---
> drivers/iio/adc/Kconfig | 7 ++
> drivers/iio/adc/Makefile | 1 +
> drivers/iio/adc/viperboard_adc.c | 181 ++++++++++++++++++++++++++++++++++++++
> drivers/mfd/viperboard.c | 3 +
> include/linux/mfd/viperboard.h | 1 +
> 5 files changed, 193 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..58345c7
> --- /dev/null
> +++ b/drivers/iio/adc/viperboard_adc.c
> @@ -0,0 +1,181 @@
> +/*
> + * Nano River Technologies viperboard iio ADC driver
IIO (told you it was a nitpick).
> + *
> + * (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 vprbrd_adc_msg {
> + u8 cmd;
> + u8 chan;
> + u8 val;
> +} __packed;
> +
> +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', \
> + .realbits = 8, \
> + .storagebits = 8, \
> + }, \
> +}
> +
> +static struct iio_chan_spec const 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 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;
> +
> + switch (info) {
> + case 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), VPRBRD_USB_REQUEST_ADC,
> + VPRBRD_USB_TYPE_OUT, 0x0000, 0x0000, admsg,
> + sizeof(struct vprbrd_adc_msg), VPRBRD_USB_TIMEOUT_MS);
> + 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), VPRBRD_USB_REQUEST_ADC,
> + VPRBRD_USB_TYPE_IN, 0x0000, 0x0000, admsg,
> + sizeof(struct vprbrd_adc_msg), VPRBRD_USB_TIMEOUT_MS);
> +
> + *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;
> + default:
> + error = -EINVAL;
> + break;
> + }
> +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 *indio_dev;
> + int ret;
> +
> + /* registering iio */
> + indio_dev = iio_device_alloc(sizeof(struct vprbrd_adc));
> + if (!indio_dev) {
> + dev_err(&pdev->dev, "failed allocating iio device\n");
> + return -ENOMEM;
> + }
> +
> + adc = iio_priv(indio_dev);
> + adc->vb = vb;
> + indio_dev->name = "viperboard adc";
> + indio_dev->dev.parent = &pdev->dev;
> + indio_dev->info = &vprbrd_adc_iio_info;
> + indio_dev->modes = INDIO_DIRECT_MODE;
> + indio_dev->channels = vprbrd_adc_iio_channels;
> + indio_dev->num_channels = ARRAY_SIZE(vprbrd_adc_iio_channels);
> +
> + ret = iio_device_register(indio_dev);
> + if (ret) {
> + dev_err(&pdev->dev, "could not register iio (adc)");
> + goto error;
> + }
> +
> + platform_set_drvdata(pdev, indio_dev);
> +
> + return 0;
> +
> +error:
> + iio_device_free(indio_dev);
> + return ret;
> +}
> +
> +static int __devexit vprbrd_adc_remove(struct platform_device *pdev)
> +{
> + struct iio_dev *indio_dev = platform_get_drvdata(pdev);
> +
> + iio_device_unregister(indio_dev);
> + iio_device_free(indio_dev);
> +
> + return 0;
> +}
> +
> +static struct platform_driver vprbrd_adc_driver = {
> + .driver = {
> + .name = "viperboard-adc",
> + .owner = THIS_MODULE,
> + },
> + .probe = vprbrd_adc_probe,
> + .remove = __devexit_p(vprbrd_adc_remove),
> +};
> +
> +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 a7b5b34..dacb3b7 100644
> --- a/drivers/mfd/viperboard.c
> +++ b/drivers/mfd/viperboard.c
> @@ -44,6 +44,9 @@ static struct mfd_cell vprbrd_devs[] = {
> {
> .name = "viperboard-i2c",
> },
> + {
> + .name = "viperboard-adc",
> + },
> };
>
> static int vprbrd_probe(struct usb_interface *interface,
> diff --git a/include/linux/mfd/viperboard.h b/include/linux/mfd/viperboard.h
> index ef78514..1934528 100644
> --- a/include/linux/mfd/viperboard.h
> +++ b/include/linux/mfd/viperboard.h
> @@ -46,6 +46,7 @@
> #define VPRBRD_USB_REQUEST_I2C 0xe9
> #define VPRBRD_USB_REQUEST_MAJOR 0xea
> #define VPRBRD_USB_REQUEST_MINOR 0xeb
> +#define VPRBRD_USB_REQUEST_ADC 0xec
> #define VPRBRD_USB_REQUEST_GPIOA 0xed
> #define VPRBRD_USB_REQUEST_GPIOB 0xdd
>
>

2012-11-06 08:24:02

by Linus Walleij

[permalink] [raw]
Subject: Re: [PATCH v3 3/5] gpio: add viperboard gpio driver

On Mon, Nov 5, 2012 at 3:48 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 I think we can maintain this.

Reviewed-by: Linus Walleij <[email protected]>

Please get Sam to merge this through his MFD tree.

Yours,
Linus Walleij

2012-11-19 15:35:45

by Lars Poeschel

[permalink] [raw]
Subject: [PATCH v4 4/5] i2c: add viperboard i2c master driver

As I got no feedback on the previous patch yet, I answer myself upcounting
the patch version. I had to change the setting of the bus frequency as
there was no usb capable memory used in patch v3
-- >8 --
>From 7a0759ee25a19f7f623543f491be5dee83f195a7 Mon Sep 17 00:00:00 2001
From: Lars Poeschel <[email protected]>
Date: Fri, 12 Oct 2012 14:12:23 +0200
Subject: [PATCH v4 4/5] i2c: add viperboard i2c master driver

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 | 480 +++++++++++++++++++++++++++++++++++
drivers/mfd/viperboard.c | 3 +
include/linux/mfd/viperboard.h | 2 +
5 files changed, 496 insertions(+)
create mode 100644 drivers/i2c/busses/i2c-viperboard.c

diff --git a/drivers/i2c/busses/Kconfig b/drivers/i2c/busses/Kconfig
index 65dd599..405a0fb 100644
--- a/drivers/i2c/busses/Kconfig
+++ b/drivers/i2c/busses/Kconfig
@@ -819,6 +819,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 2d33d62..7e8befd 100644
--- a/drivers/i2c/busses/Makefile
+++ b/drivers/i2c/busses/Makefile
@@ -79,6 +79,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..f5fa20d
--- /dev/null
+++ b/drivers/i2c/busses/i2c-viperboard.c
@@ -0,0 +1,480 @@
+/*
+ * 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;
+ u8 bus_freq_param;
+};
+
+/* i2c bus frequency module parameter */
+static u8 i2c_bus_param;
+static unsigned int i2c_bus_freq = 100;
+module_param(i2c_bus_freq, int, 0);
+MODULE_PARM_DESC(i2c_bus_freq,
+ "i2c bus frequency in khz (default is 100) valid values: 10, 100, 200, 400, 1000, 3000, 6000");
+
+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),
+ VPRBRD_USB_REQUEST_I2C, VPRBRD_USB_TYPE_IN, 0x0000, 0x0000,
+ status, bytes_xfer, VPRBRD_USB_TIMEOUT_MS);
+
+ 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,
+ VPRBRD_USB_TIMEOUT_MS);
+
+ 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, VPRBRD_USB_TIMEOUT_MS);
+
+ 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,
+ VPRBRD_USB_TIMEOUT_MS);
+
+ 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, VPRBRD_USB_TIMEOUT_MS);
+ 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;
+ /* save the param in usb capabable memory */
+ vb_i2c->bus_freq_param = i2c_bus_param;
+
+ 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_param <= VPRBRD_I2C_FREQ_10KHZ)
+ && (i2c_bus_param >= VPRBRD_I2C_FREQ_6MHZ)) {
+ pipe = usb_sndctrlpipe(vb->usb_dev, 0);
+ ret = usb_control_msg(vb->usb_dev, pipe,
+ VPRBRD_USB_REQUEST_I2C_FREQ, VPRBRD_USB_TYPE_OUT,
+ 0x0000, 0x0000, &vb_i2c->bus_freq_param, 1,
+ VPRBRD_USB_TIMEOUT_MS);
+ if (ret != 1) {
+ dev_err(&pdev->dev,
+ "failure setting i2c_bus_freq to %d\n", i2c_bus_freq);
+ ret = -EIO;
+ goto error;
+ }
+ } else {
+ dev_err(&pdev->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)
+{
+ switch (i2c_bus_freq) {
+ case 6000:
+ i2c_bus_param = VPRBRD_I2C_FREQ_6MHZ;
+ break;
+ case 3000:
+ i2c_bus_param = VPRBRD_I2C_FREQ_3MHZ;
+ break;
+ case 1000:
+ i2c_bus_param = VPRBRD_I2C_FREQ_1MHZ;
+ break;
+ case 400:
+ i2c_bus_param = VPRBRD_I2C_FREQ_400KHZ;
+ break;
+ case 200:
+ i2c_bus_param = VPRBRD_I2C_FREQ_200KHZ;
+ break;
+ case 100:
+ i2c_bus_param = VPRBRD_I2C_FREQ_100KHZ;
+ break;
+ case 10:
+ i2c_bus_param = VPRBRD_I2C_FREQ_10KHZ;
+ break;
+ default:
+ pr_warn("invalid i2c_bus_freq (%d)\n", i2c_bus_freq);
+ i2c_bus_param = VPRBRD_I2C_FREQ_100KHZ;
+ }
+
+ 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 4b2ffbf..a7b5b34 100644
--- a/drivers/mfd/viperboard.c
+++ b/drivers/mfd/viperboard.c
@@ -41,6 +41,9 @@ static struct mfd_cell vprbrd_devs[] = {
{
.name = "viperboard-gpio",
},
+ {
+ .name = "viperboard-i2c",
+ },
};

static int vprbrd_probe(struct usb_interface *interface,
diff --git a/include/linux/mfd/viperboard.h b/include/linux/mfd/viperboard.h
index 42d339f..ef78514 100644
--- a/include/linux/mfd/viperboard.h
+++ b/include/linux/mfd/viperboard.h
@@ -42,6 +42,8 @@
#define VPRBRD_USB_TYPE_OUT 0x40
#define VPRBRD_USB_TYPE_IN 0xc0
#define VPRBRD_USB_TIMEOUT_MS 100
+#define VPRBRD_USB_REQUEST_I2C_FREQ 0xe6
+#define VPRBRD_USB_REQUEST_I2C 0xe9
#define VPRBRD_USB_REQUEST_MAJOR 0xea
#define VPRBRD_USB_REQUEST_MINOR 0xeb
#define VPRBRD_USB_REQUEST_GPIOA 0xed
--
1.7.10.4

2012-11-19 17:30:44

by Samuel Ortiz

[permalink] [raw]
Subject: Re: [PATCH v3 2/5] mfd: add viperboard driver

Hi Lars,

On Mon, Nov 05, 2012 at 03:48:23PM +0100, Lars Poeschel wrote:
> 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 | 130 ++++++++++++++++++++++++++++++++++++++++
> include/linux/mfd/viperboard.h | 105 ++++++++++++++++++++++++++++++++
> 4 files changed, 250 insertions(+)
> create mode 100644 drivers/mfd/viperboard.c
> create mode 100644 include/linux/mfd/viperboard.h
This looks way better than your initial submission.
Patches 2,3,4 and 5 all applied. I would really appreciate to get an ACK from
the i2c folks for patch #4.
I received a similar patch from Charles Keepax for patch 1, and I applied the
above 4 patches on top of it.

Cheers,
Samuel.

--
Intel Open Source Technology Centre
http://oss.intel.com/

2012-11-20 08:35:11

by Wolfram Sang

[permalink] [raw]
Subject: Re: [PATCH v3 2/5] mfd: add viperboard driver


> Patches 2,3,4 and 5 all applied. I would really appreciate to get an ACK from
> the i2c folks for patch #4.

I'll try to have a look this week. It fell a bit off because linux-i2c
was not in CC. I do wonder about the naming, though. VIPERBOARD is
probably the board name, but not the IP core/SoC name?

--
Pengutronix e.K. | Wolfram Sang |
Industrial Linux Solutions | http://www.pengutronix.de/ |


Attachments:
(No filename) (460.00 B)
signature.asc (198.00 B)
Digital signature
Download all attachments

2012-11-20 09:43:55

by Lars Poeschel

[permalink] [raw]
Subject: Re: [PATCH v3 2/5] mfd: add viperboard driver

On Tuesday 20 November 2012 at 09:34:56, Wolfram Sang wrote:
> I'll try to have a look this week. It fell a bit off because linux-i2c
> was not in CC. I do wonder about the naming, though. VIPERBOARD is
> probably the board name, but not the IP core/SoC name?

I am sorry, that I forgot the CC.
You are right it is the board name but not a IP/SoC name. It seems this
device is weird to kernel developers - you are not the first one asking. You
don't have to see the term board as in kernel sense where it describes a
specific SoC and the components connected to it. It is a circuit board, that
connects to usb on one side and GPIO, I?C and so on on the other side. You
can have a look at it here:
http://nanorivertech.com/viperboard-specs.html