mail archive of the barebox mailing list
 help / color / mirror / Atom feed
* [PATCH 0/3] Linux's serdev framwork port
@ 2018-03-26 13:09 Andrey Smirnov
  2018-03-26 13:09 ` [PATCH 1/3] console: Introduce console_drain() Andrey Smirnov
                   ` (2 more replies)
  0 siblings, 3 replies; 12+ messages in thread
From: Andrey Smirnov @ 2018-03-26 13:09 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Hi everyone:

In an effort to bring this kernel driver
https://git.kernel.org/pub/scm/linux/kernel/git/torvalds/linux.git/tree/drivers/mfd/rave-sp.c?h=v4.16-rc7
to Barebox, I ended up creating a miniature and extremely simplified
version of 'serdev' subsystem which is presented in this patchset.

All feedback is wellcome!

Thanks,
Andrey Smirnov

Andrey Smirnov (3):
  console: Introduce console_drain()
  console: Add simplified 'serdev' framework from Linux kernel
  serial: Check result of console_unregister()

 common/Kconfig                   |   6 +++
 common/Makefile                  |   1 +
 common/console.c                 |  24 +++++++--
 common/serdev.c                  |  87 ++++++++++++++++++++++++++++++
 drivers/serial/serial_auart.c    |   6 ++-
 drivers/serial/serial_cadence.c  |   6 ++-
 drivers/serial/serial_clps711x.c |   6 ++-
 drivers/serial/serial_imx.c      |   6 ++-
 drivers/serial/serial_lpuart.c   |   6 ++-
 drivers/serial/serial_pxa.c      |   6 ++-
 drivers/serial/serial_s3c.c      |   6 ++-
 drivers/serial/stm-serial.c      |   6 ++-
 include/console.h                | 112 ++++++++++++++++++++++++++++++++++++++-
 include/serdev.h                 |  36 +++++++++++++
 lib/xymodem.c                    |  30 ++---------
 15 files changed, 307 insertions(+), 37 deletions(-)
 create mode 100644 common/serdev.c
 create mode 100644 include/serdev.h

-- 
2.14.3


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* [PATCH 1/3] console: Introduce console_drain()
  2018-03-26 13:09 [PATCH 0/3] Linux's serdev framwork port Andrey Smirnov
