mail archive of the barebox mailing list
 help / color / mirror / Atom feed
* [PATCH v2 0/5] Linux's serdev framwork port
@ 2018-04-12 21:33 Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 1/5] console: Introduce console_drain() Andrey Smirnov
                   ` (5 more replies)
  0 siblings, 6 replies; 7+ messages in thread
From: Andrey Smirnov @ 2018-04-12 21:33 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.

Changes since [v1]:

	- Blocking read function was added as example of API usage

	- "serial: Check result of console_unregister()" was converted
          to become "serial: Drop .remove functions from all drivers"

	- Minor spelling fixes

	- Original serdev framework patch modified to allow devices
          that do not require polling (I don't have such a usecase,
          but for the sake of being generic I added one line needed
          for that)

	- SERIAL_DEV_BUS Kconfig symbol moved into
          drivers/serial/Kconfig (where it, IMHO, fits much better)

	- Added a patch to dynamically adjust serdev's polling
          interval via device paramter. This was warranted by the
          problems that arose from real-life usage.

Feedback is wellcome!

Thanks,
Andrey Smirnov

[v1] https://www.spinics.net/lists/u-boot-v2/msg32322.html

Andrey Smirnov (5):
  console: Introduce console_drain()
  console: Add simplified 'serdev' framework from Linux kernel
  serdev: Add trivial blocking read function
  serial: Drop .remove functions from all drivers
  serdev: Allow polling interval to be adjusted at runtime

 common/Makefile                  |   1 +
 common/console.c                 |  24 ++++-
 common/serdev.c                  | 208 +++++++++++++++++++++++++++++++++++++++
 drivers/serial/Kconfig           |   6 ++
 drivers/serial/serial_auart.c    |  11 ---
 drivers/serial/serial_cadence.c  |   9 --
 drivers/serial/serial_clps711x.c |  10 --
 drivers/serial/serial_imx.c      |  10 --
 drivers/serial/serial_lpuart.c   |  13 ---
 drivers/serial/serial_pxa.c      |   9 --
 drivers/serial/serial_s3c.c      |  10 --
 drivers/serial/stm-serial.c      |  10 --
 include/console.h                | 110 +++++++++++++++++++++
 include/serdev.h                 |  44 +++++++++
 lib/xymodem.c                    |  30 +-----
 15 files changed, 395 insertions(+), 110 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] 7+ messages in thread

* [PATCH v2 1/5] console: Introduce console_drain()
  2018-04-12 21:33 [PATCH v2 0/5] Linux's serdev framwork port Andrey Smirnov
@ 2018-04-12 21:33 ` Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 2/5] console: Add simplified 'serdev' framework from Linux kernel Andrey Smirnov
                   ` (4 subsequent siblings)
  5 siblings, 0 replies; 7+ messages in thread
From: Andrey Smirnov @ 2018-04-12 21:33 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 3c14e3593..0f1fced93 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 37202e6ae..9e4ce58b6 100644
--- a/lib/xymodem.c
+++ b/lib/xymodem.c
@@ -144,36 +144,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] 7+ messages in thread

* [PATCH v2 2/5] console: Add simplified 'serdev' framework from Linux kernel
  2018-04-12 21:33 [PATCH v2 0/5] Linux's serdev framwork port Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 1/5] console: Introduce console_drain() Andrey Smirnov
@ 2018-04-12 21:33 ` Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 3/5] serdev: Add trivial blocking read function Andrey Smirnov
                   ` (3 subsequent siblings)
  5 siblings, 0 replies; 7+ messages in thread
From: Andrey Smirnov @ 2018-04-12 21:33 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/Makefile        |  1 +
 common/console.c       | 24 ++++++++++++--
 common/serdev.c        | 89 ++++++++++++++++++++++++++++++++++++++++++++++++++
 drivers/serial/Kconfig |  6 ++++
 include/console.h      | 27 +++++++++++++++
 include/serdev.h       | 36 ++++++++++++++++++++
 6 files changed, 180 insertions(+), 3 deletions(-)
 create mode 100644 common/serdev.c
 create mode 100644 include/serdev.h

diff --git a/common/Makefile b/common/Makefile
index 4e9681f20..1ff7d2370 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..ab3d4d397 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 device is a serdev, we skip the creation of
+	 * corresponding entry in /dev as well as registration in
+	 * console_list and just go straight 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..32743738e
--- /dev/null
+++ b/common/serdev.c
@@ -0,0 +1,89 @@
+
+#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;
+	}
+
+	if (serdev->polling_interval) {
+		/*
+		 * 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)
+		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/drivers/serial/Kconfig b/drivers/serial/Kconfig
index cfddc2ee9..8a56d39f7 100644
--- a/drivers/serial/Kconfig
+++ b/drivers/serial/Kconfig
@@ -1,6 +1,12 @@
 menu "serial drivers"
 	depends on !CONSOLE_NONE
 
+config SERIAL_DEV_BUS
+	bool "Serial device bus"
+	depends on CONSOLE_FULL
+	help
+	  Core support for devices connected via a serial port.
+
 config DRIVER_SERIAL_ARM_DCC
 	depends on ARM && !CPU_V8
 	bool "ARM Debug Communications Channel (DCC) serial driver"
diff --git a/include/console.h b/include/console.h
index 0f1fced93..6d3e6e123 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 cdev_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] 7+ messages in thread

* [PATCH v2 3/5] serdev: Add trivial blocking read function
  2018-04-12 21:33 [PATCH v2 0/5] Linux's serdev framwork port Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 1/5] console: Introduce console_drain() Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 2/5] console: Add simplified 'serdev' framework from Linux kernel Andrey Smirnov
@ 2018-04-12 21:33 ` Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 4/5] serial: Drop .remove functions from all drivers Andrey Smirnov
                   ` (2 subsequent siblings)
  5 siblings, 0 replies; 7+ messages in thread
From: Andrey Smirnov @ 2018-04-12 21:33 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Add example implementation of a trivial blocking read function as a
part of Barebox's serdev API.

NOTE: This code has not been tested against real devices, so use it at
your own risk.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 common/serdev.c  | 95 ++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 include/serdev.h |  8 +++++
 2 files changed, 103 insertions(+)

diff --git a/common/serdev.c b/common/serdev.c
index 32743738e..50eadc804 100644
--- a/common/serdev.c
+++ b/common/serdev.c
@@ -87,3 +87,98 @@ int serdev_device_write(struct serdev_device *serdev, const unsigned char *buf,
 	serdev_device_poller(serdev);
 	return 0;
 }
+
+/*
+ * NOTE: Code below is given primarily as an example of serdev API
+ * usage. It may or may not be as useful or work as well as the
+ * functions above.
+ */
+
+struct serdev_device_reader {
+	unsigned char *buf;
+	size_t len;
+	size_t capacity;
+};
+
+static int serdev_device_reader_receive_buf(struct serdev_device *serdev,
+					    const unsigned char *buf,
+					    size_t size)
+{
+	struct device_d *dev = serdev->dev;
+	struct serdev_device_reader *r = dev->priv;
+	const size_t room = min(r->capacity - r->len, size);
+
+	memcpy(r->buf + r->len, buf, room);
+	r->len += room;
+	/*
+	 * It's important we return 'size' even if we didn't trully
+	 * consume all of the data, since otherwise serdev will keep
+	 * re-executing us until we do. Given the logic above that
+	 * would mean infinite loop.
+	 */
+	return size;
+}
+
+/**
+ * serdev_device_reader_open - Open a reader serdev device
+ *
+ * @serdev:	Underlying serdev device
+ * @capacity:	Storage capacity of the reader
+ *
+ * This function is inteded for creating of reader serdev devices that
+ * can be used in conjunction with serdev_device_read() to perform
+ * trivial fixed length reads from a serdev device.
+ */
+int serdev_device_reader_open(struct serdev_device *serdev, size_t capacity)
+{
+	struct serdev_device_reader *r;
+
+	if (serdev->receive_buf)
+		return -EINVAL;
+
+	r = xzalloc(sizeof(*r));
+	r->capacity = capacity;
+	r->buf = xzalloc(capacity);
+
+	serdev->receive_buf = serdev_device_reader_receive_buf;
+	serdev->dev->priv   = r;
+
+	return 0;
+}
+
+/**
+ * serdev_device_read - Read data from serdev device
+ *
+ * @serdev:	Serdev device to read from (must be a serdev reader)
+ * @buf:	Buffer to read data into
+ * @count:	Number of bytes to read
+ * @timeout:	Read operation timeout
+ *
+ */
+int serdev_device_read(struct serdev_device *serdev, unsigned char *buf,
+		       size_t count, unsigned long timeout)
+{
+	struct device_d *dev = serdev->dev;
+	struct serdev_device_reader *r = dev->priv;
+	int ret;
+
+	uint64_t start = get_time_ns();
+
+	if (serdev->receive_buf != serdev_device_reader_receive_buf)
+		return -EINVAL;
+
+	/*
+	 * is_timeout will implicitly poll serdev via poller
+	 * infrastructure
+	 */
+	while (r->len < count) {
+		if (is_timeout(start, timeout))
+			return -ETIMEDOUT;
+	}
+
+	memcpy(buf, r->buf, count);
+	ret = (r->len == count) ? 0 : -EMSGSIZE;
+	r->len = 0;
+
+	return ret;
+}
diff --git a/include/serdev.h b/include/serdev.h
index efc735fed..f5d34f527 100644
--- a/include/serdev.h
+++ b/include/serdev.h
@@ -33,4 +33,12 @@ 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);
+
+/*
+ * The following two functions are not a part of original Linux API
+ */
+int serdev_device_reader_open(struct serdev_device *, size_t);
+int serdev_device_read(struct serdev_device *, 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] 7+ messages in thread

* [PATCH v2 4/5] serial: Drop .remove functions from all drivers
  2018-04-12 21:33 [PATCH v2 0/5] Linux's serdev framwork port Andrey Smirnov
                   ` (2 preceding siblings ...)
  2018-04-12 21:33 ` [PATCH v2 3/5] serdev: Add trivial blocking read function Andrey Smirnov
@ 2018-04-12 21:33 ` Andrey Smirnov
  2018-04-12 21:33 ` [PATCH v2 5/5] serdev: Allow polling interval to be adjusted at runtime Andrey Smirnov
  2018-04-16  7:00 ` [PATCH v2 0/5] Linux's serdev framwork port Sascha Hauer
  5 siblings, 0 replies; 7+ messages in thread
