* [RFC 0/4] serdev GPIO-based multiplexing support
@ 2017-06-14 14:38 Ulrich Hecht
2017-06-14 14:38 ` [RFC 1/4] serdev: add method to set parity Ulrich Hecht
` (4 more replies)
0 siblings, 5 replies; 10+ messages in thread
From: Ulrich Hecht @ 2017-06-14 14:38 UTC (permalink / raw)
To: robh, linux-serial
Cc: linux-renesas-soc, magnus.damm, laurent.pinchart, wsa, linux-i2c,
Ulrich Hecht
Hi!
This is an attempt to add multiplexer support to serdev, specifically
GPIO-based multiplexing.
Our use case is the Renesas Blanche V2H board with several MAX9260 GMSL
deserializers attached to one serial port. A sample driver that implements
i2c passthrough over the GMSL link is part of this series. This device
wants to be talked to with even parity, so a patch implementing parity
control in serdev is included as well.
The board-specific part of this series depends on the "pinctrl: sh-pfc:
r8a7792: Add SCIF1 pin groups" patch.
Please tell me if this is a suitable way to implement this functionality
in serdev, or how to improve it. Thank you.
CU
Uli
Ulrich Hecht (4):
serdev: add method to set parity
serdev: add GPIO-based multiplexer support
max9260: add driver for i2c over GMSL passthrough
ARM: dts: blanche: add SCIF1 and MAX9260 deserializer
arch/arm/boot/dts/r8a7792-blanche.dts | 45 ++++++
drivers/media/i2c/Kconfig | 6 +
drivers/media/i2c/Makefile | 1 +
drivers/media/i2c/max9260.c | 294 ++++++++++++++++++++++++++++++++++
drivers/tty/serdev/Kconfig | 3 +
drivers/tty/serdev/Makefile | 1 +
drivers/tty/serdev/core.c | 55 ++++++-
drivers/tty/serdev/mux-gpio.c | 80 +++++++++
drivers/tty/serdev/serdev-ttyport.c | 17 ++
include/linux/serdev.h | 30 +++-
10 files changed, 528 insertions(+), 4 deletions(-)
create mode 100644 drivers/media/i2c/max9260.c
create mode 100644 drivers/tty/serdev/mux-gpio.c
--
2.7.4
^ permalink raw reply [flat|nested] 10+ messages in thread
* [RFC 1/4] serdev: add method to set parity
2017-06-14 14:38 [RFC 0/4] serdev GPIO-based multiplexing support Ulrich Hecht
@ 2017-06-14 14:38 ` Ulrich Hecht
2017-06-14 14:38 ` [RFC 2/4] serdev: add GPIO-based multiplexer support Ulrich Hecht
` (3 subsequent siblings)
4 siblings, 0 replies; 10+ messages in thread
From: Ulrich Hecht @ 2017-06-14 14:38 UTC (permalink / raw)
To: robh, linux-serial
Cc: linux-renesas-soc, magnus.damm, laurent.pinchart, wsa, linux-i2c,
Ulrich Hecht
Adds serdev_device_set_parity() and an implementation for ttyport.
Signed-off-by: Ulrich Hecht <ulrich.hecht+renesas@gmail.com>
---
drivers/tty/serdev/core.c | 12 ++++++++++++
drivers/tty/serdev/serdev-ttyport.c | 17 +++++++++++++++++
include/linux/serdev.h | 4 ++++
3 files changed, 33 insertions(+)
diff --git a/drivers/tty/serdev/core.c b/drivers/tty/serdev/core.c
index f71b473..1fbaa4c 100644
--- a/drivers/tty/serdev/core.c
+++ b/drivers/tty/serdev/core.c
@@ -242,6 +242,18 @@ int serdev_device_set_tiocm(struct serdev_device *serdev, int set, int clear)
}
EXPORT_SYMBOL_GPL(serdev_device_set_tiocm);
+int serdev_device_set_parity(struct serdev_device *serdev,
+ bool enable, bool odd)
+{
+ struct serdev_controller *ctrl = serdev->ctrl;
+
+ if (!ctrl || !ctrl->ops->set_parity)
+ return -ENOTSUPP;
+
+ return ctrl->ops->set_parity(ctrl, enable, odd);
+}
+EXPORT_SYMBOL_GPL(serdev_device_set_parity);
+
static int serdev_drv_probe(struct device *dev)
{
const struct serdev_device_driver *sdrv = to_serdev_device_driver(dev->driver);
diff --git a/drivers/tty/serdev/serdev-ttyport.c b/drivers/tty/serdev/serdev-ttyport.c
index 302018d..9114956 100644
--- a/drivers/tty/serdev/serdev-ttyport.c
+++ b/drivers/tty/serdev/serdev-ttyport.c
@@ -195,6 +195,22 @@ static int ttyport_set_tiocm(struct serdev_controller *ctrl, unsigned int set, u
return tty->driver->ops->tiocmset(tty, set, clear);
}
+static int ttyport_set_parity(struct serdev_controller *ctrl,
+ bool enable, bool odd)
+{
+ struct serport *serport = serdev_controller_get_drvdata(ctrl);
+ struct tty_struct *tty = serport->tty;
+ struct ktermios ktermios = tty->termios;
+
+ ktermios.c_cflag &= ~(PARENB | PARODD);
+ if (enable)
+ ktermios.c_cflag |= PARENB;
+ if (odd)
+ ktermios.c_cflag |= PARODD;
+
+ return tty_set_termios(tty, &ktermios);
+}
+
static const struct serdev_controller_ops ctrl_ops = {
.write_buf = ttyport_write_buf,
.write_flush = ttyport_write_flush,
@@ -206,6 +222,7 @@ static const struct serdev_controller_ops ctrl_ops = {
.wait_until_sent = ttyport_wait_until_sent,
.get_tiocm = ttyport_get_tiocm,
.set_tiocm = ttyport_set_tiocm,
+ .set_parity = ttyport_set_parity,
};
struct device *serdev_tty_port_register(struct tty_port *port,
diff --git a/include/linux/serdev.h b/include/linux/serdev.h
index e69402d..8b67fcd 100644
--- a/include/linux/serdev.h
+++ b/include/linux/serdev.h
@@ -90,6 +90,7 @@ struct serdev_controller_ops {
void (*wait_until_sent)(struct serdev_controller *, long);
int (*get_tiocm)(struct serdev_controller *);
int (*set_tiocm)(struct serdev_controller *, unsigned int, unsigned int);
+ int (*set_parity)(struct serdev_controller *, bool, bool);
};
/**
@@ -298,6 +299,9 @@ static inline int serdev_device_set_rts(struct serdev_device *serdev, bool enabl
return serdev_device_set_tiocm(serdev, 0, TIOCM_RTS);
}
+int serdev_device_set_parity(struct serdev_device *serdev,
+ bool enable, bool odd);
+
/*
* serdev hooks into TTY core
*/
--
2.7.4
^ permalink raw reply related [flat|nested] 10+ messages in thread
* [RFC 2/4] serdev: add GPIO-based multiplexer support
2017-06-14 14:38 [RFC 0/4] serdev GPIO-based multiplexing support Ulrich Hecht
2017-06-14 14:38 ` [RFC 1/4] serdev: add method to set parity Ulrich Hecht
@ 2017-06-14 14:38 ` Ulrich Hecht
2017-06-15 9:34 ` Geert Uytterhoeven
2017-06-14 14:38 ` [RFC 3/4] max9260: add driver for i2c over GMSL passthrough Ulrich Hecht
` (2 subsequent siblings)
4 siblings, 1 reply; 10+ messages in thread
From: Ulrich Hecht @ 2017-06-14 14:38 UTC (permalink / raw)
To: robh, linux-serial
Cc: linux-renesas-soc, magnus.damm, laurent.pinchart, wsa, linux-i2c,
Ulrich Hecht
Adds an interface for slave device multiplexing, and an implementation
for GPIO-based multiplexers.
Signed-off-by: Ulrich Hecht <ulrich.hecht+renesas@gmail.com>
---
drivers/tty/serdev/Kconfig | 3 ++
drivers/tty/serdev/Makefile | 1 +
drivers/tty/serdev/core.c | 43 ++++++++++++++++++++++-
drivers/tty/serdev/mux-gpio.c | 80 +++++++++++++++++++++++++++++++++++++++++++
include/linux/serdev.h | 26 ++++++++++++--
5 files changed, 149 insertions(+), 4 deletions(-)
create mode 100644 drivers/tty/serdev/mux-gpio.c
diff --git a/drivers/tty/serdev/Kconfig b/drivers/tty/serdev/Kconfig
index cdc6b82..7946eeb 100644
--- a/drivers/tty/serdev/Kconfig
+++ b/drivers/tty/serdev/Kconfig
@@ -13,4 +13,7 @@ config SERIAL_DEV_CTRL_TTYPORT
depends on TTY
depends on SERIAL_DEV_BUS != m
+config SERIAL_DEV_MUX_GPIO
+ bool "Serial device GPIO multiplexer"
+
endif
diff --git a/drivers/tty/serdev/Makefile b/drivers/tty/serdev/Makefile
index 0cbdb94..08a90fa 100644
--- a/drivers/tty/serdev/Makefile
+++ b/drivers/tty/serdev/Makefile
@@ -1,5 +1,6 @@
serdev-objs := core.o
obj-$(CONFIG_SERIAL_DEV_BUS) += serdev.o
+obj-$(CONFIG_SERIAL_DEV_MUX_GPIO) += mux-gpio.o
obj-$(CONFIG_SERIAL_DEV_CTRL_TTYPORT) += serdev-ttyport.o
diff --git a/drivers/tty/serdev/core.c b/drivers/tty/serdev/core.c
index 1fbaa4c..9a2c76b 100644
--- a/drivers/tty/serdev/core.c
+++ b/drivers/tty/serdev/core.c
@@ -305,7 +305,8 @@ struct serdev_device *serdev_device_alloc(struct serdev_controller *ctrl)
return NULL;
serdev->ctrl = ctrl;
- ctrl->serdev = serdev;
+ if (!ctrl->serdev)
+ ctrl->serdev = serdev;
device_initialize(&serdev->dev);
serdev->dev.parent = &ctrl->dev;
serdev->dev.bus = &serdev_bus_type;
@@ -368,6 +369,8 @@ static int of_serdev_register_devices(struct serdev_controller *ctrl)
struct serdev_device *serdev = NULL;
int err;
bool found = false;
+ int nr = 0;
+ u32 reg;
for_each_available_child_of_node(ctrl->dev.of_node, node) {
if (!of_get_property(node, "compatible", NULL))
@@ -380,6 +383,10 @@ static int of_serdev_register_devices(struct serdev_controller *ctrl)
continue;
serdev->dev.of_node = node;
+ serdev->nr = nr++;
+
+ if (!of_property_read_u32(node, "reg", ®))
+ serdev->mux_addr = reg;
err = serdev_device_add(serdev);
if (err) {
@@ -395,6 +402,36 @@ static int of_serdev_register_devices(struct serdev_controller *ctrl)
return 0;
}
+int serdev_device_mux_select(struct serdev_device *serdev)
+{
+ struct serdev_mux *mux = serdev->ctrl->mux;
+
+ if (!mux || !mux->ops || !mux->ops->select)
+ return -EINVAL;
+
+ rt_mutex_lock(&mux->mux_lock);
+
+ mux->ops->select(serdev);
+ serdev->ctrl->serdev = serdev;
+
+ return 0;
+}
+
+int serdev_device_mux_deselect(struct serdev_device *serdev)
+{
+ struct serdev_mux *mux = serdev->ctrl->mux;
+
+ if (!mux || serdev->ctrl->serdev != serdev)
+ return -EINVAL;
+
+ if (mux->ops->deselect)
+ mux->ops->deselect(serdev);
+
+ rt_mutex_unlock(&mux->mux_lock);
+
+ return 0;
+}
+
/**
* serdev_controller_add() - Add an serdev controller
* @ctrl: controller to be registered.
@@ -414,6 +451,10 @@ int serdev_controller_add(struct serdev_controller *ctrl)
if (ret)
return ret;
+#ifdef CONFIG_SERIAL_DEV_MUX_GPIO
+ of_serdev_register_gpio_mux(ctrl);
+#endif
+
ret = of_serdev_register_devices(ctrl);
if (ret)
goto out_dev_del;
diff --git a/drivers/tty/serdev/mux-gpio.c b/drivers/tty/serdev/mux-gpio.c
new file mode 100644
index 0000000..5bedff1
--- /dev/null
+++ b/drivers/tty/serdev/mux-gpio.c
@@ -0,0 +1,80 @@
+/*
+ * Copyright (C) 2017 Ulrich Hecht
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License version 2 and
+ * only version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ */
+
+#include <linux/of_gpio.h>
+#include <linux/serdev.h>
+#include <linux/slab.h>
+
+static int serdev_device_mux_select_gpio(struct serdev_device *serdev)
+{
+ int i;
+ u32 addr;
+ struct serdev_mux *mux = serdev->ctrl->mux;
+
+ addr = serdev->mux_addr;
+ for (i = 0; i < mux->ngpios; ++i, addr >>= 1) {
+ gpio_request_one(mux->gpios[i], GPIOF_DIR_OUT |
+ (addr & 1) ? GPIOF_INIT_HIGH : GPIOF_INIT_LOW,
+ "mux-enable-gpio");
+ }
+
+ return 0;
+}
+
+static int serdev_device_mux_deselect_gpio(struct serdev_device *serdev)
+{
+ int i;
+ struct serdev_mux *mux = serdev->ctrl->mux;
+
+ for (i = 0; i < mux->ngpios; ++i)
+ gpio_free(mux->gpios[i]);
+
+ return 0;
+}
+
+static const struct serdev_mux_ops gpio_mux_ops = {
+ .select = serdev_device_mux_select_gpio,
+ .deselect = serdev_device_mux_deselect_gpio,
+};
+
+int of_serdev_register_gpio_mux(struct serdev_controller *ctrl)
+{
+ int i, ngpios;
+ struct serdev_mux *mux;
+ struct device_node *np = ctrl->dev.of_node;
+
+ ngpios = of_gpio_named_count(np, "mux-select-gpios");
+ if (ngpios <= 0)
+ return -ENODEV;
+
+ mux = kzalloc(sizeof(*mux), GFP_KERNEL);
+ if (!mux)
+ return -ENOMEM;
+
+ rt_mutex_init(&mux->mux_lock);
+ mux->ops = &gpio_mux_ops;
+
+ mux->ngpios = ngpios;
+
+ mux->gpios = kcalloc(ngpios, sizeof(int), GFP_KERNEL);
+ if (!mux->gpios)
+ return -ENOMEM;
+
+ for (i = 0; i < ngpios; ++i)
+ mux->gpios[i] = of_get_named_gpio(np, "mux-select-gpios", i);
+
+ ctrl->mux = mux;
+
+ return 0;
+}
+
diff --git a/include/linux/serdev.h b/include/linux/serdev.h
index 8b67fcd..e86a0ad 100644
--- a/include/linux/serdev.h
+++ b/include/linux/serdev.h
@@ -17,6 +17,7 @@
#include <linux/device.h>
#include <linux/termios.h>
#include <linux/delay.h>
+#include <linux/rtmutex.h>
struct serdev_controller;
struct serdev_device;
@@ -51,6 +52,7 @@ struct serdev_device {
const struct serdev_device_ops *ops;
struct completion write_comp;
struct mutex write_lock;
+ int mux_addr;
};
static inline struct serdev_device *to_serdev_device(struct device *d)
@@ -76,6 +78,20 @@ static inline struct serdev_device_driver *to_serdev_device_driver(struct device
return container_of(d, struct serdev_device_driver, driver);
}
+struct serdev_mux_ops {
+ int (*select)(struct serdev_device *);
+ int (*deselect)(struct serdev_device *);
+};
+
+struct serdev_mux {
+ int ngpios;
+ int *gpios;
+ struct rt_mutex mux_lock;
+ const struct serdev_mux_ops *ops;
+};
+
+int of_serdev_register_gpio_mux(struct serdev_controller *ctrl);
+
/*
* serdev controller structures
*/
@@ -97,14 +113,16 @@ struct serdev_controller_ops {
* struct serdev_controller - interface to the serdev controller
* @dev: Driver model representation of the device.
* @nr: number identifier for this controller/bus.
- * @serdev: Pointer to slave device for this controller.
+ * @serdev: Pointer to active slave device for this controller.
* @ops: Controller operations.
+ * @mux: Slave multiplexer.
*/
struct serdev_controller {
struct device dev;
unsigned int nr;
struct serdev_device *serdev;
const struct serdev_controller_ops *ops;
+ struct serdev_mux *mux;
};
static inline struct serdev_controller *to_serdev_controller(struct device *d)
@@ -172,7 +190,7 @@ static inline void serdev_controller_write_wakeup(struct serdev_controller *ctrl
{
struct serdev_device *serdev = ctrl->serdev;
- if (!serdev || !serdev->ops->write_wakeup)
+ if (!serdev || !serdev->ops || !serdev->ops->write_wakeup)
return;
serdev->ops->write_wakeup(serdev);
@@ -184,7 +202,7 @@ static inline int serdev_controller_receive_buf(struct serdev_controller *ctrl,
{
struct serdev_device *serdev = ctrl->serdev;
- if (!serdev || !serdev->ops->receive_buf)
+ if (!serdev || !serdev->ops || !serdev->ops->receive_buf)
return -EINVAL;
return serdev->ops->receive_buf(serdev, data, count);
@@ -204,6 +222,8 @@ void serdev_device_write_wakeup(struct serdev_device *);
int serdev_device_write(struct serdev_device *, const unsigned char *, size_t, unsigned long);
void serdev_device_write_flush(struct serdev_device *);
int serdev_device_write_room(struct serdev_device *);
+int serdev_device_mux_select(struct serdev_device *);
+int serdev_device_mux_deselect(struct serdev_device *);
/*
* serdev device driver functions
--
2.7.4
^ permalink raw reply related [flat|nested] 10+ messages in thread
* [RFC 3/4] max9260: add driver for i2c over GMSL passthrough
2017-06-14 14:38 [RFC 0/4] serdev GPIO-based multiplexing support Ulrich Hecht
2017-06-14 14:38 ` [RFC 1/4] serdev: add method to set parity Ulrich Hecht
2017-06-14 14:38 ` [RFC 2/4] serdev: add GPIO-based multiplexer support Ulrich Hecht
@ 2017-06-14 14:38 ` Ulrich Hecht
2017-06-15 7:09 ` Peter Rosin
2017-06-15 15:37 ` Wolfram Sang
2017-06-14 14:38 ` [RFC 4/4] ARM: dts: blanche: add SCIF1 and MAX9260 deserializer Ulrich Hecht
2017-06-15 7:07 ` [RFC 0/4] serdev GPIO-based multiplexing support Peter Rosin
4 siblings, 2 replies; 10+ messages in thread
From: Ulrich Hecht @ 2017-06-14 14:38 UTC (permalink / raw)
To: robh, linux-serial
Cc: linux-renesas-soc, magnus.damm, laurent.pinchart, wsa, linux-i2c,
Ulrich Hecht
This driver implements tunnelling of i2c requests over GMSL via a
MAX9260 deserializer. It provides an i2c adapter that can be used
to reach devices on the far side of the link.
Signed-off-by: Ulrich Hecht <ulrich.hecht+renesas@gmail.com>
---
drivers/media/i2c/Kconfig | 6 +
drivers/media/i2c/Makefile | 1 +
drivers/media/i2c/max9260.c | 294 ++++++++++++++++++++++++++++++++++++++++++++
3 files changed, 301 insertions(+)
create mode 100644 drivers/media/i2c/max9260.c
diff --git a/drivers/media/i2c/Kconfig b/drivers/media/i2c/Kconfig
index 7c23b7a..743f8ee 100644
--- a/drivers/media/i2c/Kconfig
+++ b/drivers/media/i2c/Kconfig
@@ -400,6 +400,12 @@ config VIDEO_VPX3220
To compile this driver as a module, choose M here: the
module will be called vpx3220.
+config VIDEO_MAX9260
+ tristate "Maxim MAX9260 GMSL deserializer support"
+ depends on I2C
+ ---help---
+ This driver supports the Maxim MAX9260 GMSL deserializer.
+
comment "Video and audio decoders"
config VIDEO_SAA717X
diff --git a/drivers/media/i2c/Makefile b/drivers/media/i2c/Makefile
index 62323ec..9b2fd13 100644
--- a/drivers/media/i2c/Makefile
+++ b/drivers/media/i2c/Makefile
@@ -86,3 +86,4 @@ obj-$(CONFIG_VIDEO_IR_I2C) += ir-kbd-i2c.o
obj-$(CONFIG_VIDEO_ML86V7667) += ml86v7667.o
obj-$(CONFIG_VIDEO_OV2659) += ov2659.o
obj-$(CONFIG_VIDEO_TC358743) += tc358743.o
+obj-$(CONFIG_VIDEO_MAX9260) += max9260.o
diff --git a/drivers/media/i2c/max9260.c b/drivers/media/i2c/max9260.c
new file mode 100644
index 0000000..2030eb0
--- /dev/null
+++ b/drivers/media/i2c/max9260.c
@@ -0,0 +1,294 @@
+/*
+ * Maxim MAX9260 GMSL Deserializer Driver
+ *
+ * Copyright (C) 2017 Ulrich Hecht
+ *
+ * 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/device.h>
+#include <linux/i2c.h>
+#include <linux/module.h>
+#include <linux/of.h>
+#include <linux/of_gpio.h>
+#include <linux/serdev.h>
+#include <linux/slab.h>
+#include <linux/tty.h>
+
+#define SYNC 0x79
+#define ACK 0xc3
+
+#define RX_FINISHED 0
+#define RX_FRAME_ERROR 1
+#define RX_EXPECT_ACK 2
+#define RX_EXPECT_ACK_DATA 3
+#define RX_EXPECT_DATA 4
+
+struct max9260_device {
+ struct serdev_device *serdev;
+ u8 *rx_buf;
+ int rx_len;
+ int rx_state;
+ wait_queue_head_t rx_wq;
+ struct i2c_adapter adap;
+};
+
+static void wait_for_transaction(struct max9260_device *dev)
+{
+ wait_event_interruptible_timeout(dev->rx_wq,
+ dev->rx_state <= RX_FRAME_ERROR,
+ HZ/2);
+}
+
+static void transact(struct max9260_device *dev,
+ int expect,
+ u8 *request, int len)
+{
+ serdev_device_mux_select(dev->serdev);
+
+ serdev_device_set_baudrate(dev->serdev, 115200);
+ serdev_device_set_parity(dev->serdev, 1, 0);
+
+ dev->rx_state = expect;
+ serdev_device_write_buf(dev->serdev, request, len);
+
+ wait_for_transaction(dev);
+
+ serdev_device_mux_deselect(dev->serdev);
+}
+
+static int max9260_read_reg(struct max9260_device *dev, int reg)
+{
+ u8 request[] = { 0x79, 0x91, reg, 1 };
+ u8 rx;
+
+ dev->rx_len = 1;
+ dev->rx_buf = ℞
+
+ transact(dev, RX_EXPECT_ACK_DATA, request, 4);
+
+ if (dev->rx_state == RX_FINISHED)
+ return rx;
+
+ return -1;
+}
+
+static int max9260_setup(struct max9260_device *dev)
+{
+ int ret;
+
+ ret = max9260_read_reg(dev, 0x1e);
+
+ if (ret != 0x02) {
+ dev_err(&dev->serdev->dev,
+ "device does not identify as MAX9260\n");
+ return -EINVAL;
+ }
+
+ return 0;
+}
+
+static void max9260_uart_write_wakeup(struct serdev_device *serdev)
+{
+}
+
+static int max9260_uart_receive_buf(struct serdev_device *serdev,
+ const u8 *data, size_t count)
+{
+ struct max9260_device *dev = serdev_device_get_drvdata(serdev);
+ int accepted;
+
+ switch (dev->rx_state) {
+ case RX_FINISHED:
+ dev_dbg(&dev->serdev->dev, "excess data ignored\n");
+ return count;
+
+ case RX_EXPECT_ACK:
+ case RX_EXPECT_ACK_DATA:
+ if (data[0] != ACK) {
+ dev_dbg(&dev->serdev->dev, "frame error");
+ dev->rx_state = RX_FRAME_ERROR;
+ wake_up_interruptible(&dev->rx_wq);
+ return 1;
+ }
+ switch (dev->rx_state) {
+ case RX_EXPECT_ACK_DATA:
+ dev->rx_state = RX_EXPECT_DATA;
+ break;
+ case RX_EXPECT_ACK:
+ dev->rx_state = RX_FINISHED;
+ wake_up_interruptible(&dev->rx_wq);
+ break;
+ }
+ return 1;
+
+ case RX_EXPECT_DATA:
+ accepted = dev->rx_len < count ? dev->rx_len : count;
+
+ memcpy(dev->rx_buf, data, accepted);
+
+ dev->rx_len -= accepted;
+ dev->rx_buf += accepted;
+
+ if (!dev->rx_len) {
+ dev->rx_state = RX_FINISHED;
+ wake_up_interruptible(&dev->rx_wq);
+ }
+
+ return accepted;
+
+ case RX_FRAME_ERROR:
+ dev_dbg(&dev->serdev->dev, "%d bytes ignored\n", count);
+ return count;
+
+ }
+ return 0;
+}
+
+struct serdev_device_ops max9260_serdev_client_ops = {
+ .receive_buf = max9260_uart_receive_buf,
+ .write_wakeup = max9260_uart_write_wakeup,
+};
+
+static u32 max9260_i2c_func(struct i2c_adapter *adapter)
+{
+ return I2C_FUNC_SMBUS_EMUL;
+}
+
+static s32 max9260_smbus_xfer(struct i2c_adapter *adap, u16 addr,
+ unsigned short flags, char read_write, u8 command, int size,
+ union i2c_smbus_data *data)
+{
+ u8 request[] = { SYNC,
+ (addr << 1) + (read_write == I2C_SMBUS_READ),
+ command, 0, 0 };
+ struct max9260_device *dev = i2c_get_adapdata(adap);
+
+ switch (size) {
+ case I2C_SMBUS_BYTE:
+ if (read_write == I2C_SMBUS_WRITE) {
+ transact(dev, RX_EXPECT_ACK, request, 4);
+ dev_dbg(&adap->dev,
+ "smbus byte - addr 0x%02x, wrote 0x%02x.\n",
+ addr, command);
+ } else {
+ /* TBD */
+ return -EOPNOTSUPP;
+ }
+ break;
+
+ case I2C_SMBUS_BYTE_DATA:
+ request[3] = 1;
+ if (read_write == I2C_SMBUS_WRITE) {
+ request[4] = data->byte;
+ transact(dev, RX_EXPECT_ACK, request, 5);
+ dev_dbg(&adap->dev,
+ "smbus byte data - addr 0x%02x, wrote 0x%02x at 0x%02x.\n",
+ addr, data->byte, command);
+ } else {
+ dev->rx_len = 1;
+ dev->rx_buf = &data->byte;
+ transact(dev, RX_EXPECT_ACK_DATA, request, 4);
+ dev_dbg(&adap->dev,
+ "smbus byte data - addr 0x%02x, read 0x%02x at 0x%02x.\n",
+ addr, data->byte, command);
+ }
+ break;
+ default:
+ dev_dbg(&adap->dev,
+ "Unsupported I2C/SMBus command %d\n", size);
+ return -EOPNOTSUPP;
+ }
+
+ if (dev->rx_state != RX_FINISHED) {
+ dev_dbg(&adap->dev, "xfer timed out\n");
+ return -EIO;
+ }
+
+ return 0;
+}
+
+static const struct i2c_algorithm max9260_i2c_algorithm = {
+ .functionality = max9260_i2c_func,
+ .smbus_xfer = max9260_smbus_xfer,
+};
+
+static int max9260_probe(struct serdev_device *serdev)
+{
+ struct max9260_device *dev;
+ struct i2c_adapter *adap;
+ int ret;
+
+ dev = kzalloc(sizeof(*dev), GFP_KERNEL);
+ if (!dev)
+ return -ENOMEM;
+
+ init_waitqueue_head(&dev->rx_wq);
+
+ dev->serdev = serdev;
+ serdev_device_open(serdev);
+ serdev_device_set_drvdata(serdev, dev);
+
+ serdev_device_set_client_ops(serdev, &max9260_serdev_client_ops);
+
+ ret = max9260_setup(dev);
+
+ if (ret < 0)
+ goto err_free;
+
+ adap = &dev->adap;
+ i2c_set_adapdata(adap, dev);
+
+ adap->owner = THIS_MODULE;
+ adap->algo = &max9260_i2c_algorithm;
+ adap->dev.parent = &serdev->dev;
+ adap->retries = 5;
+ adap->nr = -1;
+ strlcpy(adap->name, dev_name(&serdev->dev), sizeof(adap->name));
+
+ ret = i2c_add_numbered_adapter(adap);
+ if (ret < 0) {
+ dev_err(&serdev->dev, "failed to register i2c adapter\n");
+ return ret;
+ }
+
+ return 0;
+
+err_free:
+ kfree(dev);
+ return ret;
+}
+
+static void max9260_remove(struct serdev_device *serdev)
+{
+ struct max9260_device *dev = serdev_device_get_drvdata(serdev);
+
+ serdev_device_close(dev->serdev);
+
+ kfree(dev);
+}
+
+static const struct of_device_id max9260_dt_ids[] = {
+ { .compatible = "maxim,max9260" },
+ {},
+};
+
+MODULE_DEVICE_TABLE(of, max9260_dt_ids);
+
+static struct serdev_device_driver max9260_driver = {
+ .probe = max9260_probe,
+ .remove = max9260_remove,
+ .driver = {
+ .name = "max9260",
+ .of_match_table = of_match_ptr(max9260_dt_ids),
+ },
+};
+
+module_serdev_device_driver(max9260_driver);
+
+MODULE_DESCRIPTION("Maxim MAX9260 GMSL Deserializer Driver");
+MODULE_AUTHOR("Ulrich Hecht");
+MODULE_LICENSE("GPL");
--
2.7.4
^ permalink raw reply related [flat|nested] 10+ messages in thread
* [RFC 4/4] ARM: dts: blanche: add SCIF1 and MAX9260 deserializer
2017-06-14 14:38 [RFC 0/4] serdev GPIO-based multiplexing support Ulrich Hecht
` (2 preceding siblings ...)
2017-06-14 14:38 ` [RFC 3/4] max9260: add driver for i2c over GMSL passthrough Ulrich Hecht
@ 2017-06-14 14:38 ` Ulrich Hecht
2017-06-15 13:05 ` Rob Herring
2017-06-15 7:07 ` [RFC 0/4] serdev GPIO-based multiplexing support Peter Rosin
4 siblings, 1 reply; 10+ messages in thread
From: Ulrich Hecht @ 2017-06-14 14:38 UTC (permalink / raw)
To: robh, linux-serial
Cc: linux-renesas-soc, magnus.damm, laurent.pinchart, wsa, linux-i2c,
Ulrich Hecht
Adds serial port SCIF1 and the MAX9260 deserializers connected to it.
Signed-off-by: Ulrich Hecht <ulrich.hecht+renesas@gmail.com>
---
arch/arm/boot/dts/r8a7792-blanche.dts | 45 +++++++++++++++++++++++++++++++++++
1 file changed, 45 insertions(+)
diff --git a/arch/arm/boot/dts/r8a7792-blanche.dts b/arch/arm/boot/dts/r8a7792-blanche.dts
index 9b67dca..281484d 100644
--- a/arch/arm/boot/dts/r8a7792-blanche.dts
+++ b/arch/arm/boot/dts/r8a7792-blanche.dts
@@ -21,6 +21,7 @@
aliases {
serial0 = &scif0;
serial1 = &scif3;
+ serial2 = &scif1;
};
chosen {
@@ -202,6 +203,11 @@
function = "scif0";
};
+ scif1_pins: scif1 {
+ groups = "scif1_data";
+ function = "scif1";
+ };
+
scif3_pins: scif3 {
groups = "scif3_data";
function = "scif3";
@@ -246,6 +252,45 @@
status = "okay";
};
+&scif1 {
+ pinctrl-0 = <&scif1_pins>;
+ pinctrl-names = "default";
+
+ status = "okay";
+
+ mux-select-gpios = <&gpio5 12 GPIO_ACTIVE_LOW>,
+ <&gpio5 13 GPIO_ACTIVE_LOW>,
+ <&gpio5 14 GPIO_ACTIVE_LOW>,
+ <&gpio5 15 GPIO_ACTIVE_LOW>;
+
+ #address-cells = <1>;
+ #size-cells = <0>;
+ gmsl-deserializer@0 {
+ compatible = "maxim,max9260";
+ reg = <0x8>;
+ };
+ gmsl-deserializer@1 {
+ compatible = "maxim,max9260";
+ reg = <0x9>;
+ };
+ gmsl-deserializer@2 {
+ compatible = "maxim,max9260";
+ reg = <0xa>;
+ };
+ gmsl-deserializer@3 {
+ compatible = "maxim,max9260";
+ reg = <0xb>;
+ };
+ gmsl-deserializer@4 {
+ compatible = "maxim,max9260";
+ reg = <0x4>;
+ };
+ gmsl-deserializer@5 {
+ compatible = "maxim,max9260";
+ reg = <0x5>;
+ };
+};
+
&scif3 {
pinctrl-0 = <&scif3_pins>;
pinctrl-names = "default";
--
2.7.4
^ permalink raw reply related [flat|nested] 10+ messages in thread
* Re: [RFC 0/4] serdev GPIO-based multiplexing support
2017-06-14 14:38 [RFC 0/4] serdev GPIO-based multiplexing support Ulrich Hecht
` (3 preceding siblings ...)
2017-06-14 14:38 ` [RFC 4/4] ARM: dts: blanche: add SCIF1 and MAX9260 deserializer Ulrich Hecht
@ 2017-06-15 7:07 ` Peter Rosin
4 siblings, 0 replies; 10+ messages in thread
From: Peter Rosin @ 2017-06-15 7:07 UTC (permalink / raw)
To: Ulrich Hecht, robh, linux-serial
Cc: linux-renesas-soc, magnus.damm, laurent.pinchart, wsa, linux-i2c
On 2017-06-14 16:38, Ulrich Hecht wrote:
> Hi!
>
> This is an attempt to add multiplexer support to serdev, specifically
> GPIO-based multiplexing.
>
> Our use case is the Renesas Blanche V2H board with several MAX9260 GMSL
> deserializers attached to one serial port. A sample driver that implements
> i2c passthrough over the GMSL link is part of this series. This device
> wants to be talked to with even parity, so a patch implementing parity
> control in serdev is included as well.
>
> The board-specific part of this series depends on the "pinctrl: sh-pfc:
> r8a7792: Add SCIF1 pin groups" patch.
>
> Please tell me if this is a suitable way to implement this functionality
> in serdev, or how to improve it. Thank you.
When I look at patch 2/4, I can't help but think that you should perhaps
consider the new mux framework available in linux-next [1]. But as the
author of that, I'm maybe biased...
You then support other means of controlling the mux automatically (i.e.
you get free support for non-gpio muxes). You also get support for
sharing the mux controller should the same gpio pins control muxes
for unrelated functions (which happened for my hw).
However, I see that you request the gpios when you select the mux, and
free them when you deselect it. That is not how the gpio mux in the
mux framework operates; it instead keeps the gpios requested and either
leaves the gpios as-is on deselect or sets a specific idle value. But
that is perhaps ok for this use-case too?
Cheers,
peda
[1] https://lkml.org/lkml/2017/5/14/160
> CU
> Uli
>
>
> Ulrich Hecht (4):
> serdev: add method to set parity
> serdev: add GPIO-based multiplexer support
> max9260: add driver for i2c over GMSL passthrough
> ARM: dts: blanche: add SCIF1 and MAX9260 deserializer
>
> arch/arm/boot/dts/r8a7792-blanche.dts | 45 ++++++
> drivers/media/i2c/Kconfig | 6 +
> drivers/media/i2c/Makefile | 1 +
> drivers/media/i2c/max9260.c | 294 ++++++++++++++++++++++++++++++++++
> drivers/tty/serdev/Kconfig | 3 +
> drivers/tty/serdev/Makefile | 1 +
> drivers/tty/serdev/core.c | 55 ++++++-
> drivers/tty/serdev/mux-gpio.c | 80 +++++++++
> drivers/tty/serdev/serdev-ttyport.c | 17 ++
> include/linux/serdev.h | 30 +++-
> 10 files changed, 528 insertions(+), 4 deletions(-)
> create mode 100644 drivers/media/i2c/max9260.c
> create mode 100644 drivers/tty/serdev/mux-gpio.c
>
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [RFC 3/4] max9260: add driver for i2c over GMSL passthrough
2017-06-14 14:38 ` [RFC 3/4] max9260: add driver for i2c over GMSL passthrough Ulrich Hecht
@ 2017-06-15 7:09 ` Peter Rosin
2017-06-15 15:37 ` Wolfram Sang
1 sibling, 0 replies; 10+ messages in thread
From: Peter Rosin @ 2017-06-15 7:09 UTC (permalink / raw)
To: Ulrich Hecht, robh, linux-serial
Cc: linux-renesas-soc, magnus.damm, laurent.pinchart, wsa, linux-i2c
On 2017-06-14 16:38, Ulrich Hecht wrote:
> This driver implements tunnelling of i2c requests over GMSL via a
> MAX9260 deserializer. It provides an i2c adapter that can be used
> to reach devices on the far side of the link.
>
> Signed-off-by: Ulrich Hecht <ulrich.hecht+renesas@gmail.com>
> ---
> drivers/media/i2c/Kconfig | 6 +
> drivers/media/i2c/Makefile | 1 +
> drivers/media/i2c/max9260.c | 294 ++++++++++++++++++++++++++++++++++++++++++++
> 3 files changed, 301 insertions(+)
> create mode 100644 drivers/media/i2c/max9260.c
>
> diff --git a/drivers/media/i2c/Kconfig b/drivers/media/i2c/Kconfig
> index 7c23b7a..743f8ee 100644
> --- a/drivers/media/i2c/Kconfig
> +++ b/drivers/media/i2c/Kconfig
> @@ -400,6 +400,12 @@ config VIDEO_VPX3220
> To compile this driver as a module, choose M here: the
> module will be called vpx3220.
>
> +config VIDEO_MAX9260
> + tristate "Maxim MAX9260 GMSL deserializer support"
> + depends on I2C
> + ---help---
> + This driver supports the Maxim MAX9260 GMSL deserializer.
> +
> comment "Video and audio decoders"
>
> config VIDEO_SAA717X
> diff --git a/drivers/media/i2c/Makefile b/drivers/media/i2c/Makefile
> index 62323ec..9b2fd13 100644
> --- a/drivers/media/i2c/Makefile
> +++ b/drivers/media/i2c/Makefile
> @@ -86,3 +86,4 @@ obj-$(CONFIG_VIDEO_IR_I2C) += ir-kbd-i2c.o
> obj-$(CONFIG_VIDEO_ML86V7667) += ml86v7667.o
> obj-$(CONFIG_VIDEO_OV2659) += ov2659.o
> obj-$(CONFIG_VIDEO_TC358743) += tc358743.o
> +obj-$(CONFIG_VIDEO_MAX9260) += max9260.o
> diff --git a/drivers/media/i2c/max9260.c b/drivers/media/i2c/max9260.c
> new file mode 100644
> index 0000000..2030eb0
> --- /dev/null
> +++ b/drivers/media/i2c/max9260.c
> @@ -0,0 +1,294 @@
> +/*
> + * Maxim MAX9260 GMSL Deserializer Driver
> + *
> + * Copyright (C) 2017 Ulrich Hecht
> + *
> + * 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/device.h>
> +#include <linux/i2c.h>
> +#include <linux/module.h>
> +#include <linux/of.h>
> +#include <linux/of_gpio.h>
> +#include <linux/serdev.h>
> +#include <linux/slab.h>
> +#include <linux/tty.h>
> +
> +#define SYNC 0x79
> +#define ACK 0xc3
> +
> +#define RX_FINISHED 0
> +#define RX_FRAME_ERROR 1
> +#define RX_EXPECT_ACK 2
> +#define RX_EXPECT_ACK_DATA 3
> +#define RX_EXPECT_DATA 4
> +
> +struct max9260_device {
> + struct serdev_device *serdev;
> + u8 *rx_buf;
> + int rx_len;
> + int rx_state;
> + wait_queue_head_t rx_wq;
> + struct i2c_adapter adap;
> +};
> +
> +static void wait_for_transaction(struct max9260_device *dev)
> +{
> + wait_event_interruptible_timeout(dev->rx_wq,
> + dev->rx_state <= RX_FRAME_ERROR,
> + HZ/2);
> +}
> +
> +static void transact(struct max9260_device *dev,
> + int expect,
> + u8 *request, int len)
> +{
> + serdev_device_mux_select(dev->serdev);
You don't check the return value here...
> +
> + serdev_device_set_baudrate(dev->serdev, 115200);
> + serdev_device_set_parity(dev->serdev, 1, 0);
> +
> + dev->rx_state = expect;
> + serdev_device_write_buf(dev->serdev, request, len);
> +
> + wait_for_transaction(dev);
> +
> + serdev_device_mux_deselect(dev->serdev);
...and unconditionally deselect the mux here. I.e. a potential
unlock of an unlocked mutex...
Cheers,
peda
> +}
> +
> +static int max9260_read_reg(struct max9260_device *dev, int reg)
> +{
> + u8 request[] = { 0x79, 0x91, reg, 1 };
> + u8 rx;
> +
> + dev->rx_len = 1;
> + dev->rx_buf = ℞
> +
> + transact(dev, RX_EXPECT_ACK_DATA, request, 4);
> +
> + if (dev->rx_state == RX_FINISHED)
> + return rx;
> +
> + return -1;
> +}
> +
> +static int max9260_setup(struct max9260_device *dev)
> +{
> + int ret;
> +
> + ret = max9260_read_reg(dev, 0x1e);
> +
> + if (ret != 0x02) {
> + dev_err(&dev->serdev->dev,
> + "device does not identify as MAX9260\n");
> + return -EINVAL;
> + }
> +
> + return 0;
> +}
> +
> +static void max9260_uart_write_wakeup(struct serdev_device *serdev)
> +{
> +}
> +
> +static int max9260_uart_receive_buf(struct serdev_device *serdev,
> + const u8 *data, size_t count)
> +{
> + struct max9260_device *dev = serdev_device_get_drvdata(serdev);
> + int accepted;
> +
> + switch (dev->rx_state) {
> + case RX_FINISHED:
> + dev_dbg(&dev->serdev->dev, "excess data ignored\n");
> + return count;
> +
> + case RX_EXPECT_ACK:
> + case RX_EXPECT_ACK_DATA:
> + if (data[0] != ACK) {
> + dev_dbg(&dev->serdev->dev, "frame error");
> + dev->rx_state = RX_FRAME_ERROR;
> + wake_up_interruptible(&dev->rx_wq);
> + return 1;
> + }
> + switch (dev->rx_state) {
> + case RX_EXPECT_ACK_DATA:
> + dev->rx_state = RX_EXPECT_DATA;
> + break;
> + case RX_EXPECT_ACK:
> + dev->rx_state = RX_FINISHED;
> + wake_up_interruptible(&dev->rx_wq);
> + break;
> + }
> + return 1;
> +
> + case RX_EXPECT_DATA:
> + accepted = dev->rx_len < count ? dev->rx_len : count;
> +
> + memcpy(dev->rx_buf, data, accepted);
> +
> + dev->rx_len -= accepted;
> + dev->rx_buf += accepted;
> +
> + if (!dev->rx_len) {
> + dev->rx_state = RX_FINISHED;
> + wake_up_interruptible(&dev->rx_wq);
> + }
> +
> + return accepted;
> +
> + case RX_FRAME_ERROR:
> + dev_dbg(&dev->serdev->dev, "%d bytes ignored\n", count);
> + return count;
> +
> + }
> + return 0;
> +}
> +
> +struct serdev_device_ops max9260_serdev_client_ops = {
> + .receive_buf = max9260_uart_receive_buf,
> + .write_wakeup = max9260_uart_write_wakeup,
> +};
> +
> +static u32 max9260_i2c_func(struct i2c_adapter *adapter)
> +{
> + return I2C_FUNC_SMBUS_EMUL;
> +}
> +
> +static s32 max9260_smbus_xfer(struct i2c_adapter *adap, u16 addr,
> + unsigned short flags, char read_write, u8 command, int size,
> + union i2c_smbus_data *data)
> +{
> + u8 request[] = { SYNC,
> + (addr << 1) + (read_write == I2C_SMBUS_READ),
> + command, 0, 0 };
> + struct max9260_device *dev = i2c_get_adapdata(adap);
> +
> + switch (size) {
> + case I2C_SMBUS_BYTE:
> + if (read_write == I2C_SMBUS_WRITE) {
> + transact(dev, RX_EXPECT_ACK, request, 4);
> + dev_dbg(&adap->dev,
> + "smbus byte - addr 0x%02x, wrote 0x%02x.\n",
> + addr, command);
> + } else {
> + /* TBD */
> + return -EOPNOTSUPP;
> + }
> + break;
> +
> + case I2C_SMBUS_BYTE_DATA:
> + request[3] = 1;
> + if (read_write == I2C_SMBUS_WRITE) {
> + request[4] = data->byte;
> + transact(dev, RX_EXPECT_ACK, request, 5);
> + dev_dbg(&adap->dev,
> + "smbus byte data - addr 0x%02x, wrote 0x%02x at 0x%02x.\n",
> + addr, data->byte, command);
> + } else {
> + dev->rx_len = 1;
> + dev->rx_buf = &data->byte;
> + transact(dev, RX_EXPECT_ACK_DATA, request, 4);
> + dev_dbg(&adap->dev,
> + "smbus byte data - addr 0x%02x, read 0x%02x at 0x%02x.\n",
> + addr, data->byte, command);
> + }
> + break;
> + default:
> + dev_dbg(&adap->dev,
> + "Unsupported I2C/SMBus command %d\n", size);
> + return -EOPNOTSUPP;
> + }
> +
> + if (dev->rx_state != RX_FINISHED) {
> + dev_dbg(&adap->dev, "xfer timed out\n");
> + return -EIO;
> + }
> +
> + return 0;
> +}
> +
> +static const struct i2c_algorithm max9260_i2c_algorithm = {
> + .functionality = max9260_i2c_func,
> + .smbus_xfer = max9260_smbus_xfer,
> +};
> +
> +static int max9260_probe(struct serdev_device *serdev)
> +{
> + struct max9260_device *dev;
> + struct i2c_adapter *adap;
> + int ret;
> +
> + dev = kzalloc(sizeof(*dev), GFP_KERNEL);
> + if (!dev)
> + return -ENOMEM;
> +
> + init_waitqueue_head(&dev->rx_wq);
> +
> + dev->serdev = serdev;
> + serdev_device_open(serdev);
> + serdev_device_set_drvdata(serdev, dev);
> +
> + serdev_device_set_client_ops(serdev, &max9260_serdev_client_ops);
> +
> + ret = max9260_setup(dev);
> +
> + if (ret < 0)
> + goto err_free;
> +
> + adap = &dev->adap;
> + i2c_set_adapdata(adap, dev);
> +
> + adap->owner = THIS_MODULE;
> + adap->algo = &max9260_i2c_algorithm;
> + adap->dev.parent = &serdev->dev;
> + adap->retries = 5;
> + adap->nr = -1;
> + strlcpy(adap->name, dev_name(&serdev->dev), sizeof(adap->name));
> +
> + ret = i2c_add_numbered_adapter(adap);
> + if (ret < 0) {
> + dev_err(&serdev->dev, "failed to register i2c adapter\n");
> + return ret;
> + }
> +
> + return 0;
> +
> +err_free:
> + kfree(dev);
> + return ret;
> +}
> +
> +static void max9260_remove(struct serdev_device *serdev)
> +{
> + struct max9260_device *dev = serdev_device_get_drvdata(serdev);
> +
> + serdev_device_close(dev->serdev);
> +
> + kfree(dev);
> +}
> +
> +static const struct of_device_id max9260_dt_ids[] = {
> + { .compatible = "maxim,max9260" },
> + {},
> +};
> +
> +MODULE_DEVICE_TABLE(of, max9260_dt_ids);
> +
> +static struct serdev_device_driver max9260_driver = {
> + .probe = max9260_probe,
> + .remove = max9260_remove,
> + .driver = {
> + .name = "max9260",
> + .of_match_table = of_match_ptr(max9260_dt_ids),
> + },
> +};
> +
> +module_serdev_device_driver(max9260_driver);
> +
> +MODULE_DESCRIPTION("Maxim MAX9260 GMSL Deserializer Driver");
> +MODULE_AUTHOR("Ulrich Hecht");
> +MODULE_LICENSE("GPL");
>
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [RFC 2/4] serdev: add GPIO-based multiplexer support
2017-06-14 14:38 ` [RFC 2/4] serdev: add GPIO-based multiplexer support Ulrich Hecht
@ 2017-06-15 9:34 ` Geert Uytterhoeven
0 siblings, 0 replies; 10+ messages in thread
From: Geert Uytterhoeven @ 2017-06-15 9:34 UTC (permalink / raw)
To: Ulrich Hecht
Cc: Rob Herring, linux-serial@vger.kernel.org, Linux-Renesas,
Magnus Damm, Laurent Pinchart, Wolfram Sang, Linux I2C
Hi Ulrich,
On Wed, Jun 14, 2017 at 4:38 PM, Ulrich Hecht
<ulrich.hecht+renesas@gmail.com> wrote:
> Adds an interface for slave device multiplexing, and an implementation
> for GPIO-based multiplexers.
>
> Signed-off-by: Ulrich Hecht <ulrich.hecht+renesas@gmail.com>
Thanks for your patch!
> --- /dev/null
> +++ b/drivers/tty/serdev/mux-gpio.c
> +int of_serdev_register_gpio_mux(struct serdev_controller *ctrl)
> +{
> + int i, ngpios;
> + struct serdev_mux *mux;
> + struct device_node *np = ctrl->dev.of_node;
> +
> + ngpios = of_gpio_named_count(np, "mux-select-gpios");
To make if OF-agnostic, you probably want to use gpiod_count() instead...
> + for (i = 0; i < ngpios; ++i)
> + mux->gpios[i] = of_get_named_gpio(np, "mux-select-gpios", i);
... and (devm_)gpiod_get_index().
Gr{oetje,eeting}s,
Geert
--
Geert Uytterhoeven -- There's lots of Linux beyond ia32 -- geert@linux-m68k.org
In personal conversations with technical people, I call myself a hacker. But
when I'm talking to journalists I just say "programmer" or something like that.
-- Linus Torvalds
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [RFC 4/4] ARM: dts: blanche: add SCIF1 and MAX9260 deserializer
2017-06-14 14:38 ` [RFC 4/4] ARM: dts: blanche: add SCIF1 and MAX9260 deserializer Ulrich Hecht
@ 2017-06-15 13:05 ` Rob Herring
0 siblings, 0 replies; 10+ messages in thread
From: Rob Herring @ 2017-06-15 13:05 UTC (permalink / raw)
To: Ulrich Hecht
Cc: linux-serial@vger.kernel.org,
open list:MEDIA DRIVERS FOR RENESAS - FCP, Magnus Damm,
Laurent Pinchart, wsa@the-dreams.de, linux-i2c@vger.kernel.org
On Wed, Jun 14, 2017 at 9:38 AM, Ulrich Hecht
<ulrich.hecht+renesas@gmail.com> wrote:
> Adds serial port SCIF1 and the MAX9260 deserializers connected to it.
>
> Signed-off-by: Ulrich Hecht <ulrich.hecht+renesas@gmail.com>
> ---
> arch/arm/boot/dts/r8a7792-blanche.dts | 45 +++++++++++++++++++++++++++++++++++
> 1 file changed, 45 insertions(+)
>
> diff --git a/arch/arm/boot/dts/r8a7792-blanche.dts b/arch/arm/boot/dts/r8a7792-blanche.dts
> index 9b67dca..281484d 100644
> --- a/arch/arm/boot/dts/r8a7792-blanche.dts
> +++ b/arch/arm/boot/dts/r8a7792-blanche.dts
> @@ -21,6 +21,7 @@
> aliases {
> serial0 = &scif0;
> serial1 = &scif3;
> + serial2 = &scif1;
> };
>
> chosen {
> @@ -202,6 +203,11 @@
> function = "scif0";
> };
>
> + scif1_pins: scif1 {
> + groups = "scif1_data";
> + function = "scif1";
> + };
> +
> scif3_pins: scif3 {
> groups = "scif3_data";
> function = "scif3";
> @@ -246,6 +252,45 @@
> status = "okay";
> };
>
> +&scif1 {
> + pinctrl-0 = <&scif1_pins>;
> + pinctrl-names = "default";
> +
> + status = "okay";
> +
> + mux-select-gpios = <&gpio5 12 GPIO_ACTIVE_LOW>,
> + <&gpio5 13 GPIO_ACTIVE_LOW>,
> + <&gpio5 14 GPIO_ACTIVE_LOW>,
> + <&gpio5 15 GPIO_ACTIVE_LOW>;
> +
> + #address-cells = <1>;
> + #size-cells = <0>;
> + gmsl-deserializer@0 {
> + compatible = "maxim,max9260";
> + reg = <0x8>;
You need to document how muxed serdev devices are represented in
general. As Peter mentioned, you should use the mux-ctrl binding.
Maybe this should have a mux node here too. That helps if we ever have
other child nodes on the UART.
The unit address and reg property values should match.
> + };
> + gmsl-deserializer@1 {
> + compatible = "maxim,max9260";
> + reg = <0x9>;
> + };
> + gmsl-deserializer@2 {
> + compatible = "maxim,max9260";
> + reg = <0xa>;
> + };
> + gmsl-deserializer@3 {
> + compatible = "maxim,max9260";
> + reg = <0xb>;
> + };
> + gmsl-deserializer@4 {
> + compatible = "maxim,max9260";
> + reg = <0x4>;
> + };
> + gmsl-deserializer@5 {
> + compatible = "maxim,max9260";
> + reg = <0x5>;
> + };
> +};
> +
> &scif3 {
> pinctrl-0 = <&scif3_pins>;
> pinctrl-names = "default";
> --
> 2.7.4
>
^ permalink raw reply [flat|nested] 10+ messages in thread
* Re: [RFC 3/4] max9260: add driver for i2c over GMSL passthrough
2017-06-14 14:38 ` [RFC 3/4] max9260: add driver for i2c over GMSL passthrough Ulrich Hecht
2017-06-15 7:09 ` Peter Rosin
@ 2017-06-15 15:37 ` Wolfram Sang
1 sibling, 0 replies; 10+ messages in thread
From: Wolfram Sang @ 2017-06-15 15:37 UTC (permalink / raw)
To: Ulrich Hecht
Cc: robh, linux-serial, linux-renesas-soc, magnus.damm,
laurent.pinchart, linux-i2c
[-- Attachment #1: Type: text/plain, Size: 4376 bytes --]
Hi Uli,
> +static void wait_for_transaction(struct max9260_device *dev)
> +{
> + wait_event_interruptible_timeout(dev->rx_wq,
> + dev->rx_state <= RX_FRAME_ERROR,
> + HZ/2);
> +}
> +static void transact(struct max9260_device *dev,
max9260_transact?
> + int expect,
> + u8 *request, int len)
> +{
> + serdev_device_mux_select(dev->serdev);
> +
> + serdev_device_set_baudrate(dev->serdev, 115200);
> + serdev_device_set_parity(dev->serdev, 1, 0);
> +
> + dev->rx_state = expect;
> + serdev_device_write_buf(dev->serdev, request, len);
> +
> + wait_for_transaction(dev);
> +
> + serdev_device_mux_deselect(dev->serdev);
> +}
> +
> +static int max9260_read_reg(struct max9260_device *dev, int reg)
> +{
> + u8 request[] = { 0x79, 0x91, reg, 1 };
> + u8 rx;
> +
> + dev->rx_len = 1;
> + dev->rx_buf = ℞
> +
> + transact(dev, RX_EXPECT_ACK_DATA, request, 4);
> +
> + if (dev->rx_state == RX_FINISHED)
> + return rx;
> +
> + return -1;
-EIO?
> +}
> +
> +static int max9260_setup(struct max9260_device *dev)
> +{
> + int ret;
> +
> + ret = max9260_read_reg(dev, 0x1e);
> +
> + if (ret != 0x02) {
> + dev_err(&dev->serdev->dev,
> + "device does not identify as MAX9260\n");
> + return -EINVAL;
> + }
> +
> + return 0;
> +}
> +
> +static void max9260_uart_write_wakeup(struct serdev_device *serdev)
> +{
> +}
> +
> +static int max9260_uart_receive_buf(struct serdev_device *serdev,
> + const u8 *data, size_t count)
> +{
> + struct max9260_device *dev = serdev_device_get_drvdata(serdev);
> + int accepted;
> +
> + switch (dev->rx_state) {
> + case RX_FINISHED:
> + dev_dbg(&dev->serdev->dev, "excess data ignored\n");
> + return count;
> +
> + case RX_EXPECT_ACK:
> + case RX_EXPECT_ACK_DATA:
> + if (data[0] != ACK) {
> + dev_dbg(&dev->serdev->dev, "frame error");
> + dev->rx_state = RX_FRAME_ERROR;
> + wake_up_interruptible(&dev->rx_wq);
> + return 1;
> + }
> + switch (dev->rx_state) {
> + case RX_EXPECT_ACK_DATA:
> + dev->rx_state = RX_EXPECT_DATA;
> + break;
> + case RX_EXPECT_ACK:
> + dev->rx_state = RX_FINISHED;
> + wake_up_interruptible(&dev->rx_wq);
> + break;
> + }
This switch inside a switch evaluating the same variable is easy to
misunderstand. What about a simple if-else for the second switch block
above?
> + return 1;
> +
> + case RX_EXPECT_DATA:
> + accepted = dev->rx_len < count ? dev->rx_len : count;
> +
> + memcpy(dev->rx_buf, data, accepted);
> +
> + dev->rx_len -= accepted;
> + dev->rx_buf += accepted;
> +
> + if (!dev->rx_len) {
> + dev->rx_state = RX_FINISHED;
> + wake_up_interruptible(&dev->rx_wq);
> + }
> +
> + return accepted;
> +
> + case RX_FRAME_ERROR:
> + dev_dbg(&dev->serdev->dev, "%d bytes ignored\n", count);
> + return count;
> +
> + }
> + return 0;
> +}
> +
> +struct serdev_device_ops max9260_serdev_client_ops = {
> + .receive_buf = max9260_uart_receive_buf,
> + .write_wakeup = max9260_uart_write_wakeup,
> +};
> +
> +static u32 max9260_i2c_func(struct i2c_adapter *adapter)
> +{
> + return I2C_FUNC_SMBUS_EMUL;
According to the below xfer function, it should return:
I2C_SMBUS_BYTE | I2C_SMBUS_BYTE_DATA;
> +}
> +
...
> +static int max9260_probe(struct serdev_device *serdev)
> +{
> + struct max9260_device *dev;
> + struct i2c_adapter *adap;
> + int ret;
> +
> + dev = kzalloc(sizeof(*dev), GFP_KERNEL);
devm_kzalloc?
> + if (!dev)
> + return -ENOMEM;
> +
> + init_waitqueue_head(&dev->rx_wq);
> +
> + dev->serdev = serdev;
> + serdev_device_open(serdev);
> + serdev_device_set_drvdata(serdev, dev);
> +
> + serdev_device_set_client_ops(serdev, &max9260_serdev_client_ops);
> +
> + ret = max9260_setup(dev);
> +
Newline can go.
> + if (ret < 0)
> + goto err_free;
> +
> + adap = &dev->adap;
> + i2c_set_adapdata(adap, dev);
> +
> + adap->owner = THIS_MODULE;
> + adap->algo = &max9260_i2c_algorithm;
> + adap->dev.parent = &serdev->dev;
> + adap->retries = 5;
> + adap->nr = -1;
You can skip this...
> + strlcpy(adap->name, dev_name(&serdev->dev), sizeof(adap->name));
> +
> + ret = i2c_add_numbered_adapter(adap);
... if you use i2c_add_adapter(adap); here. No 'numbered'.
> + if (ret < 0) {
> + dev_err(&serdev->dev, "failed to register i2c adapter\n");
No need for dev_err. The core will properly report failures.
> + return ret;
> + }
> +
> + return 0;
> +
> +err_free:
> + kfree(dev);
> + return ret;
> +}
Regards,
Wolfram
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 833 bytes --]
^ permalink raw reply [flat|nested] 10+ messages in thread
end of thread, other threads:[~2017-06-15 15:37 UTC | newest]
Thread overview: 10+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2017-06-14 14:38 [RFC 0/4] serdev GPIO-based multiplexing support Ulrich Hecht
2017-06-14 14:38 ` [RFC 1/4] serdev: add method to set parity Ulrich Hecht
2017-06-14 14:38 ` [RFC 2/4] serdev: add GPIO-based multiplexer support Ulrich Hecht
2017-06-15 9:34 ` Geert Uytterhoeven
2017-06-14 14:38 ` [RFC 3/4] max9260: add driver for i2c over GMSL passthrough Ulrich Hecht
2017-06-15 7:09 ` Peter Rosin
2017-06-15 15:37 ` Wolfram Sang
2017-06-14 14:38 ` [RFC 4/4] ARM: dts: blanche: add SCIF1 and MAX9260 deserializer Ulrich Hecht
2017-06-15 13:05 ` Rob Herring
2017-06-15 7:07 ` [RFC 0/4] serdev GPIO-based multiplexing support Peter Rosin
This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).