@ 2018-03-26 13:09 ` Andrey Smirnov
  2018-03-26 13:09 ` [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel Andrey Smirnov
  2018-03-26 13:09 ` [PATCH 3/3] serial: Check result of console_unregister() Andrey Smirnov
  2 siblings, 0 replies; 12+ messages in thread
From: Andrey Smirnov @ 2018-03-26 13:09 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Generalize high baud rate UART polling code found in lib/xmodem.c and
expose it as a generic function in console API.

The usecase for this -- besides X/Y-mode data transfers where the code
originated -- is command/reply type of serial exchages at high baud
rates (~1Mbaud) with payloads exceeding inernal UART FIFOs in
size. Such interactions are not uncommon in serdev device and this
patch is done in preparation for serdev support code that will follow.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 include/console.h | 83 +++++++++++++++++++++++++++++++++++++++++++++++++++++++
 lib/xymodem.c     | 30 ++++----------------
 2 files changed, 88 insertions(+), 25 deletions(-)

diff --git a/include/console.h b/include/console.h
index 724168e07..4aa4c8f9e 100644
--- a/include/console.h
+++ b/include/console.h
@@ -23,6 +23,7 @@
 #include <param.h>
 #include <linux/list.h>
 #include <driver.h>
+#include <clock.h>
 
 #define CONSOLE_STDIN           (1 << 0)
 #define CONSOLE_STDOUT          (1 << 1)
@@ -88,6 +89,88 @@ unsigned console_get_active(struct console_device *cdev);
 int console_set_baudrate(struct console_device *cdev, unsigned baudrate);
 unsigned console_get_baudrate(struct console_device *cdev);
 
+
+/**
+ * console_fifo_fill - fill FIFO with as much console data as possible
+ *
+ * @cdev:	Console to poll for dat
+ * @fifo:	FIFO to store the data in
+ */
+static inline int console_fifo_fill(struct console_device *cdev,
+				    struct kfifo *fifo)
+{
+	size_t len = kfifo_len(fifo);
+	while (cdev->tstc(cdev) && len < fifo->size) {
+		kfifo_putc(fifo, (unsigned char)(cdev->getc(cdev)));
+		len++;
+	}
+
+	return len;
+}
+
+/**
+ * __console_drain - Drain console into a buffer via FIFO
+ *
+ * @__is_timeout	Callback used to determine timeout condition
+ * @cdev		Console to drain
+ * @fifo		FIFO to use as a transient buffer
+ * @buf			Buffer to drain console into
+ * @len			Size of the drain buffer
+ * @timeout		Console polling timeout in ns
+ *
+ * This function is optimized to :
+ * - maximize throughput (ie. read as much as is available in lower layer fifo)
+ * - minimize latencies (no delay or wait timeout if data available)
+ * - have a timeout
+ * This is why standard getc() is not used, and input_fifo_fill() exists.
+ */
+static inline int __console_drain(int (*__is_timeout)(uint64_t start_ns,
+						      uint64_t time_offset_ns),
+				  struct console_device *cdev,
+				  struct kfifo *fifo,
+				  unsigned char *buf,
+				  int len,
+				  uint64_t timeout)
+{
+	int i = 0;
+	uint64_t start = get_time_ns();
+
+	if (!len)
+		return -EINVAL;
+
+	do {
+		/*
+		 * To minimize wait time before we start polling Rx
+		 * (to potentially avoid overruning Rx FIFO) we call
+		 * console_fifo_fill first
+		 */
+		if (console_fifo_fill(cdev, fifo))
+			kfifo_getc(fifo, &buf[i++]);
+
+	} while (i < len && !__is_timeout(start, timeout));
+
+	return i;
+}
+
+static inline int console_drain_non_interruptible(struct console_device *cdev,
+						  struct kfifo *fifo,
+						  unsigned char *buf,
+						  int len,
+						  uint64_t timeout)
+{
+	return __console_drain(is_timeout_non_interruptible,
+			       cdev, fifo, buf, len, timeout);
+}
+
+static inline int console_drain(struct console_device *cdev,
+				struct kfifo *fifo,
+				unsigned char *buf,
+				int len,
+				uint64_t timeout)
+{
+	return __console_drain(is_timeout, cdev, fifo, buf, len, timeout);
+}
+
 #ifdef CONFIG_PBL_CONSOLE
 void pbl_set_putc(void (*putcf)(void *ctx, int c), void *ctx);
 #else
diff --git a/lib/xymodem.c b/lib/xymodem.c
index a6c4d3cd5..ff052ef8f 100644
--- a/lib/xymodem.c
+++ b/lib/xymodem.c
@@ -146,36 +146,16 @@ static const char block_nack[MAX_PROTOS][MAX_CRCS] = {
 	{ 0, 0, 0 },		/* YMODEM-G */
 };
 
-static int input_fifo_fill(struct console_device *cdev, struct kfifo *fifo)
-{
-	while (cdev->tstc(cdev) && kfifo_len(fifo) < INPUT_FIFO_SIZE)
-		kfifo_putc(fifo, (unsigned char)(cdev->getc(cdev)));
-	return kfifo_len(fifo);
-}
-
-/*
- * This function is optimized to :
- * - maximize throughput (ie. read as much as is available in lower layer fifo)
- * - minimize latencies (no delay or wait timeout if data available)
- * - have a timeout
- * This is why standard getc() is not used, and input_fifo_fill() exists.
- */
 static int xy_gets(struct console_device *cdev, struct kfifo *fifo,
 		      unsigned char *buf, int len, uint64_t timeout)
 {
-	int i, rc;
-	uint64_t start = get_time_ns();
+	int rc;
 
-	for (i = 0, rc = 0; rc >= 0 && i < len; ) {
-		if (is_timeout(start, timeout)) {
-			rc = -ETIMEDOUT;
-			continue;
-		}
-		if (input_fifo_fill(cdev, fifo))
-			kfifo_getc(fifo, &buf[i++]);
-	}
+	rc = console_drain(cdev, fifo, buf, len, timeout);
+	if (rc != len)
+		return -ETIMEDOUT;
 
-	return rc < 0 ? rc : i;
+	return len;
 }
 
 static void xy_putc(struct console_device *cdev, unsigned char c)
-- 
2.14.3


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel
  2018-03-26 13:09 [PATCH 0/3] Linux's serdev framwork port Andrey Smirnov
  2018-03-26 13:09 ` [PATCH 1/3] console: Introduce console_drain() Andrey Smirnov
@ 2018-03-26 13:09 ` Andrey Smirnov
  2018-04-03  6:54   ` Sascha Hauer
  2018-03-26 13:09 ` [PATCH 3/3] serial: Check result of console_unregister() Andrey Smirnov
  2 siblings, 1 reply; 12+ messages in thread
From: Andrey Smirnov @ 2018-03-26 13:09 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Port 'serdev' UART-slave deivce framework found in recent Linux
kernels (post 4.13) in order to be able to port 'serdev' slave drivers
from Linux.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 common/Kconfig    |  6 ++++
 common/Makefile   |  1 +
 common/console.c  | 24 +++++++++++++--
 common/serdev.c   | 87 +++++++++++++++++++++++++++++++++++++++++++++++++++++++
 include/console.h | 27 +++++++++++++++++
 include/serdev.h  | 36 +++++++++++++++++++++++
 6 files changed, 178 insertions(+), 3 deletions(-)
 create mode 100644 common/serdev.c
 create mode 100644 include/serdev.h

diff --git a/common/Kconfig b/common/Kconfig
index 81cf72a95..601bc95a4 100644
--- a/common/Kconfig
+++ b/common/Kconfig
@@ -712,6 +712,12 @@ config CONSOLE_NONE
 
 endchoice
 
+config SERIAL_DEV_BUS
+	bool "Serial device bus"
+	depends on CONSOLE_FULL
+	help
+	  Core support for devices connected via a serial port.
+
 choice
 	prompt "Console activation strategy"
 	depends on CONSOLE_FULL
diff --git a/common/Makefile b/common/Makefile
index a9abcd1bc..c945dd78e 100644
--- a/common/Makefile
+++ b/common/Makefile
@@ -61,6 +61,7 @@ obj-$(CONFIG_FIRMWARE)		+= firmware.o
 obj-$(CONFIG_UBIFORMAT)		+= ubiformat.o
 obj-$(CONFIG_BAREBOX_UPDATE_IMX_NAND_FCB) += imx-bbu-nand-fcb.o
 obj-$(CONFIG_BOOT)		+= boot.o
+obj-$(CONFIG_SERIAL_DEV_BUS)	+= serdev.o
 
 ifdef CONFIG_PASSWORD
 
diff --git a/common/console.c b/common/console.c
index f4c799fa5..13b1360b5 100644
--- a/common/console.c
+++ b/common/console.c
@@ -305,10 +305,11 @@ static ssize_t fops_write(struct cdev* dev, const void* buf, size_t count,
 
 int console_register(struct console_device *newcdev)
 {
+	struct device_node *serdev_node = console_is_serdev_node(newcdev);
 	struct device_d *dev = &newcdev->class_dev;
 	int activate = 0, ret;
 
-	if (initialized == CONSOLE_UNINITIALIZED)
+	if (!serdev_node && initialized == CONSOLE_UNINITIALIZED)
 		console_init_early();
 
 	if (newcdev->devname) {
@@ -323,6 +324,17 @@ int console_register(struct console_device *newcdev)
 		dev->parent = newcdev->dev;
 	platform_device_register(dev);
 
+	newcdev->open_count = 0;
+
+	/*
+	 * If our console deive is a serdev, we skip the creation of
+	 * corresponding entry in /dev as well as registration in
+	 * console_list and just go straigh to populating child
+	 * devices.
+	 */
+	if (serdev_node)
+		return of_platform_populate(serdev_node, NULL, dev);
+
 	if (newcdev->setbrg) {
 		ret = newcdev->setbrg(newcdev, CONFIG_BAUDRATE);
 		if (ret)
@@ -335,8 +347,6 @@ int console_register(struct console_device *newcdev)
 	if (newcdev->putc && !newcdev->puts)
 		newcdev->puts = __console_puts;
 
-	newcdev->open_count = 0;
-
 	dev_add_param_string(dev, "active", console_active_set, console_active_get,
 			     &newcdev->active_string, newcdev);
 
@@ -386,6 +396,14 @@ int console_unregister(struct console_device *cdev)
 	struct device_d *dev = &cdev->class_dev;
 	int status;
 
+	/*
+	 * We don't do any sophisticated serdev device de-population
+	 * and instead claim this console busy, preventing its
+	 * de-initialization, 'till the very end of our execution.
+	 */
+	if (console_is_serdev_node(cdev))
+		return -EBUSY;
+
 	devfs_remove(&cdev->devfs);
 
 	list_del(&cdev->list);
diff --git a/common/serdev.c b/common/serdev.c
new file mode 100644
index 000000000..58985c4b1
--- /dev/null
+++ b/common/serdev.c
@@ -0,0 +1,87 @@
+
+#include <common.h>
+#include <serdev.h>
+
+static void serdev_device_poller(void *context)
+{
+	struct serdev_device *serdev = context;
+	struct console_device *cdev = to_console_device(serdev);
+	unsigned char *buf = serdev->buf;
+	int ret, len;
+
+	/*
+	 * Since this callback is a part of poller infrastructure we
+	 * want to use _non_interruptible version of the function
+	 * below to prevent recursion from happening (regular
+	 * console_drain will call is_timeout, which might end up
+	 * calling this function again).
+	 */
+	len = console_drain_non_interruptible(cdev, serdev->fifo, buf,
+					      PAGE_SIZE,
+					      serdev->polling_window);
+	while (len > 0) {
+		ret = serdev->receive_buf(serdev, buf, len);
+		len -= ret;
+		buf += ret;
+	}
+
+	/*
+	 * Re-schedule ourselves in 'serdev->polling_interval'
+	 * nanoseconds
+	 */
+	poller_call_async(&serdev->poller,
+			  serdev->polling_interval,
+			  serdev_device_poller,
+			  serdev);
+}
+
+int serdev_device_open(struct serdev_device *serdev)
+{
+	struct console_device *cdev = to_console_device(serdev);
+	int ret;
+
+	if (!cdev->putc || !cdev->getc)
+		return -EINVAL;
+
+	if (!serdev->polling_window || !serdev->polling_interval)
+		return -EINVAL;
+
+	serdev->buf = xzalloc(PAGE_SIZE);
+	serdev->fifo = kfifo_alloc(PAGE_SIZE);
+	if (!serdev->fifo)
+		return -ENOMEM;
+
+	ret = poller_async_register(&serdev->poller);
+	if (ret)
+		return ret;
+
+	return console_open(cdev);
+}
+
+unsigned int serdev_device_set_baudrate(struct serdev_device *serdev,
+					unsigned int speed)
+{
+	struct console_device *cdev = to_console_device(serdev);
+
+	if (console_set_baudrate(cdev, speed) < 0)
+		return 0;
+
+	return console_get_baudrate(cdev);
+}
+
+int serdev_device_write(struct serdev_device *serdev, const unsigned char *buf,
+			size_t count, unsigned long timeout)
+{
+	struct console_device *cdev = to_console_device(serdev);
+
+	while (count--)
+		cdev->putc(cdev, *buf++);
+	/*
+	 * Poll Rx once right after we just send some data in case our
+	 * serdev device implements command/response type of a
+	 * protocol and we need to start draining input as soon as
+	 * possible.
+	 */
+	serdev_device_poller(serdev);
+	return 0;
+}
diff --git a/include/console.h b/include/console.h
index 4aa4c8f9e..14f00fa1e 100644
--- a/include/console.h
+++ b/include/console.h
@@ -23,6 +23,7 @@
 #include <param.h>
 #include <linux/list.h>
 #include <driver.h>
+#include <serdev.h>
 #include <clock.h>
 
 #define CONSOLE_STDIN           (1 << 0)
@@ -65,8 +66,34 @@ struct console_device {
 
 	struct cdev devfs;
 	struct file_operations fops;
+
+	struct serdev_device serdev;
 };
 
+static inline struct serdev_device *to_serdev_device(struct device_d *d)
+{
+	struct console_device *cdev =
+		container_of(d, struct console_device, class_dev);
+	return &cdev->serdev;
+}
+
+static inline struct console_device *
+to_console_device(struct serdev_device *serdev)
+{
+	return container_of(serdev, struct console_device, serdev);
+}
+
+static inline struct device_node *
+console_is_serdev_node(struct console_device *cdev)
+{
+	struct device_d *dev = cdev->dev;
+	if (dev && dev->device_node &&
+	    of_get_child_count(dev->device_node))
+		return dev->device_node;
+
+	return NULL;
+}
+
 int console_register(struct console_device *cdev);
 int console_unregister(struct console_device *cdev);
 
diff --git a/include/serdev.h b/include/serdev.h
new file mode 100644
index 000000000..efc735fed
--- /dev/null
+++ b/include/serdev.h
@@ -0,0 +1,36 @@
+#ifndef _SERDEV_H_
+#define _SERDEV_H_
+
+#include <driver.h>
+#include <poller.h>
+#include <kfifo.h>
+
+/**
+ * struct serdev_device - Basic representation of an serdev device
+ *
+ * @dev:		Corresponding device
+ * @fifo:		Circular buffer used for console draining
+ * @buf:		Buffer used to pass Rx data to consumers
+ * @poller		Async poller used to poll this serdev
+ * @polling_interval:	Async poller periodicity
+ * @polling_window:	Duration of a single busy loop poll
+ * @receive_buf:	Function called with data received from device;
+ *			returns number of bytes accepted;
+ */
+struct serdev_device {
+	struct device_d *dev;
+	struct kfifo *fifo;
+	unsigned char *buf;
+	struct poller_async poller;
+	uint64_t polling_interval;
+	uint64_t polling_window;
+
+	int (*receive_buf)(struct serdev_device *, const unsigned char *,
+			   size_t);
+};
+
+int serdev_device_open(struct serdev_device *);
+unsigned int serdev_device_set_baudrate(struct serdev_device *, unsigned int);
+int serdev_device_write(struct serdev_device *, const unsigned char *,
+			size_t, unsigned long);
+#endif
-- 
2.14.3


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* [PATCH 3/3] serial: Check result of console_unregister()
  2018-03-26 13:09 [PATCH 0/3] Linux's serdev framwork port Andrey Smirnov
  2018-03-26 13:09 ` [PATCH 1/3] console: Introduce console_drain() Andrey Smirnov
  2018-03-26 13:09 ` [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel Andrey Smirnov
@ 2018-03-26 13:09 ` Andrey Smirnov
  2018-04-03  7:04   ` Sascha Hauer
  2 siblings, 1 reply; 12+ messages in thread
From: Andrey Smirnov @ 2018-03-26 13:09 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

In order to allow 'serdev' devices to prevent parent console device
removal and correspondign memory deallocation add code to all serial
driver to check result of console_unregister() and bail out early if
it is unsuccessful.

One example of a use-case for this would be a reset handler relying on
a serdev device for transport. Without this patch underlying console
device would be removed and de-allocated before reset handler is even
run thus leading to unpredictable behaviour and crashes.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 drivers/serial/serial_auart.c    | 6 +++++-
 drivers/serial/serial_cadence.c  | 6 +++++-
 drivers/serial/serial_clps711x.c | 6 +++++-
 drivers/serial/serial_imx.c      | 6 +++++-
 drivers/serial/serial_lpuart.c   | 6 +++++-
 drivers/serial/serial_pxa.c      | 6 +++++-
 drivers/serial/serial_s3c.c      | 6 +++++-
 drivers/serial/stm-serial.c      | 6 +++++-
 include/console.h                | 2 +-
 9 files changed, 41 insertions(+), 9 deletions(-)

diff --git a/drivers/serial/serial_auart.c b/drivers/serial/serial_auart.c
index c3b9a1995..9bd0d991e 100644
--- a/drivers/serial/serial_auart.c
+++ b/drivers/serial/serial_auart.c
@@ -224,9 +224,13 @@ static int auart_serial_probe(struct device_d *dev)
 static void auart_serial_remove(struct device_d *dev)
 {
 	struct auart_priv *priv = dev->priv;
+	int ret;
 
 	auart_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
+	ret = console_unregister(&priv->cdev);
+	if (ret < 0)
+		return;
+
 	free(priv);
 }
 
diff --git a/drivers/serial/serial_cadence.c b/drivers/serial/serial_cadence.c
index 36dfa2084..f43d98172 100644
--- a/drivers/serial/serial_cadence.c
+++ b/drivers/serial/serial_cadence.c
@@ -270,8 +270,12 @@ err_free:
 static void cadence_serial_remove(struct device_d *dev)
 {
 	struct cadence_serial_priv *priv = dev->priv;
+	int ret;
+
+	ret = console_unregister(&priv->cdev);
+	if (ret < 0)
+		return;
 
-	console_unregister(&priv->cdev);
 	free(priv);
 }
 
diff --git a/drivers/serial/serial_clps711x.c b/drivers/serial/serial_clps711x.c
index ad14373ac..24ae3fdd3 100644
--- a/drivers/serial/serial_clps711x.c
+++ b/drivers/serial/serial_clps711x.c
@@ -184,9 +184,13 @@ out_err:
 static void clps711x_remove(struct device_d *dev)
 {
 	struct clps711x_uart *s = dev->priv;
+	int ret;
 
 	clps711x_flush(&s->cdev);
-	console_unregister(&s->cdev);
+	ret = console_unregister(&s->cdev);
+	if (ret < 0)
+		return;
+
 	free(s);
 }
 
diff --git a/drivers/serial/serial_imx.c b/drivers/serial/serial_imx.c
index e8c3836a6..fb865f554 100644
--- a/drivers/serial/serial_imx.c
+++ b/drivers/serial/serial_imx.c
@@ -274,9 +274,13 @@ err_free:
 static void imx_serial_remove(struct device_d *dev)
 {
 	struct imx_serial_priv *priv = dev->priv;
+	int ret;
 
 	imx_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
+	ret = console_unregister(&priv->cdev);
+	if (ret < 0)
+		return;
+
 	free(priv);
 }
 
diff --git a/drivers/serial/serial_lpuart.c b/drivers/serial/serial_lpuart.c
index 52fb6d39c..42fab8a56 100644
--- a/drivers/serial/serial_lpuart.c
+++ b/drivers/serial/serial_lpuart.c
@@ -194,9 +194,13 @@ err_free:
 static void lpuart_serial_remove(struct device_d *dev)
 {
 	struct lpuart *lpuart = dev->priv;
+	int ret;
 
 	lpuart_serial_flush(&lpuart->cdev);
-	console_unregister(&lpuart->cdev);
+	ret = console_unregister(&lpuart->cdev);
+	if (ret < 0)
+		return;
+
 	release_region(lpuart->io);
 	clk_put(lpuart->clk);
 
diff --git a/drivers/serial/serial_pxa.c b/drivers/serial/serial_pxa.c
index 1a4d7b430..146f19cf3 100644
--- a/drivers/serial/serial_pxa.c
+++ b/drivers/serial/serial_pxa.c
@@ -188,8 +188,12 @@ static int pxa_serial_probe(struct device_d *dev)
 static void pxa_serial_remove(struct device_d *dev)
 {
 	struct pxa_serial_priv *priv = dev->priv;
+	int ret;
+
+	ret = console_unregister(&priv->cdev);
+	if (ret < 0)
+		return;
 
-	console_unregister(&priv->cdev);
 	free(priv);
 }
 
diff --git a/drivers/serial/serial_s3c.c b/drivers/serial/serial_s3c.c
index 0a6e22d97..8c6443acd 100644
--- a/drivers/serial/serial_s3c.c
+++ b/drivers/serial/serial_s3c.c
@@ -205,9 +205,13 @@ static int s3c_serial_probe(struct device_d *dev)
 static void s3c_serial_remove(struct device_d *dev)
 {
 	struct s3c_uart *priv= dev->priv;
+	int ret;
 
 	s3c_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
+	ret = console_unregister(&priv->cdev);
+	if (ret < 0)
+		return;
+
 	free(priv);
 }
 
diff --git a/drivers/serial/stm-serial.c b/drivers/serial/stm-serial.c
index 83328f455..3edcdd7e8 100644
--- a/drivers/serial/stm-serial.c
+++ b/drivers/serial/stm-serial.c
@@ -185,9 +185,13 @@ static int stm_serial_probe(struct device_d *dev)
 static void stm_serial_remove(struct device_d *dev)
 {
 	struct stm_priv *priv = dev->priv;
+	int ret;
 
 	stm_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
+	ret = console_unregister(&priv->cdev);
+	if (ret < 0)
+		return;
+
 	free(priv);
 }
 
diff --git a/include/console.h b/include/console.h
index 14f00fa1e..3870e67a4 100644
--- a/include/console.h
+++ b/include/console.h
@@ -95,7 +95,7 @@ console_is_serdev_node(struct console_device *cdev)
 }
 
 int console_register(struct console_device *cdev);
-int console_unregister(struct console_device *cdev);
+int __must_check console_unregister(struct console_device *cdev);
 
 struct console_device *console_get_by_dev(struct device_d *dev);
 struct console_device *console_get_by_name(const char *name);
-- 
2.14.3


_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel
  2018-03-26 13:09 ` [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel Andrey Smirnov
@ 2018-04-03  6:54   ` Sascha Hauer
  2018-04-09 16:40     ` Andrey Smirnov
  0 siblings, 1 reply; 12+ messages in thread
From: Sascha Hauer @ 2018-04-03  6:54 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: barebox

Hi Andrey,

Some comments inside.


On Mon, Mar 26, 2018 at 06:09:14AM -0700, Andrey Smirnov wrote:
> Port 'serdev' UART-slave deivce framework found in recent Linux
> kernels (post 4.13) in order to be able to port 'serdev' slave drivers
> from Linux.
> 
> Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
> @@ -323,6 +324,17 @@ int console_register(struct console_device *newcdev)
>  		dev->parent = newcdev->dev;
>  	platform_device_register(dev);
>  
> +	newcdev->open_count = 0;
> +
> +	/*
> +	 * If our console deive is a serdev, we skip the creation of

s/deive/device/

> +	 * corresponding entry in /dev as well as registration in
> +	 * console_list and just go straigh to populating child

s/straigh/straight/

> +	 * devices.
> +	 */
> +	if (serdev_node)
> +		return of_platform_populate(serdev_node, NULL, dev);

How is this going to be used? A serdev driver binds to the serdev_node
and then it probably needs to get a pointer to the console device,
right? How does the driver accomplish this?

> +/**
> + * struct serdev_device - Basic representation of an serdev device
> + *
> + * @dev:		Corresponding device
> + * @fifo:		Circular buffer used for console draining
> + * @buf:		Buffer used to pass Rx data to consumers
> + * @poller		Async poller used to poll this serdev
> + * @polling_interval:	Async poller periodicity
> + * @polling_window:	Duration of a single busy loop poll
> + * @receive_buf:	Function called with data received from device;
> + *			returns number of bytes accepted;
> + */
> +struct serdev_device {
> +	struct device_d *dev;
> +	struct kfifo *fifo;
> +	unsigned char *buf;
> +	struct poller_async poller;
> +	uint64_t polling_interval;
> +	uint64_t polling_window;
> +
> +	int (*receive_buf)(struct serdev_device *, const unsigned char *,
> +			   size_t);
> +};
> +
> +int serdev_device_open(struct serdev_device *);
> +unsigned int serdev_device_set_baudrate(struct serdev_device *, unsigned int);
> +int serdev_device_write(struct serdev_device *, const unsigned char *,
> +			size_t, unsigned long);

So a serdev driver uses serdev_device_write() to send characters out. To
receive characters it has to implement serdev_device->receive_buf,
right? What kind of devices did you implement this for? For devices
which send data without request (GPS?) this seems the way to go. For
others a synchronous receive function might be good, no?

Sascha

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 3/3] serial: Check result of console_unregister()
  2018-03-26 13:09 ` [PATCH 3/3] serial: Check result of console_unregister() Andrey Smirnov
@ 2018-04-03  7:04   ` Sascha Hauer
  2018-04-09 16:00     ` Andrey Smirnov
  0 siblings, 1 reply; 12+ messages in thread
From: Sascha Hauer @ 2018-04-03  7:04 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: barebox

On Mon, Mar 26, 2018 at 06:09:15AM -0700, Andrey Smirnov wrote:
> In order to allow 'serdev' devices to prevent parent console device
> removal and correspondign memory deallocation add code to all serial
> driver to check result of console_unregister() and bail out early if
> it is unsuccessful.
> 
> One example of a use-case for this would be a reset handler relying on
> a serdev device for transport. Without this patch underlying console
> device would be removed and de-allocated before reset handler is even
> run thus leading to unpredictable behaviour and crashes.

Can't we make this sure at driver core level? So if a device decides not
to return -EBUSY in the remove callback then the parent devices won't be
removed?

Sascha


-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 3/3] serial: Check result of console_unregister()
  2018-04-03  7:04   ` Sascha Hauer
@ 2018-04-09 16:00     ` Andrey Smirnov
  2018-04-11  8:34       ` Sascha Hauer
  0 siblings, 1 reply; 12+ messages in thread
From: Andrey Smirnov @ 2018-04-09 16:00 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: Barebox List

On Tue, Apr 3, 2018 at 12:04 AM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> On Mon, Mar 26, 2018 at 06:09:15AM -0700, Andrey Smirnov wrote:
>> In order to allow 'serdev' devices to prevent parent console device
>> removal and correspondign memory deallocation add code to all serial
>> driver to check result of console_unregister() and bail out early if
>> it is unsuccessful.
>>
>> One example of a use-case for this would be a reset handler relying on
>> a serdev device for transport. Without this patch underlying console
>> device would be removed and de-allocated before reset handler is even
>> run thus leading to unpredictable behaviour and crashes.
>
> Can't we make this sure at driver core level?

I need to be able to prevent serial driver's "remove" function from
ever executing to prevent any de-initialization/memory freeing from
happening. The simplest way to solve this in driver core that comes to
my mind is implementing simple reference counting API that children
could use to force driver core to bail out on removing parents if they
are still in use. Does that sound like a reasonable idea?

> So if a device decides not
> to return -EBUSY in the remove callback then the parent devices won't be
> removed?

Remove callback currently returns void, we could change it to return
int and use it to implement a sort of implicit refcounting, but doing
so would result in quite a bit of code churn since all of the current
drivers would have to be converted to return int in their .remove
callbacks. Would you rather I do this or explicit refcounting?

Thanks,
Andrey Smirnov

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel
  2018-04-03  6:54   ` Sascha Hauer
@ 2018-04-09 16:40     ` Andrey Smirnov
  2018-04-11  8:39       ` Sascha Hauer
  0 siblings, 1 reply; 12+ messages in thread
From: Andrey Smirnov @ 2018-04-09 16:40 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: Barebox List

On Mon, Apr 2, 2018 at 11:54 PM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> Hi Andrey,
>
> Some comments inside.
>
>
> On Mon, Mar 26, 2018 at 06:09:14AM -0700, Andrey Smirnov wrote:
>> Port 'serdev' UART-slave deivce framework found in recent Linux
>> kernels (post 4.13) in order to be able to port 'serdev' slave drivers
>> from Linux.
>>
>> Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
>> @@ -323,6 +324,17 @@ int console_register(struct console_device *newcdev)
>>               dev->parent = newcdev->dev;
>>       platform_device_register(dev);
>>
>> +     newcdev->open_count = 0;
>> +
>> +     /*
>> +      * If our console deive is a serdev, we skip the creation of
>
> s/deive/device/

Will fix in v2.

>
>> +      * corresponding entry in /dev as well as registration in
>> +      * console_list and just go straigh to populating child
>
> s/straigh/straight/

Ditto.

>
>> +      * devices.
>> +      */
>> +     if (serdev_node)
>> +             return of_platform_populate(serdev_node, NULL, dev);
>
> How is this going to be used? A serdev driver binds to the serdev_node
> and then it probably needs to get a pointer to the console device,
> right? How does the driver accomplish this?
>

Serdev slave driver doesn't hold explicit pointer to console device,
instead accessing it via point to serdev_device. The latter could
obtained by calling to_serdev_device(dev->parent), where dev is
device_d given to slave driver's probe function.


>> +/**
>> + * struct serdev_device - Basic representation of an serdev device
>> + *
>> + * @dev:             Corresponding device
>> + * @fifo:            Circular buffer used for console draining
>> + * @buf:             Buffer used to pass Rx data to consumers
>> + * @poller           Async poller used to poll this serdev
>> + * @polling_interval:        Async poller periodicity
>> + * @polling_window:  Duration of a single busy loop poll
>> + * @receive_buf:     Function called with data received from device;
>> + *                   returns number of bytes accepted;
>> + */
>> +struct serdev_device {
>> +     struct device_d *dev;
>> +     struct kfifo *fifo;
>> +     unsigned char *buf;
>> +     struct poller_async poller;
>> +     uint64_t polling_interval;
>> +     uint64_t polling_window;
>> +
>> +     int (*receive_buf)(struct serdev_device *, const unsigned char *,
>> +                        size_t);
>> +};
>> +
>> +int serdev_device_open(struct serdev_device *);
>> +unsigned int serdev_device_set_baudrate(struct serdev_device *, unsigned int);
>> +int serdev_device_write(struct serdev_device *, const unsigned char *,
>> +                     size_t, unsigned long);
>
> So a serdev driver uses serdev_device_write() to send characters out. To
> receive characters it has to implement serdev_device->receive_buf,
> right?

Right. I tried to implement exactly the same API that Linux's serdev
API provides.

> What kind of devices did you implement this for?

I ported serdev in support of porting the driver for RAVE SP which is
a small microcontroller device found many ZII board including RDU2. It
implement a whole bunch of various functionality including watchdog,
parameter EEPROM, sensor access, backlight control, button input event
generation, etc.

> For devices which send data without request (GPS?) this seems the way to go. For
> others a synchronous receive function might be good, no?
>

I didn't implement anything like that mostly because Linux serdev API
doesn't and any ported driver wouldn't have any need for those
functions. But in general, I am not sure how useful synchronous
receive function would be. In my experience, devices like that usually
implement some binary transport protocol with packetization/escape
sequences on top of UART, which usually requires a state machine
operating with byte granularity as the data comes in to parse
responses correctly and synchronous APIs are not extremely useful for
that kind of a use-case.

FWIW, since serdev API is integrated into poller infrastructure it is
pretty trivial to write blocking code with it. Here's how I use it in
my driver to implement request-response type of a function:

rave_sp_write(sp, data, data_size);
/*
* is_timeout will implicitly poll serdev via poller
* infrastructure
*/
while (!is_timeout(start, SECOND) && !reply.received)
   ;


Thanks,
Andrey Smirnov

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 3/3] serial: Check result of console_unregister()
  2018-04-09 16:00     ` Andrey Smirnov
@ 2018-04-11  8:34       ` Sascha Hauer
  2018-04-12 18:20         ` Andrey Smirnov
  0 siblings, 1 reply; 12+ messages in thread
From: Sascha Hauer @ 2018-04-11  8:34 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: Barebox List

Hi Andrey,

On Mon, Apr 09, 2018 at 09:00:52AM -0700, Andrey Smirnov wrote:
> On Tue, Apr 3, 2018 at 12:04 AM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> > On Mon, Mar 26, 2018 at 06:09:15AM -0700, Andrey Smirnov wrote:
> >> In order to allow 'serdev' devices to prevent parent console device
> >> removal and correspondign memory deallocation add code to all serial
> >> driver to check result of console_unregister() and bail out early if
> >> it is unsuccessful.
> >>
> >> One example of a use-case for this would be a reset handler relying on
> >> a serdev device for transport. Without this patch underlying console
> >> device would be removed and de-allocated before reset handler is even
> >> run thus leading to unpredictable behaviour and crashes.
> >
> > Can't we make this sure at driver core level?
> 
> I need to be able to prevent serial driver's "remove" function from
> ever executing to prevent any de-initialization/memory freeing from
> happening. The simplest way to solve this in driver core that comes to
> my mind is implementing simple reference counting API that children
> could use to force driver core to bail out on removing parents if they
> are still in use. Does that sound like a reasonable idea?
> 
> > So if a device decides not
> > to return -EBUSY in the remove callback then the parent devices won't be
> > removed?
> 
> Remove callback currently returns void, we could change it to return
> int and use it to implement a sort of implicit refcounting, but doing
> so would result in quite a bit of code churn since all of the current
> drivers would have to be converted to return int in their .remove
> callbacks. Would you rather I do this or explicit refcounting?

Normally it helps looking at the Linux kernel to see how a problem is
solved there. Not so this time it seems. Linux distinguishes between
"remove" and "shutdown". "shutdown" is what we want during barebox
shutdown. I found a Linux driver that is similar to your situation: It
registers a restart_handler while being a i2c device itself. There seems
to be no way to prevent a device from being shutdown, it's only that the
i2c bus drivers simply do not implement it.

Where do we go from here? I think reference counting is a bit over the
top.

At the moment I would opt for a *very* simple solution: Let's drop the
call to console_unregister() and the freeing of resources entirely as
it gives us nothing. The only console driver I can see where removing
is valid is drivers/usb/gadget/u_serial.c and you won't use this for
restarting a SoC ;)