From: Andrey Smirnov @ 2018-04-12 21:33 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Depending on specifics, some 'serdev' devices might need prevent
parent console device from being removed and corresponding memory
deallocated to properly function until the very end of Barebox's
execution. An example of such a use-case would be a reset handler
relying on a serdev device for transport.

To avoid having to develop complicatione reference counting/ownership
scheme drop all of the code that calls console_unregister() and frees
the memory effectively making the problem above impossible to arise.

All of the de-initialization that serial drivers were doing in their
.remove functions was somewhat superflous anyway, so this change
should be pretty harmless.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 drivers/serial/serial_auart.c    | 11 -----------
 drivers/serial/serial_cadence.c  |  9 ---------
 drivers/serial/serial_clps711x.c | 10 ----------
 drivers/serial/serial_imx.c      | 10 ----------
 drivers/serial/serial_lpuart.c   | 13 -------------
 drivers/serial/serial_pxa.c      |  9 ---------
 drivers/serial/serial_s3c.c      | 10 ----------
 drivers/serial/stm-serial.c      | 10 ----------
 8 files changed, 82 deletions(-)

diff --git a/drivers/serial/serial_auart.c b/drivers/serial/serial_auart.c
index c3b9a1995..05cc75797 100644
--- a/drivers/serial/serial_auart.c
+++ b/drivers/serial/serial_auart.c
@@ -220,16 +220,6 @@ static int auart_serial_probe(struct device_d *dev)
 	return 0;
 }
 
