* [RFC PATCH 1/3] uart bus: Introduce new bus for UART slave devices
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
@ 2016-08-18 1:14 ` Rob Herring
2016-08-18 1:14 ` [RFC PATCH 2/3] tty: serial_core: make tty_struct optional Rob Herring
` (8 subsequent siblings)
9 siblings, 0 replies; 103+ messages in thread
From: Rob Herring @ 2016-08-18 1:14 UTC (permalink / raw)
To: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel
Cc: Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, linux-bluetooth, linux-serial,
linux-kernel
The UART bus is designed for slave devices such as Bluetooth, WiFi, GPS
and NFC connected to UARTs on host processors. Tradionally these have
been handled with tty line disciplines, rfkill, and userspace glue such
as hci_attach. This approach has many drawbacks since it doesn't fit
into the Linux driver model. Handling of sideband signals, power control
and firmware loading are the main issues.
This creates a UART bus with controllers (i.e. host UARTs) and slave
devices. Typically, these are point to point connections, but some
devices have muxing protocols or a h/w mux is conceivable. Any muxing is
not yet supported.
Signed-off-by: Rob Herring <robh@kernel.org>
---
drivers/Kconfig | 2 +
drivers/Makefile | 1 +
drivers/uart/Kconfig | 17 ++
drivers/uart/Makefile | 3 +
drivers/uart/core.c | 458 ++++++++++++++++++++++++++++++++++++++++++++
drivers/uart/loopback.c | 72 +++++++
include/linux/uart_device.h | 163 ++++++++++++++++
7 files changed, 716 insertions(+)
create mode 100644 drivers/uart/Kconfig
create mode 100644 drivers/uart/Makefile
create mode 100644 drivers/uart/core.c
create mode 100644 drivers/uart/loopback.c
create mode 100644 include/linux/uart_device.h
diff --git a/drivers/Kconfig b/drivers/Kconfig
index e1e2066..9145494 100644
--- a/drivers/Kconfig
+++ b/drivers/Kconfig
@@ -202,4 +202,6 @@ source "drivers/hwtracing/intel_th/Kconfig"
source "drivers/fpga/Kconfig"
+source "drivers/uart/Kconfig"
+
endmenu
diff --git a/drivers/Makefile b/drivers/Makefile
index 53abb4a..c915417 100644
--- a/drivers/Makefile
+++ b/drivers/Makefile
@@ -173,3 +173,4 @@ obj-$(CONFIG_STM) += hwtracing/stm/
obj-$(CONFIG_ANDROID) += android/
obj-$(CONFIG_NVMEM) += nvmem/
obj-$(CONFIG_FPGA) += fpga/
+obj-$(CONFIG_UART_DEV) += uart/
diff --git a/drivers/uart/Kconfig b/drivers/uart/Kconfig
new file mode 100644
index 0000000..b232ce3
--- /dev/null
+++ b/drivers/uart/Kconfig
@@ -0,0 +1,17 @@
+#
+# UART slave driver configuration
+#
+menuconfig UART_DEV
+ tristate "UART device support"
+ help
+ Support for devices connected via a UART
+
+if UART_DEV
+
+config UART_DEV_LOOPBACK
+ tristate "Loopback Test Driver"
+ help
+ This option enables a loopback test driver. Anything received from
+ the connected device will be echoed back.
+
+endif
diff --git a/drivers/uart/Makefile b/drivers/uart/Makefile
new file mode 100644
index 0000000..704eec0
--- /dev/null
+++ b/drivers/uart/Makefile
@@ -0,0 +1,3 @@
+obj-$(CONFIG_UART_DEV) := core.o
+
+obj-$(CONFIG_UART_DEV_LOOPBACK) += loopback.o
diff --git a/drivers/uart/core.c b/drivers/uart/core.c
new file mode 100644
index 0000000..5b5d0e1
--- /dev/null
+++ b/drivers/uart/core.c
@@ -0,0 +1,458 @@
+/*
+ * Copyright (C) 2016 Linaro Ltd.
+ * Author: Rob Herring <robh@kernel.org>
+ *
+ * Based on drivers/spmi/spmi.c:
+ * Copyright (c) 2012-2015, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License 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.
+ */
+#define DEBUG
+
+#include <linux/kernel.h>
+#include <linux/errno.h>
+#include <linux/idr.h>
+#include <linux/slab.h>
+#include <linux/module.h>
+#include <linux/of.h>
+#include <linux/of_device.h>
+#include <linux/uart_device.h>
+#include <linux/pm_runtime.h>
+#include <linux/serial_core.h>
+
+static bool is_registered;
+static DEFINE_IDA(ctrl_ida);
+
+static void uart_dev_release(struct device *dev)
+{
+ struct uart_device *udev = to_uart_device(dev);
+ kfree(udev);
+}
+
+static const struct device_type uart_dev_type = {
+ .release = uart_dev_release,
+};
+
+static void uart_ctrl_release(struct device *dev)
+{
+ struct uart_controller *ctrl = to_uart_controller(dev);
+ ida_simple_remove(&ctrl_ida, ctrl->nr);
+ kfree(ctrl);
+}
+
+static const struct device_type uart_ctrl_type = {
+ .release = uart_ctrl_release,
+};
+
+static int uart_device_match(struct device *dev, struct device_driver *drv)
+{
+ if (of_driver_match_device(dev, drv))
+ return 1;
+
+ if (drv->name)
+ return strncmp(dev_name(dev), drv->name,
+ SPMI_NAME_SIZE) == 0;
+
+ return 0;
+}
+
+/**
+ * uart_device_add() - add a device previously constructed via uart_device_alloc()
+ * @udev: uart_device to be added
+ */
+int uart_device_add(struct uart_device *udev)
+{
+ struct uart_controller *ctrl = udev->ctrl;
+ int err;
+
+ dev_set_name(&udev->dev, "uartdev-%d", ctrl->nr);
+
+ err = device_add(&udev->dev);
+ if (err < 0) {
+ dev_err(&udev->dev, "Can't add %s, status %d\n",
+ dev_name(&udev->dev), err);
+ goto err_device_add;
+ }
+
+ dev_dbg(&udev->dev, "device %s registered\n", dev_name(&udev->dev));
+
+err_device_add:
+ return err;
+}
+EXPORT_SYMBOL_GPL(uart_device_add);
+
+/**
+ * uart_device_remove(): remove an SPMI device
+ * @udev: uart_device to be removed
+ */
+void uart_device_remove(struct uart_device *udev)
+{
+ device_unregister(&udev->dev);
+}
+EXPORT_SYMBOL_GPL(uart_device_remove);
+
+int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow)
+{
+ return uart_set_options(udev->ctrl->port, NULL, baud, parity, bits, flow);
+}
+
+int uart_dev_connect(struct uart_device *udev)
+{
+ unsigned long page;
+ struct uart_port *port = udev->ctrl->port;
+ struct uart_state *state = port->state;
+
+ WARN_ON(!state);
+
+ if (!state->xmit.buf) {
+ /* This is protected by the per port mutex */
+ page = get_zeroed_page(GFP_KERNEL);
+ if (!page)
+ return -ENOMEM;
+
+ state->xmit.buf = (unsigned char *) page;
+ uart_circ_clear(&state->xmit);
+ }
+
+ if (!udev->ctrl->recv.buf) {
+ /* This is protected by the per port mutex */
+ page = get_zeroed_page(GFP_KERNEL);
+ if (!page)
+ return -ENOMEM;
+
+ udev->ctrl->recv.buf = (unsigned char *) page;
+ uart_circ_clear(&udev->ctrl->recv);
+ }
+
+ if (port && port->ops->pm)
+ port->ops->pm(port, UART_PM_STATE_ON, state->pm_state);
+ state->pm_state = UART_PM_STATE_ON;
+
+ port->ops->set_mctrl(port, TIOCM_RTS | TIOCM_DTR);
+
+ return udev->ctrl->port->ops->startup(udev->ctrl->port);
+}
+
+int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count)
+{
+ struct uart_port *port = udev->ctrl->port;
+ struct uart_state *state = port->state;
+ struct circ_buf *circ = &udev->ctrl->recv;
+ int c, ret = 0;
+
+ if (!circ->buf)
+ return 0;
+
+ while (1) {
+ c = CIRC_CNT_TO_END(circ->head, circ->tail, UART_XMIT_SIZE);
+ if (count < c)
+ c = count;
+ if (c <= 0)
+ break;
+ memcpy(buf, circ->buf + circ->tail, c);
+ circ->tail = (circ->tail + c) & (PAGE_SIZE - 1);
+
+ buf += c;
+ count -= c;
+ ret += c;
+ }
+
+ return ret;
+}
+
+int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count)
+{
+ struct uart_port *port = udev->ctrl->port;
+ struct uart_state *state = port->state;
+ struct circ_buf *circ = &state->xmit;
+ unsigned long flags;
+ int c, ret = 0;
+
+ if (!circ->buf)
+ return 0;
+
+// port = uart_port_lock(state, flags);
+ while (1) {
+ c = CIRC_SPACE_TO_END(circ->head, circ->tail, UART_XMIT_SIZE);
+ if (count < c)
+ c = count;
+ if (c <= 0)
+ break;
+ memcpy(circ->buf + circ->head, buf, c);
+ circ->head = (circ->head + c) & (UART_XMIT_SIZE - 1);
+ buf += c;
+ count -= c;
+ ret += c;
+ }
+ port->ops->start_tx(port);
+
+// uart_port_unlock(port, flags);
+
+ return ret;
+}
+
+
+static int uart_drv_probe(struct device *dev)
+{
+ const struct uart_dev_driver *sdrv = to_uart_dev_driver(dev->driver);
+ struct uart_device *udev = to_uart_device(dev);
+ int err;
+
+ pm_runtime_get_noresume(dev);
+ pm_runtime_set_active(dev);
+ pm_runtime_enable(dev);
+
+ err = sdrv->probe(udev);
+ if (err)
+ goto fail_probe;
+
+ return 0;
+
+fail_probe:
+ pm_runtime_disable(dev);
+ pm_runtime_set_suspended(dev);
+ pm_runtime_put_noidle(dev);
+ return err;
+}
+
+static int uart_drv_remove(struct device *dev)
+{
+ const struct uart_dev_driver *sdrv = to_uart_dev_driver(dev->driver);
+
+ pm_runtime_get_sync(dev);
+ sdrv->remove(to_uart_device(dev));
+ pm_runtime_put_noidle(dev);
+
+ pm_runtime_disable(dev);
+ pm_runtime_set_suspended(dev);
+ pm_runtime_put_noidle(dev);
+ return 0;
+}
+
+static struct bus_type uart_bus_type = {
+ .name = "uart",
+ .match = uart_device_match,
+ .probe = uart_drv_probe,
+ .remove = uart_drv_remove,
+};
+
+/**
+ * uart_controller_alloc() - Allocate a new SPMI device
+ * @ctrl: associated controller
+ *
+ * Caller is responsible for either calling uart_device_add() to add the
+ * newly allocated controller, or calling uart_device_put() to discard it.
+ */
+struct uart_device *uart_device_alloc(struct uart_controller *ctrl)
+{
+ struct uart_device *udev;
+
+ udev = kzalloc(sizeof(*udev), GFP_KERNEL);
+ if (!udev)
+ return NULL;
+
+ udev->ctrl = ctrl;
+ device_initialize(&udev->dev);
+ udev->dev.parent = &ctrl->dev;
+ udev->dev.bus = &uart_bus_type;
+ udev->dev.type = &uart_dev_type;
+ return udev;
+}
+EXPORT_SYMBOL_GPL(uart_device_alloc);
+
+/**
+ * uart_controller_alloc() - Allocate a new SPMI controller
+ * @parent: parent device
+ * @size: size of private data
+ *
+ * Caller is responsible for either calling uart_controller_add() to add the
+ * newly allocated controller, or calling uart_controller_put() to discard it.
+ * The allocated private data region may be accessed via
+ * uart_controller_get_drvdata()
+ */
+struct uart_controller *uart_controller_alloc(struct device *parent,
+ size_t size)
+{
+ struct uart_controller *ctrl;
+ int id;
+
+ if (WARN_ON(!parent))
+ return NULL;
+
+ ctrl = kzalloc(sizeof(*ctrl) + size, GFP_KERNEL);
+ if (!ctrl)
+ return NULL;
+
+ device_initialize(&ctrl->dev);
+ ctrl->dev.type = &uart_ctrl_type;
+ ctrl->dev.bus = &uart_bus_type;
+ ctrl->dev.parent = parent;
+ ctrl->dev.of_node = parent->of_node;
+ uart_controller_set_drvdata(ctrl, &ctrl[1]);
+
+ id = ida_simple_get(&ctrl_ida, 0, 0, GFP_KERNEL);
+ if (id < 0) {
+ dev_err(parent,
+ "unable to allocate SPMI controller identifier.\n");
+ uart_controller_put(ctrl);
+ return NULL;
+ }
+
+ ctrl->nr = id;
+ dev_set_name(&ctrl->dev, "uart-%d", id);
+
+ dev_dbg(&ctrl->dev, "allocated controller 0x%p id %d\n", ctrl, id);
+ return ctrl;
+}
+EXPORT_SYMBOL_GPL(uart_controller_alloc);
+
+static void of_uart_register_devices(struct uart_controller *ctrl)
+{
+ struct device_node *node;
+ int err;
+
+ if (!ctrl->dev.of_node)
+ return;
+
+ for_each_available_child_of_node(ctrl->dev.of_node, node) {
+ struct uart_device *udev;
+ u32 reg[2];
+
+ dev_dbg(&ctrl->dev, "adding child %s\n", node->full_name);
+
+ udev = uart_device_alloc(ctrl);
+ if (!udev)
+ continue;
+
+ udev->dev.of_node = node;
+
+ err = uart_device_add(udev);
+ if (err) {
+ dev_err(&udev->dev,
+ "failure adding device. status %d\n", err);
+ uart_device_put(udev);
+ }
+ }
+}
+
+/**
+ * uart_controller_add() - Add an SPMI controller
+ * @ctrl: controller to be registered.
+ *
+ * Register a controller previously allocated via uart_controller_alloc() with
+ * the SPMI core.
+ */
+int uart_controller_add(struct uart_controller *ctrl)
+{
+ int ret;
+
+ /* Can't register until after driver model init */
+ if (WARN_ON(!is_registered))
+ return -EAGAIN;
+
+ ret = device_add(&ctrl->dev);
+ if (ret)
+ return ret;
+
+ if (IS_ENABLED(CONFIG_OF))
+ of_uart_register_devices(ctrl);
+
+ dev_dbg(&ctrl->dev, "uart-%d registered: dev:%p\n",
+ ctrl->nr, &ctrl->dev);
+
+ return 0;
+};
+EXPORT_SYMBOL_GPL(uart_controller_add);
+
+int uart_controller_rx(struct uart_controller *ctrl, unsigned int ch)
+{
+ struct circ_buf *circ = &ctrl->recv;
+ unsigned long flags;
+ int c, ret = 0;
+
+ if (!circ->buf)
+ return -ENODEV;
+
+ c = CIRC_SPACE_TO_END(circ->head, circ->tail, PAGE_SIZE);
+ if (c <= 0)
+ return 0;
+
+ circ->buf[circ->head] = ch;
+ circ->head = (circ->head + 1) & (PAGE_SIZE - 1);
+
+ return 1;
+}
+
+/* Remove a device associated with a controller */
+static int uart_ctrl_remove_device(struct device *dev, void *data)
+{
+ struct uart_device *spmidev = to_uart_device(dev);
+ if (dev->type == &uart_dev_type)
+ uart_device_remove(spmidev);
+ return 0;
+}
+
+/**
+ * uart_controller_remove(): remove an SPMI controller
+ * @ctrl: controller to remove
+ *
+ * Remove a SPMI controller. Caller is responsible for calling
+ * uart_controller_put() to discard the allocated controller.
+ */
+void uart_controller_remove(struct uart_controller *ctrl)
+{
+ int dummy;
+
+ if (!ctrl)
+ return;
+
+ dummy = device_for_each_child(&ctrl->dev, NULL,
+ uart_ctrl_remove_device);
+ device_del(&ctrl->dev);
+}
+EXPORT_SYMBOL_GPL(uart_controller_remove);
+
+/**
+ * uart_driver_register() - Register client driver with SPMI core
+ * @sdrv: client driver to be associated with client-device.
+ *
+ * This API will register the client driver with the SPMI framework.
+ * It is typically called from the driver's module-init function.
+ */
+int __uart_dev_driver_register(struct uart_dev_driver *sdrv, struct module *owner)
+{
+ sdrv->driver.bus = &uart_bus_type;
+ sdrv->driver.owner = owner;
+ return driver_register(&sdrv->driver);
+}
+EXPORT_SYMBOL_GPL(__uart_driver_register);
+
+static void __exit uart_exit(void)
+{
+ bus_unregister(&uart_bus_type);
+}
+module_exit(uart_exit);
+
+static int __init uart_init(void)
+{
+ int ret;
+
+ ret = bus_register(&uart_bus_type);
+ if (ret)
+ return ret;
+
+ is_registered = true;
+ return 0;
+}
+postcore_initcall(uart_init);
+
+MODULE_LICENSE("GPL v2");
+MODULE_DESCRIPTION("UART module");
+//MODULE_ALIAS("platform:spmi");
diff --git a/drivers/uart/loopback.c b/drivers/uart/loopback.c
new file mode 100644
index 0000000..80b7769
--- /dev/null
+++ b/drivers/uart/loopback.c
@@ -0,0 +1,72 @@
+/*
+ * Copyright (C) 2016 Linaro Ltd.
+ * Author: Rob Herring <robh@kernel.org>
+ *
+ * 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/module.h>
+#include <linux/of.h>
+#include <linux/uart_device.h>
+#include <linux/workqueue.h>
+
+struct loopback_data {
+ struct uart_device *udev;
+ struct delayed_work work;
+};
+
+static void loopback_work(struct work_struct *work)
+{
+ struct loopback_data *data = container_of((struct delayed_work *)work, struct loopback_data, work);
+ struct uart_device *udev = data->udev;
+ int cnt;
+ char buf[64];
+
+ cnt = uart_dev_rx(udev, buf, sizeof(buf));
+ uart_dev_tx(udev, buf, cnt);
+
+ schedule_delayed_work(&data->work, 5);
+}
+
+static int loopback_probe(struct uart_device *udev)
+{
+ struct loopback_data *data;
+
+ data = devm_kzalloc(&udev->dev, sizeof(*data), GFP_KERNEL);
+ if (!data)
+ return -ENOMEM;
+ data->udev = udev;
+
+ dev_info(&udev->dev, "loopback probe!!!\n");
+
+ uart_dev_connect(udev);
+ uart_dev_config(udev, 115200, 'n', 8, 0);
+
+
+ INIT_DELAYED_WORK(&data->work, loopback_work);
+ schedule_delayed_work(&data->work, 100);
+
+ return 0;
+}
+
+static const struct of_device_id loopback_of_match[] = {
+ { .compatible = "loopback-uart", },
+ {},
+};
+MODULE_DEVICE_TABLE(of, loopback_of_match);
+
+static struct uart_dev_driver loopback_driver = {
+ .probe = loopback_probe,
+ .driver = {
+ .name = "loopback-uart",
+ .of_match_table = of_match_ptr(loopback_of_match),
+ },
+};
+module_uart_dev_driver(loopback_driver);
diff --git a/include/linux/uart_device.h b/include/linux/uart_device.h
new file mode 100644
index 0000000..a91d778
--- /dev/null
+++ b/include/linux/uart_device.h
@@ -0,0 +1,163 @@
+/*
+ * Copyright (C) 2016 Linaro Ltd.
+ * Author: Rob Herring <robh@kernel.org>
+ *
+ * Based on include/linux/spmi.h:
+ * Copyright (c) 2012-2013, The Linux Foundation. All rights reserved.
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License 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.
+ */
+#ifndef _LINUX_UART_DEVICE_H
+#define _LINUX_UART_DEVICE_H
+
+#include <linux/types.h>
+#include <linux/device.h>
+#include <linux/circ_buf.h>
+#include <linux/mod_devicetable.h>
+
+/**
+ * struct uart_device - Basic representation of an SPMI device
+ * @dev: Driver model representation of the device.
+ * @ctrl: SPMI controller managing the bus hosting this device.
+ * @usid: This devices' Unique Slave IDentifier.
+ */
+struct uart_device {
+ struct device dev;
+ struct uart_controller *ctrl;
+};
+
+static inline struct uart_device *to_uart_device(struct device *d)
+{
+ return container_of(d, struct uart_device, dev);
+}
+
+static inline void *uart_device_get_drvdata(const struct uart_device *sdev)
+{
+ return dev_get_drvdata(&sdev->dev);
+}
+
+static inline void uart_device_set_drvdata(struct uart_device *sdev, void *data)
+{
+ dev_set_drvdata(&sdev->dev, data);
+}
+
+struct uart_device *uart_device_alloc(struct uart_controller *ctrl);
+
+static inline void uart_device_put(struct uart_device *sdev)
+{
+ if (sdev)
+ put_device(&sdev->dev);
+}
+
+int uart_device_add(struct uart_device *sdev);
+
+void uart_device_remove(struct uart_device *sdev);
+
+struct uart_port;
+
+/**
+ * struct uart_controller - interface to the SPMI master controller
+ * @dev: Driver model representation of the device.
+ * @nr: board-specific number identifier for this controller/bus
+ * @cmd: sends a non-data command sequence on the SPMI bus.
+ * @read_cmd: sends a register read command sequence on the SPMI bus.
+ * @write_cmd: sends a register write command sequence on the SPMI bus.
+ */
+struct uart_controller {
+ struct device dev;
+ struct uart_port *port;
+ unsigned int nr;
+ struct circ_buf recv;
+};
+
+static inline struct uart_controller *to_uart_controller(struct device *d)
+{
+ return container_of(d, struct uart_controller, dev);
+}
+
+static inline
+void *uart_controller_get_drvdata(const struct uart_controller *ctrl)
+{
+ return dev_get_drvdata(&ctrl->dev);
+}
+
+static inline void uart_controller_set_drvdata(struct uart_controller *ctrl,
+ void *data)
+{
+ dev_set_drvdata(&ctrl->dev, data);
+}
+
+struct uart_controller *uart_controller_alloc(struct device *parent,
+ size_t size);
+
+/**
+ * uart_controller_put() - decrement controller refcount
+ * @ctrl SPMI controller.
+ */
+static inline void uart_controller_put(struct uart_controller *ctrl)
+{
+ if (ctrl)
+ put_device(&ctrl->dev);
+}
+
+int uart_controller_add(struct uart_controller *ctrl);
+void uart_controller_remove(struct uart_controller *ctrl);
+
+int uart_controller_rx(struct uart_controller *ctrl, unsigned int ch);
+
+/**
+ * struct spmi_driver - SPMI slave device driver
+ * @driver: SPMI device drivers should initialize name and owner field of
+ * this structure.
+ * @probe: binds this driver to a SPMI device.
+ * @remove: unbinds this driver from the SPMI device.
+ *
+ * If PM runtime support is desired for a slave, a device driver can call
+ * pm_runtime_put() from their probe() routine (and a balancing
+ * pm_runtime_get() in remove()). PM runtime support for a slave is
+ * implemented by issuing a SLEEP command to the slave on runtime_suspend(),
+ * transitioning the slave into the SLEEP state. On runtime_resume(), a WAKEUP
+ * command is sent to the slave to bring it back to ACTIVE.
+ */
+struct uart_dev_driver {
+ struct device_driver driver;
+ int (*probe)(struct uart_device *sdev);
+ void (*remove)(struct uart_device *sdev);
+};
+
+static inline struct uart_dev_driver *to_uart_dev_driver(struct device_driver *d)
+{
+ return container_of(d, struct uart_dev_driver, driver);
+}
+
+#define uart_dev_driver_register(sdrv) \
+ __uart_dev_driver_register(sdrv, THIS_MODULE)
+int __uart_dev_driver_register(struct uart_dev_driver *sdrv, struct module *owner);
+
+/**
+ * spmi_driver_unregister() - unregister an SPMI client driver
+ * @sdrv: the driver to unregister
+ */
+static inline void uart_dev_driver_unregister(struct uart_dev_driver *sdrv)
+{
+ if (sdrv)
+ driver_unregister(&sdrv->driver);
+}
+
+#define module_uart_dev_driver(__uart_dev_driver) \
+ module_driver(__uart_dev_driver, uart_dev_driver_register, \
+ uart_dev_driver_unregister)
+
+int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
+int uart_dev_connect(struct uart_device *udev);
+int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
+int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
+
+#endif
--
2.9.2
^ permalink raw reply related [flat|nested] 103+ messages in thread
* [RFC PATCH 2/3] tty: serial_core: make tty_struct optional
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
2016-08-18 1:14 ` [RFC PATCH 1/3] uart bus: Introduce new bus for UART slave devices Rob Herring
@ 2016-08-18 1:14 ` Rob Herring
2016-08-18 10:50 ` Pavel Machek
2016-08-18 1:14 ` [RFC PATCH 3/3] tty: serial_core: add uart controller registration Rob Herring
` (7 subsequent siblings)
9 siblings, 1 reply; 103+ messages in thread
From: Rob Herring @ 2016-08-18 1:14 UTC (permalink / raw)
To: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel
Cc: Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, linux-bluetooth, linux-serial,
linux-kernel
In order to allow serial drivers to work without a tty, make calls from
drivers and serial_core work when tty_struct is NULL.
Signed-off-by: Rob Herring <robh@kernel.org>
---
drivers/tty/serial/serial_core.c | 3 ++-
drivers/tty/tty_buffer.c | 2 ++
include/linux/serial_core.h | 2 +-
3 files changed, 5 insertions(+), 2 deletions(-)
diff --git a/drivers/tty/serial/serial_core.c b/drivers/tty/serial/serial_core.c
index 9fc1533..9dd444f 100644
--- a/drivers/tty/serial/serial_core.c
+++ b/drivers/tty/serial/serial_core.c
@@ -111,7 +111,8 @@ void uart_write_wakeup(struct uart_port *port)
* closed. No cookie for you.
*/
BUG_ON(!state);
- tty_wakeup(state->port.tty);
+ if (state->port.tty)
+ tty_wakeup(state->port.tty);
}
static void uart_stop(struct tty_struct *tty)
diff --git a/drivers/tty/tty_buffer.c b/drivers/tty/tty_buffer.c
index aa80dc9..ffab8ea 100644
--- a/drivers/tty/tty_buffer.c
+++ b/drivers/tty/tty_buffer.c
@@ -528,6 +528,8 @@ static void flush_to_ldisc(struct work_struct *work)
void tty_flip_buffer_push(struct tty_port *port)
{
+ if (!port->tty)
+ return;
tty_schedule_flip(port);
}
EXPORT_SYMBOL(tty_flip_buffer_push);
diff --git a/include/linux/serial_core.h b/include/linux/serial_core.h
index 2f44e20..a27ca1f 100644
--- a/include/linux/serial_core.h
+++ b/include/linux/serial_core.h
@@ -412,7 +412,7 @@ int uart_resume_port(struct uart_driver *reg, struct uart_port *port);
static inline int uart_tx_stopped(struct uart_port *port)
{
struct tty_struct *tty = port->state->port.tty;
- if (tty->stopped || port->hw_stopped)
+ if ((tty && tty->stopped) || port->hw_stopped)
return 1;
return 0;
}
--
2.9.2
^ permalink raw reply related [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 2/3] tty: serial_core: make tty_struct optional
2016-08-18 1:14 ` [RFC PATCH 2/3] tty: serial_core: make tty_struct optional Rob Herring
@ 2016-08-18 10:50 ` Pavel Machek
0 siblings, 0 replies; 103+ messages in thread
From: Pavel Machek @ 2016-08-18 10:50 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Arnd Bergmann, Linus Walleij,
linux-bluetooth, linux-serial, linux-kernel
On Wed 2016-08-17 20:14:44, Rob Herring wrote:
> In order to allow serial drivers to work without a tty, make calls from
> drivers and serial_core work when tty_struct is NULL.
>
> Signed-off-by: Rob Herring <robh@kernel.org>
Acked-by: Pavel Machek <pavel@ucw.cz>
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html
^ permalink raw reply [flat|nested] 103+ messages in thread
* [RFC PATCH 3/3] tty: serial_core: add uart controller registration
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
2016-08-18 1:14 ` [RFC PATCH 1/3] uart bus: Introduce new bus for UART slave devices Rob Herring
2016-08-18 1:14 ` [RFC PATCH 2/3] tty: serial_core: make tty_struct optional Rob Herring
@ 2016-08-18 1:14 ` Rob Herring
[not found] ` <20160818011445.22726-1-robh-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org>
` (6 subsequent siblings)
9 siblings, 0 replies; 103+ messages in thread
From: Rob Herring @ 2016-08-18 1:14 UTC (permalink / raw)
To: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel
Cc: Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, linux-bluetooth, linux-serial,
linux-kernel
Register serial ports with the uart device core as a controller and add
a receive handler call.
Signed-off-by: Rob Herring <robh@kernel.org>
---
drivers/tty/serial/serial_core.c | 8 ++++++++
include/linux/serial_core.h | 1 +
2 files changed, 9 insertions(+)
diff --git a/drivers/tty/serial/serial_core.c b/drivers/tty/serial/serial_core.c
index 9dd444f..1552fee 100644
--- a/drivers/tty/serial/serial_core.c
+++ b/drivers/tty/serial/serial_core.c
@@ -34,6 +34,7 @@
#include <linux/serial_core.h>
#include <linux/delay.h>
#include <linux/mutex.h>
+#include <linux/uart_device.h>
#include <asm/irq.h>
#include <asm/uaccess.h>
@@ -2800,6 +2801,10 @@ int uart_add_one_port(struct uart_driver *drv, struct uart_port *uport)
uart_configure_port(drv, state, uport);
+ uport->ctrlr = uart_controller_alloc(uport->dev, 0);
+ uport->ctrlr->port = uport;
+ uart_controller_add(uport->ctrlr);
+
num_groups = 2;
if (uport->attr_group)
num_groups++;
@@ -3027,6 +3032,9 @@ void uart_insert_char(struct uart_port *port, unsigned int status,
{
struct tty_port *tport = &port->state->port;
+ if (uart_controller_rx(port->ctrlr, ch) >= 0)
+ return;
+
if ((status & port->ignore_status_mask & ~overrun) == 0)
if (tty_insert_flip_char(tport, ch, flag) == 0)
++port->icount.buf_overrun;
diff --git a/include/linux/serial_core.h b/include/linux/serial_core.h
index a27ca1f..7cde6a9 100644
--- a/include/linux/serial_core.h
+++ b/include/linux/serial_core.h
@@ -155,6 +155,7 @@ struct uart_port {
unsigned int read_status_mask; /* driver specific */
unsigned int ignore_status_mask; /* driver specific */
+ struct uart_controller *ctrlr;
struct uart_state *state; /* pointer to parent state */
struct uart_icount icount; /* statistics */
--
2.9.2
^ permalink raw reply related [flat|nested] 103+ messages in thread
[parent not found: <20160818011445.22726-1-robh-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org>]
* Re: [RFC PATCH 0/3] UART slave device bus
[not found] ` <20160818011445.22726-1-robh-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org>
@ 2016-08-18 10:22 ` Greg Kroah-Hartman
2016-08-18 10:30 ` Marcel Holtmann
2016-08-18 13:15 ` Rob Herring
0 siblings, 2 replies; 103+ messages in thread
From: Greg Kroah-Hartman @ 2016-08-18 10:22 UTC (permalink / raw)
To: Rob Herring
Cc: Marcel Holtmann, Jiri Slaby, Sebastian Reichel, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij,
linux-bluetooth-u79uwXL29TY76Z2rM5mHXA,
linux-serial-u79uwXL29TY76Z2rM5mHXA,
linux-kernel-u79uwXL29TY76Z2rM5mHXA
On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
> Currently, devices attached via a UART are not well supported in the
> kernel. The problem is the device support is done in tty line disciplines,
> various platform drivers to handle some sideband, and in userspace with
> utilities such as hciattach.
>
> There have been several attempts to improve support, but they suffer from
> still being tied into the tty layer and/or abusing the platform bus. This
> is a prototype to show creating a proper UART bus for UART devices. It is
> tied into the serial core (really struct uart_port) below the tty layer
> in order to use existing serial drivers.
>
> This is functional with minimal testing using the loopback driver and
> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> device). It still needs lots of work and polish.
>
> TODOs:
> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
> hoping all that complexity is from the tty layer and not needed here.
It should be.
> - Split out the controller for uart_ports into separate driver. Do we see
> a need for controller drivers that are not standard serial drivers?
What do you mean by "controller" drivers here? I didn't understand them
in the code.
> - Implement/test the removal paths
> - Fix the receive callbacks for more than character at a time (i.e. DMA)
> - Need better receive buffering than just a simple circular buffer or
> perhaps a different receive interface (e.g. direct to client buffer)?
Why? Is the code as-is slow?
> - Test with other UART drivers
> - Convert a real driver/line discipline over to UART bus.
That's going to be the real test, I recommend trying that as soon as
possible as it will show where the real pain points are :)
> Before I spend more time on this, I'm looking mainly for feedback on the
> general direction and structure (the interface with the existing serial
> drivers in particular).
Yes, I like the idea (minor nit, you still have SPMI in a lot of places
instead of UART), so I recommend keeping going with it.
> drivers/uart/Kconfig | 17 ++
> drivers/uart/Makefile | 3 +
> drivers/uart/core.c | 458 +++++++++++++++++++++++++++++++++++++++
> drivers/uart/loopback.c | 72 ++++++
Why not just put this in drivers/tty/uart/ ?
thanks,
greg k-h
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:22 ` [RFC PATCH 0/3] UART slave device bus Greg Kroah-Hartman
@ 2016-08-18 10:30 ` Marcel Holtmann
2016-08-18 10:53 ` Greg Kroah-Hartman
2016-08-18 13:15 ` Rob Herring
1 sibling, 1 reply; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-18 10:30 UTC (permalink / raw)
To: Greg Kroah-Hartman
Cc: Rob Herring, Jiri Slaby, Sebastian Reichel, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial, Linux Kernel Mailing List, Loic Poulain
Hi Greg,
>> Currently, devices attached via a UART are not well supported in the
>> kernel. The problem is the device support is done in tty line disciplines,
>> various platform drivers to handle some sideband, and in userspace with
>> utilities such as hciattach.
>>
>> There have been several attempts to improve support, but they suffer from
>> still being tied into the tty layer and/or abusing the platform bus. This
>> is a prototype to show creating a proper UART bus for UART devices. It is
>> tied into the serial core (really struct uart_port) below the tty layer
>> in order to use existing serial drivers.
>>
>> This is functional with minimal testing using the loopback driver and
>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>> device). It still needs lots of work and polish.
>>
>> TODOs:
>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>> hoping all that complexity is from the tty layer and not needed here.
>
> It should be.
>
>> - Split out the controller for uart_ports into separate driver. Do we see
>> a need for controller drivers that are not standard serial drivers?
>
> What do you mean by "controller" drivers here? I didn't understand them
> in the code.
>
>> - Implement/test the removal paths
>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>> - Need better receive buffering than just a simple circular buffer or
>> perhaps a different receive interface (e.g. direct to client buffer)?
>
> Why? Is the code as-is slow?
>
>> - Test with other UART drivers
>> - Convert a real driver/line discipline over to UART bus.
>
> That's going to be the real test, I recommend trying that as soon as
> possible as it will show where the real pain points are :)
maybe we can get the Intel LnP driver ported over and see how that one works out. It is one of the more complex ones when it comes to bootloader and firmware loading. Maybe Loic can take a stab at this. We would then also see how we can map the ACPI tables into a driver.
>> Before I spend more time on this, I'm looking mainly for feedback on the
>> general direction and structure (the interface with the existing serial
>> drivers in particular).
>
> Yes, I like the idea (minor nit, you still have SPMI in a lot of places
> instead of UART), so I recommend keeping going with it.
>
>> drivers/uart/Kconfig | 17 ++
>> drivers/uart/Makefile | 3 +
>> drivers/uart/core.c | 458 +++++++++++++++++++++++++++++++++++++++
>> drivers/uart/loopback.c | 72 ++++++
>
> Why not just put this in drivers/tty/uart/ ?
Is it really then a TTY at all. Would be the UART become the basic core for a TTY? Having tty/uart/ seems a bit backward. Then again, it is just a directory name ;)
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:30 ` Marcel Holtmann
@ 2016-08-18 10:53 ` Greg Kroah-Hartman
2016-08-18 13:53 ` Rob Herring
0 siblings, 1 reply; 103+ messages in thread
From: Greg Kroah-Hartman @ 2016-08-18 10:53 UTC (permalink / raw)
To: Marcel Holtmann
Cc: Rob Herring, Jiri Slaby, Sebastian Reichel, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial, Linux Kernel Mailing List, Loic Poulain
On Thu, Aug 18, 2016 at 12:30:32PM +0200, Marcel Holtmann wrote:
> Hi Greg,
>
> >> Currently, devices attached via a UART are not well supported in the
> >> kernel. The problem is the device support is done in tty line disciplines,
> >> various platform drivers to handle some sideband, and in userspace with
> >> utilities such as hciattach.
> >>
> >> There have been several attempts to improve support, but they suffer from
> >> still being tied into the tty layer and/or abusing the platform bus. This
> >> is a prototype to show creating a proper UART bus for UART devices. It is
> >> tied into the serial core (really struct uart_port) below the tty layer
> >> in order to use existing serial drivers.
> >>
> >> This is functional with minimal testing using the loopback driver and
> >> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> >> device). It still needs lots of work and polish.
> >>
> >> TODOs:
> >> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
> >> hoping all that complexity is from the tty layer and not needed here.
> >
> > It should be.
> >
> >> - Split out the controller for uart_ports into separate driver. Do we see
> >> a need for controller drivers that are not standard serial drivers?
> >
> > What do you mean by "controller" drivers here? I didn't understand them
> > in the code.
> >
> >> - Implement/test the removal paths
> >> - Fix the receive callbacks for more than character at a time (i.e. DMA)
> >> - Need better receive buffering than just a simple circular buffer or
> >> perhaps a different receive interface (e.g. direct to client buffer)?
> >
> > Why? Is the code as-is slow?
> >
> >> - Test with other UART drivers
> >> - Convert a real driver/line discipline over to UART bus.
> >
> > That's going to be the real test, I recommend trying that as soon as
> > possible as it will show where the real pain points are :)
>
> maybe we can get the Intel LnP driver ported over and see how that one
> works out. It is one of the more complex ones when it comes to
> bootloader and firmware loading. Maybe Loic can take a stab at this.
> We would then also see how we can map the ACPI tables into a driver.
Yes, I was going to complain about the OF-only bent of this patch, but I
figured it would get fixed up once Rob started to use a "real" machine
for his testing of this code :)
> >> Before I spend more time on this, I'm looking mainly for feedback on the
> >> general direction and structure (the interface with the existing serial
> >> drivers in particular).
> >
> > Yes, I like the idea (minor nit, you still have SPMI in a lot of places
> > instead of UART), so I recommend keeping going with it.
> >
> >> drivers/uart/Kconfig | 17 ++
> >> drivers/uart/Makefile | 3 +
> >> drivers/uart/core.c | 458 +++++++++++++++++++++++++++++++++++++++
> >> drivers/uart/loopback.c | 72 ++++++
> >
> > Why not just put this in drivers/tty/uart/ ?
>
> Is it really then a TTY at all. Would be the UART become the basic
> core for a TTY?
Hm, interesting idea. Not for all TTYs of course, but for those that
are on UART devices, maybe? How would a usb-serial device fit into that
picture?
> Having tty/uart/ seems a bit backward. Then again, it is just a
> directory name ;)
And as we know, naming is hard :)
thanks,
greg k-h
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:53 ` Greg Kroah-Hartman
@ 2016-08-18 13:53 ` Rob Herring
0 siblings, 0 replies; 103+ messages in thread
From: Rob Herring @ 2016-08-18 13:53 UTC (permalink / raw)
To: Greg Kroah-Hartman
Cc: Marcel Holtmann, Jiri Slaby, Sebastian Reichel, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, Linux Kernel Mailing List,
Loic Poulain
On Thu, Aug 18, 2016 at 5:53 AM, Greg Kroah-Hartman
<gregkh@linuxfoundation.org> wrote:
> On Thu, Aug 18, 2016 at 12:30:32PM +0200, Marcel Holtmann wrote:
>> Hi Greg,
>>
>> >> Currently, devices attached via a UART are not well supported in the
>> >> kernel. The problem is the device support is done in tty line disciplines,
>> >> various platform drivers to handle some sideband, and in userspace with
>> >> utilities such as hciattach.
>> >>
>> >> There have been several attempts to improve support, but they suffer from
>> >> still being tied into the tty layer and/or abusing the platform bus. This
>> >> is a prototype to show creating a proper UART bus for UART devices. It is
>> >> tied into the serial core (really struct uart_port) below the tty layer
>> >> in order to use existing serial drivers.
>> >>
>> >> This is functional with minimal testing using the loopback driver and
>> >> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>> >> device). It still needs lots of work and polish.
>> >>
>> >> TODOs:
>> >> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>> >> hoping all that complexity is from the tty layer and not needed here.
>> >
>> > It should be.
>> >
>> >> - Split out the controller for uart_ports into separate driver. Do we see
>> >> a need for controller drivers that are not standard serial drivers?
>> >
>> > What do you mean by "controller" drivers here? I didn't understand them
>> > in the code.
>> >
>> >> - Implement/test the removal paths
>> >> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>> >> - Need better receive buffering than just a simple circular buffer or
>> >> perhaps a different receive interface (e.g. direct to client buffer)?
>> >
>> > Why? Is the code as-is slow?
>> >
>> >> - Test with other UART drivers
>> >> - Convert a real driver/line discipline over to UART bus.
>> >
>> > That's going to be the real test, I recommend trying that as soon as
>> > possible as it will show where the real pain points are :)
>>
>> maybe we can get the Intel LnP driver ported over and see how that one
>> works out. It is one of the more complex ones when it comes to
>> bootloader and firmware loading. Maybe Loic can take a stab at this.
>> We would then also see how we can map the ACPI tables into a driver.
>
> Yes, I was going to complain about the OF-only bent of this patch, but I
> figured it would get fixed up once Rob started to use a "real" machine
> for his testing of this code :)
I fully expected that from you. :)
It is no different than any other bus we have. Each
discovery/enumeration method needs hooks for matching and creating
devices. It just happens that DT is the only one added ATM.
>
>> >> Before I spend more time on this, I'm looking mainly for feedback on the
>> >> general direction and structure (the interface with the existing serial
>> >> drivers in particular).
>> >
>> > Yes, I like the idea (minor nit, you still have SPMI in a lot of places
>> > instead of UART), so I recommend keeping going with it.
>> >
>> >> drivers/uart/Kconfig | 17 ++
>> >> drivers/uart/Makefile | 3 +
>> >> drivers/uart/core.c | 458 +++++++++++++++++++++++++++++++++++++++
>> >> drivers/uart/loopback.c | 72 ++++++
>> >
>> > Why not just put this in drivers/tty/uart/ ?
>>
>> Is it really then a TTY at all. Would be the UART become the basic
>> core for a TTY?
>
> Hm, interesting idea. Not for all TTYs of course, but for those that
> are on UART devices, maybe? How would a usb-serial device fit into that
> picture?
DT overlay. Just like greybus serial. :)
That's a good question though as usb-serial doesn't use uart_port.
Perhaps there needs to be a uart controller/host driver that's a line
discipline so existing tty drivers can work. That somewhat defeats the
point of getting line disciplines out of the picture, but would
provide a solution for h/w hacking (and no worse than what can be
supported today). Longer term, the drivers would need to be adapted to
use the uart slave bus directly.
Rob
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:22 ` [RFC PATCH 0/3] UART slave device bus Greg Kroah-Hartman
2016-08-18 10:30 ` Marcel Holtmann
@ 2016-08-18 13:15 ` Rob Herring
[not found] ` <20160818160449.328b2eec@lxorguk.ukuu.org.uk>
1 sibling, 1 reply; 103+ messages in thread
From: Rob Herring @ 2016-08-18 13:15 UTC (permalink / raw)
To: Greg Kroah-Hartman
Cc: Marcel Holtmann, Jiri Slaby, Sebastian Reichel, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, linux-bluetooth,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
On Thu, Aug 18, 2016 at 5:22 AM, Greg Kroah-Hartman
<gregkh@linuxfoundation.org> wrote:
> On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
>> Currently, devices attached via a UART are not well supported in the
>> kernel. The problem is the device support is done in tty line disciplines,
>> various platform drivers to handle some sideband, and in userspace with
>> utilities such as hciattach.
>>
>> There have been several attempts to improve support, but they suffer from
>> still being tied into the tty layer and/or abusing the platform bus. This
>> is a prototype to show creating a proper UART bus for UART devices. It is
>> tied into the serial core (really struct uart_port) below the tty layer
>> in order to use existing serial drivers.
>>
>> This is functional with minimal testing using the loopback driver and
>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>> device). It still needs lots of work and polish.
>>
>> TODOs:
>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>> hoping all that complexity is from the tty layer and not needed here.
>
> It should be.
>
>> - Split out the controller for uart_ports into separate driver. Do we see
>> a need for controller drivers that are not standard serial drivers?
>
> What do you mean by "controller" drivers here? I didn't understand them
> in the code.
The host uart driver. It's basically a wrapper around struct
uart_port, but may need to evolve to have its own ops if we want to
make using struct uart_port for driver. Maybe host would be a better
name.
>> - Implement/test the removal paths
>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>> - Need better receive buffering than just a simple circular buffer or
>> perhaps a different receive interface (e.g. direct to client buffer)?
>
> Why? Is the code as-is slow?
No, the code should be fast as it is so simple. I assume there is some
reason the tty buffering is more complex than just a circular buffer.
My best guess is because the tty layer has to buffer things for
userspace and userspace can be slow to read? Do line disciplines make
assumptions about the tty buffering? Is 4KB enough buffering?
Also, the current receive implementation has no concept of blocking or
timeout. Should the uart_dev_rx() function return when there's no more
data or wait (with timeout) until all requested data is received?
(Probably do all of them is my guess).
>
>> - Test with other UART drivers
>> - Convert a real driver/line discipline over to UART bus.
>
> That's going to be the real test, I recommend trying that as soon as
> possible as it will show where the real pain points are :)
>
>> Before I spend more time on this, I'm looking mainly for feedback on the
>> general direction and structure (the interface with the existing serial
>> drivers in particular).
>
> Yes, I like the idea (minor nit, you still have SPMI in a lot of places
> instead of UART), so I recommend keeping going with it.
>
>> drivers/uart/Kconfig | 17 ++
>> drivers/uart/Makefile | 3 +
>> drivers/uart/core.c | 458 +++++++++++++++++++++++++++++++++++++++
>> drivers/uart/loopback.c | 72 ++++++
>
> Why not just put this in drivers/tty/uart/ ?
Because it has nothing to do with the tty layer. If anything, I think
the direction would be move drivers/tty/serial/ to drivers/uart/
(didn't they used to be in drivers/serial/? :)) i'm not proposing we
do that though.
Rob
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
` (3 preceding siblings ...)
[not found] ` <20160818011445.22726-1-robh-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org>
@ 2016-08-18 10:39 ` H. Nikolaus Schaller
2016-08-18 10:47 ` Pavel Machek
2016-08-18 10:49 ` Marcel Holtmann
2016-08-18 11:02 ` Pavel Machek
` (4 subsequent siblings)
9 siblings, 2 replies; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-18 10:39 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Arnd Bergmann, Linus Walleij, linux-bluetooth, linux-serial,
linux-kernel
Hi Rob,
many thanks for picking up this unsolved topic!
> Am 18.08.2016 um 03:14 schrieb Rob Herring <robh@kernel.org>:
>
> Currently, devices attached via a UART are not well supported in the
> kernel. The problem is the device support is done in tty line disciplines,
> various platform drivers to handle some sideband, and in userspace with
> utilities such as hciattach.
>
> There have been several attempts to improve support, but they suffer from
> still being tied into the tty layer and/or abusing the platform bus. This
> is a prototype to show creating a proper UART bus for UART devices. It is
> tied into the serial core (really struct uart_port) below the tty layer
> in order to use existing serial drivers.
>
> This is functional with minimal testing using the loopback driver and
> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> device). It still needs lots of work and polish.
>
> TODOs:
> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
> hoping all that complexity is from the tty layer and not needed here.
> - Split out the controller for uart_ports into separate driver. Do we see
> a need for controller drivers that are not standard serial drivers?
> - Implement/test the removal paths
> - Fix the receive callbacks for more than character at a time (i.e. DMA)
> - Need better receive buffering than just a simple circular buffer or
> perhaps a different receive interface (e.g. direct to client buffer)?
> - Test with other UART drivers
> - Convert a real driver/line discipline over to UART bus.
>
> Before I spend more time on this, I'm looking mainly for feedback on the
> general direction and structure (the interface with the existing serial
> drivers in particular).
Some quick comments (can't do any real life tests in the next weeks) from my (biased) view:
* tieing the solution into uart_port is the same as we had done. The difference seems to
me that you completely bypass serial_core (and tty) while we want to integrate it with standard tty operation.
We have tapped the tty layer only because it can not be 100% avoided if we use serial_core.
* one feedback I had received was that there may be uart device drivers not using serial_core. I am not sure if your approach addresses that.
* what I don't see is how we can implement our GPS device power control driver:
- the device should still present itself as a tty device (so that cat /dev/ttyO1 reports NMEA records) and should
not be completely hidden from user space or represented by a new interface type invented just for this device
(while the majority of other GPS receivers are still simple tty devices).
- how we can detect that the device is sending data to the UART while no user space process has the uart port open
i.e. when does the driver know when to start/stop the UART.
* I like that a driver can simply call uart_dev_config(udev, 115200, 'n', 8, 0); instead of our
uart_register_rx_notification(data->uart, rx_notification, &termios); where we have to partially
fill the termios structure.
* it appears to need more code than our proposal did:
>
> Rob
>
>
> Rob Herring (3):
> uart bus: Introduce new bus for UART slave devices
> tty: serial_core: make tty_struct optional
> tty: serial_core: add uart controller registration
>
> drivers/Kconfig | 2 +
> drivers/Makefile | 1 +
> drivers/tty/serial/serial_core.c | 11 +-
> drivers/tty/tty_buffer.c | 2 +
> drivers/uart/Kconfig | 17 ++
> drivers/uart/Makefile | 3 +
> drivers/uart/core.c | 458 +++++++++++++++++++++++++++++++++++++++
> drivers/uart/loopback.c | 72 ++++++
> include/linux/serial_core.h | 3 +-
> include/linux/uart_device.h | 163 ++++++++++++++
> 10 files changed, 730 insertions(+), 2 deletions(-)
> create mode 100644 drivers/uart/Kconfig
> create mode 100644 drivers/uart/Makefile
> create mode 100644 drivers/uart/core.c
> create mode 100644 drivers/uart/loopback.c
> create mode 100644 include/linux/uart_device.h
thereof 9 files, ~650 changes w/o loopback demo
vs.
> On 10/16/2015 11:08 AM, H. Nikolaus Schaller wrote:
>> H. Nikolaus Schaller (3):
>> tty: serial core: provide a method to search uart by phandle
>> tty: serial_core: add hooks for uart slave drivers
>> misc: Add w2sg0004 gps receiver driver
>>
>> .../devicetree/bindings/misc/wi2wi,w2sg0004.txt | 18 +
>> .../devicetree/bindings/serial/slaves.txt | 16 +
>> .../devicetree/bindings/vendor-prefixes.txt | 1 +
>> Documentation/serial/slaves.txt | 36 ++
>> drivers/misc/Kconfig | 18 +
>> drivers/misc/Makefile | 1 +
>> drivers/misc/w2sg0004.c | 443 +++++++++++++++++++++
>> drivers/tty/serial/serial_core.c | 214 +++++++++-
>> include/linux/serial_core.h | 25 +-
>> include/linux/w2sg0004.h | 27 ++
>> 10 files changed, 793 insertions(+), 6 deletions(-)
>> create mode 100644 Documentation/devicetree/bindings/misc/wi2wi,w2sg0004.txt
>> create mode 100644 Documentation/devicetree/bindings/serial/slaves.txt
>> create mode 100644 Documentation/serial/slaves.txt
>> create mode 100644 drivers/misc/w2sg0004.c
>> create mode 100644 include/linux/w2sg0004.h
Thereof 4 files, ~260 changes w/o gps demo and documentation/bindings.
BR and thanks,
Nikolaus
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:39 ` H. Nikolaus Schaller
@ 2016-08-18 10:47 ` Pavel Machek
2016-08-18 10:54 ` H. Nikolaus Schaller
2016-08-18 11:27 ` H. Nikolaus Schaller
2016-08-18 10:49 ` Marcel Holtmann
1 sibling, 2 replies; 103+ messages in thread
From: Pavel Machek @ 2016-08-18 10:47 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
>
> Thereof 4 files, ~260 changes w/o gps demo and documentation/bindings.
So what do you use for the serial devices? platform_device was vetoed
for that purpose by Greg.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:47 ` Pavel Machek
@ 2016-08-18 10:54 ` H. Nikolaus Schaller
2016-08-18 10:57 ` Greg Kroah-Hartman
2016-08-18 11:27 ` H. Nikolaus Schaller
1 sibling, 1 reply; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-18 10:54 UTC (permalink / raw)
To: Pavel Machek
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
Hi Pavel,
> Am 18.08.2016 um 12:47 schrieb Pavel Machek <pavel@ucw.cz>:
>
>
>>
>> Thereof 4 files, ~260 changes w/o gps demo and documentation/bindings.
>
> So what do you use for the serial devices? platform_device was vetoed
> for that purpose by Greg.
device tree?
This adds code of course - but only for the slave drivers. So you shouldn't count
them for a fair comparison of what it means for implementing a new API.
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:54 ` H. Nikolaus Schaller
@ 2016-08-18 10:57 ` Greg Kroah-Hartman
[not found] ` <20160818105759.GA642-U8xfFu+wG4EAvxtiuMwx3w@public.gmane.org>
0 siblings, 1 reply; 103+ messages in thread
From: Greg Kroah-Hartman @ 2016-08-18 10:57 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Pavel Machek, Rob Herring, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
On Thu, Aug 18, 2016 at 12:54:15PM +0200, H. Nikolaus Schaller wrote:
> Hi Pavel,
>
> > Am 18.08.2016 um 12:47 schrieb Pavel Machek <pavel@ucw.cz>:
> >
> >
> >>
> >> Thereof 4 files, ~260 changes w/o gps demo and documentation/bindings.
> >
> > So what do you use for the serial devices? platform_device was vetoed
> > for that purpose by Greg.
>
> device tree?
No.
This patchset from Rob is the way I have been saying it should be done
for years now. Yes, a "bus" takes up more boilerplate code (blame me
for that), but overall, it makes the drivers simpler, and fits into the
rest of the kernel driver/device model much better.
greg k-h
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:47 ` Pavel Machek
2016-08-18 10:54 ` H. Nikolaus Schaller
@ 2016-08-18 11:27 ` H. Nikolaus Schaller
1 sibling, 0 replies; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-18 11:27 UTC (permalink / raw)
To: Pavel Machek
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
Because it was misunderstood, here a longer answer.
> Am 18.08.2016 um 12:47 schrieb Pavel Machek <pavel@ucw.cz>:
>
>
>>
>> Thereof 4 files, ~260 changes w/o gps demo and documentation/bindings.
>
> So what do you use for the serial devices?
You misunderstood the w/o documentation/bindings in a way that the full patch
set doesn't use it. But it means changes w/o these aspects...
> platform_device was vetoed
> for that purpose by Greg.
That is true but not relevant at all since nobody wants to introduce platform_device
again.
I have just removed these from counting differences to make the number of
lines comparable to Rob's proposal.
Rob also uses device tree but has not added bindings or documentation to
his patch set so that it would be unfair to include them in the changes count in
one proposal and omit it in the other.
Generally it might not even be important to compare both approaches again
and then the number of files / changes is not important. But if it is, we should
count them correctly.
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:39 ` H. Nikolaus Schaller
2016-08-18 10:47 ` Pavel Machek
@ 2016-08-18 10:49 ` Marcel Holtmann
2016-08-18 10:55 ` Greg Kroah-Hartman
2016-08-18 11:02 ` H. Nikolaus Schaller
1 sibling, 2 replies; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-18 10:49 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Rob Herring, Greg Kroah-Hartman, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
Hi Nikolaus,
>> Currently, devices attached via a UART are not well supported in the
>> kernel. The problem is the device support is done in tty line disciplines,
>> various platform drivers to handle some sideband, and in userspace with
>> utilities such as hciattach.
>>
>> There have been several attempts to improve support, but they suffer from
>> still being tied into the tty layer and/or abusing the platform bus. This
>> is a prototype to show creating a proper UART bus for UART devices. It is
>> tied into the serial core (really struct uart_port) below the tty layer
>> in order to use existing serial drivers.
>>
>> This is functional with minimal testing using the loopback driver and
>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>> device). It still needs lots of work and polish.
>>
>> TODOs:
>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>> hoping all that complexity is from the tty layer and not needed here.
>> - Split out the controller for uart_ports into separate driver. Do we see
>> a need for controller drivers that are not standard serial drivers?
>> - Implement/test the removal paths
>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>> - Need better receive buffering than just a simple circular buffer or
>> perhaps a different receive interface (e.g. direct to client buffer)?
>> - Test with other UART drivers
>> - Convert a real driver/line discipline over to UART bus.
>>
>> Before I spend more time on this, I'm looking mainly for feedback on the
>> general direction and structure (the interface with the existing serial
>> drivers in particular).
>
> Some quick comments (can't do any real life tests in the next weeks) from my (biased) view:
>
> * tieing the solution into uart_port is the same as we had done. The difference seems to
> me that you completely bypass serial_core (and tty) while we want to integrate it with standard tty operation.
>
> We have tapped the tty layer only because it can not be 100% avoided if we use serial_core.
>
> * one feedback I had received was that there may be uart device drivers not using serial_core. I am not sure if your approach addresses that.
>
> * what I don't see is how we can implement our GPS device power control driver:
> - the device should still present itself as a tty device (so that cat /dev/ttyO1 reports NMEA records) and should
> not be completely hidden from user space or represented by a new interface type invented just for this device
> (while the majority of other GPS receivers are still simple tty devices).
> - how we can detect that the device is sending data to the UART while no user space process has the uart port open
> i.e. when does the driver know when to start/stop the UART.
I am actually not convinced that GPS should be represented as /dev/ttyS0 or similar TTY. It think they deserve their own driver exposing them as simple character devices. That way we can have a proper DEVTYPE and userspace can find them correctly. We can also annotate them if needed for special settings.
Such a driver then can also take care of the power control on open() and close(). As it should be done in the first place. And then we can also remove the RFKILL hacks for GPS devices as well. For example that is what Intel and Broadcom Bluetooth devices do now. The power control is hooked into hciconfig hci0 up/down.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:49 ` Marcel Holtmann
@ 2016-08-18 10:55 ` Greg Kroah-Hartman
2016-08-18 11:01 ` Marcel Holtmann
2016-08-18 11:10 ` Pavel Machek
2016-08-18 11:02 ` H. Nikolaus Schaller
1 sibling, 2 replies; 103+ messages in thread
From: Greg Kroah-Hartman @ 2016-08-18 10:55 UTC (permalink / raw)
To: Marcel Holtmann
Cc: H. Nikolaus Schaller, Rob Herring, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
On Thu, Aug 18, 2016 at 12:49:47PM +0200, Marcel Holtmann wrote:
> Hi Nikolaus,
>
> >> Currently, devices attached via a UART are not well supported in the
> >> kernel. The problem is the device support is done in tty line disciplines,
> >> various platform drivers to handle some sideband, and in userspace with
> >> utilities such as hciattach.
> >>
> >> There have been several attempts to improve support, but they suffer from
> >> still being tied into the tty layer and/or abusing the platform bus. This
> >> is a prototype to show creating a proper UART bus for UART devices. It is
> >> tied into the serial core (really struct uart_port) below the tty layer
> >> in order to use existing serial drivers.
> >>
> >> This is functional with minimal testing using the loopback driver and
> >> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> >> device). It still needs lots of work and polish.
> >>
> >> TODOs:
> >> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
> >> hoping all that complexity is from the tty layer and not needed here.
> >> - Split out the controller for uart_ports into separate driver. Do we see
> >> a need for controller drivers that are not standard serial drivers?
> >> - Implement/test the removal paths
> >> - Fix the receive callbacks for more than character at a time (i.e. DMA)
> >> - Need better receive buffering than just a simple circular buffer or
> >> perhaps a different receive interface (e.g. direct to client buffer)?
> >> - Test with other UART drivers
> >> - Convert a real driver/line discipline over to UART bus.
> >>
> >> Before I spend more time on this, I'm looking mainly for feedback on the
> >> general direction and structure (the interface with the existing serial
> >> drivers in particular).
> >
> > Some quick comments (can't do any real life tests in the next weeks) from my (biased) view:
> >
> > * tieing the solution into uart_port is the same as we had done. The difference seems to
> > me that you completely bypass serial_core (and tty) while we want to integrate it with standard tty operation.
> >
> > We have tapped the tty layer only because it can not be 100% avoided if we use serial_core.
> >
> > * one feedback I had received was that there may be uart device drivers not using serial_core. I am not sure if your approach addresses that.
> >
> > * what I don't see is how we can implement our GPS device power control driver:
> > - the device should still present itself as a tty device (so that cat /dev/ttyO1 reports NMEA records) and should
> > not be completely hidden from user space or represented by a new interface type invented just for this device
> > (while the majority of other GPS receivers are still simple tty devices).
> > - how we can detect that the device is sending data to the UART while no user space process has the uart port open
> > i.e. when does the driver know when to start/stop the UART.
>
> I am actually not convinced that GPS should be represented as
> /dev/ttyS0 or similar TTY. It think they deserve their own driver
> exposing them as simple character devices. That way we can have a
> proper DEVTYPE and userspace can find them correctly. We can also
> annotate them if needed for special settings.
I would _love_ to see that happen, but what about the GPS line
discipline that we have today? How would that match up with a char
device driver?
thanks,
greg k-h
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:55 ` Greg Kroah-Hartman
@ 2016-08-18 11:01 ` Marcel Holtmann
2016-08-18 11:24 ` Greg Kroah-Hartman
2016-08-18 11:10 ` Pavel Machek
1 sibling, 1 reply; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-18 11:01 UTC (permalink / raw)
To: Greg Kroah-Hartman
Cc: H. Nikolaus Schaller, Rob Herring, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, open list:BLUETOOTH DRIVERS, linux-serial,
linux-kernel
Hi Greg,
>>>> Currently, devices attached via a UART are not well supported in the
>>>> kernel. The problem is the device support is done in tty line disciplines,
>>>> various platform drivers to handle some sideband, and in userspace with
>>>> utilities such as hciattach.
>>>>
>>>> There have been several attempts to improve support, but they suffer from
>>>> still being tied into the tty layer and/or abusing the platform bus. This
>>>> is a prototype to show creating a proper UART bus for UART devices. It is
>>>> tied into the serial core (really struct uart_port) below the tty layer
>>>> in order to use existing serial drivers.
>>>>
>>>> This is functional with minimal testing using the loopback driver and
>>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>>>> device). It still needs lots of work and polish.
>>>>
>>>> TODOs:
>>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>>>> hoping all that complexity is from the tty layer and not needed here.
>>>> - Split out the controller for uart_ports into separate driver. Do we see
>>>> a need for controller drivers that are not standard serial drivers?
>>>> - Implement/test the removal paths
>>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>>>> - Need better receive buffering than just a simple circular buffer or
>>>> perhaps a different receive interface (e.g. direct to client buffer)?
>>>> - Test with other UART drivers
>>>> - Convert a real driver/line discipline over to UART bus.
>>>>
>>>> Before I spend more time on this, I'm looking mainly for feedback on the
>>>> general direction and structure (the interface with the existing serial
>>>> drivers in particular).
>>>
>>> Some quick comments (can't do any real life tests in the next weeks) from my (biased) view:
>>>
>>> * tieing the solution into uart_port is the same as we had done. The difference seems to
>>> me that you completely bypass serial_core (and tty) while we want to integrate it with standard tty operation.
>>>
>>> We have tapped the tty layer only because it can not be 100% avoided if we use serial_core.
>>>
>>> * one feedback I had received was that there may be uart device drivers not using serial_core. I am not sure if your approach addresses that.
>>>
>>> * what I don't see is how we can implement our GPS device power control driver:
>>> - the device should still present itself as a tty device (so that cat /dev/ttyO1 reports NMEA records) and should
>>> not be completely hidden from user space or represented by a new interface type invented just for this device
>>> (while the majority of other GPS receivers are still simple tty devices).
>>> - how we can detect that the device is sending data to the UART while no user space process has the uart port open
>>> i.e. when does the driver know when to start/stop the UART.
>>
>> I am actually not convinced that GPS should be represented as
>> /dev/ttyS0 or similar TTY. It think they deserve their own driver
>> exposing them as simple character devices. That way we can have a
>> proper DEVTYPE and userspace can find them correctly. We can also
>> annotate them if needed for special settings.
>
> I would _love_ to see that happen, but what about the GPS line
> discipline that we have today? How would that match up with a char
> device driver?
we have a GPS line discipline? What is that one doing? As far as I know all GPS implementations are fully userspace.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 11:01 ` Marcel Holtmann
@ 2016-08-18 11:24 ` Greg Kroah-Hartman
[not found] ` <20160818112435.GA20876-U8xfFu+wG4EAvxtiuMwx3w@public.gmane.org>
0 siblings, 1 reply; 103+ messages in thread
From: Greg Kroah-Hartman @ 2016-08-18 11:24 UTC (permalink / raw)
To: Marcel Holtmann
Cc: H. Nikolaus Schaller, Rob Herring, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, open list:BLUETOOTH DRIVERS, linux-serial,
linux-kernel
On Thu, Aug 18, 2016 at 01:01:24PM +0200, Marcel Holtmann wrote:
> Hi Greg,
>
> >>>> Currently, devices attached via a UART are not well supported in the
> >>>> kernel. The problem is the device support is done in tty line disciplines,
> >>>> various platform drivers to handle some sideband, and in userspace with
> >>>> utilities such as hciattach.
> >>>>
> >>>> There have been several attempts to improve support, but they suffer from
> >>>> still being tied into the tty layer and/or abusing the platform bus. This
> >>>> is a prototype to show creating a proper UART bus for UART devices. It is
> >>>> tied into the serial core (really struct uart_port) below the tty layer
> >>>> in order to use existing serial drivers.
> >>>>
> >>>> This is functional with minimal testing using the loopback driver and
> >>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> >>>> device). It still needs lots of work and polish.
> >>>>
> >>>> TODOs:
> >>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
> >>>> hoping all that complexity is from the tty layer and not needed here.
> >>>> - Split out the controller for uart_ports into separate driver. Do we see
> >>>> a need for controller drivers that are not standard serial drivers?
> >>>> - Implement/test the removal paths
> >>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
> >>>> - Need better receive buffering than just a simple circular buffer or
> >>>> perhaps a different receive interface (e.g. direct to client buffer)?
> >>>> - Test with other UART drivers
> >>>> - Convert a real driver/line discipline over to UART bus.
> >>>>
> >>>> Before I spend more time on this, I'm looking mainly for feedback on the
> >>>> general direction and structure (the interface with the existing serial
> >>>> drivers in particular).
> >>>
> >>> Some quick comments (can't do any real life tests in the next weeks) from my (biased) view:
> >>>
> >>> * tieing the solution into uart_port is the same as we had done. The difference seems to
> >>> me that you completely bypass serial_core (and tty) while we want to integrate it with standard tty operation.
> >>>
> >>> We have tapped the tty layer only because it can not be 100% avoided if we use serial_core.
> >>>
> >>> * one feedback I had received was that there may be uart device drivers not using serial_core. I am not sure if your approach addresses that.
> >>>
> >>> * what I don't see is how we can implement our GPS device power control driver:
> >>> - the device should still present itself as a tty device (so that cat /dev/ttyO1 reports NMEA records) and should
> >>> not be completely hidden from user space or represented by a new interface type invented just for this device
> >>> (while the majority of other GPS receivers are still simple tty devices).
> >>> - how we can detect that the device is sending data to the UART while no user space process has the uart port open
> >>> i.e. when does the driver know when to start/stop the UART.
> >>
> >> I am actually not convinced that GPS should be represented as
> >> /dev/ttyS0 or similar TTY. It think they deserve their own driver
> >> exposing them as simple character devices. That way we can have a
> >> proper DEVTYPE and userspace can find them correctly. We can also
> >> annotate them if needed for special settings.
> >
> > I would _love_ to see that happen, but what about the GPS line
> > discipline that we have today? How would that match up with a char
> > device driver?
>
> we have a GPS line discipline? What is that one doing? As far as I
> know all GPS implementations are fully userspace.
Hm, for some reason I thought that was what n_gsm.c was being used for,
but I could be wrong, I've never seen the hardware that uses that
code...
greg k-h
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:55 ` Greg Kroah-Hartman
2016-08-18 11:01 ` Marcel Holtmann
@ 2016-08-18 11:10 ` Pavel Machek
2016-08-18 11:18 ` H. Nikolaus Schaller
2016-08-18 11:47 ` Marcel Holtmann
1 sibling, 2 replies; 103+ messages in thread
From: Pavel Machek @ 2016-08-18 11:10 UTC (permalink / raw)
To: Greg Kroah-Hartman
Cc: Marcel Holtmann, H. Nikolaus Schaller, Rob Herring, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel,
herkne
Hi!
> > I am actually not convinced that GPS should be represented as
> > /dev/ttyS0 or similar TTY. It think they deserve their own driver
> > exposing them as simple character devices. That way we can have a
> > proper DEVTYPE and userspace can find them correctly. We can also
> > annotate them if needed for special settings.
>
> I would _love_ to see that happen, but what about the GPS line
> discipline that we have today? How would that match up with a char
> device driver?
./drivers/usb/serial/garmin_gps.c ?
Hmm, some cleanups would be welcome there... plus it would be good to
know what is its interface to userland... it is not easily apparent
from the code.
Actually, having some kind of common support for GPSes in the kernel
would be nice. (Chardev that spits NMEA data?) For example N900 GPS is
connected over network (phonet) interface, with userland driver
translating custom protocol into NMEA. Not very nice from "kernel
should provide hardware abstraction" point of view.
Best regards,
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 11:10 ` Pavel Machek
@ 2016-08-18 11:18 ` H. Nikolaus Schaller
2016-08-18 11:49 ` Marcel Holtmann
2016-08-18 11:47 ` Marcel Holtmann
1 sibling, 1 reply; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-18 11:18 UTC (permalink / raw)
To: Pavel Machek
Cc: Greg Kroah-Hartman, Marcel Holtmann, Rob Herring, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel,
herkne
> Am 18.08.2016 um 13:10 schrieb Pavel Machek <pavel@ucw.cz>:
>
> Hi!
>
>>> I am actually not convinced that GPS should be represented as
>>> /dev/ttyS0 or similar TTY. It think they deserve their own driver
>>> exposing them as simple character devices. That way we can have a
>>> proper DEVTYPE and userspace can find them correctly. We can also
>>> annotate them if needed for special settings.
>>
>> I would _love_ to see that happen, but what about the GPS line
>> discipline that we have today? How would that match up with a char
>> device driver?
>
> ./drivers/usb/serial/garmin_gps.c ?
>
> Hmm, some cleanups would be welcome there... plus it would be good to
> know what is its interface to userland... it is not easily apparent
> from the code.
>
> Actually, having some kind of common support for GPSes in the kernel
> would be nice. (Chardev that spits NMEA data?
Yes and no. How do you apply tcsetattr to such a device? More or less
by implementing another tty stack?
> ) For example N900 GPS is
> connected over network (phonet) interface, with userland driver
> translating custom protocol into NMEA. Not very nice from "kernel
> should provide hardware abstraction" point of view.
Indeed. In such a case the translation should be done in the kernel.
But it is not necessary for devices that already provide NEMA over UART.
Still user-space should be able to tcsetattr how it wants to see the records
(mainly CR/LF translations).
BR,
Nikolaus
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 11:18 ` H. Nikolaus Schaller
@ 2016-08-18 11:49 ` Marcel Holtmann
2016-08-18 12:16 ` H. Nikolaus Schaller
0 siblings, 1 reply; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-18 11:49 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Pavel Machek, Greg Kroah-Hartman, Rob Herring, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel,
herkne
Hi Nikolaus,
>>>> I am actually not convinced that GPS should be represented as
>>>> /dev/ttyS0 or similar TTY. It think they deserve their own driver
>>>> exposing them as simple character devices. That way we can have a
>>>> proper DEVTYPE and userspace can find them correctly. We can also
>>>> annotate them if needed for special settings.
>>>
>>> I would _love_ to see that happen, but what about the GPS line
>>> discipline that we have today? How would that match up with a char
>>> device driver?
>>
>> ./drivers/usb/serial/garmin_gps.c ?
>>
>> Hmm, some cleanups would be welcome there... plus it would be good to
>> know what is its interface to userland... it is not easily apparent
>> from the code.
>>
>> Actually, having some kind of common support for GPSes in the kernel
>> would be nice. (Chardev that spits NMEA data?
>
> Yes and no. How do you apply tcsetattr to such a device? More or less
> by implementing another tty stack?
>
>> ) For example N900 GPS is
>> connected over network (phonet) interface, with userland driver
>> translating custom protocol into NMEA. Not very nice from "kernel
>> should provide hardware abstraction" point of view.
>
> Indeed. In such a case the translation should be done in the kernel.
> But it is not necessary for devices that already provide NEMA over UART.
> Still user-space should be able to tcsetattr how it wants to see the records
> (mainly CR/LF translations).
I disagree here. NMEA is a standard and the kernel should just enforce framing of NMEA sentences. It makes no difference what the CR/LF is. Userspace gets full sentences.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 11:49 ` Marcel Holtmann
@ 2016-08-18 12:16 ` H. Nikolaus Schaller
0 siblings, 0 replies; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-18 12:16 UTC (permalink / raw)
To: Marcel Holtmann
Cc: Pavel Machek, Greg Kroah-Hartman, Rob Herring, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel,
herkne
> Am 18.08.2016 um 13:49 schrieb Marcel Holtmann <marcel@holtmann.org>:
>
> Hi Nikolaus,
>
>>>>> I am actually not convinced that GPS should be represented as
>>>>> /dev/ttyS0 or similar TTY. It think they deserve their own driver
>>>>> exposing them as simple character devices. That way we can have a
>>>>> proper DEVTYPE and userspace can find them correctly. We can also
>>>>> annotate them if needed for special settings.
>>>>
>>>> I would _love_ to see that happen, but what about the GPS line
>>>> discipline that we have today? How would that match up with a char
>>>> device driver?
>>>
>>> ./drivers/usb/serial/garmin_gps.c ?
>>>
>>> Hmm, some cleanups would be welcome there... plus it would be good to
>>> know what is its interface to userland... it is not easily apparent
>>> from the code.
>>>
>>> Actually, having some kind of common support for GPSes in the kernel
>>> would be nice. (Chardev that spits NMEA data?
>>
>> Yes and no. How do you apply tcsetattr to such a device? More or less
>> by implementing another tty stack?
>>
>>> ) For example N900 GPS is
>>> connected over network (phonet) interface, with userland driver
>>> translating custom protocol into NMEA. Not very nice from "kernel
>>> should provide hardware abstraction" point of view.
>>
>> Indeed. In such a case the translation should be done in the kernel.
>> But it is not necessary for devices that already provide NEMA over UART.
>> Still user-space should be able to tcsetattr how it wants to see the records
>> (mainly CR/LF translations).
>
> I disagree here. NMEA is a standard and the kernel should just enforce framing of NMEA sentences.
AFAIR, NMEA was originally sort of a serial bus going through a ship. Where masters (a gps receiver)
can send records with position and speed data and clients (e.g. an auto-pilot) can receive them and
process their actions and send control commands to a motor / winding engine. But I would have to do
more research about this.
> It makes no difference what the CR/LF is. Userspace gets full sentences.
NMEA defines that devices connected to the NMEA source receive characters and not sentences.
For example an NMEA record defines a checksum. Should that also be exposed to user space or hidden?
How should checksum errors be reported or handled by the kernel?
I would agree if we want to write an abstract "position in geospace" driver/subsystem which reports
the position on surface and height and speed and direction. Then we can hide everything in the kernel.
But this would no longer send sentences to user space but cooked coordinates. More like iio data.
And next issue: how should we handle GPS devices with a bidirectional interface where sending
some special command sequence over the UART switches to SIRF or some other proprietary
mode? Then, the driver (ans Linux) can't squeeze that into NMEA sentences any more. By
doing this in the kernel we make it more inflexible.
Puh, when digging into this topic it becomes more and more complex and we are making it more
complex than it is currently working.
BR,
Nikolaus
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 11:10 ` Pavel Machek
2016-08-18 11:18 ` H. Nikolaus Schaller
@ 2016-08-18 11:47 ` Marcel Holtmann
2016-08-18 13:01 ` Pavel Machek
1 sibling, 1 reply; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-18 11:47 UTC (permalink / raw)
To: Pavel Machek
Cc: Greg Kroah-Hartman, H. Nikolaus Schaller, Rob Herring, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel,
herkne
Hi Pavel,
>>> I am actually not convinced that GPS should be represented as
>>> /dev/ttyS0 or similar TTY. It think they deserve their own driver
>>> exposing them as simple character devices. That way we can have a
>>> proper DEVTYPE and userspace can find them correctly. We can also
>>> annotate them if needed for special settings.
>>
>> I would _love_ to see that happen, but what about the GPS line
>> discipline that we have today? How would that match up with a char
>> device driver?
>
> ./drivers/usb/serial/garmin_gps.c ?
>
> Hmm, some cleanups would be welcome there... plus it would be good to
> know what is its interface to userland... it is not easily apparent
> from the code.
however that driver is not a line discipline. That is just an USB driver. But I agree if we create a GPS driver framework / subsystem, then this one should be converted into using it.
> Actually, having some kind of common support for GPSes in the kernel
> would be nice. (Chardev that spits NMEA data?) For example N900 GPS is
> connected over network (phonet) interface, with userland driver
> translating custom protocol into NMEA. Not very nice from "kernel
> should provide hardware abstraction" point of view.
I agree that if we just had a dedicated GPS NMEA char device, then that would be great. However we might just add an additional /dev/unmea like /dev/uinput, /dev/uhid, /dev/vhci. It could be used for unit testing and also hardware where the protocol is in userspace in the first. Like the mentioned QMI or some Intel AT command based modem. We would then just convert oFono to create the /dev/unmea device for us. The advantage is that then even userspace NMEA device are part of the device tree and enumerated by udev.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 11:47 ` Marcel Holtmann
@ 2016-08-18 13:01 ` Pavel Machek
0 siblings, 0 replies; 103+ messages in thread
From: Pavel Machek @ 2016-08-18 13:01 UTC (permalink / raw)
To: Marcel Holtmann
Cc: Greg Kroah-Hartman, H. Nikolaus Schaller, Rob Herring, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel,
herkne
Hi!
> >>> I am actually not convinced that GPS should be represented as
> >>> /dev/ttyS0 or similar TTY. It think they deserve their own driver
> >>> exposing them as simple character devices. That way we can have a
> >>> proper DEVTYPE and userspace can find them correctly. We can also
> >>> annotate them if needed for special settings.
> >>
> >> I would _love_ to see that happen, but what about the GPS line
> >> discipline that we have today? How would that match up with a char
> >> device driver?
> >
> > ./drivers/usb/serial/garmin_gps.c ?
> >
> > Hmm, some cleanups would be welcome there... plus it would be good to
> > know what is its interface to userland... it is not easily apparent
> > from the code.
>
> however that driver is not a line discipline. That is just an USB driver. But I agree if we create a GPS driver framework / subsystem, then this one should be converted into using it.
>
Aha.
> > Actually, having some kind of common support for GPSes in the kernel
> > would be nice. (Chardev that spits NMEA data?) For example N900 GPS is
> > connected over network (phonet) interface, with userland driver
> > translating custom protocol into NMEA. Not very nice from "kernel
> > should provide hardware abstraction" point of view.
>
> I agree that if we just had a dedicated GPS NMEA char device, then that would be great. However we might just add an additional /dev/unmea like /dev/uinput, /dev/uhid, /dev/vhci. It could be used for unit testing and also hardware where the protocol is in userspace in the first. Like the mentioned QMI or some Intel AT command based modem. We would then just convert oFono to create the /dev/unmea device for us. The advantage is that then even userspace NMEA device are part of the device tree and enumerated by udev.
>
Yep, that would make sense, one day. (Another discussion is if NMEA is
the right protocol to use for kernel<->user interface, esr has some
rather good reasons to believe it is not. But that, too, can wait...)
Anyway, whatever works for bluetooth is likely to work for future gps
subsystem, so we should be ok here. And having support for serial
devices (not pretending they are platform) is a good step forward.
Best regards,
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 10:49 ` Marcel Holtmann
2016-08-18 10:55 ` Greg Kroah-Hartman
@ 2016-08-18 11:02 ` H. Nikolaus Schaller
2016-08-18 11:41 ` Marcel Holtmann
1 sibling, 1 reply; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-18 11:02 UTC (permalink / raw)
To: Marcel Holtmann
Cc: Rob Herring, Greg Kroah-Hartman, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
Hi Marcel,
> Am 18.08.2016 um 12:49 schrieb Marcel Holtmann <marcel@holtmann.org>:
>
> Hi Nikolaus,
>
>>> Currently, devices attached via a UART are not well supported in the
>>> kernel. The problem is the device support is done in tty line disciplines,
>>> various platform drivers to handle some sideband, and in userspace with
>>> utilities such as hciattach.
>>>
>>> There have been several attempts to improve support, but they suffer from
>>> still being tied into the tty layer and/or abusing the platform bus. This
>>> is a prototype to show creating a proper UART bus for UART devices. It is
>>> tied into the serial core (really struct uart_port) below the tty layer
>>> in order to use existing serial drivers.
>>>
>>> This is functional with minimal testing using the loopback driver and
>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>>> device). It still needs lots of work and polish.
>>>
>>> TODOs:
>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>>> hoping all that complexity is from the tty layer and not needed here.
>>> - Split out the controller for uart_ports into separate driver. Do we see
>>> a need for controller drivers that are not standard serial drivers?
>>> - Implement/test the removal paths
>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>>> - Need better receive buffering than just a simple circular buffer or
>>> perhaps a different receive interface (e.g. direct to client buffer)?
>>> - Test with other UART drivers
>>> - Convert a real driver/line discipline over to UART bus.
>>>
>>> Before I spend more time on this, I'm looking mainly for feedback on the
>>> general direction and structure (the interface with the existing serial
>>> drivers in particular).
>>
>> Some quick comments (can't do any real life tests in the next weeks) from my (biased) view:
>>
>> * tieing the solution into uart_port is the same as we had done. The difference seems to
>> me that you completely bypass serial_core (and tty) while we want to integrate it with standard tty operation.
>>
>> We have tapped the tty layer only because it can not be 100% avoided if we use serial_core.
>>
>> * one feedback I had received was that there may be uart device drivers not using serial_core. I am not sure if your approach addresses that.
>>
>> * what I don't see is how we can implement our GPS device power control driver:
>> - the device should still present itself as a tty device (so that cat /dev/ttyO1 reports NMEA records) and should
>> not be completely hidden from user space or represented by a new interface type invented just for this device
>> (while the majority of other GPS receivers are still simple tty devices).
>> - how we can detect that the device is sending data to the UART while no user space process has the uart port open
>> i.e. when does the driver know when to start/stop the UART.
>
> I am actually not convinced that GPS should be represented as /dev/ttyS0 or similar TTY. It think they deserve their own driver exposing them as simple character devices. That way we can have a proper DEVTYPE and userspace can find them correctly. We can also annotate them if needed for special settings.
Yes, we can. But AFAIK no user space GPS client is expecting to have a new DEVTYPE.
I have several different GPS devices. One is by bluetooth. So I get a /dev/tty through hci. Another one has an USB cable. I get a /dev/tty through some USB serial converter. A third one is integrated in a 4G modem which provides a /dev/ttyACM port. So I always get something which looks like a /dev/tty... Seems to be pretty standard.
Yes it would be nice to have a /dev/gps2 device.
And how do you want to control if the gps device should send records with cr / lf (INLCR, IGNCR)? Can you use tcsetattr?
>
> Such a driver then can also take care of the power control on open() and close(). As it should be done in the first place.
Yes it could do that as well.
> And then we can also remove the RFKILL hacks for GPS devices as well. For example that is what Intel and Broadcom Bluetooth devices do now. The power control is hooked into hciconfig hci0 up/down.
>
> Regards
>
> Marcel
>
BR,
Nikolaus
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 11:02 ` H. Nikolaus Schaller
@ 2016-08-18 11:41 ` Marcel Holtmann
[not found] ` <07FF6D1B-7B9B-441C-AFB9-E06AC5F469E2-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org>
0 siblings, 1 reply; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-18 11:41 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Rob Herring, Greg Kroah-Hartman, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, linux-bluetooth, linux-serial, linux-kernel
Hi Nikolaus,
>>>> Currently, devices attached via a UART are not well supported in the
>>>> kernel. The problem is the device support is done in tty line disciplines,
>>>> various platform drivers to handle some sideband, and in userspace with
>>>> utilities such as hciattach.
>>>>
>>>> There have been several attempts to improve support, but they suffer from
>>>> still being tied into the tty layer and/or abusing the platform bus. This
>>>> is a prototype to show creating a proper UART bus for UART devices. It is
>>>> tied into the serial core (really struct uart_port) below the tty layer
>>>> in order to use existing serial drivers.
>>>>
>>>> This is functional with minimal testing using the loopback driver and
>>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>>>> device). It still needs lots of work and polish.
>>>>
>>>> TODOs:
>>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>>>> hoping all that complexity is from the tty layer and not needed here.
>>>> - Split out the controller for uart_ports into separate driver. Do we see
>>>> a need for controller drivers that are not standard serial drivers?
>>>> - Implement/test the removal paths
>>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>>>> - Need better receive buffering than just a simple circular buffer or
>>>> perhaps a different receive interface (e.g. direct to client buffer)?
>>>> - Test with other UART drivers
>>>> - Convert a real driver/line discipline over to UART bus.
>>>>
>>>> Before I spend more time on this, I'm looking mainly for feedback on the
>>>> general direction and structure (the interface with the existing serial
>>>> drivers in particular).
>>>
>>> Some quick comments (can't do any real life tests in the next weeks) from my (biased) view:
>>>
>>> * tieing the solution into uart_port is the same as we had done. The difference seems to
>>> me that you completely bypass serial_core (and tty) while we want to integrate it with standard tty operation.
>>>
>>> We have tapped the tty layer only because it can not be 100% avoided if we use serial_core.
>>>
>>> * one feedback I had received was that there may be uart device drivers not using serial_core. I am not sure if your approach addresses that.
>>>
>>> * what I don't see is how we can implement our GPS device power control driver:
>>> - the device should still present itself as a tty device (so that cat /dev/ttyO1 reports NMEA records) and should
>>> not be completely hidden from user space or represented by a new interface type invented just for this device
>>> (while the majority of other GPS receivers are still simple tty devices).
>>> - how we can detect that the device is sending data to the UART while no user space process has the uart port open
>>> i.e. when does the driver know when to start/stop the UART.
>>
>> I am actually not convinced that GPS should be represented as /dev/ttyS0 or similar TTY. It think they deserve their own driver exposing them as simple character devices. That way we can have a proper DEVTYPE and userspace can find them correctly. We can also annotate them if needed for special settings.
>
> Yes, we can. But AFAIK no user space GPS client is expecting to have a new DEVTYPE.
but we can fix userspace clients to deal with DEVTYPE.
> I have several different GPS devices. One is by bluetooth. So I get a /dev/tty through hci. Another one has an USB cable. I get a /dev/tty through some USB serial converter. A third one is integrated in a 4G modem which provides a /dev/ttyACM port. So I always get something which looks like a /dev/tty... Seems to be pretty standard.
Actually for Bluetooth RFCOMM it would be a lot better to use the RFCOMM socket instead of the TTY emulation. However that said, Bluetooth RFCOMM is already split in a way that you can have either a socket or a TTY emulation. There is nothing stopping us from adding a GPS emulation and with that natively hooking it up to a future GPS driver. I mean why not have a GPS subsystem that allows for that. I know this is future talk, but it can be done.
Same goes for the USB GPS devices that use a serial converter. If they use proper VID:PID or some sort of identification, we can have a dedicated USB driver that matches it to a GPS device. At the end of the day, the only difference for the usb-serial driver is if it registers a TTY or a future GPS device.
The 4G modem ones are a bit funky. Not all of them expose a ttyACM port btw. Some of them have the NMEA via Qualcomm QMI or some other channel. So inside oFono we have abstracted that into a file descriptor so that power control etc. is handled by oFono. Since you need to use the telephony stack to control the GPS state. But again here, there is nothing stopping us from moving parts of QMI into the kernel. We have done that for the Nokia ISI and the ST-Ericsson CAIF already.
However honestly, my main focus would be to get Bluetooth UARTs integrated natively without line discipline before I would worry about GPS.
> Yes it would be nice to have a /dev/gps2 device.
>
> And how do you want to control if the gps device should send records with cr / lf (INLCR, IGNCR)? Can you use tcsetattr?
That needs to be seen. In general NMEA does not need it. However there is more than NMEA out there. Maybe it would need to focus on NMEA GPS anyway. As said above, oFono just hands out the NMEA sentences for QMI devices via file descriptor. So I am not sure we need to control that much.
I mean with Bluetooth we have done a bunch of extra framing enforcement so that a read() only returns a full frame. So that userspace applications have it a lot easier and don't have to worry about byte-byte reading. Something similar could be done for GPS NMEA. Anyway, I am just pointing out ideas here. We do not have the UART bus upstream yet.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
` (4 preceding siblings ...)
2016-08-18 10:39 ` H. Nikolaus Schaller
@ 2016-08-18 11:02 ` Pavel Machek
2016-08-18 13:07 ` Linus Walleij
` (3 subsequent siblings)
9 siblings, 0 replies; 103+ messages in thread
From: Pavel Machek @ 2016-08-18 11:02 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Arnd Bergmann, Linus Walleij,
linux-bluetooth, linux-serial, linux-kernel
Hi!
> Before I spend more time on this, I'm looking mainly for feedback on the
> general direction and structure (the interface with the existing serial
> drivers in particular).
Looks good to me.
Thanks,
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
` (5 preceding siblings ...)
2016-08-18 11:02 ` Pavel Machek
@ 2016-08-18 13:07 ` Linus Walleij
2016-08-18 17:31 ` Marcel Holtmann
2016-08-18 14:25 ` One Thousand Gnomes
` (2 subsequent siblings)
9 siblings, 1 reply; 103+ messages in thread
From: Linus Walleij @ 2016-08-18 13:07 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Arnd Bergmann,
linux-bluetooth@vger.kernel.org, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Thu, Aug 18, 2016 at 3:14 AM, Rob Herring <robh@kernel.org> wrote:
> Currently, devices attached via a UART are not well supported in the
> kernel. The problem is the device support is done in tty line disciplines,
> various platform drivers to handle some sideband, and in userspace with
> utilities such as hciattach.
Freaking *awesome* Rob, this really really needs to happen.
I'm very happy that you're driving this.
> This is functional with minimal testing using the loopback driver and
> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> device). It still needs lots of work and polish.
I have Bluetooth (HCI) over UART on the Nomadik and Ux500,
both with DMA support for the PL011 too. So I hope to be able
to utilize this.
(The HCI transport is then used for GPS, FM radio and whatnot
but that is another issue.)
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 13:07 ` Linus Walleij
@ 2016-08-18 17:31 ` Marcel Holtmann
0 siblings, 0 replies; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-18 17:31 UTC (permalink / raw)
To: Linus Walleij
Cc: Rob Herring, Greg Kroah-Hartman, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, linux-bluetooth@vger.kernel.org,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
Hi Linus,
>> Currently, devices attached via a UART are not well supported in the
>> kernel. The problem is the device support is done in tty line disciplines,
>> various platform drivers to handle some sideband, and in userspace with
>> utilities such as hciattach.
>
> Freaking *awesome* Rob, this really really needs to happen.
> I'm very happy that you're driving this.
>
>> This is functional with minimal testing using the loopback driver and
>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>> device). It still needs lots of work and polish.
>
> I have Bluetooth (HCI) over UART on the Nomadik and Ux500,
> both with DMA support for the PL011 too. So I hope to be able
> to utilize this.
>
> (The HCI transport is then used for GPS, FM radio and whatnot
> but that is another issue.)
that is something we can already solve via regmap. We have started work on Intel LnP which also includes a FM radio chip where registers/interrupts are exposed via HCI commands/events. So fundamentally the Bluetooth HCI device would expose the GPS and FM radio nodes via regmap.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
` (6 preceding siblings ...)
2016-08-18 13:07 ` Linus Walleij
@ 2016-08-18 14:25 ` One Thousand Gnomes
2016-08-18 15:14 ` H. Nikolaus Schaller
2016-08-18 22:25 ` Rob Herring
2016-08-18 20:29 ` Sebastian Reichel
2016-08-22 12:37 ` Arnd Bergmann
9 siblings, 2 replies; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-18 14:25 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Arnd Bergmann, Linus Walleij,
linux-bluetooth, linux-serial, linux-kernel
On Wed, 17 Aug 2016 20:14:42 -0500
Rob Herring <robh@kernel.org> wrote:
This was proposed ages ago and the point clearly made that
a) the idea doesn't work because uarts are not required to use the uart
layer and even those that do sometimes only use half of it
b) that you should use the tty_port abstraction
So instead of just waiting some months and recycling the proposals it's
unfortunate that no listening and reworking was done.
https://lkml.org/lkml/2016/1/18/177
So I'm giving this a large neon flashing NAK, because none of the
problems have been addressed.
> Currently, devices attached via a UART are not well supported in the
> kernel. The problem is the device support is done in tty line disciplines,
> various platform drivers to handle some sideband, and in userspace with
> utilities such as hciattach.
For most platforms it works very nicely and out of the box. The only
real issue I have actually seen is the bandwidth issue from early tty
based 3G modems. That's not hard to fix with some tty buffer changes.
Basically you need a tty port pointer that is atomic exchangable and
points either to the usual tty queue logic or to a 'fastpath' handler
which just gets thrown a block of bytes and told to use them or lose them
- which is the interface the non n_tty ldiscs want anyway. That's exactly
what you would need to fix to support in kernel stuff as well. The tty
queue mechanism for devices that can receive in blocks just becomes a
fastpath.
There are some disgusting Android turds floating around out of tree where
people use things like userspace GPIO line control but you won't fix most
of those anyway because they are generally being used for user
space modules including dumb GPS where the US government rules won't allow
them to be open sourced anyway.
> - Split out the controller for uart_ports into separate driver. Do we see
> a need for controller drivers that are not standard serial drivers?
As I told you over six months ago uart_port is not the correct
abstraction. You need to be working at the tty_port layer. The original
design of tty_port was indeed partly to push towards being able to have a
serial interface that is in use but not open to user space. The rather
nice rework that the maintainers have done to put the buffers in the
tty_port takes it closer still.
Plenty of the classic serial port interfaces also don't use the UART
layer including every USB device (which is most of them these days), SDIO
and others. USB has to be covered for this to be sensible.
Your changes also don't work because serial uart drivers are not obliged
to use any of the uart buffering helpers and particularly on the rx side
many do not do so and the performance hit would be too high.
It's been explained how to make it work with tty_port, every tty is a
dynamic file handle life time object bound to a tty_port. Every tty has a
tty_port, every tty driver has a tty_port.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 14:25 ` One Thousand Gnomes
@ 2016-08-18 15:14 ` H. Nikolaus Schaller
[not found] ` <20160818163809.1b2fcfe5@lxorguk.ukuu.org.uk>
2016-08-18 22:25 ` Rob Herring
1 sibling, 1 reply; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-18 15:14 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Arnd Bergmann, Linus Walleij, linux-bluetooth, linux-serial,
linux-kernel
Hi Alan,
> Am 18.08.2016 um 16:25 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
>
> On Wed, 17 Aug 2016 20:14:42 -0500
> Rob Herring <robh@kernel.org> wrote:
>
> This was proposed ages ago and the point clearly made that
>
> a) the idea doesn't work because uarts are not required to use the uart
> layer and even those that do sometimes only use half of it
>
> b) that you should use the tty_port abstraction
>
> So instead of just waiting some months and recycling the proposals it's
> unfortunate that no listening and reworking was done.
>
> https://lkml.org/lkml/2016/1/18/177
>
> So I'm giving this a large neon flashing NAK, because none of the
> problems have been addressed.
>
>> Currently, devices attached via a UART are not well supported in the
>> kernel. The problem is the device support is done in tty line disciplines,
>> various platform drivers to handle some sideband, and in userspace with
>> utilities such as hciattach.
>
> For most platforms it works very nicely and out of the box. The only
> real issue I have actually seen is the bandwidth issue from early tty
> based 3G modems. That's not hard to fix with some tty buffer changes.
> Basically you need a tty port pointer that is atomic exchangable and
> points either to the usual tty queue logic or to a 'fastpath' handler
> which just gets thrown a block of bytes and told to use them or lose them
> - which is the interface the non n_tty ldiscs want anyway. That's exactly
> what you would need to fix to support in kernel stuff as well. The tty
> queue mechanism for devices that can receive in blocks just becomes a
> fastpath.
>
> There are some disgusting Android turds floating around out of tree where
> people use things like userspace GPIO line control but you won't fix most
> of those anyway because they are generally being used for user
> space modules including dumb GPS where the US government rules won't allow
> them to be open sourced anyway.
>
>> - Split out the controller for uart_ports into separate driver. Do we see
>> a need for controller drivers that are not standard serial drivers?
>
> As I told you over six months ago uart_port is not the correct
> abstraction. You need to be working at the tty_port layer. The original
> design of tty_port was indeed partly to push towards being able to have a
> serial interface that is in use but not open to user space. The rather
> nice rework that the maintainers have done to put the buffers in the
> tty_port takes it closer still.
>
> Plenty of the classic serial port interfaces also don't use the UART
> layer including every USB device (which is most of them these days), SDIO
> and others. USB has to be covered for this to be sensible.
It looks as if you try to solve a different problem than some of us. Maybe this is
the reason why you get the impression that nobody is listening to your proposal
(but that seems to be common for this topic - I have the impression that
nobody is listening to my proposals... so don't mind).
I can only talk for my device where I just want to be able to write a driver that
gets access to a low level physical UART within a SoC (a little abstracted
by uart_port) to directly talk to a device connected to such an UART for reasons
I have explained plenty of times.
Other devices may have orthogonal needs (or suspected needs) and hence
a single solution may not fit everybody.
>
> Your changes also don't work because serial uart drivers are not obliged
> to use any of the uart buffering helpers and particularly on the rx side
> many do not do so and the performance hit would be too high.
The SoC I have, is using it.
>
> It's been explained how to make it work with tty_port, every tty is a
> dynamic file handle life time object bound to a tty_port. Every tty has a
> tty_port, every tty driver has a tty_port.
>
> Alan
BR, Nikolaus
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 14:25 ` One Thousand Gnomes
2016-08-18 15:14 ` H. Nikolaus Schaller
@ 2016-08-18 22:25 ` Rob Herring
2016-08-19 11:38 ` One Thousand Gnomes
1 sibling, 1 reply; 103+ messages in thread
From: Rob Herring @ 2016-08-18 22:25 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Thu, Aug 18, 2016 at 9:25 AM, One Thousand Gnomes
<gnomes@lxorguk.ukuu.org.uk> wrote:
> On Wed, 17 Aug 2016 20:14:42 -0500
> Rob Herring <robh@kernel.org> wrote:
>
> This was proposed ages ago and the point clearly made that
>
> a) the idea doesn't work because uarts are not required to use the uart
> layer and even those that do sometimes only use half of it
>
> b) that you should use the tty_port abstraction
>
> So instead of just waiting some months and recycling the proposals it's
> unfortunate that no listening and reworking was done.
>
> https://lkml.org/lkml/2016/1/18/177
>
> So I'm giving this a large neon flashing NAK, because none of the
> problems have been addressed.
>
>> Currently, devices attached via a UART are not well supported in the
>> kernel. The problem is the device support is done in tty line disciplines,
>> various platform drivers to handle some sideband, and in userspace with
>> utilities such as hciattach.
>
> For most platforms it works very nicely and out of the box. The only
> real issue I have actually seen is the bandwidth issue from early tty
> based 3G modems. That's not hard to fix with some tty buffer changes.
> Basically you need a tty port pointer that is atomic exchangable and
> points either to the usual tty queue logic or to a 'fastpath' handler
> which just gets thrown a block of bytes and told to use them or lose them
> - which is the interface the non n_tty ldiscs want anyway. That's exactly
> what you would need to fix to support in kernel stuff as well. The tty
> queue mechanism for devices that can receive in blocks just becomes a
> fastpath.
>
> There are some disgusting Android turds floating around out of tree where
> people use things like userspace GPIO line control but you won't fix most
> of those anyway because they are generally being used for user
> space modules including dumb GPS where the US government rules won't allow
> them to be open sourced anyway.
>
>> - Split out the controller for uart_ports into separate driver. Do we see
>> a need for controller drivers that are not standard serial drivers?
>
> As I told you over six months ago uart_port is not the correct
> abstraction. You need to be working at the tty_port layer. The original
> design of tty_port was indeed partly to push towards being able to have a
> serial interface that is in use but not open to user space. The rather
> nice rework that the maintainers have done to put the buffers in the
> tty_port takes it closer still.
>
> Plenty of the classic serial port interfaces also don't use the UART
> layer including every USB device (which is most of them these days), SDIO
> and others. USB has to be covered for this to be sensible.
Plenty? Really?. Lets break down the tty drivers in the kernel which
don't use uart_port.
Consoles/Debug:
arch/alpha/kernel/srmcons.c
arch/cris/arch-v10/kernel/debugport.c
arch/ia64/hp/sim/simserial.c
arch/m68k/emu/nfcon.c
arch/parisc/kernel/pdc_cons.c
arch/xtensa/platforms/iss/console.c
drivers/char/ttyprintk.c
drivers/tty/bfin_jtag_comm.c
drivers/tty/ehv_bytechan.c
drivers/tty/hvc/hvc_console.c
drivers/tty/hvc/hvcs.c
drivers/tty/hvc/hvsi.c
drivers/tty/serial/kgdb_nmi.c
drivers/tty/mips_ejtag_fdc.c
drivers/tty/metag_da.c
drivers/misc/pti.c
SDIO UART:
drivers/mmc/card/sdio_uart.c
S390 (don't think BT dongle is a use case):
drivers/s390/char/con3215.c
drivers/s390/char/sclp_tty.c
drivers/s390/char/sclp_vt220.c
drivers/s390/char/tty3270.c
Firewire serial:
drivers/staging/fwserial/fwserial.c
Amiga serial:
drivers/tty/amiserial.c
Android emulator:
drivers/tty/goldfish.c
Multi-port serial boards (standard connectors and not embedded with
sideband signals):
drivers/tty/cyclades.c
drivers/tty/isicom.c
drivers/tty/moxa.c
drivers/tty/mxser.c
drivers/tty/rocket.c
drivers/tty/synclink.c
drivers/tty/synclink_gt.c
drivers/tty/synclinkmp.c
drivers/char/pcmcia/synclink_cs.c
drivers/ipack/devices/ipoctal.c
drivers/staging/dgnc/dgnc_tty.c
Modems (already a slave device):
drivers/isdn/capi/capi.c
drivers/isdn/gigaset/interface.c
drivers/isdn/i4l/isdn_tty.c
drivers/tty/nozomi.c
drivers/tty/ipwireless/tty.c
drivers/tty/serial/ifx6x60.c
drivers/net/usb/hso.c
drivers/staging/gdm724x/gdm_tty.c
drivers/usb/class/cdc-acm.c
USB:
drivers/usb/gadget/function/u_serial.c
drivers/usb/serial/usb-serial.c
Virtual devices:
net/bluetooth/rfcomm/tty.c
net/irda/ircomm/ircomm_tty.c
Could be updated to use uart_port:
drivers/tty/serial/crisv10.c
The only ones here I see us caring about are USB and SDIO as you
mentioned. SDIO suffers from the same embedded problem we are trying
to solve here with UART slave devices. The devices are always soldered
down with sideband GPIOs and power. If there is any device, then it's
ultimately going to need its own SDIO driver, not the the generic
sdio-uart. So the generic sdio-uart is pretty useless except maybe for
a discreet SDIO card which I haven't seen in at least 10 years or in a
product for 15 years.
That leaves usb-serial. If the current support is good enough, then
that will continue to work (as you said elsewhere, can't break
userspace). If someone really wants to do USB serial and wire in
sideband controls, then we could provide a host driver that hooks into
usb_serial_port.
> Your changes also don't work because serial uart drivers are not obliged
> to use any of the uart buffering helpers and particularly on the rx side
> many do not do so and the performance hit would be too high.
Do you have an example?
The only uart buffering helper is for the receive side with
uart_insert_char. Sure, a character at a time is not efficient, but
that is easily rectified. Or do you mean something else?
Rob
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 22:25 ` Rob Herring
@ 2016-08-19 11:38 ` One Thousand Gnomes
2016-08-19 15:36 ` Sebastian Reichel
0 siblings, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-19 11:38 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> Plenty? Really?. Lets break down the tty drivers in the kernel which
> don't use uart_port.
That's the wrong list - those that use uart port but don't always use the
uart_insert_char helpers will also break. So you can start by adding
8250
amba-pl011
atmel_serial
bcm63xx_uart
bfin_sport
bfin_sport_uart
crisv10
efm32-uart
etraxfs-uart
fsl_lpuart
icom
ifx6060
imx
ioc3_serial
ioc4_serial
kgdb_nmi
lantiq
lpc32xx_hs
m32r_sio
men_z135_uart
meson_uart
mpc52xx_uart
mps2-uart
mpsc
msm_serial
mux
mvebu-uart
mxs-auart
pch_uart
pic32_uart
pmac_zilog
samsung
serial-tegra
sh-sci
sirfsoc_uart
sn_console
sunhv
sunsab
sunsu
sunzilog
tilegx
timbuart
uartline
ucc_uart
vt8500_serial
Some of those you could handle reasonably easily as they are byte
oriented, however if your code takes any longer in clock terms to run on
the low end devices you'll be a regression. Some of these don't use
uart_insert_char because the cost of that tips them over the available
clock times.
Quite a few of them however use tty_insert_flip_string or the other
buffer handling functions, particularly when doing DMA so you would have
to do significant work to fit them into some 'byte callback' type model.
This again is why it needs to be at the tty_port layer. The receive paths
can be cleanly intercepted at the point you'd push to an ldisc - the
driver level code on rx doesn't care if you have a tty attached, because
bytes arrived whether the tty is open or not.
In the case of 8250 all the recent x86 class systems which have things
like bluetooth attached via the LPSS are using 8250 and with DMA so your
interface simply won't work.
There are also some other slight complications when you look at real
world implementations. Android devices tend to keep the GPS in userspace
so most of then can't use some magic extra API but just drive GPIO lines
via the sysfs GPIO interface. Most Android doesn't use the kernel BT
stack either.
Quite a few Android and other embedded devices also do power management by
shutting off the UART, routing the rx line to an edge triggered GPIO and
on the interrupt flipping the UART back on and losing the first byte,
picking a protocol that can recover from it.
Your model doesn't I think cover that, although I am somewhat at a loss as
to how to do that nicely!
> Consoles/Debug:
> arch/alpha/kernel/srmcons.c
> arch/cris/arch-v10/kernel/debugport.c
> arch/ia64/hp/sim/simserial.c
> arch/m68k/emu/nfcon.c
> arch/parisc/kernel/pdc_cons.c
> arch/xtensa/platforms/iss/console.c
> drivers/char/ttyprintk.c
> drivers/tty/bfin_jtag_comm.c
> drivers/tty/ehv_bytechan.c
> drivers/tty/hvc/hvc_console.c
> drivers/tty/hvc/hvcs.c
> drivers/tty/hvc/hvsi.c
> drivers/tty/serial/kgdb_nmi.c
> drivers/tty/mips_ejtag_fdc.c
> drivers/tty/metag_da.c
> drivers/misc/pti.c
You could attach a dongle of some sort to a supposed console/debug port
and people do that kind of crap on embedded devices to save a few cents.
The ones above look fine though.
> SDIO UART:
> drivers/mmc/card/sdio_uart.c
This is an area that definitely needs covering, except that the way the
power works may be completely opaque to the OS if it's something like an
ACPI OpRegion controlling it.
> S390 (don't think BT dongle is a use case):
> drivers/s390/char/con3215.c
> drivers/s390/char/sclp_tty.c
> drivers/s390/char/sclp_vt220.c
> drivers/s390/char/tty3270.c
I would prefer to think of the fact BT on S390 *would* work as a test of
the API being right.
> Firewire serial:
> drivers/staging/fwserial/fwserial.c
>
> Amiga serial:
> drivers/tty/amiserial.c
>
> Android emulator:
> drivers/tty/goldfish.c
>
> Multi-port serial boards (standard connectors and not embedded with
> sideband signals):
> drivers/tty/cyclades.c
> drivers/tty/isicom.c
> drivers/tty/moxa.c
> drivers/tty/mxser.c
> drivers/tty/rocket.c
> drivers/tty/synclink.c
> drivers/tty/synclink_gt.c
> drivers/tty/synclinkmp.c
> drivers/char/pcmcia/synclink_cs.c
> drivers/ipack/devices/ipoctal.c
> drivers/staging/dgnc/dgnc_tty.c
>
> Modems (already a slave device):
> drivers/isdn/capi/capi.c
> drivers/isdn/gigaset/interface.c
> drivers/isdn/i4l/isdn_tty.c
> drivers/tty/nozomi.c
> drivers/tty/ipwireless/tty.c
> drivers/tty/serial/ifx6x60.c
> drivers/net/usb/hso.c
> drivers/staging/gdm724x/gdm_tty.c
> drivers/usb/class/cdc-acm.c
>
> USB:
> drivers/usb/gadget/function/u_serial.c
> drivers/usb/serial/usb-serial.c
Your list for USB is misleading. Just about every USB serial port uses
usb-serial as a midlayer so you are basically saying "Let's make a giant
weird special case". Just listing usb-serial would be like just listing
serial-core and saying you only support one device.
> That leaves usb-serial. If the current support is good enough, then
> that will continue to work (as you said elsewhere, can't break
> userspace). If someone really wants to do USB serial and wire in
> sideband controls, then we could provide a host driver that hooks into
> usb_serial_port.
Alreay happens when people are doing strange things nailing legacy
devices to HSIC/SSIC. USB is not just a pile of external cables that
always have the plug upside down, it has specifications for directly
routed low voltage on PCB consumers and bridges.
The fact you want two different host drivers and two APIs for the same
object connected to two identical interfaces but on different busses
should be raising alarm bells. We don't have different interfaces for
NE2000 over PCI or NE2000 over ISA !
> > Your changes also don't work because serial uart drivers are not obliged
> > to use any of the uart buffering helpers and particularly on the rx side
> > many do not do so and the performance hit would be too high.
>
> Do you have an example?
>
> The only uart buffering helper is for the receive side with
> uart_insert_char. Sure, a character at a time is not efficient, but
> that is easily rectified. Or do you mean something else?
Not all of the uart drivers even use uart_insert_char. It's a convenience
helper that most of them bypass because it's completely useless if you
are doing things like DMA. Even the modern x86 PC UARTs don't and can't
use uart_insert_char and that basically is a killer.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 11:38 ` One Thousand Gnomes
@ 2016-08-19 15:36 ` Sebastian Reichel
0 siblings, 0 replies; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-19 15:36 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 1835 bytes --]
Hi,
On Fri, Aug 19, 2016 at 12:38:08PM +0100, One Thousand Gnomes wrote:
> There are also some other slight complications when you look at
> real world implementations. Android devices tend to keep the GPS
> in userspace so most of them can't use some magic extra API but
> just drive GPIO lines via the sysfs GPIO interface. Most Android
> doesn't use the kernel BT stack either.
I don't get the reasoning for this one. What has it to do with
an in-kernel API? People are also using libusb or doing i2c/spi
from userspace. Nevertheless we have an in-kernel API for those.
> Quite a few Android and other embedded devices also do power
> management by shutting off the UART, routing the rx line to an
> edge triggered GPIO and on the interrupt flipping the UART back
> on and losing the first byte, picking a protocol that can recover
> from it.
>
> Your model doesn't I think cover that, although I am somewhat at a
> loss as to how to do that nicely!
On OMAP this is supported by the serial driver via runtime PM and
wakeirq.
Actually my usecase for the API (bluetooth on Nokia N900, N950, N9),
there is an extra GPIO for the power management (high = uart
should be able to receive sth., low = uart can sleep). For this
I can just disable the wakeirq in the UART by not adding it to DT
and instead runtime manage it from the uart_dev child device.
While we are on that topic: The omap-serial driver does not enable
runtime PM by default, since it does not know if the remote side is
ok with loosing the first byte(s). One is expected to enable it
using the sysfs API.
But I think it should be safe to enable runtime PM for the serial
device in uart_dev_connect(). Due to the child device it will still
be kept disabled, except when the uart_dev also implements runtime_pm.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
` (7 preceding siblings ...)
2016-08-18 14:25 ` One Thousand Gnomes
@ 2016-08-18 20:29 ` Sebastian Reichel
2016-08-18 23:08 ` Rob Herring
2016-08-22 12:37 ` Arnd Bergmann
9 siblings, 1 reply; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-18 20:29 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, linux-bluetooth, linux-serial,
linux-kernel
[-- Attachment #1: Type: text/plain, Size: 2511 bytes --]
Hi Rob,
Thanks for going forward and implementing this. I also started,
but was far from a functional state.
On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
> Currently, devices attached via a UART are not well supported in
> the kernel. The problem is the device support is done in tty line
> disciplines, various platform drivers to handle some sideband, and
> in userspace with utilities such as hciattach.
>
> There have been several attempts to improve support, but they suffer from
> still being tied into the tty layer and/or abusing the platform bus. This
> is a prototype to show creating a proper UART bus for UART devices. It is
> tied into the serial core (really struct uart_port) below the tty layer
> in order to use existing serial drivers.
>
> This is functional with minimal testing using the loopback driver and
> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> device). It still needs lots of work and polish.
>
> TODOs:
> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
> hoping all that complexity is from the tty layer and not needed here.
> - Split out the controller for uart_ports into separate driver. Do we see
> a need for controller drivers that are not standard serial drivers?
> - Implement/test the removal paths
> - Fix the receive callbacks for more than character at a time (i.e. DMA)
> - Need better receive buffering than just a simple circular buffer or
> perhaps a different receive interface (e.g. direct to client buffer)?
> - Test with other UART drivers
> - Convert a real driver/line discipline over to UART bus.
>
> Before I spend more time on this, I'm looking mainly for feedback on the
> general direction and structure (the interface with the existing serial
> drivers in particular).
I had a look at the uart_dev API:
int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
int uart_dev_connect(struct uart_device *udev);
The flow control configuration should be done separately. e.g.:
uart_dev_flow_control(struct uart_device *udev, bool enable);
int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
UART communication does not have to be host-initiated, so this
API requires polling. Either some function similar to poll in
userspace is needed, or it should be implemented as callback.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 20:29 ` Sebastian Reichel
@ 2016-08-18 23:08 ` Rob Herring
2016-08-19 5:21 ` Sebastian Reichel
0 siblings, 1 reply; 103+ messages in thread
From: Rob Herring @ 2016-08-18 23:08 UTC (permalink / raw)
To: Sebastian Reichel
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
On Thu, Aug 18, 2016 at 3:29 PM, Sebastian Reichel <sre@kernel.org> wrote:
> Hi Rob,
>
> Thanks for going forward and implementing this. I also started,
> but was far from a functional state.
>
> On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
>> Currently, devices attached via a UART are not well supported in
>> the kernel. The problem is the device support is done in tty line
>> disciplines, various platform drivers to handle some sideband, and
>> in userspace with utilities such as hciattach.
>>
>> There have been several attempts to improve support, but they suffer from
>> still being tied into the tty layer and/or abusing the platform bus. This
>> is a prototype to show creating a proper UART bus for UART devices. It is
>> tied into the serial core (really struct uart_port) below the tty layer
>> in order to use existing serial drivers.
>>
>> This is functional with minimal testing using the loopback driver and
>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>> device). It still needs lots of work and polish.
>>
>> TODOs:
>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>> hoping all that complexity is from the tty layer and not needed here.
>> - Split out the controller for uart_ports into separate driver. Do we see
>> a need for controller drivers that are not standard serial drivers?
>> - Implement/test the removal paths
>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>> - Need better receive buffering than just a simple circular buffer or
>> perhaps a different receive interface (e.g. direct to client buffer)?
>> - Test with other UART drivers
>> - Convert a real driver/line discipline over to UART bus.
>>
>> Before I spend more time on this, I'm looking mainly for feedback on the
>> general direction and structure (the interface with the existing serial
>> drivers in particular).
>
> I had a look at the uart_dev API:
>
> int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
> int uart_dev_connect(struct uart_device *udev);
>
> The flow control configuration should be done separately. e.g.:
> uart_dev_flow_control(struct uart_device *udev, bool enable);
No objection, but out of curiosity, why?
> int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
> int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
>
> UART communication does not have to be host-initiated, so this
> API requires polling. Either some function similar to poll in
> userspace is needed, or it should be implemented as callback.
What's the userspace need? I'm assuming the only immediate consumers
are in-kernel.
Rob
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 23:08 ` Rob Herring
@ 2016-08-19 5:21 ` Sebastian Reichel
2016-08-19 7:29 ` H. Nikolaus Schaller
2016-08-19 11:03 ` One Thousand Gnomes
0 siblings, 2 replies; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-19 5:21 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 3299 bytes --]
Hi,
On Thu, Aug 18, 2016 at 06:08:24PM -0500, Rob Herring wrote:
> On Thu, Aug 18, 2016 at 3:29 PM, Sebastian Reichel <sre@kernel.org> wrote:
> > Thanks for going forward and implementing this. I also started,
> > but was far from a functional state.
> >
> > On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
> >> Currently, devices attached via a UART are not well supported in
> >> the kernel. The problem is the device support is done in tty line
> >> disciplines, various platform drivers to handle some sideband, and
> >> in userspace with utilities such as hciattach.
> >>
> >> There have been several attempts to improve support, but they suffer from
> >> still being tied into the tty layer and/or abusing the platform bus. This
> >> is a prototype to show creating a proper UART bus for UART devices. It is
> >> tied into the serial core (really struct uart_port) below the tty layer
> >> in order to use existing serial drivers.
> >>
> >> This is functional with minimal testing using the loopback driver and
> >> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
> >> device). It still needs lots of work and polish.
> >>
> >> TODOs:
> >> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
> >> hoping all that complexity is from the tty layer and not needed here.
> >> - Split out the controller for uart_ports into separate driver. Do we see
> >> a need for controller drivers that are not standard serial drivers?
> >> - Implement/test the removal paths
> >> - Fix the receive callbacks for more than character at a time (i.e. DMA)
> >> - Need better receive buffering than just a simple circular buffer or
> >> perhaps a different receive interface (e.g. direct to client buffer)?
> >> - Test with other UART drivers
> >> - Convert a real driver/line discipline over to UART bus.
> >>
> >> Before I spend more time on this, I'm looking mainly for feedback on the
> >> general direction and structure (the interface with the existing serial
> >> drivers in particular).
> >
> > I had a look at the uart_dev API:
> >
> > int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
> > int uart_dev_connect(struct uart_device *udev);
> >
> > The flow control configuration should be done separately. e.g.:
> > uart_dev_flow_control(struct uart_device *udev, bool enable);
>
> No objection, but out of curiosity, why?
Nokia's bluetooth uart protocol disables flow control during speed
changes.
> > int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
> > int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
> >
> > UART communication does not have to be host-initiated, so this
> > API requires polling. Either some function similar to poll in
> > userspace is needed, or it should be implemented as callback.
>
> What's the userspace need?
I meant "Either some function similar to userspace's poll() is
needed, ...". Something like uart_dev_wait_for_rx()
Alternatively the rx function could be a callback, that
is called when there is new data.
> I'm assuming the only immediate consumers are in-kernel.
Yes, but the driver should be notified about incoming data.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 5:21 ` Sebastian Reichel
@ 2016-08-19 7:29 ` H. Nikolaus Schaller
[not found] ` <ACEF800E-8DB3-4345-ADE2-15C99F3659D5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>
2016-08-19 11:06 ` One Thousand Gnomes
2016-08-19 11:03 ` One Thousand Gnomes
1 sibling, 2 replies; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-19 7:29 UTC (permalink / raw)
To: Sebastian Reichel, Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 5141 bytes --]
Hi,
> Am 19.08.2016 um 07:21 schrieb Sebastian Reichel <sre@kernel.org>:
>
> Hi,
>
> On Thu, Aug 18, 2016 at 06:08:24PM -0500, Rob Herring wrote:
>> On Thu, Aug 18, 2016 at 3:29 PM, Sebastian Reichel <sre@kernel.org> wrote:
>>> Thanks for going forward and implementing this. I also started,
>>> but was far from a functional state.
>>>
>>> On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
>>>> Currently, devices attached via a UART are not well supported in
>>>> the kernel. The problem is the device support is done in tty line
>>>> disciplines, various platform drivers to handle some sideband, and
>>>> in userspace with utilities such as hciattach.
>>>>
>>>> There have been several attempts to improve support, but they suffer from
>>>> still being tied into the tty layer and/or abusing the platform bus. This
>>>> is a prototype to show creating a proper UART bus for UART devices. It is
>>>> tied into the serial core (really struct uart_port) below the tty layer
>>>> in order to use existing serial drivers.
>>>>
>>>> This is functional with minimal testing using the loopback driver and
>>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>>>> device). It still needs lots of work and polish.
>>>>
>>>> TODOs:
>>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>>>> hoping all that complexity is from the tty layer and not needed here.
>>>> - Split out the controller for uart_ports into separate driver. Do we see
>>>> a need for controller drivers that are not standard serial drivers?
>>>> - Implement/test the removal paths
>>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>>>> - Need better receive buffering than just a simple circular buffer or
>>>> perhaps a different receive interface (e.g. direct to client buffer)?
>>>> - Test with other UART drivers
>>>> - Convert a real driver/line discipline over to UART bus.
>>>>
>>>> Before I spend more time on this, I'm looking mainly for feedback on the
>>>> general direction and structure (the interface with the existing serial
>>>> drivers in particular).
>>>
>>> I had a look at the uart_dev API:
>>>
>>> int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
>>> int uart_dev_connect(struct uart_device *udev);
>>>
>>> The flow control configuration should be done separately. e.g.:
>>> uart_dev_flow_control(struct uart_device *udev, bool enable);
>>
>> No objection, but out of curiosity, why?
>
> Nokia's bluetooth uart protocol disables flow control during speed
> changes.
>
>>> int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
>>> int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
>>>
>>> UART communication does not have to be host-initiated, so this
>>> API requires polling. Either some function similar to poll in
>>> userspace is needed, or it should be implemented as callback.
>>
>> What's the userspace need?
>
> I meant "Either some function similar to userspace's poll() is
> needed, ...". Something like uart_dev_wait_for_rx()
>
> Alternatively the rx function could be a callback, that
> is called when there is new data.
>
>> I'm assuming the only immediate consumers are in-kernel.
>
> Yes, but the driver should be notified about incoming data.
Yes, this is very important.
If possible, please do a callback for every character that arrives.
And not only if the rx buffer becomes full, to give the slave driver
a chance to trigger actions almost immediately after every character.
This probably runs in interrupt context and can happen often.
In our proposal some months ago we have implemented such
an rx_notification callback for every character. This allows to work
without rx buffer and implement one in the driver if needed. This
gives the driver full control over the rx buffer dimensions.
And we have made the callback to return a boolean flag which
tells if the character is to be queued in the tty layer so that the
driver can decide for every byte if it is to be hidden from user
space or passed. Since we pass a pointer, the driver could even
modify the character passed back, but we have not used this
feature.
This should cover most (but certainly not all) situations of
implementing protocol engines in uart slave drivers.
Our API therefore was defined as:
void uart_register_slave(struct uart_port *uport, void *slave);
void uart_register_rx_notification(struct uart_port *uport,
bool (*function)(void *slave, unsigned int *c),
struct ktermios *termios);
Registering a slave appears to be comparable to uart_dev_connect()
and registering an rx_notification combines uart_dev_config() and
setting the callback.
Unregistration is done by passing a NULL pointer for 'slave' or 'function'.
If there will be a very similar API with a callback like this, we won't have
to change our driver architecture much.
If there is a uart_dev_wait_for_rx() with buffer it is much more difficult
to handle.
BR,
Nikolaus
[-- Attachment #2: Message signed with OpenPGP using GPGMail --]
[-- Type: application/pgp-signature, Size: 801 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
[parent not found: <ACEF800E-8DB3-4345-ADE2-15C99F3659D5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>]
* Re: [RFC PATCH 0/3] UART slave device bus
[not found] ` <ACEF800E-8DB3-4345-ADE2-15C99F3659D5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>
@ 2016-08-19 7:49 ` Oleksij Rempel
2016-08-19 17:50 ` H. Nikolaus Schaller
0 siblings, 1 reply; 103+ messages in thread
From: Oleksij Rempel @ 2016-08-19 7:49 UTC (permalink / raw)
To: H. Nikolaus Schaller, Sebastian Reichel, Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS,
linux-serial-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
linux-kernel-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
[-- Attachment #1.1: Type: text/plain, Size: 5659 bytes --]
Hallo Nikolaus,
do i understand it correctly. This driver is to make kind of interchip
communication and represent uart as a bus to allow use this bus from
multiple kernel driver or expose it to user space?
Correct?
Am 19.08.2016 um 09:29 schrieb H. Nikolaus Schaller:
> Hi,
>
>> Am 19.08.2016 um 07:21 schrieb Sebastian Reichel <sre-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org>:
>>
>> Hi,
>>
>> On Thu, Aug 18, 2016 at 06:08:24PM -0500, Rob Herring wrote:
>>> On Thu, Aug 18, 2016 at 3:29 PM, Sebastian Reichel <sre-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org> wrote:
>>>> Thanks for going forward and implementing this. I also started,
>>>> but was far from a functional state.
>>>>
>>>> On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
>>>>> Currently, devices attached via a UART are not well supported in
>>>>> the kernel. The problem is the device support is done in tty line
>>>>> disciplines, various platform drivers to handle some sideband, and
>>>>> in userspace with utilities such as hciattach.
>>>>>
>>>>> There have been several attempts to improve support, but they suffer from
>>>>> still being tied into the tty layer and/or abusing the platform bus. This
>>>>> is a prototype to show creating a proper UART bus for UART devices. It is
>>>>> tied into the serial core (really struct uart_port) below the tty layer
>>>>> in order to use existing serial drivers.
>>>>>
>>>>> This is functional with minimal testing using the loopback driver and
>>>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>>>>> device). It still needs lots of work and polish.
>>>>>
>>>>> TODOs:
>>>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>>>>> hoping all that complexity is from the tty layer and not needed here.
>>>>> - Split out the controller for uart_ports into separate driver. Do we see
>>>>> a need for controller drivers that are not standard serial drivers?
>>>>> - Implement/test the removal paths
>>>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>>>>> - Need better receive buffering than just a simple circular buffer or
>>>>> perhaps a different receive interface (e.g. direct to client buffer)?
>>>>> - Test with other UART drivers
>>>>> - Convert a real driver/line discipline over to UART bus.
>>>>>
>>>>> Before I spend more time on this, I'm looking mainly for feedback on the
>>>>> general direction and structure (the interface with the existing serial
>>>>> drivers in particular).
>>>>
>>>> I had a look at the uart_dev API:
>>>>
>>>> int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
>>>> int uart_dev_connect(struct uart_device *udev);
>>>>
>>>> The flow control configuration should be done separately. e.g.:
>>>> uart_dev_flow_control(struct uart_device *udev, bool enable);
>>>
>>> No objection, but out of curiosity, why?
>>
>> Nokia's bluetooth uart protocol disables flow control during speed
>> changes.
>>
>>>> int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
>>>> int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
>>>>
>>>> UART communication does not have to be host-initiated, so this
>>>> API requires polling. Either some function similar to poll in
>>>> userspace is needed, or it should be implemented as callback.
>>>
>>> What's the userspace need?
>>
>> I meant "Either some function similar to userspace's poll() is
>> needed, ...". Something like uart_dev_wait_for_rx()
>>
>> Alternatively the rx function could be a callback, that
>> is called when there is new data.
>>
>>> I'm assuming the only immediate consumers are in-kernel.
>>
>> Yes, but the driver should be notified about incoming data.
>
> Yes, this is very important.
>
> If possible, please do a callback for every character that arrives.
> And not only if the rx buffer becomes full, to give the slave driver
> a chance to trigger actions almost immediately after every character.
> This probably runs in interrupt context and can happen often.
>
> In our proposal some months ago we have implemented such
> an rx_notification callback for every character. This allows to work
> without rx buffer and implement one in the driver if needed. This
> gives the driver full control over the rx buffer dimensions.
>
> And we have made the callback to return a boolean flag which
> tells if the character is to be queued in the tty layer so that the
> driver can decide for every byte if it is to be hidden from user
> space or passed. Since we pass a pointer, the driver could even
> modify the character passed back, but we have not used this
> feature.
>
> This should cover most (but certainly not all) situations of
> implementing protocol engines in uart slave drivers.
>
> Our API therefore was defined as:
>
> void uart_register_slave(struct uart_port *uport, void *slave);
> void uart_register_rx_notification(struct uart_port *uport,
> bool (*function)(void *slave, unsigned int *c),
> struct ktermios *termios);
>
> Registering a slave appears to be comparable to uart_dev_connect()
> and registering an rx_notification combines uart_dev_config() and
> setting the callback.
>
> Unregistration is done by passing a NULL pointer for 'slave' or 'function'.
>
> If there will be a very similar API with a callback like this, we won't have
> to change our driver architecture much.
>
> If there is a uart_dev_wait_for_rx() with buffer it is much more difficult
> to handle.
>
> BR,
> Nikolaus
>
>
--
Regards,
Oleksij
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 213 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 7:49 ` Oleksij Rempel
@ 2016-08-19 17:50 ` H. Nikolaus Schaller
[not found] ` <53A846F1-33E5-48C3-B3A6-DB251661CDD5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>
2016-08-20 13:34 ` One Thousand Gnomes
0 siblings, 2 replies; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-19 17:50 UTC (permalink / raw)
To: Oleksij Rempel
Cc: Sebastian Reichel, Rob Herring, Greg Kroah-Hartman,
Marcel Holtmann, Jiri Slaby, Pavel Machek, Peter Hurley,
NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 6952 bytes --]
Hi,
> Am 19.08.2016 um 09:49 schrieb Oleksij Rempel <linux@rempel-privat.de>:
>
> Hallo Nikolaus,
>
> do i understand it correctly. This driver is to make kind of interchip
> communication and represent uart as a bus to allow use this bus from
> multiple kernel driver or expose it to user space?
The idea for UART slave devices is to handle devices connected on an
embedded board to an UART port in kernel. Currently most such devices
are just passed through to some /dev/tty and handled by user-space daemons.
So it is not necessarily about multiple kernel drivers to use the same UART, although
that could also be required.
A single one is already difficult... And some scenarios need to shield the UART
from user space (currently there is always one /dev/tty per UART - unless the
UART is completely disabled).
Some ideas where it might be needed:
* bluetooth HCI over UART
* a weird GPS device whose power state can only reliably be detected by monitoring data activity
* other chips (microcontrollers) connected through UART - similar to I2C slave devices
* it potentially could help to better implement IrDA (although that is mostly legacy)
What it is not about are UART/RS232 converters connected through USB or virtual
serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
connected through USB (even if they also run HCI protocol).
>
> Correct?
>
> Am 19.08.2016 um 09:29 schrieb H. Nikolaus Schaller:
>> Hi,
>>
>>> Am 19.08.2016 um 07:21 schrieb Sebastian Reichel <sre@kernel.org>:
>>>
>>> Hi,
>>>
>>> On Thu, Aug 18, 2016 at 06:08:24PM -0500, Rob Herring wrote:
>>>> On Thu, Aug 18, 2016 at 3:29 PM, Sebastian Reichel <sre@kernel.org> wrote:
>>>>> Thanks for going forward and implementing this. I also started,
>>>>> but was far from a functional state.
>>>>>
>>>>> On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
>>>>>> Currently, devices attached via a UART are not well supported in
>>>>>> the kernel. The problem is the device support is done in tty line
>>>>>> disciplines, various platform drivers to handle some sideband, and
>>>>>> in userspace with utilities such as hciattach.
>>>>>>
>>>>>> There have been several attempts to improve support, but they suffer from
>>>>>> still being tied into the tty layer and/or abusing the platform bus. This
>>>>>> is a prototype to show creating a proper UART bus for UART devices. It is
>>>>>> tied into the serial core (really struct uart_port) below the tty layer
>>>>>> in order to use existing serial drivers.
>>>>>>
>>>>>> This is functional with minimal testing using the loopback driver and
>>>>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>>>>>> device). It still needs lots of work and polish.
>>>>>>
>>>>>> TODOs:
>>>>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>>>>>> hoping all that complexity is from the tty layer and not needed here.
>>>>>> - Split out the controller for uart_ports into separate driver. Do we see
>>>>>> a need for controller drivers that are not standard serial drivers?
>>>>>> - Implement/test the removal paths
>>>>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>>>>>> - Need better receive buffering than just a simple circular buffer or
>>>>>> perhaps a different receive interface (e.g. direct to client buffer)?
>>>>>> - Test with other UART drivers
>>>>>> - Convert a real driver/line discipline over to UART bus.
>>>>>>
>>>>>> Before I spend more time on this, I'm looking mainly for feedback on the
>>>>>> general direction and structure (the interface with the existing serial
>>>>>> drivers in particular).
>>>>>
>>>>> I had a look at the uart_dev API:
>>>>>
>>>>> int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
>>>>> int uart_dev_connect(struct uart_device *udev);
>>>>>
>>>>> The flow control configuration should be done separately. e.g.:
>>>>> uart_dev_flow_control(struct uart_device *udev, bool enable);
>>>>
>>>> No objection, but out of curiosity, why?
>>>
>>> Nokia's bluetooth uart protocol disables flow control during speed
>>> changes.
>>>
>>>>> int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
>>>>> int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
>>>>>
>>>>> UART communication does not have to be host-initiated, so this
>>>>> API requires polling. Either some function similar to poll in
>>>>> userspace is needed, or it should be implemented as callback.
>>>>
>>>> What's the userspace need?
>>>
>>> I meant "Either some function similar to userspace's poll() is
>>> needed, ...". Something like uart_dev_wait_for_rx()
>>>
>>> Alternatively the rx function could be a callback, that
>>> is called when there is new data.
>>>
>>>> I'm assuming the only immediate consumers are in-kernel.
>>>
>>> Yes, but the driver should be notified about incoming data.
>>
>> Yes, this is very important.
>>
>> If possible, please do a callback for every character that arrives.
>> And not only if the rx buffer becomes full, to give the slave driver
>> a chance to trigger actions almost immediately after every character.
>> This probably runs in interrupt context and can happen often.
>>
>> In our proposal some months ago we have implemented such
>> an rx_notification callback for every character. This allows to work
>> without rx buffer and implement one in the driver if needed. This
>> gives the driver full control over the rx buffer dimensions.
>>
>> And we have made the callback to return a boolean flag which
>> tells if the character is to be queued in the tty layer so that the
>> driver can decide for every byte if it is to be hidden from user
>> space or passed. Since we pass a pointer, the driver could even
>> modify the character passed back, but we have not used this
>> feature.
>>
>> This should cover most (but certainly not all) situations of
>> implementing protocol engines in uart slave drivers.
>>
>> Our API therefore was defined as:
>>
>> void uart_register_slave(struct uart_port *uport, void *slave);
>> void uart_register_rx_notification(struct uart_port *uport,
>> bool (*function)(void *slave, unsigned int *c),
>> struct ktermios *termios);
>>
>> Registering a slave appears to be comparable to uart_dev_connect()
>> and registering an rx_notification combines uart_dev_config() and
>> setting the callback.
>>
>> Unregistration is done by passing a NULL pointer for 'slave' or 'function'.
>>
>> If there will be a very similar API with a callback like this, we won't have
>> to change our driver architecture much.
>>
>> If there is a uart_dev_wait_for_rx() with buffer it is much more difficult
>> to handle.
>>
>> BR,
>> Nikolaus
>>
>>
>
>
> --
> Regards,
> Oleksij
>
[-- Attachment #2: Message signed with OpenPGP using GPGMail --]
[-- Type: application/pgp-signature, Size: 801 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
[parent not found: <53A846F1-33E5-48C3-B3A6-DB251661CDD5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>]
* Re: [RFC PATCH 0/3] UART slave device bus
[not found] ` <53A846F1-33E5-48C3-B3A6-DB251661CDD5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>
@ 2016-08-19 20:19 ` Oleksij Rempel
0 siblings, 0 replies; 103+ messages in thread
From: Oleksij Rempel @ 2016-08-19 20:19 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Sebastian Reichel, Rob Herring, Greg Kroah-Hartman,
Marcel Holtmann, Jiri Slaby, Pavel Machek, Peter Hurley,
NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS,
linux-serial-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
linux-kernel-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
[-- Attachment #1.1: Type: text/plain, Size: 7900 bytes --]
Am 19.08.2016 um 19:50 schrieb H. Nikolaus Schaller:
> Hi,
>
>> Am 19.08.2016 um 09:49 schrieb Oleksij Rempel <linux-YEK0n+YFykbzxQdaRaTXBw@public.gmane.org>:
>>
>> Hallo Nikolaus,
>>
>> do i understand it correctly. This driver is to make kind of interchip
>> communication and represent uart as a bus to allow use this bus from
>> multiple kernel driver or expose it to user space?
>
> The idea for UART slave devices is to handle devices connected on an
> embedded board to an UART port in kernel. Currently most such devices
> are just passed through to some /dev/tty and handled by user-space daemons.
>
> So it is not necessarily about multiple kernel drivers to use the same UART, although
> that could also be required.
>
> A single one is already difficult... And some scenarios need to shield the UART
> from user space (currently there is always one /dev/tty per UART - unless the
> UART is completely disabled).
>
> Some ideas where it might be needed:
> * bluetooth HCI over UART
> * a weird GPS device whose power state can only reliably be detected by monitoring data activity
> * other chips (microcontrollers) connected through UART - similar to I2C slave devices
> * it potentially could help to better implement IrDA (although that is mostly legacy)
>
> What it is not about are UART/RS232 converters connected through USB or virtual
> serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
> connected through USB (even if they also run HCI protocol).
Ah... ok. thank you for explanation.
I was thinking it is going in similar direction with my project - use
SPI for communication between two SoCs. It is based on SSI32 protocol
from Bosch.
In case it is going to this direction:
Master implementation for linux side (tested on Banana Pi and iMX6):
https://github.com/olerem/linux-2.6/commits/bpi-spi-variant2-2016.07.26.2
Slave implementation for stm32f303 (tested on f3 discovery):
https://github.com/olerem/libopencm3-examples/commits/ssi32-2016.08.17.1
protocol decoder for logic analyzer (sigrok):
https://github.com/olerem/libsigrokdecode/commits/ssi32_dec-2016.08.11
>> Correct?
>>
>> Am 19.08.2016 um 09:29 schrieb H. Nikolaus Schaller:
>>> Hi,
>>>
>>>> Am 19.08.2016 um 07:21 schrieb Sebastian Reichel <sre-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org>:
>>>>
>>>> Hi,
>>>>
>>>> On Thu, Aug 18, 2016 at 06:08:24PM -0500, Rob Herring wrote:
>>>>> On Thu, Aug 18, 2016 at 3:29 PM, Sebastian Reichel <sre-DgEjT+Ai2ygdnm+yROfE0A@public.gmane.org> wrote:
>>>>>> Thanks for going forward and implementing this. I also started,
>>>>>> but was far from a functional state.
>>>>>>
>>>>>> On Wed, Aug 17, 2016 at 08:14:42PM -0500, Rob Herring wrote:
>>>>>>> Currently, devices attached via a UART are not well supported in
>>>>>>> the kernel. The problem is the device support is done in tty line
>>>>>>> disciplines, various platform drivers to handle some sideband, and
>>>>>>> in userspace with utilities such as hciattach.
>>>>>>>
>>>>>>> There have been several attempts to improve support, but they suffer from
>>>>>>> still being tied into the tty layer and/or abusing the platform bus. This
>>>>>>> is a prototype to show creating a proper UART bus for UART devices. It is
>>>>>>> tied into the serial core (really struct uart_port) below the tty layer
>>>>>>> in order to use existing serial drivers.
>>>>>>>
>>>>>>> This is functional with minimal testing using the loopback driver and
>>>>>>> pl011 (w/o DMA) UART under QEMU (modified to add a DT node for the slave
>>>>>>> device). It still needs lots of work and polish.
>>>>>>>
>>>>>>> TODOs:
>>>>>>> - Figure out the port locking. mutex plus spinlock plus refcounting? I'm
>>>>>>> hoping all that complexity is from the tty layer and not needed here.
>>>>>>> - Split out the controller for uart_ports into separate driver. Do we see
>>>>>>> a need for controller drivers that are not standard serial drivers?
>>>>>>> - Implement/test the removal paths
>>>>>>> - Fix the receive callbacks for more than character at a time (i.e. DMA)
>>>>>>> - Need better receive buffering than just a simple circular buffer or
>>>>>>> perhaps a different receive interface (e.g. direct to client buffer)?
>>>>>>> - Test with other UART drivers
>>>>>>> - Convert a real driver/line discipline over to UART bus.
>>>>>>>
>>>>>>> Before I spend more time on this, I'm looking mainly for feedback on the
>>>>>>> general direction and structure (the interface with the existing serial
>>>>>>> drivers in particular).
>>>>>>
>>>>>> I had a look at the uart_dev API:
>>>>>>
>>>>>> int uart_dev_config(struct uart_device *udev, int baud, int parity, int bits, int flow);
>>>>>> int uart_dev_connect(struct uart_device *udev);
>>>>>>
>>>>>> The flow control configuration should be done separately. e.g.:
>>>>>> uart_dev_flow_control(struct uart_device *udev, bool enable);
>>>>>
>>>>> No objection, but out of curiosity, why?
>>>>
>>>> Nokia's bluetooth uart protocol disables flow control during speed
>>>> changes.
>>>>
>>>>>> int uart_dev_tx(struct uart_device *udev, u8 *buf, size_t count);
>>>>>> int uart_dev_rx(struct uart_device *udev, u8 *buf, size_t count);
>>>>>>
>>>>>> UART communication does not have to be host-initiated, so this
>>>>>> API requires polling. Either some function similar to poll in
>>>>>> userspace is needed, or it should be implemented as callback.
>>>>>
>>>>> What's the userspace need?
>>>>
>>>> I meant "Either some function similar to userspace's poll() is
>>>> needed, ...". Something like uart_dev_wait_for_rx()
>>>>
>>>> Alternatively the rx function could be a callback, that
>>>> is called when there is new data.
>>>>
>>>>> I'm assuming the only immediate consumers are in-kernel.
>>>>
>>>> Yes, but the driver should be notified about incoming data.
>>>
>>> Yes, this is very important.
>>>
>>> If possible, please do a callback for every character that arrives.
>>> And not only if the rx buffer becomes full, to give the slave driver
>>> a chance to trigger actions almost immediately after every character.
>>> This probably runs in interrupt context and can happen often.
>>>
>>> In our proposal some months ago we have implemented such
>>> an rx_notification callback for every character. This allows to work
>>> without rx buffer and implement one in the driver if needed. This
>>> gives the driver full control over the rx buffer dimensions.
>>>
>>> And we have made the callback to return a boolean flag which
>>> tells if the character is to be queued in the tty layer so that the
>>> driver can decide for every byte if it is to be hidden from user
>>> space or passed. Since we pass a pointer, the driver could even
>>> modify the character passed back, but we have not used this
>>> feature.
>>>
>>> This should cover most (but certainly not all) situations of
>>> implementing protocol engines in uart slave drivers.
>>>
>>> Our API therefore was defined as:
>>>
>>> void uart_register_slave(struct uart_port *uport, void *slave);
>>> void uart_register_rx_notification(struct uart_port *uport,
>>> bool (*function)(void *slave, unsigned int *c),
>>> struct ktermios *termios);
>>>
>>> Registering a slave appears to be comparable to uart_dev_connect()
>>> and registering an rx_notification combines uart_dev_config() and
>>> setting the callback.
>>>
>>> Unregistration is done by passing a NULL pointer for 'slave' or 'function'.
>>>
>>> If there will be a very similar API with a callback like this, we won't have
>>> to change our driver architecture much.
>>>
>>> If there is a uart_dev_wait_for_rx() with buffer it is much more difficult
>>> to handle.
>>>
>>> BR,
>>> Nikolaus
>>>
>>>
>>
>>
>> --
>> Regards,
>> Oleksij
>>
>
--
Regards,
Oleksij
[-- Attachment #2: OpenPGP digital signature --]
[-- Type: application/pgp-signature, Size: 213 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 17:50 ` H. Nikolaus Schaller
[not found] ` <53A846F1-33E5-48C3-B3A6-DB251661CDD5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>
@ 2016-08-20 13:34 ` One Thousand Gnomes
2016-08-21 7:50 ` H. Nikolaus Schaller
1 sibling, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-20 13:34 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Oleksij Rempel, Sebastian Reichel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> A single one is already difficult... And some scenarios need to shield the UART
> from user space (currently there is always one /dev/tty per UART - unless the
> UART is completely disabled).
That bit is already covered and one or two devices support this because
they have things like 3 serial ports but one cannot be used if some other
feature is enabled.
You simply keep a private counter and return -EBUSY in the
port->activate() method if needed. That is sufficient to share a UART with
the tty layer when you have a contended resource, but not to borrow the
UART and re-use the stack which is what is needed in this case.
(You can even steal a UART this way by doing a hangup on it and then once
it drops out of use taking it over and ensuring the EBUSY behaviour)
>
> Some ideas where it might be needed:
> * bluetooth HCI over UART
> * a weird GPS device whose power state can only reliably be detected by monitoring data activity
> * other chips (microcontrollers) connected through UART - similar to I2C slave devices
> * it potentially could help to better implement IrDA (although that is mostly legacy)
>
> What it is not about are UART/RS232 converters connected through USB or virtual
> serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
> connected through USB (even if they also run HCI protocol).
It actually has to be about both because you will find the exact same
device wired via USB SSIC/HSIC to a USB UART or via a classic UART. Not is
it just about embedded boards. A current PC class device will usually have
bluetooth connected via a UART where both components are on board. The
same for GPS (or more accurately location services as it's usually more
than just a GPS nowdays). There may also be onboard WWAN modems and other
widgets wired this way.
In the PC case the power relationship and connectivity is usually
described via ACPI and that often means the kernel simply doesn't know
how to manage the power states besides telling the modem, GPS. etc to
turn itself on and off via normal ACPI power descriptions. Those may well
call OpRegion handlers so it's all abstracted nicely and generic, but
rather more invisible to the OS than DT describing pmic and/or gpio
setings for the device.
Todays low end Intel x86 PC has multiple DMA accelerated low power 16x50
compatible UARTS on die along with multiple channels of I2C and SPI.
Things like Android and PC tablet devices with sensors have pretty much
converged the old divide between a desktop/laptop/tablet PC and an
'embedded' board.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-20 13:34 ` One Thousand Gnomes
@ 2016-08-21 7:50 ` H. Nikolaus Schaller
2016-08-22 20:39 ` Sebastian Reichel
0 siblings, 1 reply; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-21 7:50 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Oleksij Rempel, Sebastian Reichel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> Am 20.08.2016 um 15:34 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
>> What it is not about are UART/RS232 converters connected through USB or virtual
>> serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
>> connected through USB (even if they also run HCI protocol).
>
> It actually has to be about both because you will find the exact same
> device wired via USB SSIC/HSIC to a USB UART or via a classic UART. Not is
> it just about embedded boards.
Not necessarily.
We often have two interface options for exactly the sam sensor chips. They can be connected
either through SPI or I2C. Which means that there is a core driver for the chip and two different
transport glue components (see e.g. iio/accel/bmc150).
This does not require I2C to be able to handle SPI or vice versa or provide a common API.
And most Bluetooth devices I know have either UART or a direct USB interface. So in the
USB case there is no need to connect it through some USB-UART bridge and treat it as
an UART at all.
BR,
Nikolaus
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-21 7:50 ` H. Nikolaus Schaller
@ 2016-08-22 20:39 ` Sebastian Reichel
2016-08-22 21:23 ` H. Nikolaus Schaller
0 siblings, 1 reply; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-22 20:39 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: One Thousand Gnomes, Oleksij Rempel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 1445 bytes --]
Hi,
On Sun, Aug 21, 2016 at 09:50:57AM +0200, H. Nikolaus Schaller wrote:
> > Am 20.08.2016 um 15:34 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
> >> What it is not about are UART/RS232 converters connected through USB or virtual
> >> serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
> >> connected through USB (even if they also run HCI protocol).
> >
> > It actually has to be about both because you will find the exact same
> > device wired via USB SSIC/HSIC to a USB UART or via a classic UART. Not is
> > it just about embedded boards.
>
> Not necessarily.
>
> We often have two interface options for exactly the sam sensor chips. They can be connected
> either through SPI or I2C. Which means that there is a core driver for the chip and two different
> transport glue components (see e.g. iio/accel/bmc150).
>
> This does not require I2C to be able to handle SPI or vice versa or provide a common API.
I don't understand this comparison. I2C and SPI are different
protocols, while native UART and USB-connected UART are both UART.
> And most Bluetooth devices I know have either UART or a direct
> USB interface. So in the USB case there is no need to connect
> it through some USB-UART bridge and treat it as an UART at all.
I think having support for USB-UART dongles is useful for
driver development and testing on non-embedded HW.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 20:39 ` Sebastian Reichel
@ 2016-08-22 21:23 ` H. Nikolaus Schaller
2016-08-22 21:43 ` Arnd Bergmann
` (2 more replies)
0 siblings, 3 replies; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-22 21:23 UTC (permalink / raw)
To: Sebastian Reichel
Cc: One Thousand Gnomes, Oleksij Rempel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 3316 bytes --]
Hi Sebastian,
> Am 22.08.2016 um 22:39 schrieb Sebastian Reichel <sre@kernel.org>:
>
> Hi,
>
> On Sun, Aug 21, 2016 at 09:50:57AM +0200, H. Nikolaus Schaller wrote:
>>> Am 20.08.2016 um 15:34 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
>>>> What it is not about are UART/RS232 converters connected through USB or virtual
>>>> serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
>>>> connected through USB (even if they also run HCI protocol).
>>>
>>> It actually has to be about both because you will find the exact same
>>> device wired via USB SSIC/HSIC to a USB UART or via a classic UART. Not is
>>> it just about embedded boards.
>>
>> Not necessarily.
>>
>> We often have two interface options for exactly the sam sensor chips. They can be connected
>> either through SPI or I2C. Which means that there is a core driver for the chip and two different
>> transport glue components (see e.g. iio/accel/bmc150).
>>
>> This does not require I2C to be able to handle SPI or vice versa or provide a common API.
>
> I don't understand this comparison. I2C and SPI are different
> protocols,
Yes, they are different on protocol level, but on both you transfer blocks of data from/to a slave device
which usually can be addressed. And for some chips they are just two slightly alternative serial interfaces.
> while native UART and USB-connected UART are both UART.
I see what you mean, but kernel divides between directly connected UART and USB-connected UART.
drivers/usb/serial/ vs. drivers/tty/serial/
to implement two different groups of UARTs. Although on user space level they are harmonized again.
This is why I compare with i2c and spi. But each such comparison is not perfect.
Anyways, to me it looks as if everybody wants to make the solution work for usb-uarts as well
(although I still would like to see a real world use-case).
>
>> And most Bluetooth devices I know have either UART or a direct
>> USB interface. So in the USB case there is no need to connect
>> it through some USB-UART bridge and treat it as an UART at all.
>
> I think having support for USB-UART dongles is useful for
> driver development and testing on non-embedded HW.
Hm. I assume you mean the Bluetooth situation where both, embedded UART
connected chips and USB dongles are available. I am not a specialist for such things,
but I think you have three options to connect bluetooth:
a) SoC-UART <-> BT-Chip-UART-port
b) USB-UART (FT232, PL2303 etc.) <-> BT-Chip-UART-port
c) USB <-> BT-Chip-USB-port (not UART involved at all)
Case c) IMHO means you anyways need a special USB driver for the BT-Chip connected
through USB and plugging it into a non-embedded USB port does not automatically
show it as a tty interface. So you can't use it for testing the UART drivers.
BTW: the Wi2Wi W2CBW003 chip comes in two firmware variants: one for UART and
one for USB. So they are also not exchangeable.
Variant b) is IMHO of no practical relevance (but I may be wrong) because it would
mean to add some costly FT232 or PL2302 chip where a different firmware variant works
with direct USB connection.
So to me it looks as if you need to develop different low-level drivers anyways.
BR,
Nikolaus
[-- Attachment #2: Message signed with OpenPGP using GPGMail --]
[-- Type: application/pgp-signature, Size: 801 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 21:23 ` H. Nikolaus Schaller
@ 2016-08-22 21:43 ` Arnd Bergmann
2016-08-22 22:42 ` Sebastian Reichel
2016-08-27 12:01 ` Michal Suchanek
2 siblings, 0 replies; 103+ messages in thread
From: Arnd Bergmann @ 2016-08-22 21:43 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Sebastian Reichel, One Thousand Gnomes, Oleksij Rempel,
Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Pavel Machek, Peter Hurley, NeilBrown, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Monday, August 22, 2016 11:23:26 PM CEST H. Nikolaus Schaller wrote:
> I see what you mean, but kernel divides between directly connected UART and USB-connected UART.
>
> drivers/usb/serial/ vs. drivers/tty/serial/
That distinction purely exists for historic reasons. I'd argue that the
former should actually go into drivers/tty/usb or similar. A long time
ago, we commonly sorted device drivers by how they were attached to
the system (as drivers/usb/serial/ and drivers/usb/storage still do),
but almost everything is now sorted according to how it is used instead.
Arnd
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 21:23 ` H. Nikolaus Schaller
2016-08-22 21:43 ` Arnd Bergmann
@ 2016-08-22 22:42 ` Sebastian Reichel
2016-08-22 22:52 ` One Thousand Gnomes
2016-08-23 7:28 ` H. Nikolaus Schaller
2016-08-27 12:01 ` Michal Suchanek
2 siblings, 2 replies; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-22 22:42 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: One Thousand Gnomes, Oleksij Rempel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 4881 bytes --]
Hi,
On Mon, Aug 22, 2016 at 11:23:26PM +0200, H. Nikolaus Schaller wrote:
> > Am 22.08.2016 um 22:39 schrieb Sebastian Reichel <sre@kernel.org>:
> >
> > Hi,
> >
> > On Sun, Aug 21, 2016 at 09:50:57AM +0200, H. Nikolaus Schaller wrote:
> >>> Am 20.08.2016 um 15:34 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
> >>>> What it is not about are UART/RS232 converters connected through USB or virtual
> >>>> serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
> >>>> connected through USB (even if they also run HCI protocol).
> >>>
> >>> It actually has to be about both because you will find the exact same
> >>> device wired via USB SSIC/HSIC to a USB UART or via a classic UART. Not is
> >>> it just about embedded boards.
> >>
> >> Not necessarily.
> >>
> >> We often have two interface options for exactly the sam sensor chips. They can be connected
> >> either through SPI or I2C. Which means that there is a core driver for the chip and two different
> >> transport glue components (see e.g. iio/accel/bmc150).
> >>
> >> This does not require I2C to be able to handle SPI or vice versa or provide a common API.
> >
> > I don't understand this comparison. I2C and SPI are different
> > protocols,
>
> Yes, they are different on protocol level, but on both you transfer blocks of data from/to a slave device
> which usually can be addressed. And for some chips they are just two slightly alternative serial interfaces.
>
> > while native UART and USB-connected UART are both UART.
>
> I see what you mean, but kernel divides between directly connected UART and USB-connected UART.
>
> drivers/usb/serial/ vs. drivers/tty/serial/
>
> to implement two different groups of UARTs. Although on user space level they are harmonized again.
> This is why I compare with i2c and spi. But each such comparison is not perfect.
>
> Anyways, to me it looks as if everybody wants to make the solution work for usb-uarts as well
> (although I still would like to see a real world use-case).
>
> >
> >> And most Bluetooth devices I know have either UART or a direct
> >> USB interface. So in the USB case there is no need to connect
> >> it through some USB-UART bridge and treat it as an UART at all.
> >
> > I think having support for USB-UART dongles is useful for
> > driver development and testing on non-embedded HW.
>
> Hm. I assume you mean the Bluetooth situation where both, embedded UART
> connected chips and USB dongles are available.
No. I mean I have some serial device, which is connected to the
embedded UART, but I also have a standalone version. For driver
development I can just use my standalone serial device, connect
it to an USB-UART and develop the driver on non embedded HW.
Then I can use the same driver on my embedded platform and it
works, since it uses the same API.
For e.g. I2C this works perfectly fine. I already did this with
the I2C interface exposed on my notebook's VGA port.
> I am not a specialist for such things, but I think you have three
> options to connect bluetooth:
>
> a) SoC-UART <-> BT-Chip-UART-port
> b) USB-UART (FT232, PL2303 etc.) <-> BT-Chip-UART-port
> c) USB <-> BT-Chip-USB-port (not UART involved at all)
>
> Case c) IMHO means you anyways need a special USB driver for the BT-Chip connected
> through USB and plugging it into a non-embedded USB port does not automatically
> show it as a tty interface. So you can't use it for testing the UART drivers.
>
> BTW: the Wi2Wi W2CBW003 chip comes in two firmware variants: one for UART and
> one for USB. So they are also not exchangeable.
Yes, let's ignore option c). I'm talking about UART only. If the
chip has native USB support, then that's a different driver. Note,
that for more complex drivers it may become possible to use the same
high-level driver via regmap at some point. Not sure if this kind of
HW exists, though.
> Variant b) is IMHO of no practical relevance (but I may be wrong)
> because it would mean to add some costly FT232 or PL2302 chip
> where a different firmware variant works with direct USB
> connection.
Well for some chips there is not native USB support. But my scenario
was about development. Let's say I have a serial-chip and I want to
develop a driver for it. It would be nice if I can develop the
driver with a USB-UART and then use it on my embedded system.
There are usb-serial devices, which could benefit from support
btw. I would find it really useful, if the Dangerous Prototype's
Bus Pirate would expose native /dev/i2c and /dev/spi and it's
based on FT232.
> So to me it looks as if you need to develop different low-level
> drivers anyways.
No. You say, that option b) is irrelevant and assume, that every
serial chip also has native USB support.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 22:42 ` Sebastian Reichel
@ 2016-08-22 22:52 ` One Thousand Gnomes
2016-08-22 23:10 ` Sebastian Reichel
2016-08-23 7:28 ` H. Nikolaus Schaller
1 sibling, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-22 22:52 UTC (permalink / raw)
To: Sebastian Reichel
Cc: H. Nikolaus Schaller, Oleksij Rempel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> There are usb-serial devices, which could benefit from support
> btw. I would find it really useful, if the Dangerous Prototype's
> Bus Pirate would expose native /dev/i2c and /dev/spi and it's
> based on FT232.
That should just need an ldisc. I2C and SPI should at this point be sane
for hotplugging as needed for an ldisc.
And having an ldisc also has another nice effect. You can plug the bus
pirate into a remote machine, run an 8bit clean link over a pty/tty pair
half way around the world and get a local i2c/spi to the remote machine's
i2c/spi bus pirate ports and devices.
It also means that if Bus Pirate 5 changes USB uart nothing breaks.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 22:52 ` One Thousand Gnomes
@ 2016-08-22 23:10 ` Sebastian Reichel
0 siblings, 0 replies; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-22 23:10 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: H. Nikolaus Schaller, Oleksij Rempel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 1225 bytes --]
Hi,
On Mon, Aug 22, 2016 at 11:52:56PM +0100, One Thousand Gnomes wrote:
> > There are usb-serial devices, which could benefit from support
> > btw. I would find it really useful, if the Dangerous Prototype's
> > Bus Pirate would expose native /dev/i2c and /dev/spi and it's
> > based on FT232.
>
> That should just need an ldisc.
Right, since it does not need any extra resources. Probably not the
best example.
> I2C and SPI should at this point be sane for hotplugging as needed
> for an ldisc.
I guess hotplugging support in the downstream kernel frameworks
would be needed anyway with usb-serial being USB based.
> And having an ldisc also has another nice effect. You can plug the bus
> pirate into a remote machine, run an 8bit clean link over a pty/tty pair
> half way around the world and get a local i2c/spi to the remote machine's
> i2c/spi bus pirate ports and devices.
Right.
> It also means that if Bus Pirate 5 changes USB uart nothing breaks.
And it means no auto-support. Which would be fine in case of Bus
Pirate, since its mainly a developer device and some people may
actually prefer the IMHO anoying serial interface.
Let's forget that example.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 22:42 ` Sebastian Reichel
2016-08-22 22:52 ` One Thousand Gnomes
@ 2016-08-23 7:28 ` H. Nikolaus Schaller
1 sibling, 0 replies; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-23 7:28 UTC (permalink / raw)
To: Sebastian Reichel
Cc: One Thousand Gnomes, Oleksij Rempel, Rob Herring,
Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby, Pavel Machek,
Peter Hurley, NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 2737 bytes --]
Hi,
> Am 23.08.2016 um 00:42 schrieb Sebastian Reichel <sre@kernel.org>:
>
>> I am not a specialist for such things, but I think you have three
>> options to connect bluetooth:
>>
>> a) SoC-UART <-> BT-Chip-UART-port
>> b) USB-UART (FT232, PL2303 etc.) <-> BT-Chip-UART-port
>> c) USB <-> BT-Chip-USB-port (not UART involved at all)
>>
>> Case c) IMHO means you anyways need a special USB driver for the BT-Chip connected
>> through USB and plugging it into a non-embedded USB port does not automatically
>> show it as a tty interface. So you can't use it for testing the UART drivers.
>>
>> BTW: the Wi2Wi W2CBW003 chip comes in two firmware variants: one for UART and
>> one for USB. So they are also not exchangeable.
>
> Yes, let's ignore option c).
> I'm talking about UART only. If the
> chip has native USB support, then that's a different driver.
Exactly.
>
>> Variant b) is IMHO of no practical relevance (but I may be wrong)
>> because it would mean to add some costly FT232 or PL2302 chip
>> where a different firmware variant works with direct USB
>> connection.
>
> Well for some chips there is not native USB support. But my scenario
> was about development. Let's say I have a serial-chip and I want to
> develop a driver for it. It would be nice if I can develop the
> driver with a USB-UART
Yes it would be nice, but is this a thing with significant practical relevance?
Usually you have to write drivers for a complete device where the slave
chip is already wired up to a SoC-UART.
Sometimes you can get a bare chip where you can connect to an
USB-UART. But someone has to design that piece of special hardware
for you. If you are really lucky there is an evaluation board.
And in that case I would use a RasPi or BeagleBone and tie up directly
to some SoC-UART instead of using an intermediate USB-UART adapter.
Because it is more close to timing relations to the final SoC based design.
> and then use it on my embedded system.
>
> There are usb-serial devices, which could benefit from support
> btw. I would find it really useful, if the Dangerous Prototype's
> Bus Pirate would expose native /dev/i2c and /dev/spi and it's
> based on FT232.
Oh, that is an interesting device I didn't know yet.
>
>> So to me it looks as if you need to develop different low-level
>> drivers anyways.
>
> No. You say, that option b) is irrelevant and assume, that every
> serial chip also has native USB support.
I just assume that b) is rarely used because there are alternatives.
Although it would be a nice option.
Anyways, while following the discussion this is not the most important
facet of the overall topic.
BR,
Nikolaus
[-- Attachment #2: Message signed with OpenPGP using GPGMail --]
[-- Type: application/pgp-signature, Size: 801 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 21:23 ` H. Nikolaus Schaller
2016-08-22 21:43 ` Arnd Bergmann
2016-08-22 22:42 ` Sebastian Reichel
@ 2016-08-27 12:01 ` Michal Suchanek
2 siblings, 0 replies; 103+ messages in thread
From: Michal Suchanek @ 2016-08-27 12:01 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Sebastian Reichel, One Thousand Gnomes, Oleksij Rempel,
Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Pavel Machek, Peter Hurley, NeilBrown, Arnd Bergmann,
Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
On 22 August 2016 at 23:23, H. Nikolaus Schaller <hns@goldelico.com> wrote:
> Hi Sebastian,
>
>> Am 22.08.2016 um 22:39 schrieb Sebastian Reichel <sre@kernel.org>:
>>
>> Hi,
>>
>> On Sun, Aug 21, 2016 at 09:50:57AM +0200, H. Nikolaus Schaller wrote:
>>>> Am 20.08.2016 um 15:34 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
>>>>> What it is not about are UART/RS232 converters connected through USB or virtual
>>>>> serial ports created for WWAN modems (e.g. /dev/ttyACM, /dev/ttyHSO). Or BT devices
>>>>> connected through USB (even if they also run HCI protocol).
>>>>
>>>> It actually has to be about both because you will find the exact same
>>>> device wired via USB SSIC/HSIC to a USB UART or via a classic UART. Not is
>>>> it just about embedded boards.
>>>
>>> Not necessarily.
>>>
>>> We often have two interface options for exactly the sam sensor chips. They can be connected
>>> either through SPI or I2C. Which means that there is a core driver for the chip and two different
>>> transport glue components (see e.g. iio/accel/bmc150).
>>>
>>> This does not require I2C to be able to handle SPI or vice versa or provide a common API.
>>
>> I don't understand this comparison. I2C and SPI are different
>> protocols,
>
> Yes, they are different on protocol level, but on both you transfer blocks of data from/to a slave device
> which usually can be addressed. And for some chips they are just two slightly alternative serial interfaces.
>
>> while native UART and USB-connected UART are both UART.
>
> I see what you mean, but kernel divides between directly connected UART and USB-connected UART.
>
> drivers/usb/serial/ vs. drivers/tty/serial/
>
> to implement two different groups of UARTs. Although on user space level they are harmonized again.
> This is why I compare with i2c and spi. But each such comparison is not perfect.
>
> Anyways, to me it looks as if everybody wants to make the solution work for usb-uarts as well
> (although I still would like to see a real world use-case).
I use a NFC reader attached to a PL2303 UART. It's a proof of concept
solution but if I needed a finished
product all it takes is to put the two pieces of PCB into a box with
the USB connector sticking out.
Or glue the PCB on the inside of a plastic part of a PC case.
Thanks
Michal
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 7:29 ` H. Nikolaus Schaller
[not found] ` <ACEF800E-8DB3-4345-ADE2-15C99F3659D5-xXXSsgcRVICgSpxsJD1C4w@public.gmane.org>
@ 2016-08-19 11:06 ` One Thousand Gnomes
2016-08-19 17:42 ` H. Nikolaus Schaller
1 sibling, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-19 11:06 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Sebastian Reichel, Rob Herring, Greg Kroah-Hartman,
Marcel Holtmann, Jiri Slaby, Pavel Machek, Peter Hurley,
NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> If possible, please do a callback for every character that arrives.
> And not only if the rx buffer becomes full, to give the slave driver
> a chance to trigger actions almost immediately after every character.
> This probably runs in interrupt context and can happen often.
We don't realistically have the clock cycles to do that on a low end
embedded processor handling high speed I/O. The best you can do is
trigger a workqueue to switch the buffer data around and call the helper
while the uart may be receiving more bytes.
What you are asking for you'd get out of the first parts of tidying up
the receive paths because you'd set a different port->rx() method and get
bursts of characters, flags and length data.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 11:06 ` One Thousand Gnomes
@ 2016-08-19 17:42 ` H. Nikolaus Schaller
2016-08-20 13:22 ` One Thousand Gnomes
0 siblings, 1 reply; 103+ messages in thread
From: H. Nikolaus Schaller @ 2016-08-19 17:42 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Sebastian Reichel, Rob Herring, Greg Kroah-Hartman,
Marcel Holtmann, Jiri Slaby, Pavel Machek, Peter Hurley,
NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> Am 19.08.2016 um 13:06 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
>
>> If possible, please do a callback for every character that arrives.
>> And not only if the rx buffer becomes full, to give the slave driver
>> a chance to trigger actions almost immediately after every character.
>> This probably runs in interrupt context and can happen often.
>
> We don't realistically have the clock cycles to do that on a low end
> embedded processor handling high speed I/O.
well, if we have a low end embedded processor and high-speed I/O, then
buffering the data before processing doesn't help either since processing
still will eat up clock cycles.
> The best you can do is
> trigger a workqueue to switch the buffer data around and call the helper
> while the uart may be receiving more bytes.
Ok, assuming DMA double buffering might (almost) double throughput.
The question is if this is needed at all. If we have a bluetooth stack with HCI the
fastest UART interface I am aware of is running at 3 Mbit/s. 10 bits incl. framing
means 300kByte/s equiv. 3µs per byte to process. Should be enough to decide
if the byte should go to a buffer or not, check checksums, or discard and move
the protocol engine to a different state. This is what I assume would be done in
a callback. No processing needing some ms per frame.
>
> What you are asking for you'd get out of the first parts of tidying up
> the receive paths because you'd set a different port->rx() method and get
> bursts of characters, flags and length data.
>
> Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 17:42 ` H. Nikolaus Schaller
@ 2016-08-20 13:22 ` One Thousand Gnomes
[not found] ` <20160820142226.6121e76d-qBU/x9rampVanCEyBjwyrvXRex20P6io@public.gmane.org>
0 siblings, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-20 13:22 UTC (permalink / raw)
To: H. Nikolaus Schaller
Cc: Sebastian Reichel, Rob Herring, Greg Kroah-Hartman,
Marcel Holtmann, Jiri Slaby, Pavel Machek, Peter Hurley,
NeilBrown, Arnd Bergmann, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Fri, 19 Aug 2016 19:42:37 +0200
"H. Nikolaus Schaller" <hns@goldelico.com> wrote:
> > Am 19.08.2016 um 13:06 schrieb One Thousand Gnomes <gnomes@lxorguk.ukuu.org.uk>:
> >
> >> If possible, please do a callback for every character that arrives.
> >> And not only if the rx buffer becomes full, to give the slave driver
> >> a chance to trigger actions almost immediately after every character.
> >> This probably runs in interrupt context and can happen often.
> >
> > We don't realistically have the clock cycles to do that on a low end
> > embedded processor handling high speed I/O.
>
> well, if we have a low end embedded processor and high-speed I/O, then
> buffering the data before processing doesn't help either since processing
> still will eat up clock cycles.
Of course it helps. You are out of the IRQ handler within the 9 serial
clocks, so you can take another interrupt and grab the next byte. You
will also get benefits from processing the bytes further in blocks, and
if you get too far behind you'll make the flow control limit.
You've also usually got multiple cores these days - although not on the
very low end quite often.
> The question is if this is needed at all. If we have a bluetooth stack with HCI the
> fastest UART interface I am aware of is running at 3 Mbit/s. 10 bits incl. framing
> means 300kByte/s equiv. 3µs per byte to process. Should be enough to decide
> if the byte should go to a buffer or not, check checksums, or discard and move
> the protocol engine to a different state. This is what I assume would be done in
> a callback. No processing needing some ms per frame.
That depends on the processor - remember people run Linux on low end CPUs
including those embedded in an FPGA not just high end PC and ARM class
devices.
The more important question is - purely for the receive side of things -
is a callback which guarantees to be called "soon" after the bytes arrive
sufficient.
If it is then almost no work is needed on the receive side to allow pure
kernel code to manage recevied data directly because the current
buffering support throughout the receive side is completely capable of
providing those services without a tty structure, and to anything which
can have a tty attached.
Doesn't solve transmit or configuration but it's one step that needs no
additional real work and re-invention.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 5:21 ` Sebastian Reichel
2016-08-19 7:29 ` H. Nikolaus Schaller
@ 2016-08-19 11:03 ` One Thousand Gnomes
2016-08-19 14:44 ` Sebastian Reichel
1 sibling, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-19 11:03 UTC (permalink / raw)
To: Sebastian Reichel
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
linux-kernel-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
> I meant "Either some function similar to userspace's poll() is
> needed, ...". Something like uart_dev_wait_for_rx()
You can't really do that - it might never return and then how do you want
to handle timeouts and cleanups
> Alternatively the rx function could be a callback, that
> is called when there is new data.
That's what the existing API gives you as an ldisc, it can't be immediate
in many cases however but must be buffered.
> > I'm assuming the only immediate consumers are in-kernel.
>
> Yes, but the driver should be notified about incoming data.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-19 11:03 ` One Thousand Gnomes
@ 2016-08-19 14:44 ` Sebastian Reichel
0 siblings, 0 replies; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-19 14:44 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Arnd Bergmann, Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 1061 bytes --]
Hi Alan,
On Fri, Aug 19, 2016 at 12:03:05PM +0100, One Thousand Gnomes wrote:
> > I meant "Either some function similar to userspace's poll() is
> > needed, ...". Something like uart_dev_wait_for_rx()
>
> You can't really do that - it might never return and then how do
> you want to handle timeouts and cleanups
Well there could be some timeout. As I said, I was thinking about
an API similar to poll(), but I agree, that a callback based API
is probably the better solution. It's simpler to implement and in
most cases simpler to use.
> > Alternatively the rx function could be a callback, that
> > is called when there is new data.
>
> That's what the existing API gives you as an ldisc, it can't be
> immediate in many cases however but must be buffered.
I know and I think the ldisc API is fine in this regard. Also
the buffering allows DMA, so that's obviously preferred.
> > > I'm assuming the only immediate consumers are in-kernel.
> >
> > Yes, but the driver should be notified about incoming data.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-18 1:14 [RFC PATCH 0/3] UART slave device bus Rob Herring
` (8 preceding siblings ...)
2016-08-18 20:29 ` Sebastian Reichel
@ 2016-08-22 12:37 ` Arnd Bergmann
2016-08-22 13:38 ` Rob Herring
9 siblings, 1 reply; 103+ messages in thread
From: Arnd Bergmann @ 2016-08-22 12:37 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij, linux-bluetooth,
linux-serial, linux-kernel
On Wednesday, August 17, 2016 8:14:42 PM CEST Rob Herring wrote:
>
> Before I spend more time on this, I'm looking mainly for feedback on the
> general direction and structure (the interface with the existing serial
> drivers in particular).
Aside from the things that have already been mentioned in the discussion,
I wonder how this should relate to the drivers/input/serio framework.
My impression is that there is some overlap in what you want
to do here, and what serio does today as a line discipline on top
of a tty line discipline (and on top of other non-uart serial
connections), so we should look into whether the two can be unified
or not. Here is what I found so far:
For all I can tell, serio is only used for drivers/input/ but could
easily be extended to other subsystems. It currently uses its own
binary ID matching between drivers and devices through user space
interfaces, though adding a DT binding for it would appear to be
a good idea regardless.
It also has a bus_type already, and with some operations defined on
it. In particular, it has an "interrupt" method that is used to
notify the client driver when a byte is available (and pass
that byte along with it). This seems to be a useful addition to
what you have. Since it is based on sending single characters
both ways, transferring large amounts of data would be slower,
but the interface is somewhat simpler. In principle, both
character based and buffer based interfaces could coexist here
as they do in some other interfaces (e.g. smbus).
While serio is typically layered on top of tty-ldisc (on top of
tty_port, which is often on top of uart_port) or on top of
i8042/ps2 drivers, I suppose we could add another back-end on top
of uart_port directly to avoid the ldisc configuration in many
cases when using devicetree based setup. This should also address
the main concern that Alan raised about generality of the
subsystem: we'd always leave the option of either manual configuration
of the tty-ldisc (for any tty_port) or configuring on-chip devices
(using uart_port) directly through DT. Of course the same thing
can be done if we hook into tty_port rather than uart_port.
Arnd
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 12:37 ` Arnd Bergmann
@ 2016-08-22 13:38 ` Rob Herring
2016-08-22 15:24 ` Arnd Bergmann
0 siblings, 1 reply; 103+ messages in thread
From: Rob Herring @ 2016-08-22 13:38 UTC (permalink / raw)
To: Arnd Bergmann
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Mon, Aug 22, 2016 at 7:37 AM, Arnd Bergmann <arnd@arndb.de> wrote:
> On Wednesday, August 17, 2016 8:14:42 PM CEST Rob Herring wrote:
>>
>> Before I spend more time on this, I'm looking mainly for feedback on the
>> general direction and structure (the interface with the existing serial
>> drivers in particular).
>
> Aside from the things that have already been mentioned in the discussion,
> I wonder how this should relate to the drivers/input/serio framework.
As I mentioned, I did investigate that route.
> My impression is that there is some overlap in what you want
> to do here, and what serio does today as a line discipline on top
> of a tty line discipline (and on top of other non-uart serial
> connections), so we should look into whether the two can be unified
> or not. Here is what I found so far:
>
> For all I can tell, serio is only used for drivers/input/ but could
> easily be extended to other subsystems. It currently uses its own
> binary ID matching between drivers and devices through user space
> interfaces, though adding a DT binding for it would appear to be
> a good idea regardless.
>
> It also has a bus_type already, and with some operations defined on
> it. In particular, it has an "interrupt" method that is used to
> notify the client driver when a byte is available (and pass
> that byte along with it). This seems to be a useful addition to
> what you have. Since it is based on sending single characters
> both ways, transferring large amounts of data would be slower,
> but the interface is somewhat simpler. In principle, both
> character based and buffer based interfaces could coexist here
> as they do in some other interfaces (e.g. smbus).
Given that about the only things it really provided are the bus_type
and associated boilerplate without much of a client interface, it
seemed to me that creating a new subsystem first made more sense. Then
we can convert serio to use the new subsystem.
I agree we'll probably need a character at time interface, but for
initial targets a buffer based interface is what's needed.
> While serio is typically layered on top of tty-ldisc (on top of
> tty_port, which is often on top of uart_port) or on top of
> i8042/ps2 drivers, I suppose we could add another back-end on top
> of uart_port directly to avoid the ldisc configuration in many
> cases when using devicetree based setup. This should also address
> the main concern that Alan raised about generality of the
> subsystem: we'd always leave the option of either manual configuration
> of the tty-ldisc (for any tty_port) or configuring on-chip devices
> (using uart_port) directly through DT. Of course the same thing
> can be done if we hook into tty_port rather than uart_port.
There are also some uart drivers that register directly with serio.
I'm also thinking of using an ldisc backend as well as a way to move
forward with the slave drivers while tty_port rework is being done. Of
course that doesn't solve the fundamental problems with using an ldisc
already. Going the tty_port route is going take some time to
restructure things in the tty layer and require tree wide changes to
tty drivers.
Rob
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 13:38 ` Rob Herring
@ 2016-08-22 15:24 ` Arnd Bergmann
2016-08-22 15:28 ` Marcel Holtmann
` (3 more replies)
0 siblings, 4 replies; 103+ messages in thread
From: Arnd Bergmann @ 2016-08-22 15:24 UTC (permalink / raw)
To: Rob Herring
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Monday, August 22, 2016 8:38:23 AM CEST Rob Herring wrote:
> On Mon, Aug 22, 2016 at 7:37 AM, Arnd Bergmann <arnd@arndb.de> wrote:
> > On Wednesday, August 17, 2016 8:14:42 PM CEST Rob Herring wrote:
> >>
> >> Before I spend more time on this, I'm looking mainly for feedback on the
> >> general direction and structure (the interface with the existing serial
> >> drivers in particular).
> >
> > Aside from the things that have already been mentioned in the discussion,
> > I wonder how this should relate to the drivers/input/serio framework.
>
> As I mentioned, I did investigate that route.
Ok, sorry for missing that.
> > My impression is that there is some overlap in what you want
> > to do here, and what serio does today as a line discipline on top
> > of a tty line discipline (and on top of other non-uart serial
> > connections), so we should look into whether the two can be unified
> > or not. Here is what I found so far:
> >
> > For all I can tell, serio is only used for drivers/input/ but could
> > easily be extended to other subsystems. It currently uses its own
> > binary ID matching between drivers and devices through user space
> > interfaces, though adding a DT binding for it would appear to be
> > a good idea regardless.
> >
> > It also has a bus_type already, and with some operations defined on
> > it. In particular, it has an "interrupt" method that is used to
> > notify the client driver when a byte is available (and pass
> > that byte along with it). This seems to be a useful addition to
> > what you have. Since it is based on sending single characters
> > both ways, transferring large amounts of data would be slower,
> > but the interface is somewhat simpler. In principle, both
> > character based and buffer based interfaces could coexist here
> > as they do in some other interfaces (e.g. smbus).
>
> Given that about the only things it really provided are the bus_type
> and associated boilerplate without much of a client interface, it
> seemed to me that creating a new subsystem first made more sense. Then
> we can convert serio to use the new subsystem.
One possible downside of merging later is that we end up having to
support the existing user space ABI for serio that may not fit well
within whatever we come up with independently.
I think there are two other valuable features provided by serio:
- an existing set of drivers written to the API
- the implementation of the tty_ldisc
> I agree we'll probably need a character at time interface, but for
> initial targets a buffer based interface is what's needed.
I think what's more important than the 'character-at-a-time' interface
is the notification about new data. Maybe I missed how you handle that
today, but it seems that you can currently only handle polling
for data using a blocking read.
> > While serio is typically layered on top of tty-ldisc (on top of
> > tty_port, which is often on top of uart_port) or on top of
> > i8042/ps2 drivers, I suppose we could add another back-end on top
> > of uart_port directly to avoid the ldisc configuration in many
> > cases when using devicetree based setup. This should also address
> > the main concern that Alan raised about generality of the
> > subsystem: we'd always leave the option of either manual configuration
> > of the tty-ldisc (for any tty_port) or configuring on-chip devices
> > (using uart_port) directly through DT. Of course the same thing
> > can be done if we hook into tty_port rather than uart_port.
>
> There are also some uart drivers that register directly with serio.
Right, I think this is done to have automatic probing for the keyboard,
rather than relying on the user space interface configuration.
> I'm also thinking of using an ldisc backend as well as a way to move
> forward with the slave drivers while tty_port rework is being done. Of
> course that doesn't solve the fundamental problems with using an ldisc
> already. Going the tty_port route is going take some time to
> restructure things in the tty layer and require tree wide changes to
> tty drivers.
Would it make sense then to define a DT binding that can cover these
four cases independent of the Linux usage:
a) an existing tty line discipline matched to a tty port
b) a serio device using the N_MOUSE line discipline (which
happens to cover non-mouse devices these days)
c) a uart_port slave attached directly to the uart (like in your
current code)
d) the same slave drivers using a new tty line discipline
If we can handle all four, then at least we have some flexibility
with moving around or merging the Linux implementation later.
Arnd
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 15:24 ` Arnd Bergmann
@ 2016-08-22 15:28 ` Marcel Holtmann
2016-08-22 15:46 ` Arnd Bergmann
2016-08-22 15:45 ` One Thousand Gnomes
` (2 subsequent siblings)
3 siblings, 1 reply; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-22 15:28 UTC (permalink / raw)
To: Arnd Bergmann
Cc: Rob Herring, Greg Kroah-Hartman, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
Hi Arnd,
>>> My impression is that there is some overlap in what you want
>>> to do here, and what serio does today as a line discipline on top
>>> of a tty line discipline (and on top of other non-uart serial
>>> connections), so we should look into whether the two can be unified
>>> or not. Here is what I found so far:
>>>
>>> For all I can tell, serio is only used for drivers/input/ but could
>>> easily be extended to other subsystems. It currently uses its own
>>> binary ID matching between drivers and devices through user space
>>> interfaces, though adding a DT binding for it would appear to be
>>> a good idea regardless.
>>>
>>> It also has a bus_type already, and with some operations defined on
>>> it. In particular, it has an "interrupt" method that is used to
>>> notify the client driver when a byte is available (and pass
>>> that byte along with it). This seems to be a useful addition to
>>> what you have. Since it is based on sending single characters
>>> both ways, transferring large amounts of data would be slower,
>>> but the interface is somewhat simpler. In principle, both
>>> character based and buffer based interfaces could coexist here
>>> as they do in some other interfaces (e.g. smbus).
>>
>> Given that about the only things it really provided are the bus_type
>> and associated boilerplate without much of a client interface, it
>> seemed to me that creating a new subsystem first made more sense. Then
>> we can convert serio to use the new subsystem.
>
> One possible downside of merging later is that we end up having to
> support the existing user space ABI for serio that may not fit well
> within whatever we come up with independently.
if we need any kind of userspace ABI to setup of Bluetooth over UART devices, then we have failed. We want that the special UARTs are identified via ACPI or DT and become an enumeratable bus. So we can attach a driver to it.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 15:28 ` Marcel Holtmann
@ 2016-08-22 15:46 ` Arnd Bergmann
0 siblings, 0 replies; 103+ messages in thread
From: Arnd Bergmann @ 2016-08-22 15:46 UTC (permalink / raw)
To: Marcel Holtmann
Cc: Rob Herring, Greg Kroah-Hartman, Jiri Slaby, Sebastian Reichel,
Pavel Machek, Peter Hurley, NeilBrown, Dr . H . Nikolaus Schaller,
Linus Walleij, open list:BLUETOOTH DRIVERS,
linux-serial@vger.kernel.org, linux-kernel@vger.kernel.org
On Monday, August 22, 2016 11:28:02 AM CEST Marcel Holtmann wrote:
> >>> My impression is that there is some overlap in what you want
> >>> to do here, and what serio does today as a line discipline on top
> >>> of a tty line discipline (and on top of other non-uart serial
> >>> connections), so we should look into whether the two can be unified
> >>> or not. Here is what I found so far:
> >>>
> >>> For all I can tell, serio is only used for drivers/input/ but could
> >>> easily be extended to other subsystems. It currently uses its own
> >>> binary ID matching between drivers and devices through user space
> >>> interfaces, though adding a DT binding for it would appear to be
> >>> a good idea regardless.
> >>>
> >>> It also has a bus_type already, and with some operations defined on
> >>> it. In particular, it has an "interrupt" method that is used to
> >>> notify the client driver when a byte is available (and pass
> >>> that byte along with it). This seems to be a useful addition to
> >>> what you have. Since it is based on sending single characters
> >>> both ways, transferring large amounts of data would be slower,
> >>> but the interface is somewhat simpler. In principle, both
> >>> character based and buffer based interfaces could coexist here
> >>> as they do in some other interfaces (e.g. smbus).
> >>
> >> Given that about the only things it really provided are the bus_type
> >> and associated boilerplate without much of a client interface, it
> >> seemed to me that creating a new subsystem first made more sense. Then
> >> we can convert serio to use the new subsystem.
> >
> > One possible downside of merging later is that we end up having to
> > support the existing user space ABI for serio that may not fit well
> > within whatever we come up with independently.
>
> if we need any kind of userspace ABI to setup of Bluetooth
> over UART devices, then we have failed. We want that the
> special UARTs are identified via ACPI or DT and become an
> enumeratable bus. So we can attach a driver to it.
I was not referring to new devices here, only to the existing user
space ABI that is used for serio (input) devices. If we have
any tools relying on e.g. the 'serio' name for the sysfs path,
using another name for the new bus_type may cause incompatibility
when merging the two.
Arnd
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 15:24 ` Arnd Bergmann
2016-08-22 15:28 ` Marcel Holtmann
@ 2016-08-22 15:45 ` One Thousand Gnomes
2016-08-22 21:07 ` Marcel Holtmann
2016-08-24 12:14 ` Linus Walleij
2016-08-22 16:44 ` Rob Herring
2016-08-23 21:04 ` Rob Herring
3 siblings, 2 replies; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-22 15:45 UTC (permalink / raw)
To: Arnd Bergmann
Cc: Rob Herring, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> Would it make sense then to define a DT binding that can cover these
> four cases independent of the Linux usage:
>
> a) an existing tty line discipline matched to a tty port
> b) a serio device using the N_MOUSE line discipline (which
> happens to cover non-mouse devices these days)
These two are the same basic thing
port x expects ldisc y {with properties ...}
> c) a uart_port slave attached directly to the uart (like in your
> current code)
c) needs to be a tty_port slave attached directly to a tty_port.
Important detail, but as uart_port is just a subset of tty_port it's a
trivial detail to the DT.
> d) the same slave drivers using a new tty line discipline
and this is also just a/b again.
What use cases and connectivity do you need to describe. Looking at the
ACPI platforms we have
- the expected serial port configuration
- the properties of the port (FIFO etc)
- the power management for the port
- the children of the port
- the power management of the children (at a very simplistic abstracted
level)
So we want to be able to describe something like
ttyS0 {
baud: 1152008N1
protocol: bluetooth hci
fixed: yes
powermanagement: { ... }
}
and if I look at the usermode crapfest on a lot of Android systems it
looks similar but with the notion of things like being able to describe
- Use GPIO mode sleeping and assume first char is X to save power
- Power up, wait n ms, write, read, wait n ms, power down (which
has to be driven at the ldisc/user level as only the ldisc
understands transactions, or via ioctls (right now Android user
space tends to do hardcoded writes to /sys.. gpio to drive power
- And a few variants thereof (power up on write, off on a timer
etc)
So I can imagine wanting to describe something like
- The bluetooth HCI hardware is managed by gpio 11 (or UART DTR,
or PMIC n etc)
The uart can switch into GPIO mode and is gpio 15
or
- Raise gpio 4 when writing, drop it after 50mS with no read/write
Then the ldisc needs to make port->ops. calls for enabling/disabling low
power mode and expected char, and the uarts that can do it need to
implement the gpio/uart switching and any timers.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 15:45 ` One Thousand Gnomes
@ 2016-08-22 21:07 ` Marcel Holtmann
2016-08-22 21:35 ` One Thousand Gnomes
2016-08-22 22:03 ` Sebastian Reichel
2016-08-24 12:14 ` Linus Walleij
1 sibling, 2 replies; 103+ messages in thread
From: Marcel Holtmann @ 2016-08-22 21:07 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Arnd Bergmann, Rob Herring, Greg Kroah-Hartman, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
Hi Alan,
>> Would it make sense then to define a DT binding that can cover these
>> four cases independent of the Linux usage:
>>
>> a) an existing tty line discipline matched to a tty port
>> b) a serio device using the N_MOUSE line discipline (which
>> happens to cover non-mouse devices these days)
>
> These two are the same basic thing
>
> port x expects ldisc y {with properties ...}
>
>> c) a uart_port slave attached directly to the uart (like in your
>> current code)
>
> c) needs to be a tty_port slave attached directly to a tty_port.
> Important detail, but as uart_port is just a subset of tty_port it's a
> trivial detail to the DT.
>
>> d) the same slave drivers using a new tty line discipline
>
> and this is also just a/b again.
>
>
> What use cases and connectivity do you need to describe. Looking at the
> ACPI platforms we have
>
> - the expected serial port configuration
> - the properties of the port (FIFO etc)
> - the power management for the port
>
> - the children of the port
> - the power management of the children (at a very simplistic abstracted
> level)
>
> So we want to be able to describe something like
>
> ttyS0 {
> baud: 1152008N1
> protocol: bluetooth hci
> fixed: yes
> powermanagement: { ... }
> }
we also need to know what Bluetooth vendor is there. Since we need to match the vendor to the firmware loading and configuration.
Additionally there might be PCM audio configurations that need to be considered. Since we have to configure direct PCM interconnect with the audio codec.
> and if I look at the usermode crapfest on a lot of Android systems it
> looks similar but with the notion of things like being able to describe
>
> - Use GPIO mode sleeping and assume first char is X to save power
>
> - Power up, wait n ms, write, read, wait n ms, power down (which
> has to be driven at the ldisc/user level as only the ldisc
> understands transactions, or via ioctls (right now Android user
> space tends to do hardcoded writes to /sys.. gpio to drive power
>
> - And a few variants thereof (power up on write, off on a timer
> etc)
Actually the sad part about the Android mess is that we can fix it for Bluetooth. We have HCI User Channel that allows to grab a HCI device and assign it to Bluedroid stack on Android. So it would work with whatever bus or whatever vendor is underneath. All this hacking would go away. And we have used this successfully for Intel based Android platforms. We know this works.
> So I can imagine wanting to describe something like
>
> - The bluetooth HCI hardware is managed by gpio 11 (or UART DTR,
> or PMIC n etc)
> The uart can switch into GPIO mode and is gpio 15
>
> or
>
> - Raise gpio 4 when writing, drop it after 50mS with no read/write
>
> Then the ldisc needs to make port->ops. calls for enabling/disabling low
> power mode and expected char, and the uarts that can do it need to
> implement the gpio/uart switching and any timers.
I now wonder if we can not just turn the ldisc into a bus. So we have a ldisc bus that exposes devices that have no business of having a userspace /dev/ttyX exposed. And our Bluetooth UART support just turns into a ldisc driver on the ldisc bus.
One of the problems is that attaching the ldisc from userspace you still need to figure out what /dev/ttyX you get assigned in the end. And figure out which one is the Bluetooth UART. If we want single images where things just work out of the box, we need to get extra information for doing auto-detection. So some sort of bus enumeration is key to make this work smoothly.
Regards
Marcel
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 21:07 ` Marcel Holtmann
@ 2016-08-22 21:35 ` One Thousand Gnomes
2016-08-22 22:03 ` Sebastian Reichel
1 sibling, 0 replies; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-22 21:35 UTC (permalink / raw)
To: Marcel Holtmann
Cc: Arnd Bergmann, Rob Herring, Greg Kroah-Hartman, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> I now wonder if we can not just turn the ldisc into a bus. So we have a ldisc bus that exposes devices that have no business of having a userspace /dev/ttyX exposed. And our Bluetooth UART support just turns into a ldisc driver on the ldisc bus.
The ldisc and tty have the wrong object lifetime for a bus, but you can
put the tty_port objects onto the bus, and it is those you need to
instantiate the stack.
The port exists for hardware lifetime, the tty and ldisc exist only while
the port is "up".
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 21:07 ` Marcel Holtmann
2016-08-22 21:35 ` One Thousand Gnomes
@ 2016-08-22 22:03 ` Sebastian Reichel
2016-08-22 22:46 ` One Thousand Gnomes
1 sibling, 1 reply; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-22 22:03 UTC (permalink / raw)
To: Marcel Holtmann
Cc: One Thousand Gnomes, Arnd Bergmann, Rob Herring,
Greg Kroah-Hartman, Jiri Slaby, Pavel Machek, Peter Hurley,
NeilBrown, Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 4980 bytes --]
Hi,
On Mon, Aug 22, 2016 at 05:07:06PM -0400, Marcel Holtmann wrote:
> >> Would it make sense then to define a DT binding that can cover these
> >> four cases independent of the Linux usage:
> >>
> >> a) an existing tty line discipline matched to a tty port
> >> b) a serio device using the N_MOUSE line discipline (which
> >> happens to cover non-mouse devices these days)
> >
> > These two are the same basic thing
> >
> > port x expects ldisc y {with properties ...}
> >
> >> c) a uart_port slave attached directly to the uart (like in your
> >> current code)
> >
> > c) needs to be a tty_port slave attached directly to a tty_port.
> > Important detail, but as uart_port is just a subset of tty_port it's a
> > trivial detail to the DT.
> >
> >> d) the same slave drivers using a new tty line discipline
> >
> > and this is also just a/b again.
> >
> >
> > What use cases and connectivity do you need to describe. Looking at the
> > ACPI platforms we have
> >
> > - the expected serial port configuration
> > - the properties of the port (FIFO etc)
> > - the power management for the port
> >
> > - the children of the port
> > - the power management of the children (at a very simplistic abstracted
> > level)
> >
> > So we want to be able to describe something like
> >
> > ttyS0 {
> > baud: 1152008N1
> > protocol: bluetooth hci
> > fixed: yes
> > powermanagement: { ... }
> > }
>
> we also need to know what Bluetooth vendor is there. Since we need
> to match the vendor to the firmware loading and configuration.
>
> Additionally there might be PCM audio configurations that need to
> be considered. Since we have to configure direct PCM interconnect
> with the audio codec.
It's not enough to automatically set a ldisc. There is also need for
additional resouces. For example the Nokia bluetooth driver needs
some extra GPIOs. The same is true for the in-tree hci_bcm, which
misuses the platform_device exactly like Greg doesn't want it.
> > and if I look at the usermode crapfest on a lot of Android systems it
> > looks similar but with the notion of things like being able to describe
> >
> > - Use GPIO mode sleeping and assume first char is X to save power
> >
> > - Power up, wait n ms, write, read, wait n ms, power down (which
> > has to be driven at the ldisc/user level as only the ldisc
> > understands transactions, or via ioctls (right now Android user
> > space tends to do hardcoded writes to /sys.. gpio to drive power
> >
> > - And a few variants thereof (power up on write, off on a timer
> > etc)
>
> Actually the sad part about the Android mess is that we can fix it
> for Bluetooth. We have HCI User Channel that allows to grab a HCI
> device and assign it to Bluedroid stack on Android. So it would
> work with whatever bus or whatever vendor is underneath. All this
> hacking would go away. And we have used this successfully for
> Intel based Android platforms. We know this works.
>
> > So I can imagine wanting to describe something like
> >
> > - The bluetooth HCI hardware is managed by gpio 11 (or UART DTR,
> > or PMIC n etc)
> > The uart can switch into GPIO mode and is gpio 15
> >
> > or
> >
> > - Raise gpio 4 when writing, drop it after 50mS with no read/write
> >
> > Then the ldisc needs to make port->ops. calls for enabling/disabling low
> > power mode and expected char, and the uarts that can do it need to
> > implement the gpio/uart switching and any timers.
>
> I now wonder if we can not just turn the ldisc into a bus. So we
> have a ldisc bus that exposes devices that have no business of
> having a userspace /dev/ttyX exposed. And our Bluetooth UART
> support just turns into a ldisc driver on the ldisc bus.
>
> One of the problems is that attaching the ldisc from userspace you
> still need to figure out what /dev/ttyX you get assigned in the
> end. And figure out which one is the Bluetooth UART. If we want
> single images where things just work out of the box, we need to
> get extra information for doing auto-detection. So some sort of
> bus enumeration is key to make this work smoothly.
I don't understand your propsoal. First you write, that no ttyX
needs to be exported at all, then you need to figure out what ttyX
got assigned in the end.
I think the problem with line disciplines is, that they do
not follow the Linux device model. UART slaves may have extra
resources like gpios or regulators. The current workaround from
the drivers is an additional platform device, which only is
used as resource storage and accessed by the line discipline.
I think having a proper slave devices would be better in the long
run than adding more hacks to work around the problem of line
discplines not being devices. It probably makes sense to make the
API similar to the line discipline API, though. That way old code
can be reused.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 22:03 ` Sebastian Reichel
@ 2016-08-22 22:46 ` One Thousand Gnomes
2016-08-22 23:41 ` Sebastian Reichel
0 siblings, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-22 22:46 UTC (permalink / raw)
To: Sebastian Reichel
Cc: Marcel Holtmann, Arnd Bergmann, Rob Herring, Greg Kroah-Hartman,
Jiri Slaby, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> It's not enough to automatically set a ldisc. There is also need for
> additional resouces. For example the Nokia bluetooth driver needs
> some extra GPIOs. The same is true for the in-tree hci_bcm, which
> misuses the platform_device exactly like Greg doesn't want it.
This is one of those cases where ACPI gets it right. For the device tree
case you will also need to describe the GPIO lines as part of your power
management for that slave device.
> I think the problem with line disciplines is, that they do
> not follow the Linux device model. UART slaves may have extra
They follow it exactly.
You have a tty_port which wraps a device, and has the lifetime of the
hardware and lives on busses and can support enumeration.
You have a tty which is a file system object with a lifetime determined
by the use of the file handle, it's like any other file->private_data but
quite complex because we must comply with POSIX and historic Unix tty
behaviour.
You have an ldisc, which is simply a modularisation of the current
protocol handler and is carefully engineered not to include any device
specific knowledge. That's how you make it scale and actually work sanely.
> resources like gpios or regulators.
Any resources belong to the tty_port or a child of the tty_port because
only it has the correct lifetime. And yes it's perfectly reasonable for
us to attach other resources to a tty_port or give it a child that is the
device the other end of the fixed link. Everything the DT describes
belongs hanging off the tty_port or a child thereof.
We don't get this problem in ACPI space in general because as far as ACPI
is concerned the tty has a child device and the child device describes
its own power management so you just power the child on or off through
ACPI and ACPI describes power sanely.
Eveything you have that is device specific belongs in the tty_port driver
for that hardware, or maybe shared library helpers if common.
Everything you have which involves invoking device defined policy
according to protocol defined behaviour belongs in the ldisc.
Unix has worked like this for well over 30 years and it works very well
as a model.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 22:46 ` One Thousand Gnomes
@ 2016-08-22 23:41 ` Sebastian Reichel
0 siblings, 0 replies; 103+ messages in thread
From: Sebastian Reichel @ 2016-08-22 23:41 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Marcel Holtmann, Arnd Bergmann, Rob Herring, Greg Kroah-Hartman,
Jiri Slaby, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
[-- Attachment #1: Type: text/plain, Size: 3615 bytes --]
Hi,
On Mon, Aug 22, 2016 at 11:46:10PM +0100, One Thousand Gnomes wrote:
> > It's not enough to automatically set a ldisc. There is also need for
> > additional resouces. For example the Nokia bluetooth driver needs
> > some extra GPIOs. The same is true for the in-tree hci_bcm, which
> > misuses the platform_device exactly like Greg doesn't want it.
>
> This is one of those cases where ACPI gets it right. For the device tree
> case you will also need to describe the GPIO lines as part of your power
> management for that slave device.
>
> > I think the problem with line disciplines is, that they do
> > not follow the Linux device model. UART slaves may have extra
>
> They follow it exactly.
>
> You have a tty_port which wraps a device, and has the lifetime of the
> hardware and lives on busses and can support enumeration.
>
> You have a tty which is a file system object with a lifetime determined
> by the use of the file handle, it's like any other file->private_data but
> quite complex because we must comply with POSIX and historic Unix tty
> behaviour.
>
> You have an ldisc, which is simply a modularisation of the current
> protocol handler and is carefully engineered not to include any device
> specific knowledge. That's how you make it scale and actually work sanely.
I think the current support is far from sane for hardwired
serial-based bluetooth devices. I open the serial device,
set the line disector, set the vendor and maybe some other
extra information and then do nothing, since the kernel
handles everything for me. All of the information given to
the kernel could be done automatically using the firmware
information. Why should I care how my bluetooth device is
connected?
> > resources like gpios or regulators.
>
> Any resources belong to the tty_port or a child of the tty_port because
> only it has the correct lifetime. And yes it's perfectly reasonable for
> us to attach other resources to a tty_port or give it a child that is the
> device the other end of the fixed link. Everything the DT describes
> belongs hanging off the tty_port or a child thereof.
Right we need a _child_, since we describe the other end of the
fixed link. Adding random remote end resources to the tty_port
looks like a huge hack.
> We don't get this problem in ACPI space in general because as far as ACPI
> is concerned the tty has a child device and the child device describes
> its own power management so you just power the child on or off through
> ACPI and ACPI describes power sanely.
>
> Eveything you have that is device specific belongs in the tty_port driver
> for that hardware, or maybe shared library helpers if common.
>
> Everything you have which involves invoking device defined policy
> according to protocol defined behaviour belongs in the ldisc.
ACPI is not better in this regard. Have a look at
drivers/bluetooth/hci_bcm.c and you will see a platform device
providing the GPIOs, which is then accessed by the line discipline.
> Unix has worked like this for well over 30 years and it works very
> well as a model.
TBH I don't think it does.
Why should I need to tell the kernel something, that it could know
automatically. Let's think about hci_bcm. The firmware tells the
kernel, that some bluetooth device is connected to the uart port.
The kernel ignores that information until the user also tells it,
that the bluetooth chip is connected to some tty. If the kernel had
done the right job, the user wouldn't even know, that bluetooth is
connected via UART.
-- Sebastian
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 819 bytes --]
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 15:45 ` One Thousand Gnomes
2016-08-22 21:07 ` Marcel Holtmann
@ 2016-08-24 12:14 ` Linus Walleij
1 sibling, 0 replies; 103+ messages in thread
From: Linus Walleij @ 2016-08-24 12:14 UTC (permalink / raw)
To: One Thousand Gnomes
Cc: Arnd Bergmann, Rob Herring, Greg Kroah-Hartman, Marcel Holtmann,
Jiri Slaby, Sebastian Reichel, Pavel Machek, Peter Hurley,
NeilBrown, Dr . H . Nikolaus Schaller,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Mon, Aug 22, 2016 at 5:45 PM, One Thousand Gnomes
<gnomes@lxorguk.ukuu.org.uk> wrote:
> and if I look at the usermode crapfest on a lot of Android systems it
> looks similar but with the notion of things like being able to describe
>
> - Use GPIO mode sleeping and assume first char is X to save power
It's really nasty hardware design, or a software hack to solve
a hardware problem: what should have been done is
of course create a UART with an asynchronous low-power mode
that can recieve a character and wake up the system at any time,
handing over the wakeup character(s) to the driver. That is
obviously the usecase they were designing for.
But yeah, I guess we have to contain hacks like that.
> - Power up, wait n ms, write, read, wait n ms, power down (which
> has to be driven at the ldisc/user level as only the ldisc
> understands transactions, or via ioctls (right now Android user
> space tends to do hardcoded writes to /sys.. gpio to drive power
This kind of abominational abuse of the GPIO sysfs ABI is
partly why I've obsoleted it. The right abstraction is the
fixed regulator with a GPIO line obviously, then some
sequencing along the lines of what you can find in
drivers/mmc/core/pwrseq*
Unfortunately that sysfs ABI crept in during a window of time
when GPIO was unmaintained and I am trying my best to
contain and improve the situation.
Yours,
Linus Walleij
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 15:24 ` Arnd Bergmann
2016-08-22 15:28 ` Marcel Holtmann
2016-08-22 15:45 ` One Thousand Gnomes
@ 2016-08-22 16:44 ` Rob Herring
2016-08-22 17:02 ` One Thousand Gnomes
2016-08-23 21:04 ` Rob Herring
3 siblings, 1 reply; 103+ messages in thread
From: Rob Herring @ 2016-08-22 16:44 UTC (permalink / raw)
To: Arnd Bergmann
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
On Mon, Aug 22, 2016 at 10:24 AM, Arnd Bergmann <arnd@arndb.de> wrote:
> On Monday, August 22, 2016 8:38:23 AM CEST Rob Herring wrote:
>> On Mon, Aug 22, 2016 at 7:37 AM, Arnd Bergmann <arnd@arndb.de> wrote:
>> > On Wednesday, August 17, 2016 8:14:42 PM CEST Rob Herring wrote:
>> >>
>> >> Before I spend more time on this, I'm looking mainly for feedback on the
>> >> general direction and structure (the interface with the existing serial
>> >> drivers in particular).
>> >
>> > Aside from the things that have already been mentioned in the discussion,
>> > I wonder how this should relate to the drivers/input/serio framework.
>>
>> As I mentioned, I did investigate that route.
>
> Ok, sorry for missing that.
>
>> > My impression is that there is some overlap in what you want
>> > to do here, and what serio does today as a line discipline on top
>> > of a tty line discipline (and on top of other non-uart serial
>> > connections), so we should look into whether the two can be unified
>> > or not. Here is what I found so far:
>> >
>> > For all I can tell, serio is only used for drivers/input/ but could
>> > easily be extended to other subsystems. It currently uses its own
>> > binary ID matching between drivers and devices through user space
>> > interfaces, though adding a DT binding for it would appear to be
>> > a good idea regardless.
>> >
>> > It also has a bus_type already, and with some operations defined on
>> > it. In particular, it has an "interrupt" method that is used to
>> > notify the client driver when a byte is available (and pass
>> > that byte along with it). This seems to be a useful addition to
>> > what you have. Since it is based on sending single characters
>> > both ways, transferring large amounts of data would be slower,
>> > but the interface is somewhat simpler. In principle, both
>> > character based and buffer based interfaces could coexist here
>> > as they do in some other interfaces (e.g. smbus).
>>
>> Given that about the only things it really provided are the bus_type
>> and associated boilerplate without much of a client interface, it
>> seemed to me that creating a new subsystem first made more sense. Then
>> we can convert serio to use the new subsystem.
>
> One possible downside of merging later is that we end up having to
> support the existing user space ABI for serio that may not fit well
> within whatever we come up with independently.
>
> I think there are two other valuable features provided by serio:
>
> - an existing set of drivers written to the API
> - the implementation of the tty_ldisc
True, though I'd expect little of the data flow part of it to be reused.
>> I agree we'll probably need a character at time interface, but for
>> initial targets a buffer based interface is what's needed.
>
> I think what's more important than the 'character-at-a-time' interface
> is the notification about new data. Maybe I missed how you handle that
> today, but it seems that you can currently only handle polling
> for data using a blocking read.
What's there now I expect to change anyway. Probably will mirror the
ldisc interface based on the discussion.
>> > While serio is typically layered on top of tty-ldisc (on top of
>> > tty_port, which is often on top of uart_port) or on top of
>> > i8042/ps2 drivers, I suppose we could add another back-end on top
>> > of uart_port directly to avoid the ldisc configuration in many
>> > cases when using devicetree based setup. This should also address
>> > the main concern that Alan raised about generality of the
>> > subsystem: we'd always leave the option of either manual configuration
>> > of the tty-ldisc (for any tty_port) or configuring on-chip devices
>> > (using uart_port) directly through DT. Of course the same thing
>> > can be done if we hook into tty_port rather than uart_port.
>>
>> There are also some uart drivers that register directly with serio.
>
> Right, I think this is done to have automatic probing for the keyboard,
> rather than relying on the user space interface configuration.
>
>> I'm also thinking of using an ldisc backend as well as a way to move
>> forward with the slave drivers while tty_port rework is being done. Of
>> course that doesn't solve the fundamental problems with using an ldisc
>> already. Going the tty_port route is going take some time to
>> restructure things in the tty layer and require tree wide changes to
>> tty drivers.
>
> Would it make sense then to define a DT binding that can cover these
> four cases independent of the Linux usage:
>
> a) an existing tty line discipline matched to a tty port
> b) a serio device using the N_MOUSE line discipline (which
> happens to cover non-mouse devices these days)
I agree with Alan these are the same. tty ldisc and tty ports are
Linux concepts which shouldn't leak into DT. I've rejected bindings
with "ttyBLAH" in them several times. Even if we did allow it, that
sounds a half solution to me. Now if the binding is the same as (c)
and there is some mapping of slave compatible string to ldisc, then
perhaps that is fine.
> c) a uart_port slave attached directly to the uart (like in your
> current code)
>From a binding standpoint, I think it is pretty simple. It's been
discussed several times, but does need to get written down in a common
binding doc. IMO it is:
- a child of the uart node
- a reg property containing the line number if the parent has multiple
uarts (I'd expect this to rarely be used).
- baudrate and other line configuration (though I would expect the
slave driver to know all this and set it w/o DT. Also, we already have
a way to set baudrate in the parent node at least.)
- other standard device properties for interrupt, gpios, regulators.
Also to consider is whether muxing of multiple slaves is needed. It's
not anything I've seen come up, but it's not hard to imagine. I think
that can be considered later and shouldn't impact the initial binding
or infrastructure.
> d) the same slave drivers using a new tty line discipline
As with (a) and (b), this should be an internal kernel detail or manual config.
Rob
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 16:44 ` Rob Herring
@ 2016-08-22 17:02 ` One Thousand Gnomes
[not found] ` <20160822180254.5c95af7c-qBU/x9rampVanCEyBjwyrvXRex20P6io@public.gmane.org>
0 siblings, 1 reply; 103+ messages in thread
From: One Thousand Gnomes @ 2016-08-22 17:02 UTC (permalink / raw)
To: Rob Herring
Cc: Arnd Bergmann, Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
> > I think there are two other valuable features provided by serio:
> >
> > - an existing set of drivers written to the API
> > - the implementation of the tty_ldisc
>
> True, though I'd expect little of the data flow part of it to be reused.
Then your design is broken.
> - a child of the uart node
> - a reg property containing the line number if the parent has multiple
> uarts (I'd expect this to rarely be used).
That surprises me as for current x86 platforms it would be the norm,
except that we use ACPI.
> - baudrate and other line configuration (though I would expect the
> slave driver to know all this and set it w/o DT. Also, we already have
> a way to set baudrate in the parent node at least.)
> - other standard device properties for interrupt, gpios, regulators.
>
> Also to consider is whether muxing of multiple slaves is needed. It's
> not anything I've seen come up, but it's not hard to imagine. I think
> that can be considered later and shouldn't impact the initial binding
> or infrastructure.
You can describe the child of the serial device as a mux and the children
of the mux as whatever so it comes out fine when you get to that point.
Alan
^ permalink raw reply [flat|nested] 103+ messages in thread
* Re: [RFC PATCH 0/3] UART slave device bus
2016-08-22 15:24 ` Arnd Bergmann
` (2 preceding siblings ...)
2016-08-22 16:44 ` Rob Herring
@ 2016-08-23 21:04 ` Rob Herring
3 siblings, 0 replies; 103+ messages in thread
From: Rob Herring @ 2016-08-23 21:04 UTC (permalink / raw)
To: Arnd Bergmann, Dmitry Torokhov
Cc: Greg Kroah-Hartman, Marcel Holtmann, Jiri Slaby,
Sebastian Reichel, Pavel Machek, Peter Hurley, NeilBrown,
Dr . H . Nikolaus Schaller, Linus Walleij,
open list:BLUETOOTH DRIVERS, linux-serial@vger.kernel.org,
linux-kernel@vger.kernel.org
+Dmitry to get his opinion on using serio.
On Mon, Aug 22, 2016 at 10:24 AM, Arnd Bergmann <arnd@arndb.de> wrote:
> On Monday, August 22, 2016 8:38:23 AM CEST Rob Herring wrote:
>> On Mon, Aug 22, 2016 at 7:37 AM, Arnd Bergmann <arnd@arndb.de> wrote:
>> > On Wednesday, August 17, 2016 8:14:42 PM CEST Rob Herring wrote:
>> >>
>> >> Before I spend more time on this, I'm looking mainly for feedback on the
>> >> general direction and structure (the interface with the existing serial
>> >> drivers in particular).
>> >
>> > Aside from the things that have already been mentioned in the discussion,
>> > I wonder how this should relate to the drivers/input/serio framework.
>>
>> As I mentioned, I did investigate that route.
>
> Ok, sorry for missing that.
>
>> > My impression is that there is some overlap in what you want
>> > to do here, and what serio does today as a line discipline on top
>> > of a tty line discipline (and on top of other non-uart serial
>> > connections), so we should look into whether the two can be unified
>> > or not. Here is what I found so far:
>> >
>> > For all I can tell, serio is only used for drivers/input/ but could
>> > easily be extended to other subsystems. It currently uses its own
>> > binary ID matching between drivers and devices through user space
>> > interfaces, though adding a DT binding for it would appear to be
>> > a good idea regardless.
>> >
>> > It also has a bus_type already, and with some operations defined on
>> > it. In particular, it has an "interrupt" method that is used to
>> > notify the client driver when a byte is available (and pass
>> > that byte along with it). This seems to be a useful addition to
>> > what you have. Since it is based on sending single characters
>> > both ways, transferring large amounts of data would be slower,
>> > but the interface is somewhat simpler. In principle, both
>> > character based and buffer based interfaces could coexist here
>> > as they do in some other interfaces (e.g. smbus).
>>
>> Given that about the only things it really provided are the bus_type
>> and associated boilerplate without much of a client interface, it
>> seemed to me that creating a new subsystem first made more sense. Then
>> we can convert serio to use the new subsystem.
>
> One possible downside of merging later is that we end up having to
> support the existing user space ABI for serio that may not fit well
> within whatever we come up with independently.
>
> I think there are two other valuable features provided by serio:
>
> - an existing set of drivers written to the API
> - the implementation of the tty_ldisc
I've looked at serio a bit more and was able to add in DT matching to
it. It's a bit hacky to make it work with the ldisc as it gets the DT
node from serio->dev.parent->parent (the parent is the tty and
grandparent is the uart dev) and still requires inputattach to open
the tty and set the ldisc. Otherwise, the mode for inputattach doesn't
matter. So I plan to continue down this path.
One thing I'm left wondering is serio essentially implements it's own
async probing with connect()/disconnect(). Seems like it was because
PS/2 port probing and resuming are slow. Is this still necessary or
could be converted to use driver core async probing? That would make
serio drivers look a bit more "normal".
Rob
^ permalink raw reply [flat|nested] 103+ messages in thread