Sascha

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel
  2018-04-09 16:40     ` Andrey Smirnov
@ 2018-04-11  8:39       ` Sascha Hauer
  2018-04-12 18:22         ` Andrey Smirnov
  0 siblings, 1 reply; 12+ messages in thread
From: Sascha Hauer @ 2018-04-11  8:39 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: Barebox List

On Mon, Apr 09, 2018 at 09:40:46AM -0700, Andrey Smirnov wrote:
> On Mon, Apr 2, 2018 at 11:54 PM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> > Hi Andrey,
> >
> > Some comments inside.
> >
> >
> > On Mon, Mar 26, 2018 at 06:09:14AM -0700, Andrey Smirnov wrote:
> >> Port 'serdev' UART-slave deivce framework found in recent Linux
> >> kernels (post 4.13) in order to be able to port 'serdev' slave drivers
> >> from Linux.
> >>
> >> Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
> >> @@ -323,6 +324,17 @@ int console_register(struct console_device *newcdev)
> >>               dev->parent = newcdev->dev;
> >>       platform_device_register(dev);
> >>
> >> +     newcdev->open_count = 0;
> >> +
> >> +     /*
> >> +      * If our console deive is a serdev, we skip the creation of
> >
> > s/deive/device/
> 
> Will fix in v2.
> 
> >
> >> +      * corresponding entry in /dev as well as registration in
> >> +      * console_list and just go straigh to populating child
> >
> > s/straigh/straight/
> 
> Ditto.
> 
> >
> >> +      * devices.
> >> +      */
> >> +     if (serdev_node)
> >> +             return of_platform_populate(serdev_node, NULL, dev);
> >
> > How is this going to be used? A serdev driver binds to the serdev_node
> > and then it probably needs to get a pointer to the console device,
> > right? How does the driver accomplish this?
> >
> 
> Serdev slave driver doesn't hold explicit pointer to console device,
> instead accessing it via point to serdev_device. The latter could
> obtained by calling to_serdev_device(dev->parent), where dev is
> device_d given to slave driver's probe function.
> 
> 
> >> +/**
> >> + * struct serdev_device - Basic representation of an serdev device
> >> + *
> >> + * @dev:             Corresponding device
> >> + * @fifo:            Circular buffer used for console draining
> >> + * @buf:             Buffer used to pass Rx data to consumers
> >> + * @poller           Async poller used to poll this serdev
> >> + * @polling_interval:        Async poller periodicity
> >> + * @polling_window:  Duration of a single busy loop poll
> >> + * @receive_buf:     Function called with data received from device;
> >> + *                   returns number of bytes accepted;
> >> + */
> >> +struct serdev_device {
> >> +     struct device_d *dev;
> >> +     struct kfifo *fifo;
> >> +     unsigned char *buf;
> >> +     struct poller_async poller;
> >> +     uint64_t polling_interval;
> >> +     uint64_t polling_window;
> >> +
> >> +     int (*receive_buf)(struct serdev_device *, const unsigned char *,
> >> +                        size_t);
> >> +};
> >> +
> >> +int serdev_device_open(struct serdev_device *);
> >> +unsigned int serdev_device_set_baudrate(struct serdev_device *, unsigned int);
> >> +int serdev_device_write(struct serdev_device *, const unsigned char *,
> >> +                     size_t, unsigned long);
> >
> > So a serdev driver uses serdev_device_write() to send characters out. To
> > receive characters it has to implement serdev_device->receive_buf,
> > right?
> 
> Right. I tried to implement exactly the same API that Linux's serdev
> API provides.
> 
> > What kind of devices did you implement this for?
> 
> I ported serdev in support of porting the driver for RAVE SP which is
> a small microcontroller device found many ZII board including RDU2. It
> implement a whole bunch of various functionality including watchdog,
> parameter EEPROM, sensor access, backlight control, button input event
> generation, etc.
> 
> > For devices which send data without request (GPS?) this seems the way to go. For
> > others a synchronous receive function might be good, no?
> >
> 
> I didn't implement anything like that mostly because Linux serdev API
> doesn't and any ported driver wouldn't have any need for those
> functions. But in general, I am not sure how useful synchronous
> receive function would be. In my experience, devices like that usually
> implement some binary transport protocol with packetization/escape
> sequences on top of UART, which usually requires a state machine
> operating with byte granularity as the data comes in to parse
> responses correctly and synchronous APIs are not extremely useful for
> that kind of a use-case.
> 
> FWIW, since serdev API is integrated into poller infrastructure it is
> pretty trivial to write blocking code with it. Here's how I use it in
> my driver to implement request-response type of a function:
> 
> rave_sp_write(sp, data, data_size);
> /*
> * is_timeout will implicitly poll serdev via poller
> * infrastructure
> */
> while (!is_timeout(start, SECOND) && !reply.received)
>    ;

I understand that synchronous receiving might not be that useful. Given
how simple it is we could add a synchronous receive wrapper function
just for the sake of completeness, even if it only provides an example
how the code can be used.

Sascha

-- 
Pengutronix e.K.                           |                             |
Industrial Linux Solutions                 | http://www.pengutronix.de/  |
Peiner Str. 6-8, 31137 Hildesheim, Germany | Phone: +49-5121-206917-0    |
Amtsgericht Hildesheim, HRA 2686           | Fax:   +49-5121-206917-5555 |

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 3/3] serial: Check result of console_unregister()
  2018-04-11  8:34       ` Sascha Hauer