-
-static void auart_serial_remove(struct device_d *dev)
-{
-	struct auart_priv *priv = dev->priv;
-
-	auart_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
-	free(priv);
-}
-
 static const __maybe_unused struct of_device_id auart_serial_dt_ids[] = {
 	{
 		.compatible = "fsl,imx23-auart",
@@ -241,7 +231,6 @@ static const __maybe_unused struct of_device_id auart_serial_dt_ids[] = {
 static struct driver_d auart_serial_driver = {
 	.name = "auart_serial",
 	.probe = auart_serial_probe,
-	.remove = auart_serial_remove,
 	.of_compatible = DRV_OF_COMPAT(auart_serial_dt_ids),
 };
 console_platform_driver(auart_serial_driver);
diff --git a/drivers/serial/serial_cadence.c b/drivers/serial/serial_cadence.c
index 36dfa2084..0501c400b 100644
--- a/drivers/serial/serial_cadence.c
+++ b/drivers/serial/serial_cadence.c
@@ -267,14 +267,6 @@ err_free:
 	return ret;
 }
 
-static void cadence_serial_remove(struct device_d *dev)
-{
-	struct cadence_serial_priv *priv = dev->priv;
-
-	console_unregister(&priv->cdev);
-	free(priv);
-}
-
 static __maybe_unused struct of_device_id cadence_serial_dt_ids[] = {
 	{
 		.compatible = "xlnx,xuartps",
@@ -296,7 +288,6 @@ static struct platform_device_id cadence_serial_ids[] = {
 static struct driver_d cadence_serial_driver = {
 	.name   = "cadence_serial",
 	.probe  = cadence_serial_probe,
-	.remove = cadence_serial_remove,
 	.of_compatible = DRV_OF_COMPAT(cadence_serial_dt_ids),
 	.id_table = cadence_serial_ids,
 };
diff --git a/drivers/serial/serial_clps711x.c b/drivers/serial/serial_clps711x.c
index ad14373ac..fa6342346 100644
--- a/drivers/serial/serial_clps711x.c
+++ b/drivers/serial/serial_clps711x.c
@@ -181,15 +181,6 @@ out_err:
 	return err;
 }
 
-static void clps711x_remove(struct device_d *dev)
-{
-	struct clps711x_uart *s = dev->priv;
-
-	clps711x_flush(&s->cdev);
-	console_unregister(&s->cdev);
-	free(s);
-}
-
 static struct of_device_id __maybe_unused clps711x_uart_dt_ids[] = {
 	{ .compatible = "cirrus,clps711x-uart", },
 };
@@ -197,7 +188,6 @@ static struct of_device_id __maybe_unused clps711x_uart_dt_ids[] = {
 static struct driver_d clps711x_driver = {
 	.name		= "clps711x-uart",
 	.probe		= clps711x_probe,
-	.remove		= clps711x_remove,
 	.of_compatible	= DRV_OF_COMPAT(clps711x_uart_dt_ids),
 };
 console_platform_driver(clps711x_driver);
diff --git a/drivers/serial/serial_imx.c b/drivers/serial/serial_imx.c
index e8c3836a6..c8af995aa 100644
--- a/drivers/serial/serial_imx.c
+++ b/drivers/serial/serial_imx.c
@@ -271,15 +271,6 @@ err_free:
 	return ret;
 }
 
-static void imx_serial_remove(struct device_d *dev)
-{
-	struct imx_serial_priv *priv = dev->priv;
-
-	imx_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
-	free(priv);
-}
-
 static __maybe_unused struct of_device_id imx_serial_dt_ids[] = {
 	{
 		.compatible = "fsl,imx1-uart",
@@ -313,7 +304,6 @@ static struct platform_device_id imx_serial_ids[] = {
 static struct driver_d imx_serial_driver = {
 	.name   = "imx_serial",
 	.probe  = imx_serial_probe,
-	.remove = imx_serial_remove,
 	.of_compatible = DRV_OF_COMPAT(imx_serial_dt_ids),
 	.id_table = imx_serial_ids,
 };
diff --git a/drivers/serial/serial_lpuart.c b/drivers/serial/serial_lpuart.c
index 8f87f7b9c..f28035a32 100644
--- a/drivers/serial/serial_lpuart.c
+++ b/drivers/serial/serial_lpuart.c
@@ -189,18 +189,6 @@ err_free:
 	return ret;
 }
 
-static void lpuart_serial_remove(struct device_d *dev)
-{
-	struct lpuart *lpuart = dev->priv;
-
-	lpuart_serial_flush(&lpuart->cdev);
-	console_unregister(&lpuart->cdev);
-	release_region(lpuart->io);
-	clk_put(lpuart->clk);
-
-	free(lpuart);
-}
-
 static struct of_device_id lpuart_serial_dt_ids[] = {
 	{ .compatible = "fsl,vf610-lpuart" },
 	{}
@@ -209,7 +197,6 @@ static struct of_device_id lpuart_serial_dt_ids[] = {
 static struct driver_d lpuart_serial_driver = {
 	.name   = "lpuart-serial",
 	.probe  = lpuart_serial_probe,
-	.remove = lpuart_serial_remove,
 	.of_compatible = DRV_OF_COMPAT(lpuart_serial_dt_ids),
 };
 console_platform_driver(lpuart_serial_driver);
diff --git a/drivers/serial/serial_pxa.c b/drivers/serial/serial_pxa.c
index 1a4d7b430..a427437b5 100644
--- a/drivers/serial/serial_pxa.c
+++ b/drivers/serial/serial_pxa.c
@@ -185,17 +185,8 @@ static int pxa_serial_probe(struct device_d *dev)
 	return 0;
 }
 
-static void pxa_serial_remove(struct device_d *dev)
-{
-	struct pxa_serial_priv *priv = dev->priv;
-
-	console_unregister(&priv->cdev);
-	free(priv);
-}
-
 static struct driver_d pxa_serial_driver = {
 	.name = "pxa_serial",
 	.probe = pxa_serial_probe,
-	.remove = pxa_serial_remove,
 };
 console_platform_driver(pxa_serial_driver);
diff --git a/drivers/serial/serial_s3c.c b/drivers/serial/serial_s3c.c
index 0a6e22d97..194556072 100644
--- a/drivers/serial/serial_s3c.c
+++ b/drivers/serial/serial_s3c.c
@@ -202,18 +202,8 @@ static int s3c_serial_probe(struct device_d *dev)
 	return 0;
 }
 
-static void s3c_serial_remove(struct device_d *dev)
-{
-	struct s3c_uart *priv= dev->priv;
-
-	s3c_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
-	free(priv);
-}
-
 static struct driver_d s3c_serial_driver = {
 	.name   = "s3c_serial",
 	.probe  = s3c_serial_probe,
-	.remove = s3c_serial_remove,
 };
 console_platform_driver(s3c_serial_driver);
diff --git a/drivers/serial/stm-serial.c b/drivers/serial/stm-serial.c
index 83328f455..ea482415c 100644
--- a/drivers/serial/stm-serial.c
+++ b/drivers/serial/stm-serial.c
@@ -182,15 +182,6 @@ static int stm_serial_probe(struct device_d *dev)
 	return 0;
 }
 
-static void stm_serial_remove(struct device_d *dev)
-{
-	struct stm_priv *priv = dev->priv;
-
-	stm_serial_flush(&priv->cdev);
-	console_unregister(&priv->cdev);
-	free(priv);
-}
-
 static __maybe_unused struct of_device_id stm_serial_dt_ids[] = {
 	{
 		.compatible = "arm,pl011",
@@ -202,7 +193,6 @@ static __maybe_unused struct of_device_id stm_serial_dt_ids[] = {
 static struct driver_d stm_serial_driver = {
         .name   = "stm_serial",
         .probe  = stm_serial_probe,
-	.remove = stm_serial_remove,
 	.of_compatible = DRV_OF_COMPAT(stm_serial_dt_ids),
 };
 console_platform_driver(stm_serial_driver);
-- 
2.14.3


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

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

* [PATCH v2 5/5] serdev: Allow polling interval to be adjusted at runtime
  2018-04-12 21:33 [PATCH v2 0/5] Linux's serdev framwork port Andrey Smirnov
                   ` (3 preceding siblings ...)
  2018-04-12 21:33 ` [PATCH v2 4/5] serial: Drop .remove functions from all drivers Andrey Smirnov
@ 2018-04-12 21:33 ` Andrey Smirnov
  2018-04-16  7:00 ` [PATCH v2 0/5] Linux's serdev framwork port Sascha Hauer
  5 siblings, 0 replies; 7+ messages in thread
From: Andrey Smirnov @ 2018-04-12 21:33 UTC (permalink / raw)
  To: barebox; +Cc: Andrey Smirnov

Due to blocking, synchronous, polling driven nature of Barebox's
serial communication handling trying to use two or more serial ports
at high (1Mbaud+) baudrates results in data loss and noticeable
perofmance degradation. This happens as soon as individual message
being sent around start exceeding HW Rx FIFO in size.

A good example of such a usecase would be using a system that has a
serdev driver (operating @ 1Mbaud+) and trying to do a X/YMODEM
transfer via serial console at comparable baudrates.

To at least partially ameliorate the problem, add code that will
expose "polling_interval" as a parameter, so that the user would have
an option of temporarily disabling (or significatly decreasing the
rate) of a given serdev's polling.

Signed-off-by: Andrey Smirnov <andrew.smirnov@gmail.com>
---
 common/serdev.c | 26 +++++++++++++++++++++++++-
 1 file changed, 25 insertions(+), 1 deletion(-)

diff --git a/common/serdev.c b/common/serdev.c
index 50eadc804..4a6dbefe6 100644
--- a/common/serdev.c
+++ b/common/serdev.c
@@ -34,12 +34,26 @@ static void serdev_device_poller(void *context)
 				  serdev->polling_interval,
 				  serdev_device_poller,
 				  serdev);
+	} else {
+		poller_async_cancel(&serdev->poller);
 	}
 }
 
+static int serdev_device_set_polling_interval(struct param_d *param, void *serdev)
+{
+	/*
+	 * We execute poller ever time polling_interval changes to get
+	 * any unprocessed immediate Rx data as well as to propagate
+	 * polling_interval chagnes to outstanging async pollers.
+	 */
+	serdev_device_poller(serdev);
+	return 0;
+}
+
 int serdev_device_open(struct serdev_device *serdev)
 {
 	struct console_device *cdev = to_console_device(serdev);
+	struct param_d *p;
 	int ret;
 
 	if (!cdev->putc || !cdev->getc)
@@ -57,7 +71,17 @@ int serdev_device_open(struct serdev_device *serdev)
 	if (ret)
 		return ret;
 
-	return console_open(cdev);
+	ret = console_open(cdev);
+	if (ret)
+		return ret;
+
+	p = dev_add_param_uint64(serdev->dev, "polling_interval",
+				 serdev_device_set_polling_interval, NULL,
+				 &serdev->polling_interval, "%llu", serdev);
+	if (IS_ERR(p))
+		return PTR_ERR(p);
+
+	return 0;
 }
 
 unsigned int serdev_device_set_baudrate(struct serdev_device *serdev,
-- 
2.14.3


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

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

* Re: [PATCH v2 0/5] Linux's serdev framwork port
  2018-04-12 21:33 [PATCH v2 0/5] Linux's serdev framwork port Andrey Smirnov
                   ` (4 preceding siblings ...)
  2018-04-12 21:33 ` [PATCH v2 5/5] serdev: Allow polling interval to be adjusted at runtime Andrey Smirnov
@ 2018-04-16  7:00 ` Sascha Hauer
  5 siblings, 0 replies; 7+ messages in thread
From: Sascha Hauer @ 2018-04-16  7:00 UTC (permalink / raw)
  To: Andrey Smirnov; +Cc: barebox

On Thu, Apr 12, 2018 at 02:33:12PM -0700, Andrey Smirnov wrote:
> 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.
> 
> Changes since [v1]:
> 
> 	- Blocking read function was added as example of API usage
> 
> 	- "serial: Check result of console_unregister()" was converted
>           to become "serial: Drop .remove functions from all drivers"
> 
> 	- Minor spelling fixes
> 
> 	- Original serdev framework patch modified to allow devices
>           that do not require polling (I don't have such a usecase,
>           but for the sake of being generic I added one line needed
>           for that)
> 
> 	- SERIAL_DEV_BUS Kconfig symbol moved into
>           drivers/serial/Kconfig (where it, IMHO, fits much better)
> 
> 	- Added a patch to dynamically adjust serdev's polling
>           interval via device paramter. This was warranted by the
>           problems that arose from real-life usage.
> 
> Feedback is wellcome!
> 
> Thanks,
> Andrey Smirnov
> 
> [v1] https://www.spinics.net/lists/u-boot-v2/msg32322.html

Applied, thanks

Sascha

> 
> Andrey Smirnov (5):
>   console: Introduce console_drain()
>   console: Add simplified 'serdev' framework from Linux kernel
>   serdev: Add trivial blocking read function
>   serial: Drop .remove functions from all drivers
>   serdev: Allow polling interval to be adjusted at runtime
> 
>  common/Makefile                  |   1 +
>  common/console.c                 |  24 ++++-
>  common/serdev.c                  | 208 +++++++++++++++++++++++++++++++++++++++
>  drivers/serial/Kconfig           |   6 ++
>  drivers/serial/serial_auart.c    |  11 ---
>  drivers/serial/serial_cadence.c  |   9 --
>  drivers/serial/serial_clps711x.c |  10 --
>  drivers/serial/serial_imx.c      |  10 --
>  drivers/serial/serial_lpuart.c   |  13 ---
>  drivers/serial/serial_pxa.c      |   9 --
>  drivers/serial/serial_s3c.c      |  10 --
>  drivers/serial/stm-serial.c      |  10 --
>  include/console.h                | 110 +++++++++++++++++++++
>  include/serdev.h                 |  44 +++++++++
>  lib/xymodem.c                    |  30 +-----
>  15 files changed, 395 insertions(+), 110 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
> 

-- 
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] 7+ messages in thread

end of thread, other threads:[~2018-04-16  7:01 UTC | newest]

Thread overview: 7+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2018-04-12 21:33 [PATCH v2 0/5] Linux's serdev framwork port Andrey Smirnov
2018-04-12 21:33 ` [PATCH v2 1/5] console: Introduce console_drain() Andrey Smirnov
2018-04-12 21:33 ` [PATCH v2 2/5] console: Add simplified 'serdev' framework from Linux kernel Andrey Smirnov
2018-04-12 21:33 ` [PATCH v2 3/5] serdev: Add trivial blocking read function Andrey Smirnov
2018-04-12 21:33 ` [PATCH v2 4/5] serial: Drop .remove functions from all drivers Andrey Smirnov
2018-04-12 21:33 ` [PATCH v2 5/5] serdev: Allow polling interval to be adjusted at runtime Andrey Smirnov
2018-04-16  7:00 ` [PATCH v2 0/5] Linux's serdev framwork port Sascha Hauer

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