@ 2018-04-12 18:20         ` Andrey Smirnov
  0 siblings, 0 replies; 12+ messages in thread
From: Andrey Smirnov @ 2018-04-12 18:20 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: Barebox List

On Wed, Apr 11, 2018 at 1:34 AM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> Hi Andrey,
>
> On Mon, Apr 09, 2018 at 09:00:52AM -0700, Andrey Smirnov wrote:
>> On Tue, Apr 3, 2018 at 12:04 AM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
>> > On Mon, Mar 26, 2018 at 06:09:15AM -0700, Andrey Smirnov wrote:
>> >> In order to allow 'serdev' devices to prevent parent console device
>> >> removal and correspondign memory deallocation add code to all serial
>> >> driver to check result of console_unregister() and bail out early if
>> >> it is unsuccessful.
>> >>
>> >> One example of a use-case for this would be a reset handler relying on
>> >> a serdev device for transport. Without this patch underlying console
>> >> device would be removed and de-allocated before reset handler is even
>> >> run thus leading to unpredictable behaviour and crashes.
>> >
>> > Can't we make this sure at driver core level?
>>
>> I need to be able to prevent serial driver's "remove" function from
>> ever executing to prevent any de-initialization/memory freeing from
>> happening. The simplest way to solve this in driver core that comes to
>> my mind is implementing simple reference counting API that children
>> could use to force driver core to bail out on removing parents if they
>> are still in use. Does that sound like a reasonable idea?
>>
>> > So if a device decides not
>> > to return -EBUSY in the remove callback then the parent devices won't be
>> > removed?
>>
>> Remove callback currently returns void, we could change it to return
>> int and use it to implement a sort of implicit refcounting, but doing
>> so would result in quite a bit of code churn since all of the current
>> drivers would have to be converted to return int in their .remove
>> callbacks. Would you rather I do this or explicit refcounting?
>
> Normally it helps looking at the Linux kernel to see how a problem is
> solved there. Not so this time it seems. Linux distinguishes between
> "remove" and "shutdown". "shutdown" is what we want during barebox
> shutdown. I found a Linux driver that is similar to your situation: It
> registers a restart_handler while being a i2c device itself. There seems
> to be no way to prevent a device from being shutdown, it's only that the
> i2c bus drivers simply do not implement it.
>
> Where do we go from here? I think reference counting is a bit over the
> top.
>
> At the moment I would opt for a *very* simple solution: Let's drop the
> call to console_unregister() and the freeing of resources entirely as
> it gives us nothing. The only console driver I can see where removing
> is valid is drivers/usb/gadget/u_serial.c and you won't use this for
> restarting a SoC ;)
>

OK, makes sense and works for me. Will do in v2.

Thanks,
Andrey Smirnov

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

* Re: [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel
  2018-04-11  8:39       ` Sascha Hauer
@ 2018-04-12 18:22         ` Andrey Smirnov
  0 siblings, 0 replies; 12+ messages in thread
From: Andrey Smirnov @ 2018-04-12 18:22 UTC (permalink / raw)
  To: Sascha Hauer; +Cc: Barebox List

On Wed, Apr 11, 2018 at 1:39 AM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
> On Mon, Apr 09, 2018 at 09:40:46AM -0700, Andrey Smirnov wrote:
>> On Mon, Apr 2, 2018 at 11:54 PM, Sascha Hauer <s.hauer@pengutronix.de> wrote:
>> > Hi Andrey,
>> >
>> > Some comments inside.
>> >
>> >
>> > On Mon, Mar 26, 2018 at 06:09:14AM -0700, Andrey Smirnov wrote:
>> >> Port 'serdev' UART-slave deivce framework found in recent Linux
>> >> kernels (post 4.13) in order to be able to port 'serdev' slave drivers
>> >> from Linux.
>> >>
>> >> Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
>> >> @@ -323,6 +324,17 @@ int console_register(struct console_device *newcdev)
>> >>               dev->parent = newcdev->dev;
>> >>       platform_device_register(dev);
>> >>
>> >> +     newcdev->open_count = 0;
>> >> +
>> >> +     /*
>> >> +      * If our console deive is a serdev, we skip the creation of
>> >
>> > s/deive/device/
>>
>> Will fix in v2.
>>
>> >
>> >> +      * corresponding entry in /dev as well as registration in
>> >> +      * console_list and just go straigh to populating child
>> >
>> > s/straigh/straight/
>>
>> Ditto.
>>
>> >
>> >> +      * devices.
>> >> +      */
>> >> +     if (serdev_node)
>> >> +             return of_platform_populate(serdev_node, NULL, dev);
>> >
>> > How is this going to be used? A serdev driver binds to the serdev_node
>> > and then it probably needs to get a pointer to the console device,
>> > right? How does the driver accomplish this?
>> >
>>
>> Serdev slave driver doesn't hold explicit pointer to console device,
>> instead accessing it via point to serdev_device. The latter could
>> obtained by calling to_serdev_device(dev->parent), where dev is
>> device_d given to slave driver's probe function.
>>
>>
>> >> +/**
>> >> + * struct serdev_device - Basic representation of an serdev device
>> >> + *
>> >> + * @dev:             Corresponding device
>> >> + * @fifo:            Circular buffer used for console draining
>> >> + * @buf:             Buffer used to pass Rx data to consumers
>> >> + * @poller           Async poller used to poll this serdev
>> >> + * @polling_interval:        Async poller periodicity
>> >> + * @polling_window:  Duration of a single busy loop poll
>> >> + * @receive_buf:     Function called with data received from device;
>> >> + *                   returns number of bytes accepted;
>> >> + */
>> >> +struct serdev_device {
>> >> +     struct device_d *dev;
>> >> +     struct kfifo *fifo;
>> >> +     unsigned char *buf;
>> >> +     struct poller_async poller;
>> >> +     uint64_t polling_interval;
>> >> +     uint64_t polling_window;
>> >> +
>> >> +     int (*receive_buf)(struct serdev_device *, const unsigned char *,
>> >> +                        size_t);
>> >> +};
>> >> +
>> >> +int serdev_device_open(struct serdev_device *);
>> >> +unsigned int serdev_device_set_baudrate(struct serdev_device *, unsigned int);
>> >> +int serdev_device_write(struct serdev_device *, const unsigned char *,
>> >> +                     size_t, unsigned long);
>> >
>> > So a serdev driver uses serdev_device_write() to send characters out. To
>> > receive characters it has to implement serdev_device->receive_buf,
>> > right?
>>
>> Right. I tried to implement exactly the same API that Linux's serdev
>> API provides.
>>
>> > What kind of devices did you implement this for?
>>
>> I ported serdev in support of porting the driver for RAVE SP which is
>> a small microcontroller device found many ZII board including RDU2. It
>> implement a whole bunch of various functionality including watchdog,
>> parameter EEPROM, sensor access, backlight control, button input event
>> generation, etc.
>>
>> > For devices which send data without request (GPS?) this seems the way to go. For
>> > others a synchronous receive function might be good, no?
>> >
>>
>> I didn't implement anything like that mostly because Linux serdev API
>> doesn't and any ported driver wouldn't have any need for those
>> functions. But in general, I am not sure how useful synchronous
>> receive function would be. In my experience, devices like that usually
>> implement some binary transport protocol with packetization/escape
>> sequences on top of UART, which usually requires a state machine
>> operating with byte granularity as the data comes in to parse
>> responses correctly and synchronous APIs are not extremely useful for
>> that kind of a use-case.
>>
>> FWIW, since serdev API is integrated into poller infrastructure it is
>> pretty trivial to write blocking code with it. Here's how I use it in
>> my driver to implement request-response type of a function:
>>
>> rave_sp_write(sp, data, data_size);
>> /*
>> * is_timeout will implicitly poll serdev via poller
>> * infrastructure
>> */
>> while (!is_timeout(start, SECOND) && !reply.received)
>>    ;
>
> I understand that synchronous receiving might not be that useful. Given
> how simple it is we could add a synchronous receive wrapper function
> just for the sake of completeness, even if it only provides an example
> how the code can be used.

OK, will do in v2.

Thanks,
Andrey Smirnov

_______________________________________________
barebox mailing list
barebox@lists.infradead.org
http://lists.infradead.org/mailman/listinfo/barebox

^ permalink raw reply	[flat|nested] 12+ messages in thread

end of thread, other threads:[~2018-04-12 18:22 UTC | newest]

Thread overview: 12+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2018-03-26 13:09 [PATCH 0/3] Linux's serdev framwork port Andrey Smirnov
2018-03-26 13:09 ` [PATCH 1/3] console: Introduce console_drain() Andrey Smirnov
2018-03-26 13:09 ` [PATCH 2/3] console: Add simplified 'serdev' framework from Linux kernel Andrey Smirnov
2018-04-03  6:54   ` Sascha Hauer
2018-04-09 16:40     ` Andrey Smirnov
2018-04-11  8:39       ` Sascha Hauer
2018-04-12 18:22         ` Andrey Smirnov
2018-03-26 13:09 ` [PATCH 3/3] serial: Check result of console_unregister() Andrey Smirnov
2018-04-03  7:04   ` Sascha Hauer
2018-04-09 16:00     ` Andrey Smirnov
2018-04-11  8:34       ` Sascha Hauer
2018-04-12 18:20         ` Andrey Smirnov

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox