All the mail mirrored from lore.kernel.org
 help / color / mirror / Atom feed
* [PATCH v4 0/4] Broadcom Bluetooth UART device driver
@ 2015-06-17 21:30 Ilya Faenson
  2015-06-17 21:30 ` [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings Ilya Faenson
                   ` (3 more replies)
  0 siblings, 4 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 21:30 UTC (permalink / raw)
  To: Marcel Holtmann; +Cc: linux-bluetooth, Arend van Spriel, Ilya Faenson

v4 - 	Make idle-timeout the device tree parameter
	Keep speeds both in the line discipline and in the protocol
	Remove unnecessary checks and traces
v3 -	Renamed brcm device into bcm.
	Allowed for the Broadcom protocol running without Broadcom device
		at the request of Loic Poulain.
	Introduced structure definitions for vendor specific commands.
	Transferred init-speed and oper-speed from protocol into the
		line discipline as they are configurable.
	Introduced hci_uart_init_tty function.
	Removed driver specific Kconfig menu option.
	Introduced protocol timer helper function.
	Converted single driver control dispatch routine into individual
		action routines & removed interface versioning.
	Eliminated specific firmware file name.
	Removed excessive tracing.
	Took care of numerous other comments from Marcel.
v2 -	Release upon the acceptance of Fred's updates, updated as per
		the latest comments from Marcel.
v1 -	Original release against the Fred Danis' updates.

Ilya Faenson (4):
  Broadcom Bluetooth UART Device Tree bindings
  hci_uart: line discipline enhancements
  btbcm_uart: Broadcom UART Platform Driver
  hci_bcm: Broadcom UART protocol enhancements

 .../devicetree/bindings/net/bluetooth/btbcm.txt    |  86 ++++
 drivers/bluetooth/Makefile                         |   1 +
 drivers/bluetooth/btbcm_uart.c                     | 538 +++++++++++++++++++++
 drivers/bluetooth/btbcm_uart.h                     |  74 +++
 drivers/bluetooth/hci_bcm.c                        | 340 ++++++++++++-
 drivers/bluetooth/hci_ldisc.c                      | 106 +++-
 drivers/bluetooth/hci_uart.h                       |   7 +
 7 files changed, 1137 insertions(+), 15 deletions(-)
 create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
 create mode 100644 drivers/bluetooth/btbcm_uart.c
 create mode 100644 drivers/bluetooth/btbcm_uart.h

-- 
1.9.1

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

* [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-17 21:30 [PATCH v4 0/4] Broadcom Bluetooth UART device driver Ilya Faenson
@ 2015-06-17 21:30 ` Ilya Faenson
  2015-06-17 21:33   ` Arend van Spriel
                     ` (2 more replies)
  2015-06-17 21:30 ` [PATCH v4 2/4] hci_uart: line discipline enhancements Ilya Faenson
                   ` (2 subsequent siblings)
  3 siblings, 3 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 21:30 UTC (permalink / raw)
  To: Marcel Holtmann; +Cc: linux-bluetooth, Arend van Spriel, Ilya Faenson

Device Tree bindings to configure the Broadcom Bluetooth UART device.

Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
---
 .../devicetree/bindings/net/bluetooth/btbcm.txt    | 86 ++++++++++++++++++++++
 1 file changed, 86 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.txt

diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
new file mode 100644
index 0000000..5dbcd57
--- /dev/null
+++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
@@ -0,0 +1,86 @@
+btbcm
+------
+
+Required properties:
+
+	- compatible : must be "brcm,brcm-bt-uart".
+	- tty : tty device connected to this Bluetooth device.
+
+Optional properties:
+
+  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
+
+  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
+
+  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
+
+  - oper-speed : Bluetooth device operational baud rate.
+    Default: 3000000.
+
+  - manual-fc : flow control UART in suspend / resume scenarios.
+    Default: 0.
+
+  - configure-sleep : configure suspend / resume flag.
+    Default: false.
+
+  - idle-timeout : Number of seconds of inactivity before suspending.
+    Default: 5.
+
+  - configure-audio : configure platform PCM SCO flag.
+    Default: false.
+
+  - pcm-clockmode : PCM clock mode. 0-slave, 1-master.
+    Default: 0.
+
+  - pcm-fillmethod : PCM fill method. 0 to 3.
+    Default: 2.
+
+  - pcm-fillnum : PCM number of fill bits. 0 to 3.
+    Default: 0.
+
+  - pcm-fillvalue : PCM fill value. 0 to 7.
+    Default: 3.
+
+  - pcm-incallbitclock : PCM interface rate. 0-128Kbps, 1-256Kbps, 2-512Kbps,
+    3-1024Kbps, 4-2048Kbps.
+    Default: 0.
+
+  - pcm-lsbfirst : PCM LSB first. 0 or 1.
+    Default: 0.
+
+  - pcm-rightjustify : PCM Justify. 0-left, 1-right.
+    Default: 0.
+
+  - pcm-routing : PCM routing. 0-PCM, 1-SCO over HCI.
+    Default: 0.
+
+  - pcm-shortframesync : PCM sync. 0-short, 1-long.
+    Default: 0.
+
+  - pcm-syncmode : PCM sync mode. 0-slave, 1-master.
+    Default: 0.
+
+
+Example:
+
+	bcm4354_bt_uart: bcm4354-bt-uart {
+		compatible = "brcm,brcm-bt-uart";
+		bt-wake-gpios = <&gpio4 30 GPIO_ACTIVE_HIGH>;
+		bt-host-wake-gpios = <&gpio4 31 GPIO_ACTIVE_HIGH>;
+		tty = "ttyS0";
+		oper-speed = <3000000>;
+		configure-sleep;
+		idle-timeout = <5>;
+		configure-audio;
+		pcm-clockmode = <0>;
+		pcm-fillmethod = <2>;
+		pcm-fillnum = <0>;
+		pcm-fillvalue = <3>;
+		pcm-incallbitclock = <0>;
+		pcm-lsbfirst = <0>;
+		pcm-rightjustify = <0>;
+		pcm-routing = <0>;
+		pcm-shortframesync = <0>;
+		pcm-syncmode = <0>;
+	};
+
-- 
1.9.1

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

* [PATCH v4 2/4] hci_uart: line discipline enhancements
  2015-06-17 21:30 [PATCH v4 0/4] Broadcom Bluetooth UART device driver Ilya Faenson
  2015-06-17 21:30 ` [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings Ilya Faenson
@ 2015-06-17 21:30 ` Ilya Faenson
  2015-06-17 21:50   ` Marcel Holtmann
  2015-06-17 21:30 ` [PATCH v4 3/4] btbcm_uart: Broadcom UART Platform Driver Ilya Faenson
  2015-06-17 21:30 ` [PATCH v4 4/4] hci_bcm: Broadcom UART protocol enhancements Ilya Faenson
  3 siblings, 1 reply; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 21:30 UTC (permalink / raw)
  To: Marcel Holtmann; +Cc: linux-bluetooth, Arend van Spriel, Ilya Faenson

Added the ability to flow control the UART, improved the UART baud
rate setting, transferred the speeds into line discipline from the
protocol and introduced the tty init function.

Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
---
 drivers/bluetooth/hci_ldisc.c | 106 +++++++++++++++++++++++++++++++++++++++---
 drivers/bluetooth/hci_uart.h  |   7 +++
 2 files changed, 106 insertions(+), 7 deletions(-)

diff --git a/drivers/bluetooth/hci_ldisc.c b/drivers/bluetooth/hci_ldisc.c
index ac87346..959dd64 100644
--- a/drivers/bluetooth/hci_ldisc.c
+++ b/drivers/bluetooth/hci_ldisc.c
@@ -266,6 +266,85 @@ static int hci_uart_send_frame(struct hci_dev *hdev, struct sk_buff *skb)
 	return 0;
 }
 
+/* Flow control or un-flow control the device */
+void hci_uart_set_flow_control(struct hci_uart *hu, bool enable)
+{
+	struct tty_struct *tty = hu->tty;
+	struct ktermios ktermios;
+	int status;
+	unsigned int set = 0;
+	unsigned int clear = 0;
+
+	if (enable) {
+		/* Disable hardware flow control */
+		ktermios = tty->termios;
+		ktermios.c_cflag &= ~CRTSCTS;
+		status = tty_set_termios(tty, &ktermios);
+		BT_DBG("Disabling hardware flow control: %s", status ?
+		       "failed" : "success");
+
+		/* Clear RTS to prevent the device from sending */
+		/* Most UARTs need OUT2 to enable interrupts */
+		status = tty->driver->ops->tiocmget(tty);
+		BT_DBG("Current tiocm 0x%x", status);
+
+		set &= ~(TIOCM_OUT2 | TIOCM_RTS);
+		clear = ~set;
+		set &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
+		       TIOCM_OUT2 | TIOCM_LOOP;
+		clear &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
+			 TIOCM_OUT2 | TIOCM_LOOP;
+		status = tty->driver->ops->tiocmset(tty, set, clear);
+		BT_DBG("Clearing RTS: %s", status ? "failed" : "success");
+	} else {
+		/* Set RTS to allow the device to send again */
+		status = tty->driver->ops->tiocmget(tty);
+		BT_DBG("Current tiocm 0x%x", status);
+
+		set |= (TIOCM_OUT2 | TIOCM_RTS);
+		clear = ~set;
+		set &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
+		       TIOCM_OUT2 | TIOCM_LOOP;
+		clear &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
+			 TIOCM_OUT2 | TIOCM_LOOP;
+		status = tty->driver->ops->tiocmset(tty, set, clear);
+		BT_DBG("Setting RTS: %s", status ? "failed" : "success");
+
+		/* Re-enable hardware flow control */
+		ktermios = tty->termios;
+		ktermios.c_cflag |= CRTSCTS;
+		status = tty_set_termios(tty, &ktermios);
+		BT_DBG("Enabling hardware flow control: %s", status ?
+		       "failed" : "success");
+	}
+}
+
+void hci_uart_set_speeds(struct hci_uart *hu, unsigned int init_speed,
+			 unsigned int oper_speed)
+{
+	hu->init_speed = init_speed;
+	hu->oper_speed = oper_speed;
+}
+
+void hci_uart_init_tty(struct hci_uart *hu)
+{
+	struct tty_struct *tty = hu->tty;
+	struct ktermios ktermios;
+
+	/* Bring the UART into a known 8 bits no parity hw fc state */
+	ktermios = tty->termios;
+	ktermios.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP
+			    | INLCR | IGNCR | ICRNL | IXON);
+	ktermios.c_oflag &= ~OPOST;
+	ktermios.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
+	ktermios.c_cflag &= ~(CSIZE | PARENB);
+	ktermios.c_cflag |= CS8;
+	ktermios.c_cflag |= CRTSCTS;
+
+	/* tty_set_termios() return not checked as it is always 0 */
+	tty_set_termios(tty, &ktermios);
+}
+
 void hci_uart_set_baudrate(struct hci_uart *hu, unsigned int speed)
 {
 	struct tty_struct *tty = hu->tty;
@@ -273,13 +352,13 @@ void hci_uart_set_baudrate(struct hci_uart *hu, unsigned int speed)
 
 	ktermios = tty->termios;
 	ktermios.c_cflag &= ~CBAUD;
-	ktermios.c_cflag |= BOTHER;
 	tty_termios_encode_baud_rate(&ktermios, speed, speed);
 
 	/* tty_set_termios() return not checked as it is always 0 */
 	tty_set_termios(tty, &ktermios);
 
-	BT_DBG("%s: New tty speed: %d", hu->hdev->name, tty->termios.c_ispeed);
+	BT_DBG("%s: New tty speeds: %d/%d", hu->hdev->name,
+	       tty->termios.c_ispeed, tty->termios.c_ospeed);
 }
 
 static int hci_uart_setup(struct hci_dev *hdev)
@@ -287,15 +366,28 @@ static int hci_uart_setup(struct hci_dev *hdev)
 	struct hci_uart *hu = hci_get_drvdata(hdev);
 	struct hci_rp_read_local_version *ver;
 	struct sk_buff *skb;
+	unsigned int speed;
 	int err;
 
+	/* Init speed if any */
+	speed = 0;
 	if (hu->proto->init_speed)
-		hci_uart_set_baudrate(hu, hu->proto->init_speed);
-
-	if (hu->proto->set_baudrate && hu->proto->oper_speed) {
-		err = hu->proto->set_baudrate(hu, hu->proto->oper_speed);
+		speed = hu->proto->init_speed;
+	else if (hu->init_speed)
+		speed = hu->init_speed;
+	if (speed)
+		hci_uart_set_baudrate(hu, speed);
+
+	/* Operational speed if any */
+	speed = 0;
+	if (hu->proto->oper_speed)
+		speed = hu->proto->oper_speed;
+	else if (hu->oper_speed)
+		speed = hu->oper_speed;
+	if (hu->proto->set_baudrate && speed) {
+		err = hu->proto->set_baudrate(hu, speed);
 		if (!err)
-			hci_uart_set_baudrate(hu, hu->proto->oper_speed);
+			hci_uart_set_baudrate(hu, speed);
 	}
 
 	if (hu->proto->setup)
diff --git a/drivers/bluetooth/hci_uart.h b/drivers/bluetooth/hci_uart.h
index e9f970c..ce9c670 100644
--- a/drivers/bluetooth/hci_uart.h
+++ b/drivers/bluetooth/hci_uart.h
@@ -85,6 +85,9 @@ struct hci_uart {
 	struct sk_buff		*tx_skb;
 	unsigned long		tx_state;
 	spinlock_t		rx_lock;
+
+	unsigned int init_speed;
+	unsigned int oper_speed;
 };
 
 /* HCI_UART proto flag bits */
@@ -99,7 +102,11 @@ int hci_uart_register_proto(const struct hci_uart_proto *p);
 int hci_uart_unregister_proto(const struct hci_uart_proto *p);
 int hci_uart_tx_wakeup(struct hci_uart *hu);
 int hci_uart_init_ready(struct hci_uart *hu);
+void hci_uart_init_tty(struct hci_uart *hu);
 void hci_uart_set_baudrate(struct hci_uart *hu, unsigned int speed);
+void hci_uart_set_flow_control(struct hci_uart *hu, bool enable);
+void hci_uart_set_speeds(struct hci_uart *hu, unsigned int init_speed,
+			 unsigned int oper_speed);
 
 #ifdef CONFIG_BT_HCIUART_H4
 int h4_init(void);
-- 
1.9.1

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

* [PATCH v4 3/4] btbcm_uart: Broadcom UART Platform Driver
  2015-06-17 21:30 [PATCH v4 0/4] Broadcom Bluetooth UART device driver Ilya Faenson
  2015-06-17 21:30 ` [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings Ilya Faenson
  2015-06-17 21:30 ` [PATCH v4 2/4] hci_uart: line discipline enhancements Ilya Faenson
@ 2015-06-17 21:30 ` Ilya Faenson
  2015-06-17 21:30 ` [PATCH v4 4/4] hci_bcm: Broadcom UART protocol enhancements Ilya Faenson
  3 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 21:30 UTC (permalink / raw)
  To: Marcel Holtmann; +Cc: linux-bluetooth, Arend van Spriel, Ilya Faenson

Introduce the device tree enumerated Broadcom Bluetooth UART driver:
	Retrieves the device parameters from the node
	Manages the device's power on/off and suspend/resume GPIOs
	Processes wakeup interrupts
	Maintains the list of bluetooth UART devices
	Maps device instances to BlueZ protocol instances
	Manages the device upon platform suspend/resume actions
	Provides the interface for the BlueZ protocol actions

Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
---
 drivers/bluetooth/Makefile     |   1 +
 drivers/bluetooth/btbcm_uart.c | 538 +++++++++++++++++++++++++++++++++++++++++
 drivers/bluetooth/btbcm_uart.h |  74 ++++++
 3 files changed, 613 insertions(+)
 create mode 100644 drivers/bluetooth/btbcm_uart.c
 create mode 100644 drivers/bluetooth/btbcm_uart.h

diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
index f40e194..7947abb 100644
--- a/drivers/bluetooth/Makefile
+++ b/drivers/bluetooth/Makefile
@@ -21,6 +21,7 @@ obj-$(CONFIG_BT_MRVL)		+= btmrvl.o
 obj-$(CONFIG_BT_MRVL_SDIO)	+= btmrvl_sdio.o
 obj-$(CONFIG_BT_WILINK)		+= btwilink.o
 obj-$(CONFIG_BT_BCM)		+= btbcm.o
+obj-$(CONFIG_BT_BCM)		+= btbcm_uart.o
 obj-$(CONFIG_BT_RTL)		+= btrtl.o
 
 btmrvl-y			:= btmrvl_main.o
diff --git a/drivers/bluetooth/btbcm_uart.c b/drivers/bluetooth/btbcm_uart.c
new file mode 100644
index 0000000..e77eb1d
--- /dev/null
+++ b/drivers/bluetooth/btbcm_uart.c
@@ -0,0 +1,538 @@
+/*
+ *  Bluetooth BCM UART Driver
+ *
+ *  Copyright (c) 2015 Broadcom Corporation
+ *
+ *  This program is free software; you can redistribute it and/or modify
+ *  it under the terms of the GNU General Public License as published by
+ *  the Free Software Foundation; either version 2 of the License, or
+ *  (at your option) any later version.
+ *
+ *  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/kernel.h>
+#include <linux/init.h>
+#include <linux/types.h>
+#include <linux/fcntl.h>
+#include <linux/interrupt.h>
+#include <linux/ptrace.h>
+#include <linux/poll.h>
+
+#include <linux/slab.h>
+#include <linux/tty.h>
+#include <linux/errno.h>
+#include <linux/string.h>
+#include <linux/signal.h>
+#include <linux/ioctl.h>
+#include <linux/skbuff.h>
+#include <linux/list.h>
+
+#include <net/bluetooth/bluetooth.h>
+#include <net/bluetooth/hci_core.h>
+
+#include <linux/gpio/consumer.h>
+#include <linux/of.h>
+#include <linux/of_gpio.h>
+#include <linux/of_platform.h>
+
+#include "btbcm_uart.h"
+
+/* Device context */
+struct bcm_device {
+	struct list_head list;
+
+	struct platform_device *pdev;
+	struct gpio_desc *bt_wake_gpio;
+	struct gpio_desc *dev_wake_gpio;
+	struct gpio_desc *reg_on_gpio;
+	int bt_wake_irq;
+	int dev_wake_active_low;
+	int reg_on_active_low;
+	int bt_wake_active_low;
+	bool configure_sleep;
+	u32 idle_timeout;
+	u32 manual_fc;
+	u32 oper_speed;
+	bool configure_audio;
+	u32 pcm_clockmode;
+	u32 pcm_fillmethod;
+	u32 pcm_fillnum;
+	u32 pcm_fillvalue;
+	u32 pcm_incallbitclock;
+	u32 pcm_lsbfirst;
+	u32 pcm_rightjustify;
+	u32 pcm_routing;
+	u32 pcm_shortframesync;
+	u32 pcm_syncmode;
+
+	char tty_name[64];
+
+	struct btbcm_uart_callbacks callbacks;
+	struct work_struct wakeup_work;
+};
+
+/* List of BCM BT UART devices */
+static DEFINE_SPINLOCK(device_list_lock);
+static LIST_HEAD(device_list);
+
+/* Calling the BCM protocol at lower execution priority */
+static void bcm_wakeup_task(struct work_struct *work)
+{
+	struct bcm_device *dev = container_of(work, struct bcm_device,
+					      wakeup_work);
+	int gpio_value;
+
+	/* Make sure the device is resumed */
+	gpio_value = !dev->dev_wake_active_low;
+	if (dev->dev_wake_gpio) {
+		gpiod_set_value(dev->dev_wake_gpio, gpio_value);
+		BT_DBG("wakeup_task - resume %d written, delaying 15 ms",
+		       gpio_value);
+		mdelay(15);
+	}
+
+	/* Let the protocol know it's time to wake up */
+	if (dev->callbacks.wakeup)
+		dev->callbacks.wakeup(dev->callbacks.context);
+}
+
+/* Interrupt routine for the wake from the device */
+static irqreturn_t bcm_uart_isr(int irq, void *context)
+{
+	unsigned int bt_wake;
+	struct bcm_device *p = (struct bcm_device *)context;
+
+	bt_wake = gpiod_get_value(p->bt_wake_gpio);
+	BT_DBG("isr with bt_wake of %d (active_low %d), req bh",
+	       bt_wake, p->bt_wake_active_low);
+
+	/* Defer the actual processing to the platform work queue */
+	schedule_work(&p->wakeup_work);
+	return IRQ_HANDLED;
+}
+
+/* Device instance startup */
+static int bcm_uart_probe(struct platform_device *pdev)
+{
+	struct device_node *np = pdev->dev.of_node;
+	const char *tty_name;
+	int ret;
+	struct bcm_device *dev;
+
+	dev = devm_kzalloc(&pdev->dev, sizeof(*dev), GFP_KERNEL);
+	if (!dev)
+		return -ENOMEM;
+
+	dev->pdev = pdev;
+
+	/* Get dev wake GPIO */
+	dev->dev_wake_gpio = gpiod_get(&pdev->dev, "bt-wake");
+	if (IS_ERR(dev->dev_wake_gpio)) {
+		ret = PTR_ERR(dev->dev_wake_gpio);
+		if (ret != -ENOENT)
+			dev_err(&pdev->dev, "probe - dev_wake GPIO: %d\n", ret);
+		dev->dev_wake_gpio = NULL;
+	} else {
+		int gpio_value;
+
+		dev->dev_wake_active_low = gpiod_is_active_low
+			(dev->dev_wake_gpio);
+		BT_DBG("probe - dev_wake %p a-low is %d (cans %d)",
+		       dev->dev_wake_gpio, dev->dev_wake_active_low,
+		       gpiod_cansleep(dev->dev_wake_gpio));
+
+		/* configure dev_wake as output with init resumed state */
+		gpio_value = !dev->dev_wake_active_low;
+		ret = gpiod_direction_output(dev->dev_wake_gpio, gpio_value);
+		if (ret < 0) {
+			dev_err(&pdev->dev,
+				"probe - output dev_wake GPIO: %d\n", ret);
+			gpiod_put(dev->dev_wake_gpio);
+			dev->dev_wake_gpio = NULL;
+			goto end;
+		}
+	}
+
+	/* Get power on/off GPIO */
+	dev->reg_on_gpio = gpiod_get(&pdev->dev, "bt-reg-on");
+	if (IS_ERR(dev->reg_on_gpio)) {
+		ret = PTR_ERR(dev->reg_on_gpio);
+		if (ret != -ENOENT)
+			dev_err(&pdev->dev, "probe - reg_on GPIO: %d\n", ret);
+		dev->reg_on_gpio = NULL;
+	} else {
+		int poweron_flag;
+
+		dev->reg_on_active_low = gpiod_is_active_low(dev->reg_on_gpio);
+		BT_DBG("probe - reg_on %p a-low is %d (cansleep %d)",
+		       dev->reg_on_gpio, dev->reg_on_active_low,
+		       gpiod_cansleep(dev->reg_on_gpio));
+
+		/* configure reg_on as output with init on state */
+		poweron_flag = !dev->reg_on_active_low;
+		ret = gpiod_direction_output(dev->reg_on_gpio, poweron_flag);
+		if (ret < 0) {
+			dev_err(&pdev->dev,
+				"probe - set reg_on GPIO: %d\n", ret);
+			gpiod_put(dev->reg_on_gpio);
+			dev->reg_on_gpio = NULL;
+		}
+	}
+
+	platform_set_drvdata(pdev, dev);
+	/* Must be done before interrupt is requested */
+	INIT_WORK(&dev->wakeup_work, bcm_wakeup_task);
+
+	/* Get bt host wake GPIO */
+	dev->bt_wake_gpio = gpiod_get(&pdev->dev, "bt-host-wake");
+	if (IS_ERR(dev->bt_wake_gpio)) {
+		ret = PTR_ERR(dev->bt_wake_gpio);
+		if (ret != -ENOENT)
+			dev_err(&pdev->dev, "probe - bt_wake GPIO: %d\n", ret);
+		dev->bt_wake_gpio = NULL;
+	} else {
+		/* configure bt_wake as input */
+		ret = gpiod_direction_input(dev->bt_wake_gpio);
+		if (ret < 0) {
+			dev_err(&pdev->dev,
+				"probe - set bt_wake GPIO: %d\n", ret);
+			gpiod_put(dev->bt_wake_gpio);
+			dev->bt_wake_gpio = NULL;
+		} else {
+			dev->bt_wake_active_low = gpiod_is_active_low
+				(dev->bt_wake_gpio);
+			BT_DBG("probe - bt_wake %p a-low is %d(cansleep %d)",
+			       dev->bt_wake_gpio, dev->bt_wake_active_low,
+			       gpiod_cansleep(dev->bt_wake_gpio));
+			dev->bt_wake_irq = gpiod_to_irq(dev->bt_wake_gpio);
+			if (dev->bt_wake_irq >= 0) {
+				unsigned long intflags = IRQF_TRIGGER_RISING;
+
+				if (dev->bt_wake_active_low)
+					intflags = IRQF_TRIGGER_FALLING;
+				ret = request_irq(dev->bt_wake_irq,
+						  bcm_uart_isr, intflags,
+						  "bt_host_wake", dev);
+				if (ret < 0)
+					dev_err(&pdev->dev,
+						"probe - failed IRQ %d: %d",
+						dev->bt_wake_irq, ret);
+				else
+					BT_DBG("probe - IRQ %d",
+					       dev->bt_wake_irq);
+			}
+		}
+	}
+
+	dev->configure_sleep = of_property_read_bool(np, "configure-sleep");
+	dev->idle_timeout = 5;
+	of_property_read_u32(np, "idle-timeout", &dev->idle_timeout);
+	dev->manual_fc = 0;
+	of_property_read_u32(np, "manual-fc", &dev->manual_fc);
+	dev->oper_speed = 3000000;
+	of_property_read_u32(np, "oper-speed", &dev->oper_speed);
+	dev->configure_audio = of_property_read_bool(np, "configure-audio");
+	BT_DBG("conf-sleep %d, tout %d, manual-fc %d, speed %d, conf-audio %d",
+	       dev->configure_sleep, dev->idle_timeout, dev->manual_fc,
+	       dev->oper_speed, dev->configure_audio);
+
+	if (dev->configure_audio) {
+		/* Defaults for audio */
+		dev->pcm_clockmode = 0;
+		dev->pcm_fillmethod = 2;
+		dev->pcm_fillnum = 0;
+		dev->pcm_fillvalue = 3;
+		dev->pcm_incallbitclock = 0;
+		dev->pcm_lsbfirst = 0;
+		dev->pcm_rightjustify = 0;
+		dev->pcm_routing = 0;
+		dev->pcm_shortframesync = 0;
+		dev->pcm_syncmode = 0;
+
+		of_property_read_u32(np, "pcm-clockmode", &dev->pcm_clockmode);
+		of_property_read_u32(np, "pcm-fillmethod",
+				     &dev->pcm_fillmethod);
+		of_property_read_u32(np, "pcm-fillnum", &dev->pcm_fillnum);
+		of_property_read_u32(np, "pcm-fillvalue", &dev->pcm_fillvalue);
+		of_property_read_u32(np, "pcm-incallbitclock",
+				     &dev->pcm_incallbitclock);
+		BT_DBG("pcm-clockmode %d, method %d, num %d, value %d, bit %d",
+		       dev->pcm_clockmode, dev->pcm_fillmethod,
+		       dev->pcm_fillnum, dev->pcm_fillvalue,
+		       dev->pcm_incallbitclock);
+
+		of_property_read_u32(np, "pcm-lsbfirst", &dev->pcm_lsbfirst);
+		of_property_read_u32(np, "pcm-rightjustify",
+				     &dev->pcm_rightjustify);
+		of_property_read_u32(np, "pcm-routing", &dev->pcm_routing);
+		of_property_read_u32(np, "pcm-shortframesync",
+				     &dev->pcm_shortframesync);
+		of_property_read_u32(np, "pcm-syncmode", &dev->pcm_syncmode);
+		BT_DBG("pcm-lsb %d, right %d, routing %d, short %d, sync %d",
+		       dev->pcm_lsbfirst, dev->pcm_rightjustify,
+		       dev->pcm_routing, dev->pcm_shortframesync,
+		       dev->pcm_syncmode);
+	}
+
+	if (!of_property_read_string(np, "tty", &tty_name)) {
+		strcpy(dev->tty_name, tty_name);
+		BT_DBG("tty name read as %s", dev->tty_name);
+	}
+
+	ret = 0;  /* If we made it here, we're fine */
+
+	/* Place this instance on the device list */
+	spin_lock(&device_list_lock);
+	list_add_tail(&dev->list, &device_list);
+	spin_unlock(&device_list_lock);
+
+end:
+	if (ret) {
+		if (dev->reg_on_gpio) {
+			gpiod_put(dev->reg_on_gpio);
+			dev->reg_on_gpio = NULL;
+		}
+		if (dev->bt_wake_gpio) {
+			gpiod_put(dev->bt_wake_gpio);
+			dev->bt_wake_gpio = NULL;
+		}
+		if (dev->dev_wake_gpio) {
+			gpiod_put(dev->dev_wake_gpio);
+			dev->dev_wake_gpio = NULL;
+		}
+	}
+
+	return ret;
+}
+
+/* Device instance removal */
+static int bcm_uart_remove(struct platform_device *pdev)
+{
+	struct bcm_device *dev = platform_get_drvdata(pdev);
+
+	spin_lock(&device_list_lock);
+	list_del(&dev->list);
+	spin_unlock(&device_list_lock);
+
+	BT_DBG("remove %p - freeing interrupt %d", dev, dev->bt_wake_irq);
+	free_irq(dev->bt_wake_irq, dev);
+
+	if (dev->reg_on_gpio) {
+		BT_DBG("remove - releasing reg_on_gpio");
+		gpiod_put(dev->reg_on_gpio);
+		dev->reg_on_gpio = NULL;
+	}
+
+	if (dev->dev_wake_gpio) {
+		BT_DBG("remove - releasing dev_wake_gpio");
+		gpiod_put(dev->dev_wake_gpio);
+		dev->dev_wake_gpio = NULL;
+	}
+
+	if (dev->bt_wake_gpio) {
+		BT_DBG("remove - releasing bt_wake_gpio");
+		gpiod_put(dev->bt_wake_gpio);
+		dev->bt_wake_gpio = NULL;
+	}
+
+	BT_DBG("remove - %p done", dev);
+	return 0;
+}
+
+/* Platform resume callback */
+static int bcm_uart_resume(struct device *pdev)
+{
+	struct bcm_device *dev = platform_get_drvdata(
+		to_platform_device(pdev));
+	int gpio_value;
+
+	BT_DBG("resume %p", dev);
+
+	gpio_value = !dev->dev_wake_active_low;
+	if (dev->dev_wake_gpio) {
+		gpiod_set_value(dev->dev_wake_gpio, gpio_value);
+		BT_DBG("resume - %d written, delaying 15 ms", gpio_value);
+		mdelay(15);
+	}
+
+	/* Let the protocol know the platform is resuming */
+	if (dev->callbacks.resume)
+		dev->callbacks.resume(dev->callbacks.context);
+
+	return 0;
+}
+
+/* Platform suspend callback */
+static int bcm_uart_suspend(struct device *pdev)
+{
+	struct bcm_device *dev = platform_get_drvdata(
+		to_platform_device(pdev));
+	int gpio_value;
+
+	BT_DBG("suspend - %p", dev);
+
+	/* Let the protocol know the platform is suspending */
+	if (dev->callbacks.suspend)
+		dev->callbacks.suspend(dev->callbacks.context);
+
+	/* Suspend the device */
+	if (dev->dev_wake_gpio) {
+		gpio_value = !!dev->dev_wake_active_low;
+		gpiod_set_value(dev->dev_wake_gpio, gpio_value);
+		BT_DBG("suspend - %d written, delaying 15 ms", gpio_value);
+		mdelay(15);
+	}
+
+	return 0;
+}
+
+/* Entry point for calls from the protocol */
+void *btbcm_uart_set_callbacks(struct btbcm_uart_callbacks *pc)
+{
+	struct bcm_device *dev = NULL;
+	bool is_found = false;
+	struct list_head *ptr;
+
+	BT_DBG("set_callbacks for %s(%p)", pc->name, pc->context);
+
+	spin_lock(&device_list_lock);
+	list_for_each(ptr, &device_list) {
+		dev = list_entry(ptr, struct bcm_device, list);
+		if (!strcmp(dev->tty_name, pc->name)) {
+			is_found = true;
+			break;
+		}
+	}
+	spin_unlock(&device_list_lock);
+
+	if (!is_found) {
+		BT_DBG("set_callbacks - no device!");
+		return NULL;
+	}
+
+	dev->callbacks = *pc;
+	return dev;
+}
+EXPORT_SYMBOL_GPL(btbcm_uart_set_callbacks);
+
+void btbcm_uart_reset_callbacks(void *device_context)
+{
+	struct bcm_device *dev = device_context;
+
+	memset(&dev->callbacks, 0, sizeof(dev->callbacks));
+}
+EXPORT_SYMBOL_GPL(btbcm_uart_reset_callbacks);
+
+void btbcm_uart_poweron(void *device_context)
+{
+	struct bcm_device *dev = device_context;
+	int poweron_flag;
+
+	if (dev->reg_on_gpio) {
+		poweron_flag = !dev->reg_on_active_low;
+		gpiod_set_value(dev->reg_on_gpio, poweron_flag);
+		BT_DBG("poweron %d, delay 15 ms", poweron_flag);
+	}
+}
+EXPORT_SYMBOL_GPL(btbcm_uart_poweron);
+
+void btbcm_uart_poweroff(void *device_context)
+{
+	struct bcm_device *dev = device_context;
+	int poweron_flag;
+
+	if (dev->reg_on_gpio) {
+		poweron_flag = dev->reg_on_active_low;
+		gpiod_set_value(dev->reg_on_gpio, poweron_flag);
+		BT_DBG("poweroff %d, delay 15 ms", poweron_flag);
+	}
+}
+EXPORT_SYMBOL_GPL(btbcm_uart_poweroff);
+
+void btbcm_uart_suspend(void *device_context)
+{
+	struct bcm_device *dev = device_context;
+	int gpio_value;
+
+	if (dev->dev_wake_gpio) {
+		gpio_value = !!dev->dev_wake_active_low;
+		gpiod_set_value(dev->dev_wake_gpio, gpio_value);
+		BT_DBG("suspend %d, delay 15ms", gpio_value);
+		mdelay(15);
+	}
+}
+EXPORT_SYMBOL_GPL(btbcm_uart_suspend);
+
+void btbcm_uart_resume(void *device_context)
+{
+	struct bcm_device *dev = device_context;
+	int gpio_value;
+
+	if (dev->dev_wake_gpio) {
+		gpio_value = !dev->dev_wake_active_low;
+		gpiod_set_value(dev->dev_wake_gpio, gpio_value);
+		BT_DBG("resume %d, delay 15ms", gpio_value);
+		mdelay(15);
+	}
+}
+EXPORT_SYMBOL_GPL(btbcm_uart_resume);
+
+void btbcm_uart_get_params(void *device_context, struct btbcm_uart_params *pp)
+{
+	struct bcm_device *dev = device_context;
+
+	memset(pp, 0, sizeof(struct btbcm_uart_params));
+	pp->configure_sleep = dev->configure_sleep;
+	pp->manual_fc = dev->manual_fc;
+	pp->dev_wake_active_low = dev->dev_wake_active_low;
+	pp->bt_wake_active_low = dev->bt_wake_active_low;
+	pp->idle_timeout_in_secs = dev->idle_timeout;
+	pp->oper_speed = dev->oper_speed;
+	pp->configure_audio = dev->configure_audio;
+	pp->pcm_clockmode = dev->pcm_clockmode;
+	pp->pcm_fillmethod = dev->pcm_fillmethod;
+	pp->pcm_fillnum = dev->pcm_fillnum;
+	pp->pcm_fillvalue = dev->pcm_fillvalue;
+	pp->pcm_incallbitclock = dev->pcm_incallbitclock;
+	pp->pcm_lsbfirst = dev->pcm_lsbfirst;
+	pp->pcm_rightjustify = dev->pcm_rightjustify;
+	pp->pcm_routing = dev->pcm_routing;
+	pp->pcm_shortframesync = dev->pcm_shortframesync;
+	pp->pcm_syncmode = dev->pcm_syncmode;
+}
+EXPORT_SYMBOL_GPL(btbcm_uart_get_params);
+
+/* Platform susp and resume callbacks */
+static SIMPLE_DEV_PM_OPS(bcm_uart_pm_ops, bcm_uart_suspend, bcm_uart_resume);
+
+/* Driver match table */
+static const struct of_device_id bcm_uart_table[] = {
+	{ .compatible = "brcm,brcm-bt-uart" },
+	{}
+};
+
+/* Driver configuration */
+static struct platform_driver bcm_uart_driver = {
+	.probe = bcm_uart_probe,
+	.remove = bcm_uart_remove,
+	.driver = {
+		.name = "btbcm_uart",
+		.of_match_table = of_match_ptr(bcm_uart_table),
+		.owner = THIS_MODULE,
+		.pm = &bcm_uart_pm_ops,
+	},
+};
+
+module_platform_driver(bcm_uart_driver);
+
+MODULE_AUTHOR("Ilya Faenson <ifaenson@broadcom.com>");
+MODULE_DESCRIPTION("Broadcom Bluetooth UART Driver");
+MODULE_LICENSE("GPL");
+
diff --git a/drivers/bluetooth/btbcm_uart.h b/drivers/bluetooth/btbcm_uart.h
new file mode 100644
index 0000000..4274fd5
--- /dev/null
+++ b/drivers/bluetooth/btbcm_uart.h
@@ -0,0 +1,74 @@
+/*
+ *  Bluetooth BCM UART Driver Header
+ *
+ *  Copyright (c) 2015 Broadcom Corporation
+ *
+ *  This program is free software; you can redistribute it and/or modify
+ *  it under the terms of the GNU General Public License as published by
+ *  the Free Software Foundation; either version 2 of the License, or
+ *  (at your option) any later version.
+ *
+ *  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.
+ *
+ */
+
+/* Callbacks from the driver into the protocol */
+struct btbcm_uart_callbacks {
+	void *context;	/* protocol instance context */
+	char name[64];	/* protocol tty device, for example, ttyS0 */
+
+	/* client callbacks */
+	void (*suspend)(void *context);
+	void (*resume)(void *context);
+	void (*wakeup)(void *context);
+};
+
+/* Driver parameters retrieved from the DT or ACPI */
+struct btbcm_uart_params {
+	bool configure_sleep;
+	int manual_fc;
+	int dev_wake_active_low;
+	int bt_wake_active_low;
+	int idle_timeout_in_secs;
+	int oper_speed;
+	bool configure_audio;
+	int pcm_clockmode;
+	int pcm_fillmethod;
+	int pcm_fillnum;
+	int pcm_fillvalue;
+	int pcm_incallbitclock;
+	int pcm_lsbfirst;
+	int pcm_rightjustify;
+	int pcm_routing;
+	int pcm_shortframesync;
+	int pcm_syncmode;
+};
+
+/* Actions on the BTBCM_UART driver
+ */
+
+/* Configure protocol callbacks */
+void *btbcm_uart_set_callbacks(struct btbcm_uart_callbacks *pc);
+
+/* Reset protocol callbacks */
+void btbcm_uart_reset_callbacks(void *device_context);
+
+/* Retrieve BT device parameters */
+void btbcm_uart_get_params(void *device_context,
+			   struct btbcm_uart_params *pp);
+
+/* Resume the BT device via GPIO */
+void btbcm_uart_resume(void *device_context);
+
+/* Suspend the BT device via GPIO */
+void btbcm_uart_suspend(void *device_context);
+
+/* Power the BT device off via GPIO */
+void btbcm_uart_poweroff(void *device_context);
+
+/* Power the BT device on via GPIO */
+void btbcm_uart_poweron(void *device_context);
+
-- 
1.9.1

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

* [PATCH v4 4/4] hci_bcm: Broadcom UART protocol enhancements
  2015-06-17 21:30 [PATCH v4 0/4] Broadcom Bluetooth UART device driver Ilya Faenson
                   ` (2 preceding siblings ...)
  2015-06-17 21:30 ` [PATCH v4 3/4] btbcm_uart: Broadcom UART Platform Driver Ilya Faenson
@ 2015-06-17 21:30 ` Ilya Faenson
  3 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 21:30 UTC (permalink / raw)
  To: Marcel Holtmann; +Cc: linux-bluetooth, Arend van Spriel, Ilya Faenson

Merge Broadcom protocol with the existing implementation, providing:
	UART setup
	Idle suspend
	Suspend/resume upon platform suspend/resume
	Integration with the Broadcom platform device
	PCM configuration

Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
---
 drivers/bluetooth/hci_bcm.c | 340 ++++++++++++++++++++++++++++++++++++++++++--
 1 file changed, 332 insertions(+), 8 deletions(-)

diff --git a/drivers/bluetooth/hci_bcm.c b/drivers/bluetooth/hci_bcm.c
index aa3c9ac..bfe04df 100644
--- a/drivers/bluetooth/hci_bcm.c
+++ b/drivers/bluetooth/hci_bcm.c
@@ -3,6 +3,7 @@
  *  Bluetooth HCI UART driver for Broadcom devices
  *
  *  Copyright (C) 2015  Intel Corporation
+ *  Copyright (C) 2015  Broadcom Corporation
  *
  *
  *  This program is free software; you can redistribute it and/or modify
@@ -24,6 +25,7 @@
 #include <linux/kernel.h>
 #include <linux/errno.h>
 #include <linux/skbuff.h>
+#include <linux/tty.h>
 #include <linux/firmware.h>
 
 #include <net/bluetooth/bluetooth.h>
@@ -31,12 +33,161 @@
 
 #include "btbcm.h"
 #include "hci_uart.h"
+#include "btbcm_uart.h"
 
 struct bcm_data {
 	struct sk_buff *rx_skb;
 	struct sk_buff_head txq;
+	struct hci_uart *hu;
+
+	bool is_suspended; /* suspend/resume flag */
+
+	struct timer_list timer; /* idle timer */
+
+	struct btbcm_uart_params params; /* device parameters */
+	void *device_context; /* ACPI/DT device context */
 };
 
+/* Suspend/resume synchronization mutex */
+static DEFINE_MUTEX(power_lock);
+
+/* Useful timer restart helper */
+static void restart_idle_timer(struct hci_uart *hu)
+{
+	struct bcm_data *h4 = hu->priv;
+
+	mod_timer(&h4->timer, jiffies +
+		  msecs_to_jiffies(h4->params.idle_timeout_in_secs * 1000));
+}
+
+/* Callbacks from the BCMBT_UART device
+ */
+
+/* The platform is suspending. Stop UART activity */
+static void suspend_notification(void *context)
+{
+	struct hci_uart *hu = (struct hci_uart *)context;
+	struct bcm_data *h4 = hu->priv;
+
+	BT_DBG("suspend: is_suspended %d", h4->is_suspended);
+
+	if (!h4->params.configure_sleep)
+		return;
+
+	if (!h4->is_suspended) {
+		if (h4->params.manual_fc)
+			hci_uart_set_flow_control(hu, true);
+
+		/* Once this callback returns, driver suspends BT via GPIO */
+		h4->is_suspended = true;
+	}
+}
+
+/*
+ * The platform is resuming. Resume UART activity.
+ */
+static void resume_notification(void *context)
+{
+	struct hci_uart *hu = (struct hci_uart *)context;
+	struct bcm_data *h4 = hu->priv;
+
+	BT_DBG("resume: is_suspended %d", h4->is_suspended);
+
+	if (!h4->params.configure_sleep)
+		return;
+
+	/* When this callback executes, the device has woken up already */
+	if (h4->is_suspended) {
+		h4->is_suspended = false;
+
+		if (h4->params.manual_fc)
+			hci_uart_set_flow_control(hu, false);
+	}
+
+	/* If we're resumed, the idle timer must be running */
+	restart_idle_timer(hu);
+}
+
+/*
+ * The BT device is resuming. Resume UART activity if suspended
+ */
+static void wakeup_notification(void *context)
+{
+	struct hci_uart *hu = (struct hci_uart *)context;
+	struct bcm_data *h4 = hu->priv;
+
+	BT_DBG("wakeup: is_suspended %d", h4->is_suspended);
+
+	if (!h4->params.configure_sleep)
+		return;
+
+	if (h4->is_suspended) {
+		if (h4->params.manual_fc)
+			hci_uart_set_flow_control(hu, false);
+
+		h4->is_suspended = false;
+	}
+
+	/* If we're resumed, the idle timer must be running */
+	restart_idle_timer(hu);
+}
+
+/*
+ * Make sure we're awake
+ * (called when the resumed state is required)
+ */
+static void bcm_ensure_wakeup(struct hci_uart *hu)
+{
+	struct bcm_data *h4 = hu->priv;
+
+	if (!h4->params.configure_sleep)
+		return;
+
+	/* Suspend/resume operations are serialized */
+	mutex_lock(&power_lock);
+
+	/* Nothing to do if resumed already */
+	if (!h4->is_suspended) {
+		mutex_unlock(&power_lock);
+
+		/* Just reset the timer */
+		restart_idle_timer(hu);
+		return;
+	}
+
+	/* Wakeup the device */
+	btbcm_uart_resume(h4->device_context);
+
+	/* Unflow control the port if configured */
+	resume_notification(hu);
+
+	mutex_unlock(&power_lock);
+}
+
+/*
+ * Idle timer callback
+ */
+static void bcm_idle_timeout(unsigned long arg)
+{
+	struct hci_uart *hu = (struct hci_uart *)arg;
+	struct bcm_data *h4 = hu->priv;
+
+	BT_DBG("idle_timeout: hu %p", hu);
+
+	/* Suspend/resume operations are serialized */
+	mutex_lock(&power_lock);
+
+	if (!h4->is_suspended) {
+		/* Flow control the port if configured */
+		suspend_notification(hu);
+
+		/* Suspend the device */
+		btbcm_uart_suspend(h4->device_context);
+	}
+
+	mutex_unlock(&power_lock);
+}
+
 static int bcm_set_baudrate(struct hci_uart *hu, unsigned int speed)
 {
 	struct hci_dev *hdev = hu->hdev;
@@ -89,6 +240,8 @@ static int bcm_set_baudrate(struct hci_uart *hu, unsigned int speed)
 static int bcm_open(struct hci_uart *hu)
 {
 	struct bcm_data *bcm;
+	struct btbcm_uart_callbacks callbacks;
+	struct tty_struct *tty = hu->tty;
 
 	BT_DBG("hu %p", hu);
 
@@ -99,6 +252,48 @@ static int bcm_open(struct hci_uart *hu)
 	skb_queue_head_init(&bcm->txq);
 
 	hu->priv = bcm;
+	bcm->hu = hu;
+	bcm->is_suspended = false;
+	memset(&bcm->params, 0, sizeof(bcm->params));
+
+	/* Reset UART to a default state */
+	hci_uart_init_tty(hu);
+
+	/* Configure callbacks on the driver */
+	callbacks.context = hu;
+	strcpy(callbacks.name, tty->name);
+	callbacks.suspend = suspend_notification;
+	callbacks.resume = resume_notification;
+	callbacks.wakeup = wakeup_notification;
+	bcm->device_context = btbcm_uart_set_callbacks(&callbacks);
+	if (!bcm->device_context) {
+		/* That is likely an indication of no bcm driver present */
+		BT_DBG("Callback set failure (no driver present)");
+
+		/* Using speed defaults */
+		hci_uart_set_speeds(hu, 115200, 3000000);
+		return 0;
+	}
+
+	/* Retrieve device parameters */
+	btbcm_uart_get_params(bcm->device_context, &bcm->params);
+	BT_DBG("Context %p conf_sleep %d dev_actlow %d bt_actlow %d idle_t %d",
+	       bcm->device_context, bcm->params.configure_sleep,
+	       bcm->params.dev_wake_active_low, bcm->params.bt_wake_active_low,
+	       bcm->params.idle_timeout_in_secs);
+	hci_uart_set_speeds(hu, 115200, bcm->params.oper_speed);
+
+	/* Cycle power to make sure the device is in the known state */
+	btbcm_uart_poweroff(bcm->device_context);
+	btbcm_uart_poweron(bcm->device_context);
+
+	/* Start the idle timer */
+	if (bcm->params.configure_sleep) {
+		setup_timer(&bcm->timer, bcm_idle_timeout, (unsigned long)hu);
+		if (bcm->params.configure_sleep)
+			restart_idle_timer(hu);
+	}
+
 	return 0;
 }
 
@@ -108,6 +303,31 @@ static int bcm_close(struct hci_uart *hu)
 
 	BT_DBG("hu %p", hu);
 
+	/* If we're being closed, we must suspend */
+	if (bcm->params.configure_sleep) {
+		mutex_lock(&power_lock);
+
+		if (!bcm->is_suspended) {
+			/* Flow control the port */
+			suspend_notification(hu);
+
+			/* Suspend the device */
+			btbcm_uart_suspend(bcm->device_context);
+		}
+
+		mutex_unlock(&power_lock);
+
+		del_timer_sync(&bcm->timer);
+	}
+
+	/* Power off the device if possible */
+	if (bcm->device_context) {
+		btbcm_uart_poweroff(bcm->device_context);
+
+		/* de-configure callbacks on the driver */
+		btbcm_uart_reset_callbacks(bcm->device_context);
+	}
+
 	skb_queue_purge(&bcm->txq);
 	kfree_skb(bcm->rx_skb);
 	kfree(bcm);
@@ -129,9 +349,12 @@ static int bcm_flush(struct hci_uart *hu)
 
 static int bcm_setup(struct hci_uart *hu)
 {
-	char fw_name[64];
+	char fw_name[128];
 	const struct firmware *fw;
 	int err;
+	struct sk_buff *skb;
+	struct bcm_data *h4 = hu->priv;
+	unsigned char time_slot_number = 0;
 
 	BT_DBG("hu %p", hu);
 
@@ -153,13 +376,110 @@ static int bcm_setup(struct hci_uart *hu)
 		goto finalize;
 	}
 
-	if (hu->proto->init_speed)
-		hci_uart_set_baudrate(hu, hu->proto->init_speed);
+	if (hu->init_speed)
+		hci_uart_set_baudrate(hu, hu->init_speed);
 
-	if (hu->proto->oper_speed) {
-		err = bcm_set_baudrate(hu, hu->proto->oper_speed);
+	if (hu->oper_speed) {
+		err = bcm_set_baudrate(hu, hu->oper_speed);
 		if (!err)
-			hci_uart_set_baudrate(hu, hu->proto->oper_speed);
+			hci_uart_set_baudrate(hu, hu->oper_speed);
+	}
+
+	/* Configure SCO PCM parameters */
+	if (h4->params.configure_audio) {
+		struct bcm_set_pcm_int_params pcm_int_params;
+		struct bcm_set_pcm_format_params pcm_format_params;
+
+		/* 0=PCM routing, 1=SCO over HCI */
+		pcm_int_params.routing = h4->params.pcm_routing;
+		/* 0=128Kbps,1=256Kbps,2=512Kbps,3=1024Kbps,4=2048Kbps */
+		pcm_int_params.rate = h4->params.pcm_incallbitclock;
+		/* short frame sync 0=short, 1=long */
+		pcm_int_params.frame_sync = h4->params.pcm_shortframesync;
+		/* sync mode 0=slave, 1=master */
+		pcm_int_params.sync_mode = h4->params.pcm_syncmode;
+		/* clock mode 0=slave, 1=master */
+		pcm_int_params.clock_mode = h4->params.pcm_clockmode;
+
+		skb = __hci_cmd_sync(hu->hdev, 0xfc1c, sizeof(pcm_int_params),
+				     &pcm_int_params, HCI_INIT_TIMEOUT);
+		if (IS_ERR(skb)) {
+			err = PTR_ERR(skb);
+			BT_ERR("bcm_setup PCM INT VSC failed (%d)", err);
+			goto finalize;
+		}
+		kfree_skb(skb);
+		BT_DBG("bcm_setup PCM INT Parameters VSC succeeded");
+
+		/* LSB_First 1=TRUE, 0=FALSE */
+		pcm_format_params.lsb_first = h4->params.pcm_lsbfirst;
+		/* Fill_Value (use 0-7 for fill bits value) */
+		pcm_format_params.fill_value = h4->params.pcm_fillvalue;
+		/* Fill_Method (2=sign extended) */
+		pcm_format_params.fill_method = h4->params.pcm_fillmethod;
+		/* Fill_Num # of fill bits 0-3) */
+		pcm_format_params.fill_num = h4->params.pcm_fillnum;
+		/* Right_Justify 1=TRUE, 0=FALSE */
+		pcm_format_params.right_justify = h4->params.pcm_rightjustify;
+
+		skb = __hci_cmd_sync(hu->hdev, 0xfc1e,
+				     sizeof(pcm_format_params),
+				     &pcm_format_params, HCI_INIT_TIMEOUT);
+		if (IS_ERR(skb)) {
+			err = PTR_ERR(skb);
+			BT_ERR("bcm_setup PCM Format VSC failed (%d)",
+			       err);
+			goto finalize;
+		}
+		kfree_skb(skb);
+		BT_DBG("bcm_setup PCM Format VSC succeeded");
+
+		skb = __hci_cmd_sync(hu->hdev, 0xfc22, sizeof(time_slot_number),
+				     &time_slot_number, HCI_INIT_TIMEOUT);
+		if (IS_ERR(skb)) {
+			err = PTR_ERR(skb);
+			BT_ERR("bcm_setup SCO Time Slot VSC failed (%d)",
+			       err);
+			goto finalize;
+		}
+		kfree_skb(skb);
+		BT_DBG("bcm_setup SCO Time Slot VSC succeeded");
+	}
+
+	/* Configure device's suspend/resume operation */
+	if (h4->params.configure_sleep) {
+		struct bcm_set_sleep_mode sleep_params;
+
+		sleep_params.sleep_mode = 1; /* UART */
+		sleep_params.idle_host = 2; /* idle threshold HOST, in 300ms */
+		sleep_params.idle_dev = 2; /* idle threshold device, in 300ms */
+		/* BT_WAKE active mode - 1=active high, 0 = active low */
+		sleep_params.bt_wake_active = (unsigned char)
+					      !h4->params.bt_wake_active_low;
+		/* HOST_WAKE active mode - 1=active high, 0 = active low */
+		sleep_params.host_wake_active = (unsigned char)
+						!h4->params.dev_wake_active_low;
+		/* Allow host sleep in SCO flag */
+		sleep_params.allow_host_sleep = 1;
+		/* Combine sleep and LPM flag */
+		sleep_params.combine_modes = 1;
+		/** Allow tristate control of UART tx flag */
+		sleep_params.tristate_control = 0;
+		/* Irrelevant USB flags */
+		sleep_params.usb_auto_sleep = 0;
+		sleep_params.usb_resume_timeout = 0;
+		sleep_params.pulsed_host_wake = 0;
+		sleep_params.break_to_host = 0;
+
+		skb = __hci_cmd_sync(hu->hdev, 0xfc27, sizeof(sleep_params),
+				     &sleep_params, HCI_INIT_TIMEOUT);
+		if (IS_ERR(skb)) {
+			err = PTR_ERR(skb);
+			BT_ERR("bcm_setup Sleep VSC failed (%d)", err);
+			goto finalize;
+		}
+		kfree_skb(skb);
+		BT_DBG("bcm_setup Set Sleep Parameters VSC succeeded");
 	}
 
 finalize:
@@ -183,6 +503,9 @@ static int bcm_recv(struct hci_uart *hu, const void *data, int count)
 	if (!test_bit(HCI_UART_REGISTERED, &hu->flags))
 		return -EUNATCH;
 
+	/* Make sure we're resumed */
+	bcm_ensure_wakeup(hu);
+
 	bcm->rx_skb = h4_recv_buf(hu->hdev, bcm->rx_skb, data, count,
 				  bcm_recv_pkts, ARRAY_SIZE(bcm_recv_pkts));
 	if (IS_ERR(bcm->rx_skb)) {
@@ -201,6 +524,9 @@ static int bcm_enqueue(struct hci_uart *hu, struct sk_buff *skb)
 
 	BT_DBG("hu %p skb %p", hu, skb);
 
+	/* Make sure we're resumed */
+	bcm_ensure_wakeup(hu);
+
 	/* Prepend skb with frame type */
 	memcpy(skb_push(skb, 1), &bt_cb(skb)->pkt_type, 1);
 	skb_queue_tail(&bcm->txq, skb);
@@ -218,8 +544,6 @@ static struct sk_buff *bcm_dequeue(struct hci_uart *hu)
 static const struct hci_uart_proto bcm_proto = {
 	.id		= HCI_UART_BCM,
 	.name		= "BCM",
-	.init_speed	= 115200,
-	.oper_speed	= 4000000,
 	.open		= bcm_open,
 	.close		= bcm_close,
 	.flush		= bcm_flush,
-- 
1.9.1


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

* Re: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-17 21:30 ` [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings Ilya Faenson
@ 2015-06-17 21:33   ` Arend van Spriel
       [not found]   ` <1434576658-20730-2-git-send-email-ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
  2015-06-19 19:23   ` Fabio Estevam
  2 siblings, 0 replies; 36+ messages in thread
From: Arend van Spriel @ 2015-06-17 21:33 UTC (permalink / raw)
  To: Ilya Faenson; +Cc: Marcel Holtmann, linux-bluetooth

On 06/17/15 23:30, Ilya Faenson wrote:
> Device Tree bindings to configure the Broadcom Bluetooth UART device.

As Marcel mentioned we really want DT people to Ack this one so better 
Cc: DT mailing list.

Regards,
Arend

> Signed-off-by: Ilya Faenson<ifaenson@broadcom.com>
> ---
>   .../devicetree/bindings/net/bluetooth/btbcm.txt    | 86 ++++++++++++++++++++++
>   1 file changed, 86 insertions(+)
>   create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>
> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> new file mode 100644
> index 0000000..5dbcd57
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> @@ -0,0 +1,86 @@
> +btbcm
> +------
> +
> +Required properties:
> +
> +	- compatible : must be "brcm,brcm-bt-uart".
> +	- tty : tty device connected to this Bluetooth device.
> +
> +Optional properties:
> +
> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
> +
> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
> +
> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
> +
> +  - oper-speed : Bluetooth device operational baud rate.
> +    Default: 3000000.
> +
> +  - manual-fc : flow control UART in suspend / resume scenarios.
> +    Default: 0.
> +
> +  - configure-sleep : configure suspend / resume flag.
> +    Default: false.
> +
> +  - idle-timeout : Number of seconds of inactivity before suspending.
> +    Default: 5.
> +
> +  - configure-audio : configure platform PCM SCO flag.
> +    Default: false.
> +
> +  - pcm-clockmode : PCM clock mode. 0-slave, 1-master.
> +    Default: 0.
> +
> +  - pcm-fillmethod : PCM fill method. 0 to 3.
> +    Default: 2.
> +
> +  - pcm-fillnum : PCM number of fill bits. 0 to 3.
> +    Default: 0.
> +
> +  - pcm-fillvalue : PCM fill value. 0 to 7.
> +    Default: 3.
> +
> +  - pcm-incallbitclock : PCM interface rate. 0-128Kbps, 1-256Kbps, 2-512Kbps,
> +    3-1024Kbps, 4-2048Kbps.
> +    Default: 0.
> +
> +  - pcm-lsbfirst : PCM LSB first. 0 or 1.
> +    Default: 0.
> +
> +  - pcm-rightjustify : PCM Justify. 0-left, 1-right.
> +    Default: 0.
> +
> +  - pcm-routing : PCM routing. 0-PCM, 1-SCO over HCI.
> +    Default: 0.
> +
> +  - pcm-shortframesync : PCM sync. 0-short, 1-long.
> +    Default: 0.
> +
> +  - pcm-syncmode : PCM sync mode. 0-slave, 1-master.
> +    Default: 0.
> +
> +
> +Example:
> +
> +	bcm4354_bt_uart: bcm4354-bt-uart {
> +		compatible = "brcm,brcm-bt-uart";
> +		bt-wake-gpios =<&gpio4 30 GPIO_ACTIVE_HIGH>;
> +		bt-host-wake-gpios =<&gpio4 31 GPIO_ACTIVE_HIGH>;
> +		tty = "ttyS0";
> +		oper-speed =<3000000>;
> +		configure-sleep;
> +		idle-timeout =<5>;
> +		configure-audio;
> +		pcm-clockmode =<0>;
> +		pcm-fillmethod =<2>;
> +		pcm-fillnum =<0>;
> +		pcm-fillvalue =<3>;
> +		pcm-incallbitclock =<0>;
> +		pcm-lsbfirst =<0>;
> +		pcm-rightjustify =<0>;
> +		pcm-routing =<0>;
> +		pcm-shortframesync =<0>;
> +		pcm-syncmode =<0>;
> +	};
> +

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

* Re: [PATCH v4 2/4] hci_uart: line discipline enhancements
  2015-06-17 21:30 ` [PATCH v4 2/4] hci_uart: line discipline enhancements Ilya Faenson
@ 2015-06-17 21:50   ` Marcel Holtmann
  2015-06-17 21:53     ` Ilya Faenson
  0 siblings, 1 reply; 36+ messages in thread
From: Marcel Holtmann @ 2015-06-17 21:50 UTC (permalink / raw)
  To: Ilya Faenson; +Cc: BlueZ development, Arend van Spriel

Hi Ilya,

> Added the ability to flow control the UART, improved the UART baud
> rate setting, transferred the speeds into line discipline from the
> protocol and introduced the tty init function.
> 
> Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
> ---
> drivers/bluetooth/hci_ldisc.c | 106 +++++++++++++++++++++++++++++++++++++++---
> drivers/bluetooth/hci_uart.h  |   7 +++
> 2 files changed, 106 insertions(+), 7 deletions(-)

I applied this patch to bluetooth-next tree, but I had to amend it a little bit.

Please make sure the subject is prefixed with Bluetooth: all the time.

> diff --git a/drivers/bluetooth/hci_ldisc.c b/drivers/bluetooth/hci_ldisc.c
> index ac87346..959dd64 100644
> --- a/drivers/bluetooth/hci_ldisc.c
> +++ b/drivers/bluetooth/hci_ldisc.c
> @@ -266,6 +266,85 @@ static int hci_uart_send_frame(struct hci_dev *hdev, struct sk_buff *skb)
> 	return 0;
> }
> 
> +/* Flow control or un-flow control the device */
> +void hci_uart_set_flow_control(struct hci_uart *hu, bool enable)
> +{
> +	struct tty_struct *tty = hu->tty;
> +	struct ktermios ktermios;
> +	int status;
> +	unsigned int set = 0;
> +	unsigned int clear = 0;
> +
> +	if (enable) {
> +		/* Disable hardware flow control */
> +		ktermios = tty->termios;
> +		ktermios.c_cflag &= ~CRTSCTS;
> +		status = tty_set_termios(tty, &ktermios);
> +		BT_DBG("Disabling hardware flow control: %s", status ?
> +		       "failed" : "success");

I moved these into this

			status ? "failed" : "success"

so that the conditional statement is on the same line.

> +
> +		/* Clear RTS to prevent the device from sending */
> +		/* Most UARTs need OUT2 to enable interrupts */
> +		status = tty->driver->ops->tiocmget(tty);
> +		BT_DBG("Current tiocm 0x%x", status);
> +
> +		set &= ~(TIOCM_OUT2 | TIOCM_RTS);
> +		clear = ~set;
> +		set &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +		       TIOCM_OUT2 | TIOCM_LOOP;
> +		clear &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +			 TIOCM_OUT2 | TIOCM_LOOP;
> +		status = tty->driver->ops->tiocmset(tty, set, clear);
> +		BT_DBG("Clearing RTS: %s", status ? "failed" : "success");
> +	} else {
> +		/* Set RTS to allow the device to send again */
> +		status = tty->driver->ops->tiocmget(tty);
> +		BT_DBG("Current tiocm 0x%x", status);
> +
> +		set |= (TIOCM_OUT2 | TIOCM_RTS);
> +		clear = ~set;
> +		set &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +		       TIOCM_OUT2 | TIOCM_LOOP;
> +		clear &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +			 TIOCM_OUT2 | TIOCM_LOOP;
> +		status = tty->driver->ops->tiocmset(tty, set, clear);
> +		BT_DBG("Setting RTS: %s", status ? "failed" : "success");
> +
> +		/* Re-enable hardware flow control */
> +		ktermios = tty->termios;
> +		ktermios.c_cflag |= CRTSCTS;
> +		status = tty_set_termios(tty, &ktermios);
> +		BT_DBG("Enabling hardware flow control: %s", status ?
> +		       "failed" : "success");
> +	}
> +}
> +
> +void hci_uart_set_speeds(struct hci_uart *hu, unsigned int init_speed,
> +			 unsigned int oper_speed)
> +{
> +	hu->init_speed = init_speed;
> +	hu->oper_speed = oper_speed;
> +}
> +
> +void hci_uart_init_tty(struct hci_uart *hu)
> +{
> +	struct tty_struct *tty = hu->tty;
> +	struct ktermios ktermios;
> +
> +	/* Bring the UART into a known 8 bits no parity hw fc state */
> +	ktermios = tty->termios;
> +	ktermios.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP
> +			    | INLCR | IGNCR | ICRNL | IXON);

I fixed this up to have the | on the previous line and then INCLR line up with IGNBRK.

> +	ktermios.c_oflag &= ~OPOST;
> +	ktermios.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
> +	ktermios.c_cflag &= ~(CSIZE | PARENB);
> +	ktermios.c_cflag |= CS8;
> +	ktermios.c_cflag |= CRTSCTS;
> +
> +	/* tty_set_termios() return not checked as it is always 0 */
> +	tty_set_termios(tty, &ktermios);
> +}
> +
> void hci_uart_set_baudrate(struct hci_uart *hu, unsigned int speed)
> {
> 	struct tty_struct *tty = hu->tty;
> @@ -273,13 +352,13 @@ void hci_uart_set_baudrate(struct hci_uart *hu, unsigned int speed)
> 
> 	ktermios = tty->termios;
> 	ktermios.c_cflag &= ~CBAUD;
> -	ktermios.c_cflag |= BOTHER;
> 	tty_termios_encode_baud_rate(&ktermios, speed, speed);
> 
> 	/* tty_set_termios() return not checked as it is always 0 */
> 	tty_set_termios(tty, &ktermios);
> 
> -	BT_DBG("%s: New tty speed: %d", hu->hdev->name, tty->termios.c_ispeed);
> +	BT_DBG("%s: New tty speeds: %d/%d", hu->hdev->name,
> +	       tty->termios.c_ispeed, tty->termios.c_ospeed);
> }
> 
> static int hci_uart_setup(struct hci_dev *hdev)
> @@ -287,15 +366,28 @@ static int hci_uart_setup(struct hci_dev *hdev)
> 	struct hci_uart *hu = hci_get_drvdata(hdev);
> 	struct hci_rp_read_local_version *ver;
> 	struct sk_buff *skb;
> +	unsigned int speed;
> 	int err;
> 
> +	/* Init speed if any */
> +	speed = 0;
> 	if (hu->proto->init_speed)
> -		hci_uart_set_baudrate(hu, hu->proto->init_speed);
> -
> -	if (hu->proto->set_baudrate && hu->proto->oper_speed) {
> -		err = hu->proto->set_baudrate(hu, hu->proto->oper_speed);
> +		speed = hu->proto->init_speed;
> +	else if (hu->init_speed)
> +		speed = hu->init_speed;

I added the speed assignment as else statement

	else
		speed = 0;

> +	if (speed)
> +		hci_uart_set_baudrate(hu, speed);
> +
> +	/* Operational speed if any */
> +	speed = 0;
> +	if (hu->proto->oper_speed)
> +		speed = hu->proto->oper_speed;
> +	else if (hu->oper_speed)
> +		speed = hu->oper_speed;
> +	if (hu->proto->set_baudrate && speed) {
> +		err = hu->proto->set_baudrate(hu, speed);
> 		if (!err)
> -			hci_uart_set_baudrate(hu, hu->proto->oper_speed);
> +			hci_uart_set_baudrate(hu, speed);
> 	}
> 
> 	if (hu->proto->setup)
> diff --git a/drivers/bluetooth/hci_uart.h b/drivers/bluetooth/hci_uart.h
> index e9f970c..ce9c670 100644
> --- a/drivers/bluetooth/hci_uart.h
> +++ b/drivers/bluetooth/hci_uart.h
> @@ -85,6 +85,9 @@ struct hci_uart {
> 	struct sk_buff		*tx_skb;
> 	unsigned long		tx_state;
> 	spinlock_t		rx_lock;
> +
> +	unsigned int init_speed;
> +	unsigned int oper_speed;
> };
> 

Regards

Marcel


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

* RE: [PATCH v4 2/4] hci_uart: line discipline enhancements
  2015-06-17 21:50   ` Marcel Holtmann
@ 2015-06-17 21:53     ` Ilya Faenson
  2015-06-18  9:46       ` Frederic Danis
  0 siblings, 1 reply; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 21:53 UTC (permalink / raw)
  To: Marcel Holtmann; +Cc: BlueZ development, Arend Van Spriel

Thanks a lot, Marcel.

-----Original Message-----
From: Marcel Holtmann [mailto:marcel@holtmann.org] 
Sent: Wednesday, June 17, 2015 5:51 PM
To: Ilya Faenson
Cc: BlueZ development; Arend Van Spriel
Subject: Re: [PATCH v4 2/4] hci_uart: line discipline enhancements

Hi Ilya,

> Added the ability to flow control the UART, improved the UART baud
> rate setting, transferred the speeds into line discipline from the
> protocol and introduced the tty init function.
> 
> Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
> ---
> drivers/bluetooth/hci_ldisc.c | 106 +++++++++++++++++++++++++++++++++++++++---
> drivers/bluetooth/hci_uart.h  |   7 +++
> 2 files changed, 106 insertions(+), 7 deletions(-)

I applied this patch to bluetooth-next tree, but I had to amend it a little bit.

Please make sure the subject is prefixed with Bluetooth: all the time.

> diff --git a/drivers/bluetooth/hci_ldisc.c b/drivers/bluetooth/hci_ldisc.c
> index ac87346..959dd64 100644
> --- a/drivers/bluetooth/hci_ldisc.c
> +++ b/drivers/bluetooth/hci_ldisc.c
> @@ -266,6 +266,85 @@ static int hci_uart_send_frame(struct hci_dev *hdev, struct sk_buff *skb)
> 	return 0;
> }
> 
> +/* Flow control or un-flow control the device */
> +void hci_uart_set_flow_control(struct hci_uart *hu, bool enable)
> +{
> +	struct tty_struct *tty = hu->tty;
> +	struct ktermios ktermios;
> +	int status;
> +	unsigned int set = 0;
> +	unsigned int clear = 0;
> +
> +	if (enable) {
> +		/* Disable hardware flow control */
> +		ktermios = tty->termios;
> +		ktermios.c_cflag &= ~CRTSCTS;
> +		status = tty_set_termios(tty, &ktermios);
> +		BT_DBG("Disabling hardware flow control: %s", status ?
> +		       "failed" : "success");

I moved these into this

			status ? "failed" : "success"

so that the conditional statement is on the same line.

> +
> +		/* Clear RTS to prevent the device from sending */
> +		/* Most UARTs need OUT2 to enable interrupts */
> +		status = tty->driver->ops->tiocmget(tty);
> +		BT_DBG("Current tiocm 0x%x", status);
> +
> +		set &= ~(TIOCM_OUT2 | TIOCM_RTS);
> +		clear = ~set;
> +		set &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +		       TIOCM_OUT2 | TIOCM_LOOP;
> +		clear &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +			 TIOCM_OUT2 | TIOCM_LOOP;
> +		status = tty->driver->ops->tiocmset(tty, set, clear);
> +		BT_DBG("Clearing RTS: %s", status ? "failed" : "success");
> +	} else {
> +		/* Set RTS to allow the device to send again */
> +		status = tty->driver->ops->tiocmget(tty);
> +		BT_DBG("Current tiocm 0x%x", status);
> +
> +		set |= (TIOCM_OUT2 | TIOCM_RTS);
> +		clear = ~set;
> +		set &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +		       TIOCM_OUT2 | TIOCM_LOOP;
> +		clear &= TIOCM_DTR | TIOCM_RTS | TIOCM_OUT1 |
> +			 TIOCM_OUT2 | TIOCM_LOOP;
> +		status = tty->driver->ops->tiocmset(tty, set, clear);
> +		BT_DBG("Setting RTS: %s", status ? "failed" : "success");
> +
> +		/* Re-enable hardware flow control */
> +		ktermios = tty->termios;
> +		ktermios.c_cflag |= CRTSCTS;
> +		status = tty_set_termios(tty, &ktermios);
> +		BT_DBG("Enabling hardware flow control: %s", status ?
> +		       "failed" : "success");
> +	}
> +}
> +
> +void hci_uart_set_speeds(struct hci_uart *hu, unsigned int init_speed,
> +			 unsigned int oper_speed)
> +{
> +	hu->init_speed = init_speed;
> +	hu->oper_speed = oper_speed;
> +}
> +
> +void hci_uart_init_tty(struct hci_uart *hu)
> +{
> +	struct tty_struct *tty = hu->tty;
> +	struct ktermios ktermios;
> +
> +	/* Bring the UART into a known 8 bits no parity hw fc state */
> +	ktermios = tty->termios;
> +	ktermios.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP
> +			    | INLCR | IGNCR | ICRNL | IXON);

I fixed this up to have the | on the previous line and then INCLR line up with IGNBRK.

> +	ktermios.c_oflag &= ~OPOST;
> +	ktermios.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
> +	ktermios.c_cflag &= ~(CSIZE | PARENB);
> +	ktermios.c_cflag |= CS8;
> +	ktermios.c_cflag |= CRTSCTS;
> +
> +	/* tty_set_termios() return not checked as it is always 0 */
> +	tty_set_termios(tty, &ktermios);
> +}
> +
> void hci_uart_set_baudrate(struct hci_uart *hu, unsigned int speed)
> {
> 	struct tty_struct *tty = hu->tty;
> @@ -273,13 +352,13 @@ void hci_uart_set_baudrate(struct hci_uart *hu, unsigned int speed)
> 
> 	ktermios = tty->termios;
> 	ktermios.c_cflag &= ~CBAUD;
> -	ktermios.c_cflag |= BOTHER;
> 	tty_termios_encode_baud_rate(&ktermios, speed, speed);
> 
> 	/* tty_set_termios() return not checked as it is always 0 */
> 	tty_set_termios(tty, &ktermios);
> 
> -	BT_DBG("%s: New tty speed: %d", hu->hdev->name, tty->termios.c_ispeed);
> +	BT_DBG("%s: New tty speeds: %d/%d", hu->hdev->name,
> +	       tty->termios.c_ispeed, tty->termios.c_ospeed);
> }
> 
> static int hci_uart_setup(struct hci_dev *hdev)
> @@ -287,15 +366,28 @@ static int hci_uart_setup(struct hci_dev *hdev)
> 	struct hci_uart *hu = hci_get_drvdata(hdev);
> 	struct hci_rp_read_local_version *ver;
> 	struct sk_buff *skb;
> +	unsigned int speed;
> 	int err;
> 
> +	/* Init speed if any */
> +	speed = 0;
> 	if (hu->proto->init_speed)
> -		hci_uart_set_baudrate(hu, hu->proto->init_speed);
> -
> -	if (hu->proto->set_baudrate && hu->proto->oper_speed) {
> -		err = hu->proto->set_baudrate(hu, hu->proto->oper_speed);
> +		speed = hu->proto->init_speed;
> +	else if (hu->init_speed)
> +		speed = hu->init_speed;

I added the speed assignment as else statement

	else
		speed = 0;

> +	if (speed)
> +		hci_uart_set_baudrate(hu, speed);
> +
> +	/* Operational speed if any */
> +	speed = 0;
> +	if (hu->proto->oper_speed)
> +		speed = hu->proto->oper_speed;
> +	else if (hu->oper_speed)
> +		speed = hu->oper_speed;
> +	if (hu->proto->set_baudrate && speed) {
> +		err = hu->proto->set_baudrate(hu, speed);
> 		if (!err)
> -			hci_uart_set_baudrate(hu, hu->proto->oper_speed);
> +			hci_uart_set_baudrate(hu, speed);
> 	}
> 
> 	if (hu->proto->setup)
> diff --git a/drivers/bluetooth/hci_uart.h b/drivers/bluetooth/hci_uart.h
> index e9f970c..ce9c670 100644
> --- a/drivers/bluetooth/hci_uart.h
> +++ b/drivers/bluetooth/hci_uart.h
> @@ -85,6 +85,9 @@ struct hci_uart {
> 	struct sk_buff		*tx_skb;
> 	unsigned long		tx_state;
> 	spinlock_t		rx_lock;
> +
> +	unsigned int init_speed;
> +	unsigned int oper_speed;
> };
> 

Regards

Marcel


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

* FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-17 21:30 ` [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings Ilya Faenson
@ 2015-06-17 23:11       ` Ilya Faenson
       [not found]   ` <1434576658-20730-2-git-send-email-ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
  2015-06-19 19:23   ` Fabio Estevam
  2 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 23:11 UTC (permalink / raw)
  To: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org, Arend Van Spriel,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	devicetree-spec-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
  Cc: linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

+ devicetree lists

-----Original Message-----
From: Ilya Faenson [mailto:ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org] 
Sent: Wednesday, June 17, 2015 5:31 PM
To: Marcel Holtmann
Cc: linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org; Arend Van Spriel; Ilya Faenson
Subject: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings

Device Tree bindings to configure the Broadcom Bluetooth UART device.

Signed-off-by: Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
---
 .../devicetree/bindings/net/bluetooth/btbcm.txt    | 86 ++++++++++++++++++++++
 1 file changed, 86 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.txt

diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
new file mode 100644
index 0000000..5dbcd57
--- /dev/null
+++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
@@ -0,0 +1,86 @@
+btbcm
+------
+
+Required properties:
+
+	- compatible : must be "brcm,brcm-bt-uart".
+	- tty : tty device connected to this Bluetooth device.
+
+Optional properties:
+
+  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
+
+  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
+
+  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
+
+  - oper-speed : Bluetooth device operational baud rate.
+    Default: 3000000.
+
+  - manual-fc : flow control UART in suspend / resume scenarios.
+    Default: 0.
+
+  - configure-sleep : configure suspend / resume flag.
+    Default: false.
+
+  - idle-timeout : Number of seconds of inactivity before suspending.
+    Default: 5.
+
+  - configure-audio : configure platform PCM SCO flag.
+    Default: false.
+
+  - pcm-clockmode : PCM clock mode. 0-slave, 1-master.
+    Default: 0.
+
+  - pcm-fillmethod : PCM fill method. 0 to 3.
+    Default: 2.
+
+  - pcm-fillnum : PCM number of fill bits. 0 to 3.
+    Default: 0.
+
+  - pcm-fillvalue : PCM fill value. 0 to 7.
+    Default: 3.
+
+  - pcm-incallbitclock : PCM interface rate. 0-128Kbps, 1-256Kbps, 2-512Kbps,
+    3-1024Kbps, 4-2048Kbps.
+    Default: 0.
+
+  - pcm-lsbfirst : PCM LSB first. 0 or 1.
+    Default: 0.
+
+  - pcm-rightjustify : PCM Justify. 0-left, 1-right.
+    Default: 0.
+
+  - pcm-routing : PCM routing. 0-PCM, 1-SCO over HCI.
+    Default: 0.
+
+  - pcm-shortframesync : PCM sync. 0-short, 1-long.
+    Default: 0.
+
+  - pcm-syncmode : PCM sync mode. 0-slave, 1-master.
+    Default: 0.
+
+
+Example:
+
+	bcm4354_bt_uart: bcm4354-bt-uart {
+		compatible = "brcm,brcm-bt-uart";
+		bt-wake-gpios = <&gpio4 30 GPIO_ACTIVE_HIGH>;
+		bt-host-wake-gpios = <&gpio4 31 GPIO_ACTIVE_HIGH>;
+		tty = "ttyS0";
+		oper-speed = <3000000>;
+		configure-sleep;
+		idle-timeout = <5>;
+		configure-audio;
+		pcm-clockmode = <0>;
+		pcm-fillmethod = <2>;
+		pcm-fillnum = <0>;
+		pcm-fillvalue = <3>;
+		pcm-incallbitclock = <0>;
+		pcm-lsbfirst = <0>;
+		pcm-rightjustify = <0>;
+		pcm-routing = <0>;
+		pcm-shortframesync = <0>;
+		pcm-syncmode = <0>;
+	};
+
-- 
1.9.1

--
To unsubscribe from this list: send the line "unsubscribe devicetree" in
the body of a message to majordomo-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
More majordomo info at  http://vger.kernel.org/majordomo-info.html

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

* FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-17 23:11       ` Ilya Faenson
  0 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-17 23:11 UTC (permalink / raw)
  To: marcel@holtmann.org, Arend Van Spriel, devicetree@vger.kernel.org,
	devicetree-spec@vger.kernel.org
  Cc: linux-bluetooth@vger.kernel.org

+ devicetree lists

-----Original Message-----
From: Ilya Faenson [mailto:ifaenson@broadcom.com]=20
Sent: Wednesday, June 17, 2015 5:31 PM
To: Marcel Holtmann
Cc: linux-bluetooth@vger.kernel.org; Arend Van Spriel; Ilya Faenson
Subject: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings

Device Tree bindings to configure the Broadcom Bluetooth UART device.

Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
---
 .../devicetree/bindings/net/bluetooth/btbcm.txt    | 86 ++++++++++++++++++=
++++
 1 file changed, 86 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.t=
xt

diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Do=
cumentation/devicetree/bindings/net/bluetooth/btbcm.txt
new file mode 100644
index 0000000..5dbcd57
--- /dev/null
+++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
@@ -0,0 +1,86 @@
+btbcm
+------
+
+Required properties:
+
+	- compatible : must be "brcm,brcm-bt-uart".
+	- tty : tty device connected to this Bluetooth device.
+
+Optional properties:
+
+  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrup=
t.
+
+  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume dev=
ice.
+
+  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off=
.
+
+  - oper-speed : Bluetooth device operational baud rate.
+    Default: 3000000.
+
+  - manual-fc : flow control UART in suspend / resume scenarios.
+    Default: 0.
+
+  - configure-sleep : configure suspend / resume flag.
+    Default: false.
+
+  - idle-timeout : Number of seconds of inactivity before suspending.
+    Default: 5.
+
+  - configure-audio : configure platform PCM SCO flag.
+    Default: false.
+
+  - pcm-clockmode : PCM clock mode. 0-slave, 1-master.
+    Default: 0.
+
+  - pcm-fillmethod : PCM fill method. 0 to 3.
+    Default: 2.
+
+  - pcm-fillnum : PCM number of fill bits. 0 to 3.
+    Default: 0.
+
+  - pcm-fillvalue : PCM fill value. 0 to 7.
+    Default: 3.
+
+  - pcm-incallbitclock : PCM interface rate. 0-128Kbps, 1-256Kbps, 2-512Kb=
ps,
+    3-1024Kbps, 4-2048Kbps.
+    Default: 0.
+
+  - pcm-lsbfirst : PCM LSB first. 0 or 1.
+    Default: 0.
+
+  - pcm-rightjustify : PCM Justify. 0-left, 1-right.
+    Default: 0.
+
+  - pcm-routing : PCM routing. 0-PCM, 1-SCO over HCI.
+    Default: 0.
+
+  - pcm-shortframesync : PCM sync. 0-short, 1-long.
+    Default: 0.
+
+  - pcm-syncmode : PCM sync mode. 0-slave, 1-master.
+    Default: 0.
+
+
+Example:
+
+	bcm4354_bt_uart: bcm4354-bt-uart {
+		compatible =3D "brcm,brcm-bt-uart";
+		bt-wake-gpios =3D <&gpio4 30 GPIO_ACTIVE_HIGH>;
+		bt-host-wake-gpios =3D <&gpio4 31 GPIO_ACTIVE_HIGH>;
+		tty =3D "ttyS0";
+		oper-speed =3D <3000000>;
+		configure-sleep;
+		idle-timeout =3D <5>;
+		configure-audio;
+		pcm-clockmode =3D <0>;
+		pcm-fillmethod =3D <2>;
+		pcm-fillnum =3D <0>;
+		pcm-fillvalue =3D <3>;
+		pcm-incallbitclock =3D <0>;
+		pcm-lsbfirst =3D <0>;
+		pcm-rightjustify =3D <0>;
+		pcm-routing =3D <0>;
+		pcm-shortframesync =3D <0>;
+		pcm-syncmode =3D <0>;
+	};
+
--=20
1.9.1

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

* Re: [PATCH v4 2/4] hci_uart: line discipline enhancements
  2015-06-17 21:53     ` Ilya Faenson
@ 2015-06-18  9:46       ` Frederic Danis
  2015-06-18 10:17         ` Marcel Holtmann
  0 siblings, 1 reply; 36+ messages in thread
From: Frederic Danis @ 2015-06-18  9:46 UTC (permalink / raw)
  To: Ilya Faenson, Marcel Holtmann; +Cc: BlueZ development, Arend Van Spriel

Hello Marcel and Ilya,

On 17/06/2015 23:53, Ilya Faenson wrote:
> Thanks a lot, Marcel.
>
> -----Original Message-----
> From: Marcel Holtmann [mailto:marcel@holtmann.org]
> Sent: Wednesday, June 17, 2015 5:51 PM
> To: Ilya Faenson
> Cc: BlueZ development; Arend Van Spriel
> Subject: Re: [PATCH v4 2/4] hci_uart: line discipline enhancements
>
> Hi Ilya,

<snip>
>> @@ -287,15 +366,28 @@ static int hci_uart_setup(struct hci_dev *hdev)
>> 	struct hci_uart *hu = hci_get_drvdata(hdev);
>> 	struct hci_rp_read_local_version *ver;
>> 	struct sk_buff *skb;
>> +	unsigned int speed;
>> 	int err;
>>
>> +	/* Init speed if any */
>> +	speed = 0;
>> 	if (hu->proto->init_speed)
>> -		hci_uart_set_baudrate(hu, hu->proto->init_speed);
>> -
>> -	if (hu->proto->set_baudrate && hu->proto->oper_speed) {
>> -		err = hu->proto->set_baudrate(hu, hu->proto->oper_speed);
>> +		speed = hu->proto->init_speed;
>> +	else if (hu->init_speed)
>> +		speed = hu->init_speed;
>
> I added the speed assignment as else statement
>
> 	else
> 		speed = 0;

Afaiu, with this change hu->proto->*speed will always be used for all 
bcm device.
I think hu->*speed should be used if exist or hu->proto->*speed, so the 
test should be swapped.

The equivalent change is needed in bcm_setup() of hci_bcm.c.

Ilya, do you want to do it or should I send a patch ?

Regards

Fred

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

* Re: [PATCH v4 2/4] hci_uart: line discipline enhancements
  2015-06-18  9:46       ` Frederic Danis
@ 2015-06-18 10:17         ` Marcel Holtmann
  0 siblings, 0 replies; 36+ messages in thread
From: Marcel Holtmann @ 2015-06-18 10:17 UTC (permalink / raw)
  To: Frederic Danis; +Cc: Ilya Faenson, BlueZ development, Arend Van Spriel

Hi Fred,

> <snip>
>>> @@ -287,15 +366,28 @@ static int hci_uart_setup(struct hci_dev *hdev)
>>> 	struct hci_uart *hu = hci_get_drvdata(hdev);
>>> 	struct hci_rp_read_local_version *ver;
>>> 	struct sk_buff *skb;
>>> +	unsigned int speed;
>>> 	int err;
>>> 
>>> +	/* Init speed if any */
>>> +	speed = 0;
>>> 	if (hu->proto->init_speed)
>>> -		hci_uart_set_baudrate(hu, hu->proto->init_speed);
>>> -
>>> -	if (hu->proto->set_baudrate && hu->proto->oper_speed) {
>>> -		err = hu->proto->set_baudrate(hu, hu->proto->oper_speed);
>>> +		speed = hu->proto->init_speed;
>>> +	else if (hu->init_speed)
>>> +		speed = hu->init_speed;
>> 
>> I added the speed assignment as else statement
>> 
>> 	else
>> 		speed = 0;
> 
> Afaiu, with this change hu->proto->*speed will always be used for all bcm device.
> I think hu->*speed should be used if exist or hu->proto->*speed, so the test should be swapped.
> 
> The equivalent change is needed in bcm_setup() of hci_bcm.c.
> 
> Ilya, do you want to do it or should I send a patch ?

if I screwed this up, then please send a patch right away.

Regards

Marcel


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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-17 23:11       ` Ilya Faenson
@ 2015-06-18 15:02           ` Rob Herring
  -1 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-18 15:02 UTC (permalink / raw)
  To: Ilya Faenson
  Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org, Arend Van Spriel,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
> + devicetree lists

Please use get_maintainers.pl.

> -----Original Message-----
> From: Ilya Faenson [mailto:ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org]
> Sent: Wednesday, June 17, 2015 5:31 PM
> To: Marcel Holtmann
> Cc: linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org; Arend Van Spriel; Ilya Faenson
> Subject: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>
> Device Tree bindings to configure the Broadcom Bluetooth UART device.
>
> Signed-off-by: Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
> ---

Change history from the last v4 version?

>  .../devicetree/bindings/net/bluetooth/btbcm.txt    | 86 ++++++++++++++++++++++
>  1 file changed, 86 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>
> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> new file mode 100644
> index 0000000..5dbcd57
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> @@ -0,0 +1,86 @@
> +btbcm
> +------
> +
> +Required properties:
> +
> +       - compatible : must be "brcm,brcm-bt-uart".

You need to describe the chip, not the interface.

> +       - tty : tty device connected to this Bluetooth device.

"tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
is no guarantee which uart is assigned ttyS0.

This should be a phandle to the connected uart if not a sub node of
the uart. This is complicated since these chips have multiple host
connections. It needs to go under either uart or SDIO host and have a
reference back to the one it is not under. Given the SDIO interface is
discoverable (although sideband gpios and regulators are not), I would
put this under the uart node as that is never discoverable.

As I've mentioned previously, there's several cases of bindings for
UART slave devices being posted. This all needs to be coordinated to
use a common structure.

> +
> +Optional properties:
> +
> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
> +
> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
> +
> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
> +
> +  - oper-speed : Bluetooth device operational baud rate.
> +    Default: 3000000.
> +
> +  - manual-fc : flow control UART in suspend / resume scenarios.
> +    Default: 0.

Can be boolean?

I don't really follow the description.

> +
> +  - configure-sleep : configure suspend / resume flag.
> +    Default: false.

Please describe better what this does. Perhaps "idle-sleep-en" would be better.

> +
> +  - idle-timeout : Number of seconds of inactivity before suspending.

idle-timeout-sec

Is this only applicable when configure-sleep is set?

You mix the terms sleep and suspend a lot. Can you be more consistent.

> +    Default: 5.
> +
> +  - configure-audio : configure platform PCM SCO flag.
> +    Default: false.

So ignore the rest of the settings if not set? Perhaps combine with pcm-routing:

<blank> - no audio
audio-mode = "pcm";
audio-mode = "hci"; (or "sco-hci"?)

> +
> +  - pcm-clockmode : PCM clock mode. 0-slave, 1-master.
> +    Default: 0.

Can be boolean (property present or not): pcm-clock-mode-master

> +
> +  - pcm-fillmethod : PCM fill method. 0 to 3.

pcm-fill-method

> +    Default: 2.
> +
> +  - pcm-fillnum : PCM number of fill bits. 0 to 3.
> +    Default: 0.

pcm-fill-bits

> +
> +  - pcm-fillvalue : PCM fill value. 0 to 7.
> +    Default: 3.

pcm-fill-value

> +
> +  - pcm-incallbitclock : PCM interface rate. 0-128Kbps, 1-256Kbps, 2-512Kbps,
> +    3-1024Kbps, 4-2048Kbps.

pcm-incall-bitclock-hz

Use the actual rate rather than an enumeration. It is a simple div by
128k and log2 to convert in the driver. This makes the property more
compatible with other chips.

What does incall mean? What is the bit rate when not in a call?

> +    Default: 0.
> +
> +  - pcm-lsbfirst : PCM LSB first. 0 or 1.
> +    Default: 0.

Can be boolean

> +
> +  - pcm-rightjustify : PCM Justify. 0-left, 1-right.
> +    Default: 0.

Can be boolean

> +  - pcm-routing : PCM routing. 0-PCM, 1-SCO over HCI.
> +    Default: 0.

Can be boolean: pcm-routing-hci

> +
> +  - pcm-shortframesync : PCM sync. 0-short, 1-long.
> +    Default: 0.

Can be boolean

> +
> +  - pcm-syncmode : PCM sync mode. 0-slave, 1-master.
> +    Default: 0.

Can be boolean: pcm-sync-mode-master

Rob

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-18 15:02           ` Rob Herring
  0 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-18 15:02 UTC (permalink / raw)
  To: Ilya Faenson
  Cc: marcel@holtmann.org, Arend Van Spriel, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:
> + devicetree lists

Please use get_maintainers.pl.

> -----Original Message-----
> From: Ilya Faenson [mailto:ifaenson@broadcom.com]
> Sent: Wednesday, June 17, 2015 5:31 PM
> To: Marcel Holtmann
> Cc: linux-bluetooth@vger.kernel.org; Arend Van Spriel; Ilya Faenson
> Subject: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>
> Device Tree bindings to configure the Broadcom Bluetooth UART device.
>
> Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
> ---

Change history from the last v4 version?

>  .../devicetree/bindings/net/bluetooth/btbcm.txt    | 86 ++++++++++++++++++++++
>  1 file changed, 86 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>
> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> new file mode 100644
> index 0000000..5dbcd57
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> @@ -0,0 +1,86 @@
> +btbcm
> +------
> +
> +Required properties:
> +
> +       - compatible : must be "brcm,brcm-bt-uart".

You need to describe the chip, not the interface.

> +       - tty : tty device connected to this Bluetooth device.

"tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
is no guarantee which uart is assigned ttyS0.

This should be a phandle to the connected uart if not a sub node of
the uart. This is complicated since these chips have multiple host
connections. It needs to go under either uart or SDIO host and have a
reference back to the one it is not under. Given the SDIO interface is
discoverable (although sideband gpios and regulators are not), I would
put this under the uart node as that is never discoverable.

As I've mentioned previously, there's several cases of bindings for
UART slave devices being posted. This all needs to be coordinated to
use a common structure.

> +
> +Optional properties:
> +
> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
> +
> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
> +
> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
> +
> +  - oper-speed : Bluetooth device operational baud rate.
> +    Default: 3000000.
> +
> +  - manual-fc : flow control UART in suspend / resume scenarios.
> +    Default: 0.

Can be boolean?

I don't really follow the description.

> +
> +  - configure-sleep : configure suspend / resume flag.
> +    Default: false.

Please describe better what this does. Perhaps "idle-sleep-en" would be better.

> +
> +  - idle-timeout : Number of seconds of inactivity before suspending.

idle-timeout-sec

Is this only applicable when configure-sleep is set?

You mix the terms sleep and suspend a lot. Can you be more consistent.

> +    Default: 5.
> +
> +  - configure-audio : configure platform PCM SCO flag.
> +    Default: false.

So ignore the rest of the settings if not set? Perhaps combine with pcm-routing:

<blank> - no audio
audio-mode = "pcm";
audio-mode = "hci"; (or "sco-hci"?)

> +
> +  - pcm-clockmode : PCM clock mode. 0-slave, 1-master.
> +    Default: 0.

Can be boolean (property present or not): pcm-clock-mode-master

> +
> +  - pcm-fillmethod : PCM fill method. 0 to 3.

pcm-fill-method

> +    Default: 2.
> +
> +  - pcm-fillnum : PCM number of fill bits. 0 to 3.
> +    Default: 0.

pcm-fill-bits

> +
> +  - pcm-fillvalue : PCM fill value. 0 to 7.
> +    Default: 3.

pcm-fill-value

> +
> +  - pcm-incallbitclock : PCM interface rate. 0-128Kbps, 1-256Kbps, 2-512Kbps,
> +    3-1024Kbps, 4-2048Kbps.

pcm-incall-bitclock-hz

Use the actual rate rather than an enumeration. It is a simple div by
128k and log2 to convert in the driver. This makes the property more
compatible with other chips.

What does incall mean? What is the bit rate when not in a call?

> +    Default: 0.
> +
> +  - pcm-lsbfirst : PCM LSB first. 0 or 1.
> +    Default: 0.

Can be boolean

> +
> +  - pcm-rightjustify : PCM Justify. 0-left, 1-right.
> +    Default: 0.

Can be boolean

> +  - pcm-routing : PCM routing. 0-PCM, 1-SCO over HCI.
> +    Default: 0.

Can be boolean: pcm-routing-hci

> +
> +  - pcm-shortframesync : PCM sync. 0-short, 1-long.
> +    Default: 0.

Can be boolean

> +
> +  - pcm-syncmode : PCM sync mode. 0-slave, 1-master.
> +    Default: 0.

Can be boolean: pcm-sync-mode-master

Rob

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

* RE: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-18 15:02           ` Rob Herring
@ 2015-06-18 18:54               ` Ilya Faenson
  -1 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-18 18:54 UTC (permalink / raw)
  To: Rob Herring
  Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org, Arend Van Spriel,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

Hi Rob,

-----Original Message-----
From: Rob Herring [mailto:robherring2@gmail.com] 
Sent: Thursday, June 18, 2015 11:03 AM
To: Ilya Faenson
Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings

On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:
> + devicetree lists

Please use get_maintainers.pl.

IF: Will try, thanks.

> -----Original Message-----
> From: Ilya Faenson [mailto:ifaenson@broadcom.com]
> Sent: Wednesday, June 17, 2015 5:31 PM
> To: Marcel Holtmann
> Cc: linux-bluetooth@vger.kernel.org; Arend Van Spriel; Ilya Faenson
> Subject: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>
> Device Tree bindings to configure the Broadcom Bluetooth UART device.
>
> Signed-off-by: Ilya Faenson <ifaenson@broadcom.com>
> ---

Change history from the last v4 version?

IF: The history was basically relevant for the bluetooth specific code changes only. Some of them have been applied by now so the rest of the code is a lot more device tree oriented. I will send the next set of patches to both device tree and bluetooth lists with a complete revision history.

>  .../devicetree/bindings/net/bluetooth/btbcm.txt    | 86 ++++++++++++++++++++++
>  1 file changed, 86 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>
> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> new file mode 100644
> index 0000000..5dbcd57
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
> @@ -0,0 +1,86 @@
> +btbcm
> +------
> +
> +Required properties:
> +
> +       - compatible : must be "brcm,brcm-bt-uart".

You need to describe the chip, not the interface.

IF: This driver is for all Broadcom Bluetooth UART based chips.

> +       - tty : tty device connected to this Bluetooth device.

"tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
is no guarantee which uart is assigned ttyS0.

This should be a phandle to the connected uart if not a sub node of
the uart. This is complicated since these chips have multiple host
connections. It needs to go under either uart or SDIO host and have a
reference back to the one it is not under. Given the SDIO interface is
discoverable (although sideband gpios and regulators are not), I would
put this under the uart node as that is never discoverable.

As I've mentioned previously, there's several cases of bindings for
UART slave devices being posted. This all needs to be coordinated to
use a common structure.

IF: This driver does not really access the UART. If just needs to have a string of some sort to map instances of the BlueZ protocol into platform devices to employ the right GPIOs and interrupts. I could use anything you recommend available through the tty_struct coming to the protocol from the BlueZ line discipline. Moreover, every end user platform I've ever dealt with in 16 years of working with Bluetooth had a single BT UART device. So these are really rare (typically test platforms) cases only. The mapping is not needed for most platforms at all. I suspect the right thing to do would be to make this parameter optional. The mapping would be done only if the parameter is present. I will use anything tty_struct derived you specify. Makes sense?

> +
> +Optional properties:
> +
> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
> +
> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
> +
> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
> +
> +  - oper-speed : Bluetooth device operational baud rate.
> +    Default: 3000000.
> +
> +  - manual-fc : flow control UART in suspend / resume scenarios.
> +    Default: 0.

Can be boolean?

I don't really follow the description.

IF: Okay, I will make it boolean. To clarify the description, it controls whether the BlueZ protocol needs to flow control the UART when the BT device is suspended and un-flow control it when the device is resumed.

> +
> +  - configure-sleep : configure suspend / resume flag.
> +    Default: false.

Please describe better what this does. Perhaps "idle-sleep-en" would be better.

IF: Okay, I will rename it as you specify and will describe it better.

> +
> +  - idle-timeout : Number of seconds of inactivity before suspending.

idle-timeout-sec

IF: Okay, I will rename it.

Is this only applicable when configure-sleep is set?

IF: Yes.

You mix the terms sleep and suspend a lot. Can you be more consistent.

IF: Broadcom BT device folks use "sleep" while Linux employs "suspend". Okay, I will try using suspend everywhere.

> +    Default: 5.
> +
> +  - configure-audio : configure platform PCM SCO flag.
> +    Default: false.

So ignore the rest of the settings if not set? Perhaps combine with pcm-routing:

<blank> - no audio
audio-mode = "pcm";
audio-mode = "hci"; (or "sco-hci"?)

IF: That's right: the rest of the parameters are not needed if configure-audio is false. Talking about your suggestions, this driver does nothing if the audio is either sent inbound or not used at all. Would you agree to something like the configure-pcm-audio flag?

> +
> +  - pcm-clockmode : PCM clock mode. 0-slave, 1-master.
> +    Default: 0.

Can be boolean (property present or not): pcm-clock-mode-master

IF: Okay.

> +
> +  - pcm-fillmethod : PCM fill method. 0 to 3.

pcm-fill-method

IF: Okay, will change.

> +    Default: 2.
> +
> +  - pcm-fillnum : PCM number of fill bits. 0 to 3.
> +    Default: 0.

pcm-fill-bits

IF: Okay, will change.

> +
> +  - pcm-fillvalue : PCM fill value. 0 to 7.
> +    Default: 3.

pcm-fill-value

IF: Okay, will change.

> +
> +  - pcm-incallbitclock : PCM interface rate. 0-128Kbps, 1-256Kbps, 2-512Kbps,
> +    3-1024Kbps, 4-2048Kbps.

pcm-incall-bitclock-hz

IF: Okay, will change.

Use the actual rate rather than an enumeration. It is a simple div by
128k and log2 to convert in the driver. This makes the property more
compatible with other chips.

IF: These rates are subject to change in future chips with no guarantees of the pattern holding. I would prefer to use the actual value expected by the firmware if you don't mind to avoid maintaining the extra driver code.

What does incall mean? What is the bit rate when not in a call?

IF: That's the name given to me by the hardware guys. What do you think about the "pcm-interface-rate" instead?

> +    Default: 0.
> +
> +  - pcm-lsbfirst : PCM LSB first. 0 or 1.
> +    Default: 0.

Can be boolean

IF: Okay.

> +
> +  - pcm-rightjustify : PCM Justify. 0-left, 1-right.
> +    Default: 0.

Can be boolean

IF: Okay.

> +  - pcm-routing : PCM routing. 0-PCM, 1-SCO over HCI.
> +    Default: 0.

Can be boolean: pcm-routing-hci

IF: Okay.

> +
> +  - pcm-shortframesync : PCM sync. 0-short, 1-long.
> +    Default: 0.

Can be boolean

IF: Okay.

> +
> +  - pcm-syncmode : PCM sync mode. 0-slave, 1-master.
> +    Default: 0.

Can be boolean: pcm-sync-mode-master

IF: Okay.

Rob

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

* RE: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-18 18:54               ` Ilya Faenson
  0 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-18 18:54 UTC (permalink / raw)
  To: Rob Herring
  Cc: marcel@holtmann.org, Arend Van Spriel, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org
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^ permalink raw reply	[flat|nested] 36+ messages in thread

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-18 18:54               ` Ilya Faenson
@ 2015-06-18 19:41                   ` Rob Herring
  -1 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-18 19:41 UTC (permalink / raw)
  To: Ilya Faenson
  Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org, Arend Van Spriel,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
> Hi Rob,

Your emails are base64 encoded. They should be plain text for the list.

> -----Original Message-----
> From: Rob Herring [mailto:robherring2-Re5JQEeQqe8AvxtiuMwx3w@public.gmane.org]
> Sent: Thursday, June 18, 2015 11:03 AM
> To: Ilya Faenson
> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org; linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>
> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
>> + devicetree lists

[...]

>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>> new file mode 100644
>> index 0000000..5dbcd57
>> --- /dev/null
>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>> @@ -0,0 +1,86 @@
>> +btbcm
>> +------
>> +
>> +Required properties:
>> +
>> +       - compatible : must be "brcm,brcm-bt-uart".
>
> You need to describe the chip, not the interface.
>
> IF: This driver is for all Broadcom Bluetooth UART based chips.

BT only chips? Most/many Broadcom chips are combo chips. I understand
the driver for BT is *mostly* separate from other chip functions like
WiFi, GPS and NFC, but the h/w is a single chip. I say most because
likely there are some parts shared: a voltage rail, reset line, or
power down line. I think some can do BT over the SDIO interface too,
so the interface may be shared. The DT is a description of the h/w
(i.e. what part # for a chip) and not a driver data structure. You
need to describe the whole chip in the binding. It is a Linux problem
if there needs to be multiple separate drivers.

>
>> +       - tty : tty device connected to this Bluetooth device.
>
> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
> is no guarantee which uart is assigned ttyS0.
>
> This should be a phandle to the connected uart if not a sub node of
> the uart. This is complicated since these chips have multiple host
> connections. It needs to go under either uart or SDIO host and have a
> reference back to the one it is not under. Given the SDIO interface is
> discoverable (although sideband gpios and regulators are not), I would
> put this under the uart node as that is never discoverable.
>
> As I've mentioned previously, there's several cases of bindings for
> UART slave devices being posted. This all needs to be coordinated to
> use a common structure.
>
> IF: This driver does not really access the UART. If just needs to have a string of some sort to map instances of the BlueZ protocol into platform devices to employ the right GPIOs and interrupts. I could use anything you recommend available through the tty_struct coming to the protocol from the BlueZ line discipline. Moreover, every end user platform I've ever dealt with in 16 years of working with Bluetooth had a single BT UART device. So these are really rare (typically test platforms) cases only. The mapping is not needed for most platforms at all. I suspect the right thing to do would be to make this parameter optional. The mapping would be done only if the parameter is present. I will use anything tty_struct derived you specify. Makes sense?


You've missed my point. I'm not talking about connecting multiple
devices to a UART at once. There are several instances of people
trying to add UART connected devices into DT[1][2]. My point is these
devices all need to have the DT binding done in a common way across
different platforms. Otherwise, we can not have common code to parse
the DT and find devices attached to a UART.


>
>> +
>> +Optional properties:
>> +
>> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
>> +
>> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
>> +
>> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
>> +
>> +  - oper-speed : Bluetooth device operational baud rate.
>> +    Default: 3000000.
>> +
>> +  - manual-fc : flow control UART in suspend / resume scenarios.
>> +    Default: 0.
>
> Can be boolean?
>
> I don't really follow the description.
>
> IF: Okay, I will make it boolean. To clarify the description, it controls whether the BlueZ protocol needs to flow control the UART when the BT device is suspended and un-flow control it when the device is resumed.

Okay. Discussion of BlueZ is not relevant to bindings. I would say
something like "The hardware requires the host UART flow-control to be
de-asserted during suspend."

[...]

>> +  - configure-audio : configure platform PCM SCO flag.
>> +    Default: false.
>
> So ignore the rest of the settings if not set? Perhaps combine with pcm-routing:
>
> <blank> - no audio
> audio-mode = "pcm";
> audio-mode = "hci"; (or "sco-hci"?)
>
> IF: That's right: the rest of the parameters are not needed if configure-audio is false. Talking about your suggestions, this driver does nothing if the audio is either sent inbound or not used at all. Would you agree to something like the configure-pcm-audio flag?

So why not combine with pcm-routing?

[...]

> Use the actual rate rather than an enumeration. It is a simple div by
> 128k and log2 to convert in the driver. This makes the property more
> compatible with other chips.
>
> IF: These rates are subject to change in future chips with no guarantees of the pattern holding. I would prefer to use the actual value expected by the firmware if you don't mind to avoid maintaining the extra driver code.

Exactly my point. If the next chip has 0-64k, 1-256k, 2-2048k, your
binding is broken. Just put the bit rate in the binding and do the
mapping to register value in the driver.

> What does incall mean? What is the bit rate when not in a call?
>
> IF: That's the name given to me by the hardware guys. What do you think about the "pcm-interface-rate" instead?

That's somewhat ambiguous. Is that the clock, sample rate, or bit rate
(sample rate * sample size * channels).

Rob

[1] https://lwn.net/Articles/643878/
[2] http://www.spinics.net/lists/devicetree/msg83596.html

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-18 19:41                   ` Rob Herring
  0 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-18 19:41 UTC (permalink / raw)
  To: Ilya Faenson
  Cc: marcel@holtmann.org, Arend Van Spriel, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson <ifaenson@broadcom.com> wrote=
:
> Hi Rob,

Your emails are base64 encoded. They should be plain text for the list.

> -----Original Message-----
> From: Rob Herring [mailto:robherring2@gmail.com]
> Sent: Thursday, June 18, 2015 11:03 AM
> To: Ilya Faenson
> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; li=
nux-bluetooth@vger.kernel.org
> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindi=
ngs
>
> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson@broadcom.com> wro=
te:
>> + devicetree lists

[...]

>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b=
/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>> new file mode 100644
>> index 0000000..5dbcd57
>> --- /dev/null
>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>> @@ -0,0 +1,86 @@
>> +btbcm
>> +------
>> +
>> +Required properties:
>> +
>> +       - compatible : must be "brcm,brcm-bt-uart".
>
> You need to describe the chip, not the interface.
>
> IF: This driver is for all Broadcom Bluetooth UART based chips.

BT only chips? Most/many Broadcom chips are combo chips. I understand
the driver for BT is *mostly* separate from other chip functions like
WiFi, GPS and NFC, but the h/w is a single chip. I say most because
likely there are some parts shared: a voltage rail, reset line, or
power down line. I think some can do BT over the SDIO interface too,
so the interface may be shared. The DT is a description of the h/w
(i.e. what part # for a chip) and not a driver data structure. You
need to describe the whole chip in the binding. It is a Linux problem
if there needs to be multiple separate drivers.

>
>> +       - tty : tty device connected to this Bluetooth device.
>
> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
> is no guarantee which uart is assigned ttyS0.
>
> This should be a phandle to the connected uart if not a sub node of
> the uart. This is complicated since these chips have multiple host
> connections. It needs to go under either uart or SDIO host and have a
> reference back to the one it is not under. Given the SDIO interface is
> discoverable (although sideband gpios and regulators are not), I would
> put this under the uart node as that is never discoverable.
>
> As I've mentioned previously, there's several cases of bindings for
> UART slave devices being posted. This all needs to be coordinated to
> use a common structure.
>
> IF: This driver does not really access the UART. If just needs to have a =
string of some sort to map instances of the BlueZ protocol into platform de=
vices to employ the right GPIOs and interrupts. I could use anything you re=
commend available through the tty_struct coming to the protocol from the Bl=
ueZ line discipline. Moreover, every end user platform I've ever dealt with=
 in 16 years of working with Bluetooth had a single BT UART device. So thes=
e are really rare (typically test platforms) cases only. The mapping is not=
 needed for most platforms at all. I suspect the right thing to do would be=
 to make this parameter optional. The mapping would be done only if the par=
ameter is present. I will use anything tty_struct derived you specify. Make=
s sense?


You've missed my point. I'm not talking about connecting multiple
devices to a UART at once. There are several instances of people
trying to add UART connected devices into DT[1][2]. My point is these
devices all need to have the DT binding done in a common way across
different platforms. Otherwise, we can not have common code to parse
the DT and find devices attached to a UART.


>
>> +
>> +Optional properties:
>> +
>> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an inter=
rupt.
>> +
>> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume =
device.
>> +
>> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/=
off.
>> +
>> +  - oper-speed : Bluetooth device operational baud rate.
>> +    Default: 3000000.
>> +
>> +  - manual-fc : flow control UART in suspend / resume scenarios.
>> +    Default: 0.
>
> Can be boolean?
>
> I don't really follow the description.
>
> IF: Okay, I will make it boolean. To clarify the description, it controls=
 whether the BlueZ protocol needs to flow control the UART when the BT devi=
ce is suspended and un-flow control it when the device is resumed.

Okay. Discussion of BlueZ is not relevant to bindings. I would say
something like "The hardware requires the host UART flow-control to be
de-asserted during suspend."

[...]

>> +  - configure-audio : configure platform PCM SCO flag.
>> +    Default: false.
>
> So ignore the rest of the settings if not set? Perhaps combine with pcm-r=
outing:
>
> <blank> - no audio
> audio-mode =3D "pcm";
> audio-mode =3D "hci"; (or "sco-hci"?)
>
> IF: That's right: the rest of the parameters are not needed if configure-=
audio is false. Talking about your suggestions, this driver does nothing if=
 the audio is either sent inbound or not used at all. Would you agree to so=
mething like the configure-pcm-audio flag?

So why not combine with pcm-routing?

[...]

> Use the actual rate rather than an enumeration. It is a simple div by
> 128k and log2 to convert in the driver. This makes the property more
> compatible with other chips.
>
> IF: These rates are subject to change in future chips with no guarantees =
of the pattern holding. I would prefer to use the actual value expected by =
the firmware if you don't mind to avoid maintaining the extra driver code.

Exactly my point. If the next chip has 0-64k, 1-256k, 2-2048k, your
binding is broken. Just put the bit rate in the binding and do the
mapping to register value in the driver.

> What does incall mean? What is the bit rate when not in a call?
>
> IF: That's the name given to me by the hardware guys. What do you think a=
bout the "pcm-interface-rate" instead?

That's somewhat ambiguous. Is that the clock, sample rate, or bit rate
(sample rate * sample size * channels).

Rob

[1] https://lwn.net/Articles/643878/
[2] http://www.spinics.net/lists/devicetree/msg83596.html

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

* RE: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-18 19:41                   ` Rob Herring
@ 2015-06-18 20:37                       ` Ilya Faenson
  -1 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-18 20:37 UTC (permalink / raw)
  To: Rob Herring
  Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org, Arend Van Spriel,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

Hi Rob.

-----Original Message-----
From: linux-bluetooth-owner@vger.kernel.org [mailto:linux-bluetooth-owner@vger.kernel.org] On Behalf Of Rob Herring
Sent: Thursday, June 18, 2015 3:41 PM
To: Ilya Faenson
Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings

On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:
> Hi Rob,

Your emails are base64 encoded. They should be plain text for the list.

IF: The Outlook is configured to respond in the sender's format. I therefore respond in the encoding you've used.

> -----Original Message-----
> From: Rob Herring [mailto:robherring2@gmail.com]
> Sent: Thursday, June 18, 2015 11:03 AM
> To: Ilya Faenson
> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>
> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:
>> + devicetree lists

[...]

>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>> new file mode 100644
>> index 0000000..5dbcd57
>> --- /dev/null
>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>> @@ -0,0 +1,86 @@
>> +btbcm
>> +------
>> +
>> +Required properties:
>> +
>> +       - compatible : must be "brcm,brcm-bt-uart".
>
> You need to describe the chip, not the interface.
>
> IF: This driver is for all Broadcom Bluetooth UART based chips.

BT only chips? Most/many Broadcom chips are combo chips. I understand
the driver for BT is *mostly* separate from other chip functions like
WiFi, GPS and NFC, but the h/w is a single chip. I say most because
likely there are some parts shared: a voltage rail, reset line, or
power down line. I think some can do BT over the SDIO interface too,
so the interface may be shared. The DT is a description of the h/w
(i.e. what part # for a chip) and not a driver data structure. You
need to describe the whole chip in the binding. It is a Linux problem
if there needs to be multiple separate drivers.

IF: Defining complete DT description for the Broadcom combo chips for multiple interfaces is well beyond the scope of what I am doing. I just need to define a DT node for the input and output GPIOs connected to the BT UART chip. BT may or may not be part of the combo chip: it does not really matter for this exercise. I thought I would take this opportunity to place some BT device parameters into that node as well. If you're not comfortable with this, I could just call it a "GPIO set" to avoid mentioning BT and UART at all but it would make little sense. Still, I could consider it. Would you have "GPIO set" recommendations? Alternatively, NFC Marvell code you're referring to has parameters configured as Linux module parameters. I could do the same too, avoiding this device tree discussion. Let me know.

Generally speaking (pontification hat on :-)), what you're trying to do (description of the whole chip) is well beyond what say ACPI has done (I was involved some in the BT ACPI exercise a few years ago). BT UART interface is described in ACPI independently of other parts of the same combo chip. Requirements like that slow down the DT development in my opinion as companies are understandably reluctant to work with unrealistic goals. End of pontification. :-)

>
>> +       - tty : tty device connected to this Bluetooth device.
>
> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
> is no guarantee which uart is assigned ttyS0.
>
> This should be a phandle to the connected uart if not a sub node of
> the uart. This is complicated since these chips have multiple host
> connections. It needs to go under either uart or SDIO host and have a
> reference back to the one it is not under. Given the SDIO interface is
> discoverable (although sideband gpios and regulators are not), I would
> put this under the uart node as that is never discoverable.
>
> As I've mentioned previously, there's several cases of bindings for
> UART slave devices being posted. This all needs to be coordinated to
> use a common structure.
>
> IF: This driver does not really access the UART. If just needs to have a string of some sort to map instances of the BlueZ protocol into platform devices to employ the right GPIOs and interrupts. I could use anything you recommend available through the tty_struct coming to the protocol from the BlueZ line discipline. Moreover, every end user platform I've ever dealt with in 16 years of working with Bluetooth had a single BT UART device. So these are really rare (typically test platforms) cases only. The mapping is not needed for most platforms at all. I suspect the right thing to do would be to make this parameter optional. The mapping would be done only if the parameter is present. I will use anything tty_struct derived you specify. Makes sense?


You've missed my point. I'm not talking about connecting multiple
devices to a UART at once. There are several instances of people
trying to add UART connected devices into DT[1][2]. My point is these
devices all need to have the DT binding done in a common way across
different platforms. Otherwise, we can not have common code to parse
the DT and find devices attached to a UART.

IF: Chances are I was not clear enough. I was not talking about connecting multiple devices to a UART. I was talking about connecting one Broadcom BT device to one serial port and another Broadcom BT device to another serial port (rare enough setup). I do understand your goals though. I would be happy to participate in that exercise (subject to the management approval) once DT has published the UART device parameters and the Linux bluetooth-next has support for DT enumerated devices. I don’t see it happening soon though. Marvell example you've referred me to has nothing of the sort. What do you think of allowing us something to ship now with an understanding that we would support your UART enumerated devices once they are published?
>
>> +
>> +Optional properties:
>> +
>> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
>> +
>> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
>> +
>> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.
>> +
>> +  - oper-speed : Bluetooth device operational baud rate.
>> +    Default: 3000000.
>> +
>> +  - manual-fc : flow control UART in suspend / resume scenarios.
>> +    Default: 0.
>
> Can be boolean?
>
> I don't really follow the description.
>
> IF: Okay, I will make it boolean. To clarify the description, it controls whether the BlueZ protocol needs to flow control the UART when the BT device is suspended and un-flow control it when the device is resumed.

Okay. Discussion of BlueZ is not relevant to bindings. I would say
something like "The hardware requires the host UART flow-control to be
de-asserted during suspend."

IF: Okay.

[...]

>> +  - configure-audio : configure platform PCM SCO flag.
>> +    Default: false.
>
> So ignore the rest of the settings if not set? Perhaps combine with pcm-routing:
>
> <blank> - no audio
> audio-mode = "pcm";
> audio-mode = "hci"; (or "sco-hci"?)
>
> IF: That's right: the rest of the parameters are not needed if configure-audio is false. Talking about your suggestions, this driver does nothing if the audio is either sent inbound or not used at all. Would you agree to something like the configure-pcm-audio flag?

So why not combine with pcm-routing?

IF: Okay, I can derive one from another.

[...]

> Use the actual rate rather than an enumeration. It is a simple div by
> 128k and log2 to convert in the driver. This makes the property more
> compatible with other chips.
>
> IF: These rates are subject to change in future chips with no guarantees of the pattern holding. I would prefer to use the actual value expected by the firmware if you don't mind to avoid maintaining the extra driver code.

Exactly my point. If the next chip has 0-64k, 1-256k, 2-2048k, your
binding is broken. Just put the bit rate in the binding and do the
mapping to register value in the driver.

IF: Okay, will implement.

> What does incall mean? What is the bit rate when not in a call?
>
> IF: That's the name given to me by the hardware guys. What do you think about the "pcm-interface-rate" instead?

That's somewhat ambiguous. Is that the clock, sample rate, or bit rate
(sample rate * sample size * channels).

IF: Okay, will use the original name.

Rob

[1] https://lwn.net/Articles/643878/
[2] http://www.spinics.net/lists/devicetree/msg83596.html
--
To unsubscribe from this list: send the line "unsubscribe linux-bluetooth" in
the body of a message to majordomo@vger.kernel.org
More majordomo info at  http://vger.kernel.org/majordomo-info.html

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

* RE: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-18 20:37                       ` Ilya Faenson
  0 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-18 20:37 UTC (permalink / raw)
  To: Rob Herring
  Cc: marcel@holtmann.org, Arend Van Spriel, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

SGkgUm9iLg0KDQotLS0tLU9yaWdpbmFsIE1lc3NhZ2UtLS0tLQ0KRnJvbTogbGludXgtYmx1ZXRv
b3RoLW93bmVyQHZnZXIua2VybmVsLm9yZyBbbWFpbHRvOmxpbnV4LWJsdWV0b290aC1vd25lckB2
Z2VyLmtlcm5lbC5vcmddIE9uIEJlaGFsZiBPZiBSb2IgSGVycmluZw0KU2VudDogVGh1cnNkYXks
IEp1bmUgMTgsIDIwMTUgMzo0MSBQTQ0KVG86IElseWEgRmFlbnNvbg0KQ2M6IG1hcmNlbEBob2x0
bWFubi5vcmc7IEFyZW5kIFZhbiBTcHJpZWw7IGRldmljZXRyZWVAdmdlci5rZXJuZWwub3JnOyBs
aW51eC1ibHVldG9vdGhAdmdlci5rZXJuZWwub3JnDQpTdWJqZWN0OiBSZTogRlc6IFtQQVRDSCB2
NCAxLzRdIEJyb2FkY29tIEJsdWV0b290aCBVQVJUIERldmljZSBUcmVlIGJpbmRpbmdzDQoNCk9u
IFRodSwgSnVuIDE4LCAyMDE1IGF0IDE6NTQgUE0sIElseWEgRmFlbnNvbiA8aWZhZW5zb25AYnJv
YWRjb20uY29tPiB3cm90ZToNCj4gSGkgUm9iLA0KDQpZb3VyIGVtYWlscyBhcmUgYmFzZTY0IGVu
Y29kZWQuIFRoZXkgc2hvdWxkIGJlIHBsYWluIHRleHQgZm9yIHRoZSBsaXN0Lg0KDQpJRjogVGhl
IE91dGxvb2sgaXMgY29uZmlndXJlZCB0byByZXNwb25kIGluIHRoZSBzZW5kZXIncyBmb3JtYXQu
IEkgdGhlcmVmb3JlIHJlc3BvbmQgaW4gdGhlIGVuY29kaW5nIHlvdSd2ZSB1c2VkLg0KDQo+IC0t
LS0tT3JpZ2luYWwgTWVzc2FnZS0tLS0tDQo+IEZyb206IFJvYiBIZXJyaW5nIFttYWlsdG86cm9i
aGVycmluZzJAZ21haWwuY29tXQ0KPiBTZW50OiBUaHVyc2RheSwgSnVuZSAxOCwgMjAxNSAxMTow
MyBBTQ0KPiBUbzogSWx5YSBGYWVuc29uDQo+IENjOiBtYXJjZWxAaG9sdG1hbm4ub3JnOyBBcmVu
ZCBWYW4gU3ByaWVsOyBkZXZpY2V0cmVlQHZnZXIua2VybmVsLm9yZzsgbGludXgtYmx1ZXRvb3Ro
QHZnZXIua2VybmVsLm9yZw0KPiBTdWJqZWN0OiBSZTogRlc6IFtQQVRDSCB2NCAxLzRdIEJyb2Fk
Y29tIEJsdWV0b290aCBVQVJUIERldmljZSBUcmVlIGJpbmRpbmdzDQo+DQo+IE9uIFdlZCwgSnVu
IDE3LCAyMDE1IGF0IDY6MTEgUE0sIElseWEgRmFlbnNvbiA8aWZhZW5zb25AYnJvYWRjb20uY29t
PiB3cm90ZToNCj4+ICsgZGV2aWNldHJlZSBsaXN0cw0KDQpbLi4uXQ0KDQo+PiBkaWZmIC0tZ2l0
IGEvRG9jdW1lbnRhdGlvbi9kZXZpY2V0cmVlL2JpbmRpbmdzL25ldC9ibHVldG9vdGgvYnRiY20u
dHh0IGIvRG9jdW1lbnRhdGlvbi9kZXZpY2V0cmVlL2JpbmRpbmdzL25ldC9ibHVldG9vdGgvYnRi
Y20udHh0DQo+PiBuZXcgZmlsZSBtb2RlIDEwMDY0NA0KPj4gaW5kZXggMDAwMDAwMC4uNWRiY2Q1
Nw0KPj4gLS0tIC9kZXYvbnVsbA0KPj4gKysrIGIvRG9jdW1lbnRhdGlvbi9kZXZpY2V0cmVlL2Jp
bmRpbmdzL25ldC9ibHVldG9vdGgvYnRiY20udHh0DQo+PiBAQCAtMCwwICsxLDg2IEBADQo+PiAr
YnRiY20NCj4+ICstLS0tLS0NCj4+ICsNCj4+ICtSZXF1aXJlZCBwcm9wZXJ0aWVzOg0KPj4gKw0K
Pj4gKyAgICAgICAtIGNvbXBhdGlibGUgOiBtdXN0IGJlICJicmNtLGJyY20tYnQtdWFydCIuDQo+
DQo+IFlvdSBuZWVkIHRvIGRlc2NyaWJlIHRoZSBjaGlwLCBub3QgdGhlIGludGVyZmFjZS4NCj4N
Cj4gSUY6IFRoaXMgZHJpdmVyIGlzIGZvciBhbGwgQnJvYWRjb20gQmx1ZXRvb3RoIFVBUlQgYmFz
ZWQgY2hpcHMuDQoNCkJUIG9ubHkgY2hpcHM/IE1vc3QvbWFueSBCcm9hZGNvbSBjaGlwcyBhcmUg
Y29tYm8gY2hpcHMuIEkgdW5kZXJzdGFuZA0KdGhlIGRyaXZlciBmb3IgQlQgaXMgKm1vc3RseSog
c2VwYXJhdGUgZnJvbSBvdGhlciBjaGlwIGZ1bmN0aW9ucyBsaWtlDQpXaUZpLCBHUFMgYW5kIE5G
QywgYnV0IHRoZSBoL3cgaXMgYSBzaW5nbGUgY2hpcC4gSSBzYXkgbW9zdCBiZWNhdXNlDQpsaWtl
bHkgdGhlcmUgYXJlIHNvbWUgcGFydHMgc2hhcmVkOiBhIHZvbHRhZ2UgcmFpbCwgcmVzZXQgbGlu
ZSwgb3INCnBvd2VyIGRvd24gbGluZS4gSSB0aGluayBzb21lIGNhbiBkbyBCVCBvdmVyIHRoZSBT
RElPIGludGVyZmFjZSB0b28sDQpzbyB0aGUgaW50ZXJmYWNlIG1heSBiZSBzaGFyZWQuIFRoZSBE
VCBpcyBhIGRlc2NyaXB0aW9uIG9mIHRoZSBoL3cNCihpLmUuIHdoYXQgcGFydCAjIGZvciBhIGNo
aXApIGFuZCBub3QgYSBkcml2ZXIgZGF0YSBzdHJ1Y3R1cmUuIFlvdQ0KbmVlZCB0byBkZXNjcmli
ZSB0aGUgd2hvbGUgY2hpcCBpbiB0aGUgYmluZGluZy4gSXQgaXMgYSBMaW51eCBwcm9ibGVtDQpp
ZiB0aGVyZSBuZWVkcyB0byBiZSBtdWx0aXBsZSBzZXBhcmF0ZSBkcml2ZXJzLg0KDQpJRjogRGVm
aW5pbmcgY29tcGxldGUgRFQgZGVzY3JpcHRpb24gZm9yIHRoZSBCcm9hZGNvbSBjb21ibyBjaGlw
cyBmb3IgbXVsdGlwbGUgaW50ZXJmYWNlcyBpcyB3ZWxsIGJleW9uZCB0aGUgc2NvcGUgb2Ygd2hh
dCBJIGFtIGRvaW5nLiBJIGp1c3QgbmVlZCB0byBkZWZpbmUgYSBEVCBub2RlIGZvciB0aGUgaW5w
dXQgYW5kIG91dHB1dCBHUElPcyBjb25uZWN0ZWQgdG8gdGhlIEJUIFVBUlQgY2hpcC4gQlQgbWF5
IG9yIG1heSBub3QgYmUgcGFydCBvZiB0aGUgY29tYm8gY2hpcDogaXQgZG9lcyBub3QgcmVhbGx5
IG1hdHRlciBmb3IgdGhpcyBleGVyY2lzZS4gSSB0aG91Z2h0IEkgd291bGQgdGFrZSB0aGlzIG9w
cG9ydHVuaXR5IHRvIHBsYWNlIHNvbWUgQlQgZGV2aWNlIHBhcmFtZXRlcnMgaW50byB0aGF0IG5v
ZGUgYXMgd2VsbC4gSWYgeW91J3JlIG5vdCBjb21mb3J0YWJsZSB3aXRoIHRoaXMsIEkgY291bGQg
anVzdCBjYWxsIGl0IGEgIkdQSU8gc2V0IiB0byBhdm9pZCBtZW50aW9uaW5nIEJUIGFuZCBVQVJU
IGF0IGFsbCBidXQgaXQgd291bGQgbWFrZSBsaXR0bGUgc2Vuc2UuIFN0aWxsLCBJIGNvdWxkIGNv
bnNpZGVyIGl0LiBXb3VsZCB5b3UgaGF2ZSAiR1BJTyBzZXQiIHJlY29tbWVuZGF0aW9ucz8gQWx0
ZXJuYXRpdmVseSwgTkZDIE1hcnZlbGwgY29kZSB5b3UncmUgcmVmZXJyaW5nIHRvIGhhcyBwYXJh
bWV0ZXJzIGNvbmZpZ3VyZWQgYXMgTGludXggbW9kdWxlIHBhcmFtZXRlcnMuIEkgY291bGQgZG8g
dGhlIHNhbWUgdG9vLCBhdm9pZGluZyB0aGlzIGRldmljZSB0cmVlIGRpc2N1c3Npb24uIExldCBt
ZSBrbm93Lg0KDQpHZW5lcmFsbHkgc3BlYWtpbmcgKHBvbnRpZmljYXRpb24gaGF0IG9uIDotKSks
IHdoYXQgeW91J3JlIHRyeWluZyB0byBkbyAoZGVzY3JpcHRpb24gb2YgdGhlIHdob2xlIGNoaXAp
IGlzIHdlbGwgYmV5b25kIHdoYXQgc2F5IEFDUEkgaGFzIGRvbmUgKEkgd2FzIGludm9sdmVkIHNv
bWUgaW4gdGhlIEJUIEFDUEkgZXhlcmNpc2UgYSBmZXcgeWVhcnMgYWdvKS4gQlQgVUFSVCBpbnRl
cmZhY2UgaXMgZGVzY3JpYmVkIGluIEFDUEkgaW5kZXBlbmRlbnRseSBvZiBvdGhlciBwYXJ0cyBv
ZiB0aGUgc2FtZSBjb21ibyBjaGlwLiBSZXF1aXJlbWVudHMgbGlrZSB0aGF0IHNsb3cgZG93biB0
aGUgRFQgZGV2ZWxvcG1lbnQgaW4gbXkgb3BpbmlvbiBhcyBjb21wYW5pZXMgYXJlIHVuZGVyc3Rh
bmRhYmx5IHJlbHVjdGFudCB0byB3b3JrIHdpdGggdW5yZWFsaXN0aWMgZ29hbHMuIEVuZCBvZiBw
b250aWZpY2F0aW9uLiA6LSkNCg0KPg0KPj4gKyAgICAgICAtIHR0eSA6IHR0eSBkZXZpY2UgY29u
bmVjdGVkIHRvIHRoaXMgQmx1ZXRvb3RoIGRldmljZS4NCj4NCj4gInR0eSIgaXMgYSBiaXQgb2Yg
YSBMaW51eGlzbSBhbmQgInR0eVMwIiBjZXJ0YWlubHkgaXMuIEZ1cnRoZXIsIHRoZXJlDQo+IGlz
IG5vIGd1YXJhbnRlZSB3aGljaCB1YXJ0IGlzIGFzc2lnbmVkIHR0eVMwLg0KPg0KPiBUaGlzIHNo
b3VsZCBiZSBhIHBoYW5kbGUgdG8gdGhlIGNvbm5lY3RlZCB1YXJ0IGlmIG5vdCBhIHN1YiBub2Rl
IG9mDQo+IHRoZSB1YXJ0LiBUaGlzIGlzIGNvbXBsaWNhdGVkIHNpbmNlIHRoZXNlIGNoaXBzIGhh
dmUgbXVsdGlwbGUgaG9zdA0KPiBjb25uZWN0aW9ucy4gSXQgbmVlZHMgdG8gZ28gdW5kZXIgZWl0
aGVyIHVhcnQgb3IgU0RJTyBob3N0IGFuZCBoYXZlIGENCj4gcmVmZXJlbmNlIGJhY2sgdG8gdGhl
IG9uZSBpdCBpcyBub3QgdW5kZXIuIEdpdmVuIHRoZSBTRElPIGludGVyZmFjZSBpcw0KPiBkaXNj
b3ZlcmFibGUgKGFsdGhvdWdoIHNpZGViYW5kIGdwaW9zIGFuZCByZWd1bGF0b3JzIGFyZSBub3Qp
LCBJIHdvdWxkDQo+IHB1dCB0aGlzIHVuZGVyIHRoZSB1YXJ0IG5vZGUgYXMgdGhhdCBpcyBuZXZl
ciBkaXNjb3ZlcmFibGUuDQo+DQo+IEFzIEkndmUgbWVudGlvbmVkIHByZXZpb3VzbHksIHRoZXJl
J3Mgc2V2ZXJhbCBjYXNlcyBvZiBiaW5kaW5ncyBmb3INCj4gVUFSVCBzbGF2ZSBkZXZpY2VzIGJl
aW5nIHBvc3RlZC4gVGhpcyBhbGwgbmVlZHMgdG8gYmUgY29vcmRpbmF0ZWQgdG8NCj4gdXNlIGEg
Y29tbW9uIHN0cnVjdHVyZS4NCj4NCj4gSUY6IFRoaXMgZHJpdmVyIGRvZXMgbm90IHJlYWxseSBh
Y2Nlc3MgdGhlIFVBUlQuIElmIGp1c3QgbmVlZHMgdG8gaGF2ZSBhIHN0cmluZyBvZiBzb21lIHNv
cnQgdG8gbWFwIGluc3RhbmNlcyBvZiB0aGUgQmx1ZVogcHJvdG9jb2wgaW50byBwbGF0Zm9ybSBk
ZXZpY2VzIHRvIGVtcGxveSB0aGUgcmlnaHQgR1BJT3MgYW5kIGludGVycnVwdHMuIEkgY291bGQg
dXNlIGFueXRoaW5nIHlvdSByZWNvbW1lbmQgYXZhaWxhYmxlIHRocm91Z2ggdGhlIHR0eV9zdHJ1
Y3QgY29taW5nIHRvIHRoZSBwcm90b2NvbCBmcm9tIHRoZSBCbHVlWiBsaW5lIGRpc2NpcGxpbmUu
IE1vcmVvdmVyLCBldmVyeSBlbmQgdXNlciBwbGF0Zm9ybSBJJ3ZlIGV2ZXIgZGVhbHQgd2l0aCBp
biAxNiB5ZWFycyBvZiB3b3JraW5nIHdpdGggQmx1ZXRvb3RoIGhhZCBhIHNpbmdsZSBCVCBVQVJU
IGRldmljZS4gU28gdGhlc2UgYXJlIHJlYWxseSByYXJlICh0eXBpY2FsbHkgdGVzdCBwbGF0Zm9y
bXMpIGNhc2VzIG9ubHkuIFRoZSBtYXBwaW5nIGlzIG5vdCBuZWVkZWQgZm9yIG1vc3QgcGxhdGZv
cm1zIGF0IGFsbC4gSSBzdXNwZWN0IHRoZSByaWdodCB0aGluZyB0byBkbyB3b3VsZCBiZSB0byBt
YWtlIHRoaXMgcGFyYW1ldGVyIG9wdGlvbmFsLiBUaGUgbWFwcGluZyB3b3VsZCBiZSBkb25lIG9u
bHkgaWYgdGhlIHBhcmFtZXRlciBpcyBwcmVzZW50LiBJIHdpbGwgdXNlIGFueXRoaW5nIHR0eV9z
dHJ1Y3QgZGVyaXZlZCB5b3Ugc3BlY2lmeS4gTWFrZXMgc2Vuc2U/DQoNCg0KWW91J3ZlIG1pc3Nl
ZCBteSBwb2ludC4gSSdtIG5vdCB0YWxraW5nIGFib3V0IGNvbm5lY3RpbmcgbXVsdGlwbGUNCmRl
dmljZXMgdG8gYSBVQVJUIGF0IG9uY2UuIFRoZXJlIGFyZSBzZXZlcmFsIGluc3RhbmNlcyBvZiBw
ZW9wbGUNCnRyeWluZyB0byBhZGQgVUFSVCBjb25uZWN0ZWQgZGV2aWNlcyBpbnRvIERUWzFdWzJd
LiBNeSBwb2ludCBpcyB0aGVzZQ0KZGV2aWNlcyBhbGwgbmVlZCB0byBoYXZlIHRoZSBEVCBiaW5k
aW5nIGRvbmUgaW4gYSBjb21tb24gd2F5IGFjcm9zcw0KZGlmZmVyZW50IHBsYXRmb3Jtcy4gT3Ro
ZXJ3aXNlLCB3ZSBjYW4gbm90IGhhdmUgY29tbW9uIGNvZGUgdG8gcGFyc2UNCnRoZSBEVCBhbmQg
ZmluZCBkZXZpY2VzIGF0dGFjaGVkIHRvIGEgVUFSVC4NCg0KSUY6IENoYW5jZXMgYXJlIEkgd2Fz
IG5vdCBjbGVhciBlbm91Z2guIEkgd2FzIG5vdCB0YWxraW5nIGFib3V0IGNvbm5lY3RpbmcgbXVs
dGlwbGUgZGV2aWNlcyB0byBhIFVBUlQuIEkgd2FzIHRhbGtpbmcgYWJvdXQgY29ubmVjdGluZyBv
bmUgQnJvYWRjb20gQlQgZGV2aWNlIHRvIG9uZSBzZXJpYWwgcG9ydCBhbmQgYW5vdGhlciBCcm9h
ZGNvbSBCVCBkZXZpY2UgdG8gYW5vdGhlciBzZXJpYWwgcG9ydCAocmFyZSBlbm91Z2ggc2V0dXAp
LiBJIGRvIHVuZGVyc3RhbmQgeW91ciBnb2FscyB0aG91Z2guIEkgd291bGQgYmUgaGFwcHkgdG8g
cGFydGljaXBhdGUgaW4gdGhhdCBleGVyY2lzZSAoc3ViamVjdCB0byB0aGUgbWFuYWdlbWVudCBh
cHByb3ZhbCkgb25jZSBEVCBoYXMgcHVibGlzaGVkIHRoZSBVQVJUIGRldmljZSBwYXJhbWV0ZXJz
IGFuZCB0aGUgTGludXggYmx1ZXRvb3RoLW5leHQgaGFzIHN1cHBvcnQgZm9yIERUIGVudW1lcmF0
ZWQgZGV2aWNlcy4gSSBkb27igJl0IHNlZSBpdCBoYXBwZW5pbmcgc29vbiB0aG91Z2guIE1hcnZl
bGwgZXhhbXBsZSB5b3UndmUgcmVmZXJyZWQgbWUgdG8gaGFzIG5vdGhpbmcgb2YgdGhlIHNvcnQu
IFdoYXQgZG8geW91IHRoaW5rIG9mIGFsbG93aW5nIHVzIHNvbWV0aGluZyB0byBzaGlwIG5vdyB3
aXRoIGFuIHVuZGVyc3RhbmRpbmcgdGhhdCB3ZSB3b3VsZCBzdXBwb3J0IHlvdXIgVUFSVCBlbnVt
ZXJhdGVkIGRldmljZXMgb25jZSB0aGV5IGFyZSBwdWJsaXNoZWQ/DQo+DQo+PiArDQo+PiArT3B0
aW9uYWwgcHJvcGVydGllczoNCj4+ICsNCj4+ICsgIC0gYnQtaG9zdC13YWtlLWdwaW9zIDogYnQt
aG9zdC13YWtlIGlucHV0IEdQSU8gdG8gYmUgdXNlZCBhcyBhbiBpbnRlcnJ1cHQuDQo+PiArDQo+
PiArICAtIGJ0LXdha2UtZ3Bpb3MgOiBidC13YWtlIG91dHB1dCBHUElPIHRvIGJlIHVzZWQgdG8g
c3VzcGVuZCAvIHJlc3VtZSBkZXZpY2UuDQo+PiArDQo+PiArICAtIGJ0LXJlZy1vbi1ncGlvcyA6
IHJlZy1vbiBvdXRwdXQgR1BJTyB0byBiZSB1c2VkIHRvIHBvd2VyIGRldmljZSBvbi9vZmYuDQo+
PiArDQo+PiArICAtIG9wZXItc3BlZWQgOiBCbHVldG9vdGggZGV2aWNlIG9wZXJhdGlvbmFsIGJh
dWQgcmF0ZS4NCj4+ICsgICAgRGVmYXVsdDogMzAwMDAwMC4NCj4+ICsNCj4+ICsgIC0gbWFudWFs
LWZjIDogZmxvdyBjb250cm9sIFVBUlQgaW4gc3VzcGVuZCAvIHJlc3VtZSBzY2VuYXJpb3MuDQo+
PiArICAgIERlZmF1bHQ6IDAuDQo+DQo+IENhbiBiZSBib29sZWFuPw0KPg0KPiBJIGRvbid0IHJl
YWxseSBmb2xsb3cgdGhlIGRlc2NyaXB0aW9uLg0KPg0KPiBJRjogT2theSwgSSB3aWxsIG1ha2Ug
aXQgYm9vbGVhbi4gVG8gY2xhcmlmeSB0aGUgZGVzY3JpcHRpb24sIGl0IGNvbnRyb2xzIHdoZXRo
ZXIgdGhlIEJsdWVaIHByb3RvY29sIG5lZWRzIHRvIGZsb3cgY29udHJvbCB0aGUgVUFSVCB3aGVu
IHRoZSBCVCBkZXZpY2UgaXMgc3VzcGVuZGVkIGFuZCB1bi1mbG93IGNvbnRyb2wgaXQgd2hlbiB0
aGUgZGV2aWNlIGlzIHJlc3VtZWQuDQoNCk9rYXkuIERpc2N1c3Npb24gb2YgQmx1ZVogaXMgbm90
IHJlbGV2YW50IHRvIGJpbmRpbmdzLiBJIHdvdWxkIHNheQ0Kc29tZXRoaW5nIGxpa2UgIlRoZSBo
YXJkd2FyZSByZXF1aXJlcyB0aGUgaG9zdCBVQVJUIGZsb3ctY29udHJvbCB0byBiZQ0KZGUtYXNz
ZXJ0ZWQgZHVyaW5nIHN1c3BlbmQuIg0KDQpJRjogT2theS4NCg0KWy4uLl0NCg0KPj4gKyAgLSBj
b25maWd1cmUtYXVkaW8gOiBjb25maWd1cmUgcGxhdGZvcm0gUENNIFNDTyBmbGFnLg0KPj4gKyAg
ICBEZWZhdWx0OiBmYWxzZS4NCj4NCj4gU28gaWdub3JlIHRoZSByZXN0IG9mIHRoZSBzZXR0aW5n
cyBpZiBub3Qgc2V0PyBQZXJoYXBzIGNvbWJpbmUgd2l0aCBwY20tcm91dGluZzoNCj4NCj4gPGJs
YW5rPiAtIG5vIGF1ZGlvDQo+IGF1ZGlvLW1vZGUgPSAicGNtIjsNCj4gYXVkaW8tbW9kZSA9ICJo
Y2kiOyAob3IgInNjby1oY2kiPykNCj4NCj4gSUY6IFRoYXQncyByaWdodDogdGhlIHJlc3Qgb2Yg
dGhlIHBhcmFtZXRlcnMgYXJlIG5vdCBuZWVkZWQgaWYgY29uZmlndXJlLWF1ZGlvIGlzIGZhbHNl
LiBUYWxraW5nIGFib3V0IHlvdXIgc3VnZ2VzdGlvbnMsIHRoaXMgZHJpdmVyIGRvZXMgbm90aGlu
ZyBpZiB0aGUgYXVkaW8gaXMgZWl0aGVyIHNlbnQgaW5ib3VuZCBvciBub3QgdXNlZCBhdCBhbGwu
IFdvdWxkIHlvdSBhZ3JlZSB0byBzb21ldGhpbmcgbGlrZSB0aGUgY29uZmlndXJlLXBjbS1hdWRp
byBmbGFnPw0KDQpTbyB3aHkgbm90IGNvbWJpbmUgd2l0aCBwY20tcm91dGluZz8NCg0KSUY6IE9r
YXksIEkgY2FuIGRlcml2ZSBvbmUgZnJvbSBhbm90aGVyLg0KDQpbLi4uXQ0KDQo+IFVzZSB0aGUg
YWN0dWFsIHJhdGUgcmF0aGVyIHRoYW4gYW4gZW51bWVyYXRpb24uIEl0IGlzIGEgc2ltcGxlIGRp
diBieQ0KPiAxMjhrIGFuZCBsb2cyIHRvIGNvbnZlcnQgaW4gdGhlIGRyaXZlci4gVGhpcyBtYWtl
cyB0aGUgcHJvcGVydHkgbW9yZQ0KPiBjb21wYXRpYmxlIHdpdGggb3RoZXIgY2hpcHMuDQo+DQo+
IElGOiBUaGVzZSByYXRlcyBhcmUgc3ViamVjdCB0byBjaGFuZ2UgaW4gZnV0dXJlIGNoaXBzIHdp
dGggbm8gZ3VhcmFudGVlcyBvZiB0aGUgcGF0dGVybiBob2xkaW5nLiBJIHdvdWxkIHByZWZlciB0
byB1c2UgdGhlIGFjdHVhbCB2YWx1ZSBleHBlY3RlZCBieSB0aGUgZmlybXdhcmUgaWYgeW91IGRv
bid0IG1pbmQgdG8gYXZvaWQgbWFpbnRhaW5pbmcgdGhlIGV4dHJhIGRyaXZlciBjb2RlLg0KDQpF
eGFjdGx5IG15IHBvaW50LiBJZiB0aGUgbmV4dCBjaGlwIGhhcyAwLTY0aywgMS0yNTZrLCAyLTIw
NDhrLCB5b3VyDQpiaW5kaW5nIGlzIGJyb2tlbi4gSnVzdCBwdXQgdGhlIGJpdCByYXRlIGluIHRo
ZSBiaW5kaW5nIGFuZCBkbyB0aGUNCm1hcHBpbmcgdG8gcmVnaXN0ZXIgdmFsdWUgaW4gdGhlIGRy
aXZlci4NCg0KSUY6IE9rYXksIHdpbGwgaW1wbGVtZW50Lg0KDQo+IFdoYXQgZG9lcyBpbmNhbGwg
bWVhbj8gV2hhdCBpcyB0aGUgYml0IHJhdGUgd2hlbiBub3QgaW4gYSBjYWxsPw0KPg0KPiBJRjog
VGhhdCdzIHRoZSBuYW1lIGdpdmVuIHRvIG1lIGJ5IHRoZSBoYXJkd2FyZSBndXlzLiBXaGF0IGRv
IHlvdSB0aGluayBhYm91dCB0aGUgInBjbS1pbnRlcmZhY2UtcmF0ZSIgaW5zdGVhZD8NCg0KVGhh
dCdzIHNvbWV3aGF0IGFtYmlndW91cy4gSXMgdGhhdCB0aGUgY2xvY2ssIHNhbXBsZSByYXRlLCBv
ciBiaXQgcmF0ZQ0KKHNhbXBsZSByYXRlICogc2FtcGxlIHNpemUgKiBjaGFubmVscykuDQoNCklG
OiBPa2F5LCB3aWxsIHVzZSB0aGUgb3JpZ2luYWwgbmFtZS4NCg0KUm9iDQoNClsxXSBodHRwczov
L2x3bi5uZXQvQXJ0aWNsZXMvNjQzODc4Lw0KWzJdIGh0dHA6Ly93d3cuc3Bpbmljcy5uZXQvbGlz
dHMvZGV2aWNldHJlZS9tc2c4MzU5Ni5odG1sDQotLQ0KVG8gdW5zdWJzY3JpYmUgZnJvbSB0aGlz
IGxpc3Q6IHNlbmQgdGhlIGxpbmUgInVuc3Vic2NyaWJlIGxpbnV4LWJsdWV0b290aCIgaW4NCnRo
ZSBib2R5IG9mIGEgbWVzc2FnZSB0byBtYWpvcmRvbW9Admdlci5rZXJuZWwub3JnDQpNb3JlIG1h
am9yZG9tbyBpbmZvIGF0ICBodHRwOi8vdmdlci5rZXJuZWwub3JnL21ham9yZG9tby1pbmZvLmh0
bWwNCg==

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-18 20:37                       ` Ilya Faenson
@ 2015-06-19 15:47                           ` Rob Herring
  -1 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-19 15:47 UTC (permalink / raw)
  To: Ilya Faenson
  Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org, Arend Van Spriel,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
> Hi Rob.
>
> -----Original Message-----
> From: linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org [mailto:linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org] On Behalf Of Rob Herring
> Sent: Thursday, June 18, 2015 3:41 PM
> To: Ilya Faenson
> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org; linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>
> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
>> Hi Rob,
>
> Your emails are base64 encoded. They should be plain text for the list.
>
> IF: The Outlook is configured to respond in the sender's format. I therefore respond in the encoding you've used.

I assure you that that is not the case or I would be banished from
lists by now. Outlook is generally incapable of correctly sending
mails to lists. The reply header above is one aspect of that. The
other problem is your replies don't get wrapped and prefixed properly.
That could be my client I guess, but *all* other mails are fine.

My sent mails have:

Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: quoted-printable


>> -----Original Message-----
>> From: Rob Herring [mailto:robherring2-Re5JQEeQqe8AvxtiuMwx3w@public.gmane.org]
>> Sent: Thursday, June 18, 2015 11:03 AM
>> To: Ilya Faenson
>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TaqPxH82wqD4g@public.gmane.orgg; linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>>
>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
>>> + devicetree lists
>
> [...]
>
>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>> new file mode 100644
>>> index 0000000..5dbcd57
>>> --- /dev/null
>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>> @@ -0,0 +1,86 @@
>>> +btbcm
>>> +------
>>> +
>>> +Required properties:
>>> +
>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>
>> You need to describe the chip, not the interface.
>>
>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>
> BT only chips? Most/many Broadcom chips are combo chips. I understand
> the driver for BT is *mostly* separate from other chip functions like
> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
> likely there are some parts shared: a voltage rail, reset line, or
> power down line. I think some can do BT over the SDIO interface too,
> so the interface may be shared. The DT is a description of the h/w
> (i.e. what part # for a chip) and not a driver data structure. You
> need to describe the whole chip in the binding. It is a Linux problem
> if there needs to be multiple separate drivers.
>
> IF: Defining complete DT description for the Broadcom combo chips for multiple interfaces is well beyond the scope of what I am doing. I just need to define a DT node for the input and output GPIOs connected to the BT UART chip. BT may or may not be part of the combo chip: it does not really matter for this exercise. I thought I would take this opportunity to place some BT device parameters into that node as well. If you're not comfortable with this, I could just call it a "GPIO set" to avoid mentioning BT and UART at all but it would make little sense. Still, I could consider it. Would you have "GPIO set" recommendations? Alternatively, NFC Marvell code you're referring to has parameters configured as Linux module parameters. I could do the same too, avoiding this device tree discussion. Let me know.
>

I don't completely follow what you mean by "GPIO set", but I'm
guessing that is not the right path.

> Generally speaking (pontification hat on :-)), what you're trying to do (description of the whole chip) is well beyond what say ACPI has done (I was involved some in the BT ACPI exercise a few years ago). BT UART interface is described in ACPI independently of other parts of the same combo chip. Requirements like that slow down the DT development in my opinion as companies are understandably reluctant to work with unrealistic goals. End of pontification. :-)
>

ACPI and DT are very different models in terms of abstraction and
governance. I'm not going to hash through all the details.

I'm not necessarily saying we have to have a single node, but that is
my default position. You have convince me that the functions are
completely independent and I cannot judge that if you are completely
ignoring the WiFi part. From Broadcom chips I've worked with, the
supplies at least are shared (something ACPI does not expose). Perhaps
we could fudge that and just require the same supply has to be
connected to each half. I still worry there could be other internal
inter-dependencies. Perhaps BT requires the SDIO clock to be active or
something like that. Maybe not on Broadcom chips, but on other vendors
and I have to care about them all.

Let's step back to what I'm asking for:

- A more specific compatible string. This should include the chip
name/number. You may not need it today, but it is insurance in case
you do find differences latter. The only impact is the match table in
your driver. You can also have a less specific compatible string if
you want that the driver can match on.

- Changing the location of the node. The node hierarchy implicitly
defines connections. You have a connection from the host UART to the
BT device. This needs to be described. Whether splitting BT and WiFi
nodes or not, I've already said it probably makes the most sense to
put this under the host uart node.

- Splitting the nodes. Here we are looking at doing either:

serial@1234 {
  compatible = "some-soc-uart";

  brcm43340 {
    compatible = "brcm,brcm43340";
    sdio-host = <&soc-sdhost>;
    // BT props
    // WiFi props
  };
};

Or:

serial@1234 {
  compatible = "some-soc-uart";

  brcm43340 {
    compatible = "brcm,brcm43340-bt";
    // BT props
  };
};

mmc@5678 {
  compatible = "some-soc-sdhci";

  brcm43340@0 {
    reg = <0>;
    compatible = "brcm,brcm43340-wifi";
    // WiFi props
  };
};

Or maybe it is the latter example but we just add phandle links
between the 2 nodes.

We haven't even considered what happens when a chip also has FM, NFC,
and/or GPS. Nor have we considered how to describe the audio
connection to the host processor, but we've got nothing common and
that can probably come latter.

We need to agree figuring all this out is needed. Otherwise, this
whole conversation is a waste of time.

>>
>>> +       - tty : tty device connected to this Bluetooth device.
>>
>> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
>> is no guarantee which uart is assigned ttyS0.
>>
>> This should be a phandle to the connected uart if not a sub node of
>> the uart. This is complicated since these chips have multiple host
>> connections. It needs to go under either uart or SDIO host and have a
>> reference back to the one it is not under. Given the SDIO interface is
>> discoverable (although sideband gpios and regulators are not), I would
>> put this under the uart node as that is never discoverable.
>>
>> As I've mentioned previously, there's several cases of bindings for
>> UART slave devices being posted. This all needs to be coordinated to
>> use a common structure.
>>
>> IF: This driver does not really access the UART. If just needs to have a string of some sort to map instances of the BlueZ protocol into platform devices to employ the right GPIOs and interrupts. I could use anything you recommend available through the tty_struct coming to the protocol from the BlueZ line discipline. Moreover, every end user platform I've ever dealt with in 16 years of working with Bluetooth had a single BT UART device. So these are really rare (typically test platforms) cases only. The mapping is not needed for most platforms at all. I suspect the right thing to do would be to make this parameter optional. The mapping would be done only if the parameter is present. I will use anything tty_struct derived you specify. Makes sense?
>
>
> You've missed my point. I'm not talking about connecting multiple
> devices to a UART at once. There are several instances of people
> trying to add UART connected devices into DT[1][2]. My point is these
> devices all need to have the DT binding done in a common way across
> different platforms. Otherwise, we can not have common code to parse
> the DT and find devices attached to a UART.
>
> IF: Chances are I was not clear enough. I was not talking about connecting multiple devices to a UART. I was talking about connecting one Broadcom BT device to one serial port and another Broadcom BT device to another serial port (rare enough setup). I do understand your goals though. I would be happy to participate in that exercise (subject to the management approval) once DT has published the UART device parameters and the Linux bluetooth-next has support for DT enumerated devices. I don’t see it happening soon though. Marvell example you've referred me to has nothing of the sort. What do you think of allowing us something to ship now with an understanding that we would support your UART enumerated devices once they are published?

Okay. Several people want to describe a connection between a host uart
and a device connected to the uart (BT, NFC, GPS, etc.). You are doing
this with your "tty" property. My goal and requirement is that this
connection be described in DT in the same way regardless of the device
attached. Just like all I2C device connections are described by being
child nodes under the I2C host regardless of the type of I2C device
attached.

Rob

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-19 15:47                           ` Rob Herring
  0 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-19 15:47 UTC (permalink / raw)
  To: Ilya Faenson
  Cc: marcel@holtmann.org, Arend Van Spriel, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson <ifaenson@broadcom.com> wrote=
:
> Hi Rob.
>
> -----Original Message-----
> From: linux-bluetooth-owner@vger.kernel.org [mailto:linux-bluetooth-owner=
@vger.kernel.org] On Behalf Of Rob Herring
> Sent: Thursday, June 18, 2015 3:41 PM
> To: Ilya Faenson
> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; li=
nux-bluetooth@vger.kernel.org
> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindi=
ngs
>
> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson <ifaenson@broadcom.com> wro=
te:
>> Hi Rob,
>
> Your emails are base64 encoded. They should be plain text for the list.
>
> IF: The Outlook is configured to respond in the sender's format. I theref=
ore respond in the encoding you've used.

I assure you that that is not the case or I would be banished from
lists by now. Outlook is generally incapable of correctly sending
mails to lists. The reply header above is one aspect of that. The
other problem is your replies don't get wrapped and prefixed properly.
That could be my client I guess, but *all* other mails are fine.

My sent mails have:

Content-Type: text/plain; charset=3DUTF-8
Content-Transfer-Encoding: quoted-printable


>> -----Original Message-----
>> From: Rob Herring [mailto:robherring2@gmail.com]
>> Sent: Thursday, June 18, 2015 11:03 AM
>> To: Ilya Faenson
>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; l=
inux-bluetooth@vger.kernel.org
>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bind=
ings
>>
>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson@broadcom.com> wr=
ote:
>>> + devicetree lists
>
> [...]
>
>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt =
b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>> new file mode 100644
>>> index 0000000..5dbcd57
>>> --- /dev/null
>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>> @@ -0,0 +1,86 @@
>>> +btbcm
>>> +------
>>> +
>>> +Required properties:
>>> +
>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>
>> You need to describe the chip, not the interface.
>>
>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>
> BT only chips? Most/many Broadcom chips are combo chips. I understand
> the driver for BT is *mostly* separate from other chip functions like
> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
> likely there are some parts shared: a voltage rail, reset line, or
> power down line. I think some can do BT over the SDIO interface too,
> so the interface may be shared. The DT is a description of the h/w
> (i.e. what part # for a chip) and not a driver data structure. You
> need to describe the whole chip in the binding. It is a Linux problem
> if there needs to be multiple separate drivers.
>
> IF: Defining complete DT description for the Broadcom combo chips for mul=
tiple interfaces is well beyond the scope of what I am doing. I just need t=
o define a DT node for the input and output GPIOs connected to the BT UART =
chip. BT may or may not be part of the combo chip: it does not really matte=
r for this exercise. I thought I would take this opportunity to place some =
BT device parameters into that node as well. If you're not comfortable with=
 this, I could just call it a "GPIO set" to avoid mentioning BT and UART at=
 all but it would make little sense. Still, I could consider it. Would you =
have "GPIO set" recommendations? Alternatively, NFC Marvell code you're ref=
erring to has parameters configured as Linux module parameters. I could do =
the same too, avoiding this device tree discussion. Let me know.
>

I don't completely follow what you mean by "GPIO set", but I'm
guessing that is not the right path.

> Generally speaking (pontification hat on :-)), what you're trying to do (=
description of the whole chip) is well beyond what say ACPI has done (I was=
 involved some in the BT ACPI exercise a few years ago). BT UART interface =
is described in ACPI independently of other parts of the same combo chip. R=
equirements like that slow down the DT development in my opinion as compani=
es are understandably reluctant to work with unrealistic goals. End of pont=
ification. :-)
>

ACPI and DT are very different models in terms of abstraction and
governance. I'm not going to hash through all the details.

I'm not necessarily saying we have to have a single node, but that is
my default position. You have convince me that the functions are
completely independent and I cannot judge that if you are completely
ignoring the WiFi part. From Broadcom chips I've worked with, the
supplies at least are shared (something ACPI does not expose). Perhaps
we could fudge that and just require the same supply has to be
connected to each half. I still worry there could be other internal
inter-dependencies. Perhaps BT requires the SDIO clock to be active or
something like that. Maybe not on Broadcom chips, but on other vendors
and I have to care about them all.

Let's step back to what I'm asking for:

- A more specific compatible string. This should include the chip
name/number. You may not need it today, but it is insurance in case
you do find differences latter. The only impact is the match table in
your driver. You can also have a less specific compatible string if
you want that the driver can match on.

- Changing the location of the node. The node hierarchy implicitly
defines connections. You have a connection from the host UART to the
BT device. This needs to be described. Whether splitting BT and WiFi
nodes or not, I've already said it probably makes the most sense to
put this under the host uart node.

- Splitting the nodes. Here we are looking at doing either:

serial@1234 {
  compatible =3D "some-soc-uart";

  brcm43340 {
    compatible =3D "brcm,brcm43340";
    sdio-host =3D <&soc-sdhost>;
    // BT props
    // WiFi props
  };
};

Or:

serial@1234 {
  compatible =3D "some-soc-uart";

  brcm43340 {
    compatible =3D "brcm,brcm43340-bt";
    // BT props
  };
};

mmc@5678 {
  compatible =3D "some-soc-sdhci";

  brcm43340@0 {
    reg =3D <0>;
    compatible =3D "brcm,brcm43340-wifi";
    // WiFi props
  };
};

Or maybe it is the latter example but we just add phandle links
between the 2 nodes.

We haven't even considered what happens when a chip also has FM, NFC,
and/or GPS. Nor have we considered how to describe the audio
connection to the host processor, but we've got nothing common and
that can probably come latter.

We need to agree figuring all this out is needed. Otherwise, this
whole conversation is a waste of time.

>>
>>> +       - tty : tty device connected to this Bluetooth device.
>>
>> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
>> is no guarantee which uart is assigned ttyS0.
>>
>> This should be a phandle to the connected uart if not a sub node of
>> the uart. This is complicated since these chips have multiple host
>> connections. It needs to go under either uart or SDIO host and have a
>> reference back to the one it is not under. Given the SDIO interface is
>> discoverable (although sideband gpios and regulators are not), I would
>> put this under the uart node as that is never discoverable.
>>
>> As I've mentioned previously, there's several cases of bindings for
>> UART slave devices being posted. This all needs to be coordinated to
>> use a common structure.
>>
>> IF: This driver does not really access the UART. If just needs to have a=
 string of some sort to map instances of the BlueZ protocol into platform d=
evices to employ the right GPIOs and interrupts. I could use anything you r=
ecommend available through the tty_struct coming to the protocol from the B=
lueZ line discipline. Moreover, every end user platform I've ever dealt wit=
h in 16 years of working with Bluetooth had a single BT UART device. So the=
se are really rare (typically test platforms) cases only. The mapping is no=
t needed for most platforms at all. I suspect the right thing to do would b=
e to make this parameter optional. The mapping would be done only if the pa=
rameter is present. I will use anything tty_struct derived you specify. Mak=
es sense?
>
>
> You've missed my point. I'm not talking about connecting multiple
> devices to a UART at once. There are several instances of people
> trying to add UART connected devices into DT[1][2]. My point is these
> devices all need to have the DT binding done in a common way across
> different platforms. Otherwise, we can not have common code to parse
> the DT and find devices attached to a UART.
>
> IF: Chances are I was not clear enough. I was not talking about connectin=
g multiple devices to a UART. I was talking about connecting one Broadcom B=
T device to one serial port and another Broadcom BT device to another seria=
l port (rare enough setup). I do understand your goals though. I would be h=
appy to participate in that exercise (subject to the management approval) o=
nce DT has published the UART device parameters and the Linux bluetooth-nex=
t has support for DT enumerated devices. I don=E2=80=99t see it happening s=
oon though. Marvell example you've referred me to has nothing of the sort. =
What do you think of allowing us something to ship now with an understandin=
g that we would support your UART enumerated devices once they are publishe=
d?

Okay. Several people want to describe a connection between a host uart
and a device connected to the uart (BT, NFC, GPS, etc.). You are doing
this with your "tty" property. My goal and requirement is that this
connection be described in DT in the same way regardless of the device
attached. Just like all I2C device connections are described by being
child nodes under the I2C host regardless of the type of I2C device
attached.

Rob

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-19 15:47                           ` Rob Herring
@ 2015-06-19 17:06                               ` Arend van Spriel
  -1 siblings, 0 replies; 36+ messages in thread
From: Arend van Spriel @ 2015-06-19 17:06 UTC (permalink / raw)
  To: Rob Herring
  Cc: Ilya Faenson, marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

On 06/19/15 17:47, Rob Herring wrote:
> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>  wrote:
>> Hi Rob.
>>
>> -----Original Message-----
>> From: linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org [mailto:linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org] On Behalf Of Rob Herring
>> Sent: Thursday, June 18, 2015 3:41 PM
>> To: Ilya Faenson
>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TaqPxH82wqD4g@public.gmane.orgg; linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>>
>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>  wrote:
>>> Hi Rob,
>>
>> Your emails are base64 encoded. They should be plain text for the list.
>>
>> IF: The Outlook is configured to respond in the sender's format. I therefore respond in the encoding you've used.
>
> I assure you that that is not the case or I would be banished from
> lists by now. Outlook is generally incapable of correctly sending
> mails to lists. The reply header above is one aspect of that. The
> other problem is your replies don't get wrapped and prefixed properly.
> That could be my client I guess, but *all* other mails are fine.
>
> My sent mails have:
>
> Content-Type: text/plain; charset=UTF-8
> Content-Transfer-Encoding: quoted-printable
>
>
>>> -----Original Message-----
>>> From: Rob Herring [mailto:robherring2-Re5JQEeQqe8AvxtiuMwx3w@public.gmane.org]
>>> Sent: Thursday, June 18, 2015 11:03 AM
>>> To: Ilya Faenson
>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TbrhsbdSgBK9A@public.gmane.orgrg; linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>>>
>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>  wrote:
>>>> + devicetree lists
>>
>> [...]
>>
>>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>> new file mode 100644
>>>> index 0000000..5dbcd57
>>>> --- /dev/null
>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>> @@ -0,0 +1,86 @@
>>>> +btbcm
>>>> +------
>>>> +
>>>> +Required properties:
>>>> +
>>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>>
>>> You need to describe the chip, not the interface.
>>>
>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>
>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>> the driver for BT is *mostly* separate from other chip functions like
>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>> likely there are some parts shared: a voltage rail, reset line, or
>> power down line. I think some can do BT over the SDIO interface too,
>> so the interface may be shared. The DT is a description of the h/w
>> (i.e. what part # for a chip) and not a driver data structure. You
>> need to describe the whole chip in the binding. It is a Linux problem
>> if there needs to be multiple separate drivers.
>>
>> IF: Defining complete DT description for the Broadcom combo chips for multiple interfaces is well beyond the scope of what I am doing. I just need to define a DT node for the input and output GPIOs connected to the BT UART chip. BT may or may not be part of the combo chip: it does not really matter for this exercise. I thought I would take this opportunity to place some BT device parameters into that node as well. If you're not comfortable with this, I could just call it a "GPIO set" to avoid mentioning BT and UART at all but it would make little sense. Still, I could consider it. Would you have "GPIO set" recommendations? Alternatively, NFC Marvell code you're referring to has parameters configured as Linux module parameters. I could do the same too, avoiding this device tree discussion. Let me know.
>>
>
> I don't completely follow what you mean by "GPIO set", but I'm
> guessing that is not the right path.
>
>> Generally speaking (pontification hat on :-)), what you're trying to do (description of the whole chip) is well beyond what say ACPI has done (I was involved some in the BT ACPI exercise a few years ago). BT UART interface is described in ACPI independently of other parts of the same combo chip. Requirements like that slow down the DT development in my opinion as companies are understandably reluctant to work with unrealistic goals. End of pontification. :-)
>>
>
> ACPI and DT are very different models in terms of abstraction and
> governance. I'm not going to hash through all the details.
>
> I'm not necessarily saying we have to have a single node, but that is
> my default position. You have convince me that the functions are
> completely independent and I cannot judge that if you are completely
> ignoring the WiFi part. From Broadcom chips I've worked with, the
> supplies at least are shared (something ACPI does not expose). Perhaps
> we could fudge that and just require the same supply has to be
> connected to each half. I still worry there could be other internal
> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
> something like that. Maybe not on Broadcom chips, but on other vendors
> and I have to care about them all.

All Broadcom combo chips that I know of have separate supplies, ie. 
wl-reg-on and bt-reg-on. There already is a binding present for the wifi 
part. Not extending that may seem ignorant, but as wifi and bt can have 
a separate interface to the host (admittedly they could share SDIO 
interface, but they would be exposed as a separate SDIO function) I did 
not see a reason to object against a separate binding for BT. Whether 
wifi and bt are on the same device does not seem like something that 
must be expressed in DT. The physical state may help in determining DT 
bindings, but it should not be mandatory in my opinion.

> Let's step back to what I'm asking for:
>
> - A more specific compatible string. This should include the chip
> name/number. You may not need it today, but it is insurance in case
> you do find differences latter. The only impact is the match table in
> your driver. You can also have a less specific compatible string if
> you want that the driver can match on.
>
> - Changing the location of the node. The node hierarchy implicitly
> defines connections. You have a connection from the host UART to the
> BT device. This needs to be described. Whether splitting BT and WiFi
> nodes or not, I've already said it probably makes the most sense to
> put this under the host uart node.
>
> - Splitting the nodes. Here we are looking at doing either:
>
> serial@1234 {
>    compatible = "some-soc-uart";
>
>    brcm43340 {
>      compatible = "brcm,brcm43340";
>      sdio-host =<&soc-sdhost>;
>      // BT props
>      // WiFi props
>    };
> };
>
> Or:
>
> serial@1234 {
>    compatible = "some-soc-uart";
>
>    brcm43340 {
>      compatible = "brcm,brcm43340-bt";
>      // BT props
>    };
> };
>
> mmc@5678 {
>    compatible = "some-soc-sdhci";
>
>    brcm43340@0 {
>      reg =<0>;
>      compatible = "brcm,brcm43340-wifi";
>      // WiFi props
>    };
> };

This is more or less what is in the wifi binding today. See 
bindings/net/wireless/brcm,bcm43xx-fmac.txt.

Regards,
Arend

> Or maybe it is the latter example but we just add phandle links
> between the 2 nodes.
>
> We haven't even considered what happens when a chip also has FM, NFC,
> and/or GPS. Nor have we considered how to describe the audio
> connection to the host processor, but we've got nothing common and
> that can probably come latter.
>
> We need to agree figuring all this out is needed. Otherwise, this
> whole conversation is a waste of time.
>
>>>
>>>> +       - tty : tty device connected to this Bluetooth device.
>>>
>>> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
>>> is no guarantee which uart is assigned ttyS0.
>>>
>>> This should be a phandle to the connected uart if not a sub node of
>>> the uart. This is complicated since these chips have multiple host
>>> connections. It needs to go under either uart or SDIO host and have a
>>> reference back to the one it is not under. Given the SDIO interface is
>>> discoverable (although sideband gpios and regulators are not), I would
>>> put this under the uart node as that is never discoverable.
>>>
>>> As I've mentioned previously, there's several cases of bindings for
>>> UART slave devices being posted. This all needs to be coordinated to
>>> use a common structure.
>>>
>>> IF: This driver does not really access the UART. If just needs to have a string of some sort to map instances of the BlueZ protocol into platform devices to employ the right GPIOs and interrupts. I could use anything you recommend available through the tty_struct coming to the protocol from the BlueZ line discipline. Moreover, every end user platform I've ever dealt with in 16 years of working with Bluetooth had a single BT UART device. So these are really rare (typically test platforms) cases only. The mapping is not needed for most platforms at all. I suspect the right thing to do would be to make this parameter optional. The mapping would be done only if the parameter is present. I will use anything tty_struct derived you specify. Makes sense?
>>
>>
>> You've missed my point. I'm not talking about connecting multiple
>> devices to a UART at once. There are several instances of people
>> trying to add UART connected devices into DT[1][2]. My point is these
>> devices all need to have the DT binding done in a common way across
>> different platforms. Otherwise, we can not have common code to parse
>> the DT and find devices attached to a UART.
>>
>> IF: Chances are I was not clear enough. I was not talking about connecting multiple devices to a UART. I was talking about connecting one Broadcom BT device to one serial port and another Broadcom BT device to another serial port (rare enough setup). I do understand your goals though. I would be happy to participate in that exercise (subject to the management approval) once DT has published the UART device parameters and the Linux bluetooth-next has support for DT enumerated devices. I don’t see it happening soon though. Marvell example you've referred me to has nothing of the sort. What do you think of allowing us something to ship now with an understanding that we would support your UART enumerated devices once they are published?
>
> Okay. Several people want to describe a connection between a host uart
> and a device connected to the uart (BT, NFC, GPS, etc.). You are doing
> this with your "tty" property. My goal and requirement is that this
> connection be described in DT in the same way regardless of the device
> attached. Just like all I2C device connections are described by being
> child nodes under the I2C host regardless of the type of I2C device
> attached.
>
> Rob

--
To unsubscribe from this list: send the line "unsubscribe devicetree" in

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-19 17:06                               ` Arend van Spriel
  0 siblings, 0 replies; 36+ messages in thread
From: Arend van Spriel @ 2015-06-19 17:06 UTC (permalink / raw)
  To: Rob Herring
  Cc: Ilya Faenson, marcel@holtmann.org, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

On 06/19/15 17:47, Rob Herring wrote:
> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson@broadcom.com>  wrote:
>> Hi Rob.
>>
>> -----Original Message-----
>> From: linux-bluetooth-owner@vger.kernel.org [mailto:linux-bluetooth-owner@vger.kernel.org] On Behalf Of Rob Herring
>> Sent: Thursday, June 18, 2015 3:41 PM
>> To: Ilya Faenson
>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>>
>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson@broadcom.com>  wrote:
>>> Hi Rob,
>>
>> Your emails are base64 encoded. They should be plain text for the list.
>>
>> IF: The Outlook is configured to respond in the sender's format. I therefore respond in the encoding you've used.
>
> I assure you that that is not the case or I would be banished from
> lists by now. Outlook is generally incapable of correctly sending
> mails to lists. The reply header above is one aspect of that. The
> other problem is your replies don't get wrapped and prefixed properly.
> That could be my client I guess, but *all* other mails are fine.
>
> My sent mails have:
>
> Content-Type: text/plain; charset=UTF-8
> Content-Transfer-Encoding: quoted-printable
>
>
>>> -----Original Message-----
>>> From: Rob Herring [mailto:robherring2@gmail.com]
>>> Sent: Thursday, June 18, 2015 11:03 AM
>>> To: Ilya Faenson
>>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>>>
>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson@broadcom.com>  wrote:
>>>> + devicetree lists
>>
>> [...]
>>
>>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>> new file mode 100644
>>>> index 0000000..5dbcd57
>>>> --- /dev/null
>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>> @@ -0,0 +1,86 @@
>>>> +btbcm
>>>> +------
>>>> +
>>>> +Required properties:
>>>> +
>>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>>
>>> You need to describe the chip, not the interface.
>>>
>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>
>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>> the driver for BT is *mostly* separate from other chip functions like
>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>> likely there are some parts shared: a voltage rail, reset line, or
>> power down line. I think some can do BT over the SDIO interface too,
>> so the interface may be shared. The DT is a description of the h/w
>> (i.e. what part # for a chip) and not a driver data structure. You
>> need to describe the whole chip in the binding. It is a Linux problem
>> if there needs to be multiple separate drivers.
>>
>> IF: Defining complete DT description for the Broadcom combo chips for multiple interfaces is well beyond the scope of what I am doing. I just need to define a DT node for the input and output GPIOs connected to the BT UART chip. BT may or may not be part of the combo chip: it does not really matter for this exercise. I thought I would take this opportunity to place some BT device parameters into that node as well. If you're not comfortable with this, I could just call it a "GPIO set" to avoid mentioning BT and UART at all but it would make little sense. Still, I could consider it. Would you have "GPIO set" recommendations? Alternatively, NFC Marvell code you're referring to has parameters configured as Linux module parameters. I could do the same too, avoiding this device tree discussion. Let me know.
>>
>
> I don't completely follow what you mean by "GPIO set", but I'm
> guessing that is not the right path.
>
>> Generally speaking (pontification hat on :-)), what you're trying to do (description of the whole chip) is well beyond what say ACPI has done (I was involved some in the BT ACPI exercise a few years ago). BT UART interface is described in ACPI independently of other parts of the same combo chip. Requirements like that slow down the DT development in my opinion as companies are understandably reluctant to work with unrealistic goals. End of pontification. :-)
>>
>
> ACPI and DT are very different models in terms of abstraction and
> governance. I'm not going to hash through all the details.
>
> I'm not necessarily saying we have to have a single node, but that is
> my default position. You have convince me that the functions are
> completely independent and I cannot judge that if you are completely
> ignoring the WiFi part. From Broadcom chips I've worked with, the
> supplies at least are shared (something ACPI does not expose). Perhaps
> we could fudge that and just require the same supply has to be
> connected to each half. I still worry there could be other internal
> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
> something like that. Maybe not on Broadcom chips, but on other vendors
> and I have to care about them all.

All Broadcom combo chips that I know of have separate supplies, ie. 
wl-reg-on and bt-reg-on. There already is a binding present for the wifi 
part. Not extending that may seem ignorant, but as wifi and bt can have 
a separate interface to the host (admittedly they could share SDIO 
interface, but they would be exposed as a separate SDIO function) I did 
not see a reason to object against a separate binding for BT. Whether 
wifi and bt are on the same device does not seem like something that 
must be expressed in DT. The physical state may help in determining DT 
bindings, but it should not be mandatory in my opinion.

> Let's step back to what I'm asking for:
>
> - A more specific compatible string. This should include the chip
> name/number. You may not need it today, but it is insurance in case
> you do find differences latter. The only impact is the match table in
> your driver. You can also have a less specific compatible string if
> you want that the driver can match on.
>
> - Changing the location of the node. The node hierarchy implicitly
> defines connections. You have a connection from the host UART to the
> BT device. This needs to be described. Whether splitting BT and WiFi
> nodes or not, I've already said it probably makes the most sense to
> put this under the host uart node.
>
> - Splitting the nodes. Here we are looking at doing either:
>
> serial@1234 {
>    compatible = "some-soc-uart";
>
>    brcm43340 {
>      compatible = "brcm,brcm43340";
>      sdio-host =<&soc-sdhost>;
>      // BT props
>      // WiFi props
>    };
> };
>
> Or:
>
> serial@1234 {
>    compatible = "some-soc-uart";
>
>    brcm43340 {
>      compatible = "brcm,brcm43340-bt";
>      // BT props
>    };
> };
>
> mmc@5678 {
>    compatible = "some-soc-sdhci";
>
>    brcm43340@0 {
>      reg =<0>;
>      compatible = "brcm,brcm43340-wifi";
>      // WiFi props
>    };
> };

This is more or less what is in the wifi binding today. See 
bindings/net/wireless/brcm,bcm43xx-fmac.txt.

Regards,
Arend

> Or maybe it is the latter example but we just add phandle links
> between the 2 nodes.
>
> We haven't even considered what happens when a chip also has FM, NFC,
> and/or GPS. Nor have we considered how to describe the audio
> connection to the host processor, but we've got nothing common and
> that can probably come latter.
>
> We need to agree figuring all this out is needed. Otherwise, this
> whole conversation is a waste of time.
>
>>>
>>>> +       - tty : tty device connected to this Bluetooth device.
>>>
>>> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
>>> is no guarantee which uart is assigned ttyS0.
>>>
>>> This should be a phandle to the connected uart if not a sub node of
>>> the uart. This is complicated since these chips have multiple host
>>> connections. It needs to go under either uart or SDIO host and have a
>>> reference back to the one it is not under. Given the SDIO interface is
>>> discoverable (although sideband gpios and regulators are not), I would
>>> put this under the uart node as that is never discoverable.
>>>
>>> As I've mentioned previously, there's several cases of bindings for
>>> UART slave devices being posted. This all needs to be coordinated to
>>> use a common structure.
>>>
>>> IF: This driver does not really access the UART. If just needs to have a string of some sort to map instances of the BlueZ protocol into platform devices to employ the right GPIOs and interrupts. I could use anything you recommend available through the tty_struct coming to the protocol from the BlueZ line discipline. Moreover, every end user platform I've ever dealt with in 16 years of working with Bluetooth had a single BT UART device. So these are really rare (typically test platforms) cases only. The mapping is not needed for most platforms at all. I suspect the right thing to do would be to make this parameter optional. The mapping would be done only if the parameter is present. I will use anything tty_struct derived you specify. Makes sense?
>>
>>
>> You've missed my point. I'm not talking about connecting multiple
>> devices to a UART at once. There are several instances of people
>> trying to add UART connected devices into DT[1][2]. My point is these
>> devices all need to have the DT binding done in a common way across
>> different platforms. Otherwise, we can not have common code to parse
>> the DT and find devices attached to a UART.
>>
>> IF: Chances are I was not clear enough. I was not talking about connecting multiple devices to a UART. I was talking about connecting one Broadcom BT device to one serial port and another Broadcom BT device to another serial port (rare enough setup). I do understand your goals though. I would be happy to participate in that exercise (subject to the management approval) once DT has published the UART device parameters and the Linux bluetooth-next has support for DT enumerated devices. I don’t see it happening soon though. Marvell example you've referred me to has nothing of the sort. What do you think of allowing us something to ship now with an understanding that we would support your UART enumerated devices once they are published?
>
> Okay. Several people want to describe a connection between a host uart
> and a device connected to the uart (BT, NFC, GPS, etc.). You are doing
> this with your "tty" property. My goal and requirement is that this
> connection be described in DT in the same way regardless of the device
> attached. Just like all I2C device connections are described by being
> child nodes under the I2C host regardless of the type of I2C device
> attached.
>
> Rob

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-19 17:06                               ` Arend van Spriel
@ 2015-06-19 18:49                                   ` Rob Herring
  -1 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-19 18:49 UTC (permalink / raw)
  To: Arend van Spriel
  Cc: Ilya Faenson, marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel <arend-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
> On 06/19/15 17:47, Rob Herring wrote:
>>
>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>> wrote:
>>>
>>> Hi Rob.
>>>
>>> -----Original Message-----
>>> From: linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>> [mailto:linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org] On Behalf Of Rob Herring
>>> Sent: Thursday, June 18, 2015 3:41 PM
>>> To: Ilya Faenson
>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>> bindings
>>>
>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>> wrote:
>>>>
>>>> Hi Rob,
>>>
>>>
>>> Your emails are base64 encoded. They should be plain text for the list.
>>>
>>> IF: The Outlook is configured to respond in the sender's format. I
>>> therefore respond in the encoding you've used.
>>
>>
>> I assure you that that is not the case or I would be banished from
>> lists by now. Outlook is generally incapable of correctly sending
>> mails to lists. The reply header above is one aspect of that. The
>> other problem is your replies don't get wrapped and prefixed properly.
>> That could be my client I guess, but *all* other mails are fine.
>>
>> My sent mails have:
>>
>> Content-Type: text/plain; charset=UTF-8
>> Content-Transfer-Encoding: quoted-printable
>>
>>
>>>> -----Original Message-----
>>>> From: Rob Herring [mailto:robherring2-Re5JQEeQqe8AvxtiuMwx3w@public.gmane.org]
>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>> To: Ilya Faenson
>>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>> bindings
>>>>
>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>> wrote:
>>>>>
>>>>> + devicetree lists
>>>
>>>
>>> [...]
>>>
>>>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>> new file mode 100644
>>>>> index 0000000..5dbcd57
>>>>> --- /dev/null
>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>> @@ -0,0 +1,86 @@
>>>>> +btbcm
>>>>> +------
>>>>> +
>>>>> +Required properties:
>>>>> +
>>>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>>>
>>>>
>>>> You need to describe the chip, not the interface.
>>>>
>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>
>>>
>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>> the driver for BT is *mostly* separate from other chip functions like
>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>> likely there are some parts shared: a voltage rail, reset line, or
>>> power down line. I think some can do BT over the SDIO interface too,
>>> so the interface may be shared. The DT is a description of the h/w
>>> (i.e. what part # for a chip) and not a driver data structure. You
>>> need to describe the whole chip in the binding. It is a Linux problem
>>> if there needs to be multiple separate drivers.
>>>
>>> IF: Defining complete DT description for the Broadcom combo chips for
>>> multiple interfaces is well beyond the scope of what I am doing. I just need
>>> to define a DT node for the input and output GPIOs connected to the BT UART
>>> chip. BT may or may not be part of the combo chip: it does not really matter
>>> for this exercise. I thought I would take this opportunity to place some BT
>>> device parameters into that node as well. If you're not comfortable with
>>> this, I could just call it a "GPIO set" to avoid mentioning BT and UART at
>>> all but it would make little sense. Still, I could consider it. Would you
>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code you're
>>> referring to has parameters configured as Linux module parameters. I could
>>> do the same too, avoiding this device tree discussion. Let me know.
>>>
>>
>> I don't completely follow what you mean by "GPIO set", but I'm
>> guessing that is not the right path.
>>
>>> Generally speaking (pontification hat on :-)), what you're trying to do
>>> (description of the whole chip) is well beyond what say ACPI has done (I was
>>> involved some in the BT ACPI exercise a few years ago). BT UART interface is
>>> described in ACPI independently of other parts of the same combo chip.
>>> Requirements like that slow down the DT development in my opinion as
>>> companies are understandably reluctant to work with unrealistic goals. End
>>> of pontification. :-)
>>>
>>
>> ACPI and DT are very different models in terms of abstraction and
>> governance. I'm not going to hash through all the details.
>>
>> I'm not necessarily saying we have to have a single node, but that is
>> my default position. You have convince me that the functions are
>> completely independent and I cannot judge that if you are completely
>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>> supplies at least are shared (something ACPI does not expose). Perhaps
>> we could fudge that and just require the same supply has to be
>> connected to each half. I still worry there could be other internal
>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>> something like that. Maybe not on Broadcom chips, but on other vendors
>> and I have to care about them all.
>
>
> All Broadcom combo chips that I know of have separate supplies, ie.
> wl-reg-on and bt-reg-on. There already is a binding present for the wifi

GPIOs are not supplies. For the module I'm working with (43340 based)
there is a single VDDIO and VBAT supplies which are shared. Now
whether the module or the chip are tying things together, I don't
know. There is also a 32kHz clock input. Is that part of WiFi or BT?

> part. Not extending that may seem ignorant, but as wifi and bt can have a
> separate interface to the host (admittedly they could share SDIO interface,
> but they would be exposed as a separate SDIO function) I did not see a
> reason to object against a separate binding for BT. Whether wifi and bt are
> on the same device does not seem like something that must be expressed in
> DT. The physical state may help in determining DT bindings, but it should
> not be mandatory in my opinion.

We don't need it in DT until we do. Soon as there is some some
interdependence, something in DT will be needed.

Rob

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-19 18:49                                   ` Rob Herring
  0 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-06-19 18:49 UTC (permalink / raw)
  To: Arend van Spriel
  Cc: Ilya Faenson, marcel@holtmann.org, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel <arend@broadcom.com> wrote:
> On 06/19/15 17:47, Rob Herring wrote:
>>
>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson@broadcom.com>
>> wrote:
>>>
>>> Hi Rob.
>>>
>>> -----Original Message-----
>>> From: linux-bluetooth-owner@vger.kernel.org
>>> [mailto:linux-bluetooth-owner@vger.kernel.org] On Behalf Of Rob Herring
>>> Sent: Thursday, June 18, 2015 3:41 PM
>>> To: Ilya Faenson
>>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org;
>>> linux-bluetooth@vger.kernel.org
>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>> bindings
>>>
>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson@broadcom.com>
>>> wrote:
>>>>
>>>> Hi Rob,
>>>
>>>
>>> Your emails are base64 encoded. They should be plain text for the list.
>>>
>>> IF: The Outlook is configured to respond in the sender's format. I
>>> therefore respond in the encoding you've used.
>>
>>
>> I assure you that that is not the case or I would be banished from
>> lists by now. Outlook is generally incapable of correctly sending
>> mails to lists. The reply header above is one aspect of that. The
>> other problem is your replies don't get wrapped and prefixed properly.
>> That could be my client I guess, but *all* other mails are fine.
>>
>> My sent mails have:
>>
>> Content-Type: text/plain; charset=UTF-8
>> Content-Transfer-Encoding: quoted-printable
>>
>>
>>>> -----Original Message-----
>>>> From: Rob Herring [mailto:robherring2@gmail.com]
>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>> To: Ilya Faenson
>>>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org;
>>>> linux-bluetooth@vger.kernel.org
>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>> bindings
>>>>
>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>> wrote:
>>>>>
>>>>> + devicetree lists
>>>
>>>
>>> [...]
>>>
>>>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>> new file mode 100644
>>>>> index 0000000..5dbcd57
>>>>> --- /dev/null
>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>> @@ -0,0 +1,86 @@
>>>>> +btbcm
>>>>> +------
>>>>> +
>>>>> +Required properties:
>>>>> +
>>>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>>>
>>>>
>>>> You need to describe the chip, not the interface.
>>>>
>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>
>>>
>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>> the driver for BT is *mostly* separate from other chip functions like
>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>> likely there are some parts shared: a voltage rail, reset line, or
>>> power down line. I think some can do BT over the SDIO interface too,
>>> so the interface may be shared. The DT is a description of the h/w
>>> (i.e. what part # for a chip) and not a driver data structure. You
>>> need to describe the whole chip in the binding. It is a Linux problem
>>> if there needs to be multiple separate drivers.
>>>
>>> IF: Defining complete DT description for the Broadcom combo chips for
>>> multiple interfaces is well beyond the scope of what I am doing. I just need
>>> to define a DT node for the input and output GPIOs connected to the BT UART
>>> chip. BT may or may not be part of the combo chip: it does not really matter
>>> for this exercise. I thought I would take this opportunity to place some BT
>>> device parameters into that node as well. If you're not comfortable with
>>> this, I could just call it a "GPIO set" to avoid mentioning BT and UART at
>>> all but it would make little sense. Still, I could consider it. Would you
>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code you're
>>> referring to has parameters configured as Linux module parameters. I could
>>> do the same too, avoiding this device tree discussion. Let me know.
>>>
>>
>> I don't completely follow what you mean by "GPIO set", but I'm
>> guessing that is not the right path.
>>
>>> Generally speaking (pontification hat on :-)), what you're trying to do
>>> (description of the whole chip) is well beyond what say ACPI has done (I was
>>> involved some in the BT ACPI exercise a few years ago). BT UART interface is
>>> described in ACPI independently of other parts of the same combo chip.
>>> Requirements like that slow down the DT development in my opinion as
>>> companies are understandably reluctant to work with unrealistic goals. End
>>> of pontification. :-)
>>>
>>
>> ACPI and DT are very different models in terms of abstraction and
>> governance. I'm not going to hash through all the details.
>>
>> I'm not necessarily saying we have to have a single node, but that is
>> my default position. You have convince me that the functions are
>> completely independent and I cannot judge that if you are completely
>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>> supplies at least are shared (something ACPI does not expose). Perhaps
>> we could fudge that and just require the same supply has to be
>> connected to each half. I still worry there could be other internal
>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>> something like that. Maybe not on Broadcom chips, but on other vendors
>> and I have to care about them all.
>
>
> All Broadcom combo chips that I know of have separate supplies, ie.
> wl-reg-on and bt-reg-on. There already is a binding present for the wifi

GPIOs are not supplies. For the module I'm working with (43340 based)
there is a single VDDIO and VBAT supplies which are shared. Now
whether the module or the chip are tying things together, I don't
know. There is also a 32kHz clock input. Is that part of WiFi or BT?

> part. Not extending that may seem ignorant, but as wifi and bt can have a
> separate interface to the host (admittedly they could share SDIO interface,
> but they would be exposed as a separate SDIO function) I did not see a
> reason to object against a separate binding for BT. Whether wifi and bt are
> on the same device does not seem like something that must be expressed in
> DT. The physical state may help in determining DT bindings, but it should
> not be mandatory in my opinion.

We don't need it in DT until we do. Soon as there is some some
interdependence, something in DT will be needed.

Rob

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-19 18:49                                   ` Rob Herring
@ 2015-06-19 19:20                                       ` Arend van Spriel
  -1 siblings, 0 replies; 36+ messages in thread
From: Arend van Spriel @ 2015-06-19 19:20 UTC (permalink / raw)
  To: Rob Herring
  Cc: Ilya Faenson, marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

On 06/19/15 20:49, Rob Herring wrote:
> On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel<arend-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>  wrote:
>> On 06/19/15 17:47, Rob Herring wrote:
>>>
>>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>> wrote:
>>>>
>>>> Hi Rob.
>>>>
>>>> -----Original Message-----
>>>> From: linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>> [mailto:linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org] On Behalf Of Rob Herring
>>>> Sent: Thursday, June 18, 2015 3:41 PM
>>>> To: Ilya Faenson
>>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>> bindings
>>>>
>>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>> wrote:
>>>>>
>>>>> Hi Rob,
>>>>
>>>>
>>>> Your emails are base64 encoded. They should be plain text for the list.
>>>>
>>>> IF: The Outlook is configured to respond in the sender's format. I
>>>> therefore respond in the encoding you've used.
>>>
>>>
>>> I assure you that that is not the case or I would be banished from
>>> lists by now. Outlook is generally incapable of correctly sending
>>> mails to lists. The reply header above is one aspect of that. The
>>> other problem is your replies don't get wrapped and prefixed properly.
>>> That could be my client I guess, but *all* other mails are fine.
>>>
>>> My sent mails have:
>>>
>>> Content-Type: text/plain; charset=UTF-8
>>> Content-Transfer-Encoding: quoted-printable
>>>
>>>
>>>>> -----Original Message-----
>>>>> From: Rob Herring [mailto:robherring2-Re5JQEeQqe8AvxtiuMwx3w@public.gmane.org]
>>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>>> To: Ilya Faenson
>>>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>> bindings
>>>>>
>>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>>> wrote:
>>>>>>
>>>>>> + devicetree lists
>>>>
>>>>
>>>> [...]
>>>>
>>>>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>> new file mode 100644
>>>>>> index 0000000..5dbcd57
>>>>>> --- /dev/null
>>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>> @@ -0,0 +1,86 @@
>>>>>> +btbcm
>>>>>> +------
>>>>>> +
>>>>>> +Required properties:
>>>>>> +
>>>>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>>>>
>>>>>
>>>>> You need to describe the chip, not the interface.
>>>>>
>>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>>
>>>>
>>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>>> the driver for BT is *mostly* separate from other chip functions like
>>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>>> likely there are some parts shared: a voltage rail, reset line, or
>>>> power down line. I think some can do BT over the SDIO interface too,
>>>> so the interface may be shared. The DT is a description of the h/w
>>>> (i.e. what part # for a chip) and not a driver data structure. You
>>>> need to describe the whole chip in the binding. It is a Linux problem
>>>> if there needs to be multiple separate drivers.
>>>>
>>>> IF: Defining complete DT description for the Broadcom combo chips for
>>>> multiple interfaces is well beyond the scope of what I am doing. I just need
>>>> to define a DT node for the input and output GPIOs connected to the BT UART
>>>> chip. BT may or may not be part of the combo chip: it does not really matter
>>>> for this exercise. I thought I would take this opportunity to place some BT
>>>> device parameters into that node as well. If you're not comfortable with
>>>> this, I could just call it a "GPIO set" to avoid mentioning BT and UART at
>>>> all but it would make little sense. Still, I could consider it. Would you
>>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code you're
>>>> referring to has parameters configured as Linux module parameters. I could
>>>> do the same too, avoiding this device tree discussion. Let me know.
>>>>
>>>
>>> I don't completely follow what you mean by "GPIO set", but I'm
>>> guessing that is not the right path.
>>>
>>>> Generally speaking (pontification hat on :-)), what you're trying to do
>>>> (description of the whole chip) is well beyond what say ACPI has done (I was
>>>> involved some in the BT ACPI exercise a few years ago). BT UART interface is
>>>> described in ACPI independently of other parts of the same combo chip.
>>>> Requirements like that slow down the DT development in my opinion as
>>>> companies are understandably reluctant to work with unrealistic goals. End
>>>> of pontification. :-)
>>>>
>>>
>>> ACPI and DT are very different models in terms of abstraction and
>>> governance. I'm not going to hash through all the details.
>>>
>>> I'm not necessarily saying we have to have a single node, but that is
>>> my default position. You have convince me that the functions are
>>> completely independent and I cannot judge that if you are completely
>>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>>> supplies at least are shared (something ACPI does not expose). Perhaps
>>> we could fudge that and just require the same supply has to be
>>> connected to each half. I still worry there could be other internal
>>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>>> something like that. Maybe not on Broadcom chips, but on other vendors
>>> and I have to care about them all.
>>
>>
>> All Broadcom combo chips that I know of have separate supplies, ie.
>> wl-reg-on and bt-reg-on. There already is a binding present for the wifi
>
> GPIOs are not supplies. For the module I'm working with (43340 based)
> there is a single VDDIO and VBAT supplies which are shared. Now
> whether the module or the chip are tying things together, I don't
> know. There is also a 32kHz clock input. Is that part of WiFi or BT?

True and I see where you are going here. The 32kHz clock is input for 
low-power oscillator in the chip. That LPO provides clock for the 
interconnect in the chip so it is not part of wifi nor bt.

>> part. Not extending that may seem ignorant, but as wifi and bt can have a
>> separate interface to the host (admittedly they could share SDIO interface,
>> but they would be exposed as a separate SDIO function) I did not see a
>> reason to object against a separate binding for BT. Whether wifi and bt are
>> on the same device does not seem like something that must be expressed in
>> DT. The physical state may help in determining DT bindings, but it should
>> not be mandatory in my opinion.
>
> We don't need it in DT until we do. Soon as there is some some
> interdependence, something in DT will be needed.

Agree.

Regards,
Arend

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-19 19:20                                       ` Arend van Spriel
  0 siblings, 0 replies; 36+ messages in thread
From: Arend van Spriel @ 2015-06-19 19:20 UTC (permalink / raw)
  To: Rob Herring
  Cc: Ilya Faenson, marcel@holtmann.org, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

On 06/19/15 20:49, Rob Herring wrote:
> On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel<arend@broadcom.com>  wrote:
>> On 06/19/15 17:47, Rob Herring wrote:
>>>
>>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson@broadcom.com>
>>> wrote:
>>>>
>>>> Hi Rob.
>>>>
>>>> -----Original Message-----
>>>> From: linux-bluetooth-owner@vger.kernel.org
>>>> [mailto:linux-bluetooth-owner@vger.kernel.org] On Behalf Of Rob Herring
>>>> Sent: Thursday, June 18, 2015 3:41 PM
>>>> To: Ilya Faenson
>>>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org;
>>>> linux-bluetooth@vger.kernel.org
>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>> bindings
>>>>
>>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>> wrote:
>>>>>
>>>>> Hi Rob,
>>>>
>>>>
>>>> Your emails are base64 encoded. They should be plain text for the list.
>>>>
>>>> IF: The Outlook is configured to respond in the sender's format. I
>>>> therefore respond in the encoding you've used.
>>>
>>>
>>> I assure you that that is not the case or I would be banished from
>>> lists by now. Outlook is generally incapable of correctly sending
>>> mails to lists. The reply header above is one aspect of that. The
>>> other problem is your replies don't get wrapped and prefixed properly.
>>> That could be my client I guess, but *all* other mails are fine.
>>>
>>> My sent mails have:
>>>
>>> Content-Type: text/plain; charset=UTF-8
>>> Content-Transfer-Encoding: quoted-printable
>>>
>>>
>>>>> -----Original Message-----
>>>>> From: Rob Herring [mailto:robherring2@gmail.com]
>>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>>> To: Ilya Faenson
>>>>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org;
>>>>> linux-bluetooth@vger.kernel.org
>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>> bindings
>>>>>
>>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>>> wrote:
>>>>>>
>>>>>> + devicetree lists
>>>>
>>>>
>>>> [...]
>>>>
>>>>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>> new file mode 100644
>>>>>> index 0000000..5dbcd57
>>>>>> --- /dev/null
>>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>> @@ -0,0 +1,86 @@
>>>>>> +btbcm
>>>>>> +------
>>>>>> +
>>>>>> +Required properties:
>>>>>> +
>>>>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>>>>
>>>>>
>>>>> You need to describe the chip, not the interface.
>>>>>
>>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>>
>>>>
>>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>>> the driver for BT is *mostly* separate from other chip functions like
>>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>>> likely there are some parts shared: a voltage rail, reset line, or
>>>> power down line. I think some can do BT over the SDIO interface too,
>>>> so the interface may be shared. The DT is a description of the h/w
>>>> (i.e. what part # for a chip) and not a driver data structure. You
>>>> need to describe the whole chip in the binding. It is a Linux problem
>>>> if there needs to be multiple separate drivers.
>>>>
>>>> IF: Defining complete DT description for the Broadcom combo chips for
>>>> multiple interfaces is well beyond the scope of what I am doing. I just need
>>>> to define a DT node for the input and output GPIOs connected to the BT UART
>>>> chip. BT may or may not be part of the combo chip: it does not really matter
>>>> for this exercise. I thought I would take this opportunity to place some BT
>>>> device parameters into that node as well. If you're not comfortable with
>>>> this, I could just call it a "GPIO set" to avoid mentioning BT and UART at
>>>> all but it would make little sense. Still, I could consider it. Would you
>>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code you're
>>>> referring to has parameters configured as Linux module parameters. I could
>>>> do the same too, avoiding this device tree discussion. Let me know.
>>>>
>>>
>>> I don't completely follow what you mean by "GPIO set", but I'm
>>> guessing that is not the right path.
>>>
>>>> Generally speaking (pontification hat on :-)), what you're trying to do
>>>> (description of the whole chip) is well beyond what say ACPI has done (I was
>>>> involved some in the BT ACPI exercise a few years ago). BT UART interface is
>>>> described in ACPI independently of other parts of the same combo chip.
>>>> Requirements like that slow down the DT development in my opinion as
>>>> companies are understandably reluctant to work with unrealistic goals. End
>>>> of pontification. :-)
>>>>
>>>
>>> ACPI and DT are very different models in terms of abstraction and
>>> governance. I'm not going to hash through all the details.
>>>
>>> I'm not necessarily saying we have to have a single node, but that is
>>> my default position. You have convince me that the functions are
>>> completely independent and I cannot judge that if you are completely
>>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>>> supplies at least are shared (something ACPI does not expose). Perhaps
>>> we could fudge that and just require the same supply has to be
>>> connected to each half. I still worry there could be other internal
>>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>>> something like that. Maybe not on Broadcom chips, but on other vendors
>>> and I have to care about them all.
>>
>>
>> All Broadcom combo chips that I know of have separate supplies, ie.
>> wl-reg-on and bt-reg-on. There already is a binding present for the wifi
>
> GPIOs are not supplies. For the module I'm working with (43340 based)
> there is a single VDDIO and VBAT supplies which are shared. Now
> whether the module or the chip are tying things together, I don't
> know. There is also a 32kHz clock input. Is that part of WiFi or BT?

True and I see where you are going here. The 32kHz clock is input for 
low-power oscillator in the chip. That LPO provides clock for the 
interconnect in the chip so it is not part of wifi nor bt.

>> part. Not extending that may seem ignorant, but as wifi and bt can have a
>> separate interface to the host (admittedly they could share SDIO interface,
>> but they would be exposed as a separate SDIO function) I did not see a
>> reason to object against a separate binding for BT. Whether wifi and bt are
>> on the same device does not seem like something that must be expressed in
>> DT. The physical state may help in determining DT bindings, but it should
>> not be mandatory in my opinion.
>
> We don't need it in DT until we do. Soon as there is some some
> interdependence, something in DT will be needed.

Agree.

Regards,
Arend
--
To unsubscribe from this list: send the line "unsubscribe linux-bluetooth" in

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

* Re: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-17 21:30 ` [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings Ilya Faenson
  2015-06-17 21:33   ` Arend van Spriel
       [not found]   ` <1434576658-20730-2-git-send-email-ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
@ 2015-06-19 19:23   ` Fabio Estevam
  2015-06-19 20:40     ` Ilya Faenson
  2 siblings, 1 reply; 36+ messages in thread
From: Fabio Estevam @ 2015-06-19 19:23 UTC (permalink / raw)
  To: Ilya Faenson; +Cc: Marcel Holtmann, linux-bluetooth, Arend van Spriel

On Wed, Jun 17, 2015 at 6:30 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:

> +Optional properties:
> +
> +  - bt-host-wake-gpios : bt-host-wake input GPIO to be used as an interrupt.
> +
> +  - bt-wake-gpios : bt-wake output GPIO to be used to suspend / resume device.
> +
> +  - bt-reg-on-gpios : reg-on output GPIO to be used to power device on/off.

Shouldn't this be modelled as a regulator instead? What if the board
drives a PMIC output to provide power to the BT interface?

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

* RE: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-19 15:47                           ` Rob Herring
@ 2015-06-19 20:37                               ` Ilya Faenson
  -1 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-19 20:37 UTC (permalink / raw)
  To: Rob Herring
  Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org, Arend Van Spriel,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

Hi Rob,

-----Original Message-----
From: Rob Herring [mailto:robherring2@gmail.com] 
Sent: Friday, June 19, 2015 11:48 AM
To: Ilya Faenson
Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings

On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:
> Hi Rob.
>
> -----Original Message-----
> From: linux-bluetooth-owner@vger.kernel.org [mailto:linux-bluetooth-owner@vger.kernel.org] On Behalf Of Rob Herring
> Sent: Thursday, June 18, 2015 3:41 PM
> To: Ilya Faenson
> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>
> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:
>> Hi Rob,
>
> Your emails are base64 encoded. They should be plain text for the list.
>
> IF: The Outlook is configured to respond in the sender's format. I therefore respond in the encoding you've used.

I assure you that that is not the case or I would be banished from
lists by now. Outlook is generally incapable of correctly sending
mails to lists. The reply header above is one aspect of that. The
other problem is your replies don't get wrapped and prefixed properly.
That could be my client I guess, but *all* other mails are fine.

My sent mails have:

Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: quoted-printable

IF: Unluckily, Outlook is what I am supposed to use. I post patches from the Ubuntu VM but I have the command line access to it only.

>> -----Original Message-----
>> From: Rob Herring [mailto:robherring2@gmail.com]
>> Sent: Thursday, June 18, 2015 11:03 AM
>> To: Ilya Faenson
>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org; linux-bluetooth@vger.kernel.org
>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
>>
>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson <ifaenson@broadcom.com> wrote:
>>> + devicetree lists
>
> [...]
>
>>> diff --git a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>> new file mode 100644
>>> index 0000000..5dbcd57
>>> --- /dev/null
>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>> @@ -0,0 +1,86 @@
>>> +btbcm
>>> +------
>>> +
>>> +Required properties:
>>> +
>>> +       - compatible : must be "brcm,brcm-bt-uart".
>>
>> You need to describe the chip, not the interface.
>>
>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>
> BT only chips? Most/many Broadcom chips are combo chips. I understand
> the driver for BT is *mostly* separate from other chip functions like
> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
> likely there are some parts shared: a voltage rail, reset line, or
> power down line. I think some can do BT over the SDIO interface too,
> so the interface may be shared. The DT is a description of the h/w
> (i.e. what part # for a chip) and not a driver data structure. You
> need to describe the whole chip in the binding. It is a Linux problem
> if there needs to be multiple separate drivers.
>
> IF: Defining complete DT description for the Broadcom combo chips for multiple interfaces is well beyond the scope of what I am doing. I just need to define a DT node for the input and output GPIOs connected to the BT UART chip. BT may or may not be part of the combo chip: it does not really matter for this exercise. I thought I would take this opportunity to place some BT device parameters into that node as well. If you're not comfortable with this, I could just call it a "GPIO set" to avoid mentioning BT and UART at all but it would make little sense. Still, I could consider it. Would you have "GPIO set" recommendations? Alternatively, NFC Marvell code you're referring to has parameters configured as Linux module parameters. I could do the same too, avoiding this device tree discussion. Let me know.
>

I don't completely follow what you mean by "GPIO set", but I'm
guessing that is not the right path.

> Generally speaking (pontification hat on :-)), what you're trying to do (description of the whole chip) is well beyond what say ACPI has done (I was involved some in the BT ACPI exercise a few years ago). BT UART interface is described in ACPI independently of other parts of the same combo chip. Requirements like that slow down the DT development in my opinion as companies are understandably reluctant to work with unrealistic goals. End of pontification. :-)
>

ACPI and DT are very different models in terms of abstraction and
governance. I'm not going to hash through all the details.

I'm not necessarily saying we have to have a single node, but that is
my default position. You have convince me that the functions are
completely independent and I cannot judge that if you are completely
ignoring the WiFi part. From Broadcom chips I've worked with, the
supplies at least are shared (something ACPI does not expose). Perhaps
we could fudge that and just require the same supply has to be
connected to each half. I still worry there could be other internal
inter-dependencies. Perhaps BT requires the SDIO clock to be active or
something like that. Maybe not on Broadcom chips, but on other vendors
and I have to care about them all.

Let's step back to what I'm asking for:

- A more specific compatible string. This should include the chip
name/number. You may not need it today, but it is insurance in case
you do find differences latter. The only impact is the match table in
your driver. You can also have a less specific compatible string if
you want that the driver can match on.

IF: Okay, I can change that.

- Changing the location of the node. The node hierarchy implicitly
defines connections. You have a connection from the host UART to the
BT device. This needs to be described. Whether splitting BT and WiFi
nodes or not, I've already said it probably makes the most sense to
put this under the host uart node.

IF: Okay, I have just tried placing my node under the UART. The platform driver probe is no longer called then though. What am I doing wrong? Pasting the relevant snippet:

IF: &uart1 {
IF:         status = "okay";
IF:         ...
IF:         bcm4354_bt_uart: bcm4354-bt-uart {
IF:                 compatible = "brcm,brcm4354-bt-uart";
IF:                 bt-wake-gpios = <&gpio4 30 GPIO_ACTIVE_HIGH>;
IF:                 ...
IF:         };
IF: };

- Splitting the nodes. Here we are looking at doing either:

serial@1234 {
  compatible = "some-soc-uart";

  brcm43340 {
    compatible = "brcm,brcm43340";
    sdio-host = <&soc-sdhost>;
    // BT props
    // WiFi props
  };
};

Or:

serial@1234 {
  compatible = "some-soc-uart";

  brcm43340 {
    compatible = "brcm,brcm43340-bt";
    // BT props
  };
};

mmc@5678 {
  compatible = "some-soc-sdhci";

  brcm43340@0 {
    reg = <0>;
    compatible = "brcm,brcm43340-wifi";
    // WiFi props
  };
};

Or maybe it is the latter example but we just add phandle links
between the 2 nodes.

We haven't even considered what happens when a chip also has FM, NFC,
and/or GPS. Nor have we considered how to describe the audio
connection to the host processor, but we've got nothing common and
that can probably come latter.

We need to agree figuring all this out is needed. Otherwise, this
whole conversation is a waste of time.

IF: Appreciate the detailed elaborations. The latter example with phandle links sounds reasonable to me. I am afraid I'm not in a position to agree to everything though as I'm responsible for the BT only. Arend Van Spriel representing Broadcom WLAN has started talking to you: that's good.

>>
>>> +       - tty : tty device connected to this Bluetooth device.
>>
>> "tty" is a bit of a Linuxism and "ttyS0" certainly is. Further, there
>> is no guarantee which uart is assigned ttyS0.
>>
>> This should be a phandle to the connected uart if not a sub node of
>> the uart. This is complicated since these chips have multiple host
>> connections. It needs to go under either uart or SDIO host and have a
>> reference back to the one it is not under. Given the SDIO interface is
>> discoverable (although sideband gpios and regulators are not), I would
>> put this under the uart node as that is never discoverable.
>>
>> As I've mentioned previously, there's several cases of bindings for
>> UART slave devices being posted. This all needs to be coordinated to
>> use a common structure.
>>
>> IF: This driver does not really access the UART. If just needs to have a string of some sort to map instances of the BlueZ protocol into platform devices to employ the right GPIOs and interrupts. I could use anything you recommend available through the tty_struct coming to the protocol from the BlueZ line discipline. Moreover, every end user platform I've ever dealt with in 16 years of working with Bluetooth had a single BT UART device. So these are really rare (typically test platforms) cases only. The mapping is not needed for most platforms at all. I suspect the right thing to do would be to make this parameter optional. The mapping would be done only if the parameter is present. I will use anything tty_struct derived you specify. Makes sense?
>
>
> You've missed my point. I'm not talking about connecting multiple
> devices to a UART at once. There are several instances of people
> trying to add UART connected devices into DT[1][2]. My point is these
> devices all need to have the DT binding done in a common way across
> different platforms. Otherwise, we can not have common code to parse
> the DT and find devices attached to a UART.
>
> IF: Chances are I was not clear enough. I was not talking about connecting multiple devices to a UART. I was talking about connecting one Broadcom BT device to one serial port and another Broadcom BT device to another serial port (rare enough setup). I do understand your goals though. I would be happy to participate in that exercise (subject to the management approval) once DT has published the UART device parameters and the Linux bluetooth-next has support for DT enumerated devices. I don’t see it happening soon though. Marvell example you've referred me to has nothing of the sort. What do you think of allowing us something to ship now with an understanding that we would support your UART enumerated devices once they are published?

Okay. Several people want to describe a connection between a host uart
and a device connected to the uart (BT, NFC, GPS, etc.). You are doing
this with your "tty" property. My goal and requirement is that this
connection be described in DT in the same way regardless of the device
attached. Just like all I2C device connections are described by being
child nodes under the I2C host regardless of the type of I2C device
attached.

IF: All good points, Rob. I will certainly get rid of the tty property if I can make the child device idea work. My complication is in the need to map say the DT device parent (UART) into the tty_struct used by the Linux BlueZ protocol. Any ideas on how to implement that ? Many thanks!

Rob

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

* RE: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-19 20:37                               ` Ilya Faenson
  0 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-19 20:37 UTC (permalink / raw)
  To: Rob Herring
  Cc: marcel@holtmann.org, Arend Van Spriel, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

SGkgUm9iLA0KDQotLS0tLU9yaWdpbmFsIE1lc3NhZ2UtLS0tLQ0KRnJvbTogUm9iIEhlcnJpbmcg
W21haWx0bzpyb2JoZXJyaW5nMkBnbWFpbC5jb21dIA0KU2VudDogRnJpZGF5LCBKdW5lIDE5LCAy
MDE1IDExOjQ4IEFNDQpUbzogSWx5YSBGYWVuc29uDQpDYzogbWFyY2VsQGhvbHRtYW5uLm9yZzsg
QXJlbmQgVmFuIFNwcmllbDsgZGV2aWNldHJlZUB2Z2VyLmtlcm5lbC5vcmc7IGxpbnV4LWJsdWV0
b290aEB2Z2VyLmtlcm5lbC5vcmcNClN1YmplY3Q6IFJlOiBGVzogW1BBVENIIHY0IDEvNF0gQnJv
YWRjb20gQmx1ZXRvb3RoIFVBUlQgRGV2aWNlIFRyZWUgYmluZGluZ3MNCg0KT24gVGh1LCBKdW4g
MTgsIDIwMTUgYXQgMzozNyBQTSwgSWx5YSBGYWVuc29uIDxpZmFlbnNvbkBicm9hZGNvbS5jb20+
IHdyb3RlOg0KPiBIaSBSb2IuDQo+DQo+IC0tLS0tT3JpZ2luYWwgTWVzc2FnZS0tLS0tDQo+IEZy
b206IGxpbnV4LWJsdWV0b290aC1vd25lckB2Z2VyLmtlcm5lbC5vcmcgW21haWx0bzpsaW51eC1i
bHVldG9vdGgtb3duZXJAdmdlci5rZXJuZWwub3JnXSBPbiBCZWhhbGYgT2YgUm9iIEhlcnJpbmcN
Cj4gU2VudDogVGh1cnNkYXksIEp1bmUgMTgsIDIwMTUgMzo0MSBQTQ0KPiBUbzogSWx5YSBGYWVu
c29uDQo+IENjOiBtYXJjZWxAaG9sdG1hbm4ub3JnOyBBcmVuZCBWYW4gU3ByaWVsOyBkZXZpY2V0
cmVlQHZnZXIua2VybmVsLm9yZzsgbGludXgtYmx1ZXRvb3RoQHZnZXIua2VybmVsLm9yZw0KPiBT
dWJqZWN0OiBSZTogRlc6IFtQQVRDSCB2NCAxLzRdIEJyb2FkY29tIEJsdWV0b290aCBVQVJUIERl
dmljZSBUcmVlIGJpbmRpbmdzDQo+DQo+IE9uIFRodSwgSnVuIDE4LCAyMDE1IGF0IDE6NTQgUE0s
IElseWEgRmFlbnNvbiA8aWZhZW5zb25AYnJvYWRjb20uY29tPiB3cm90ZToNCj4+IEhpIFJvYiwN
Cj4NCj4gWW91ciBlbWFpbHMgYXJlIGJhc2U2NCBlbmNvZGVkLiBUaGV5IHNob3VsZCBiZSBwbGFp
biB0ZXh0IGZvciB0aGUgbGlzdC4NCj4NCj4gSUY6IFRoZSBPdXRsb29rIGlzIGNvbmZpZ3VyZWQg
dG8gcmVzcG9uZCBpbiB0aGUgc2VuZGVyJ3MgZm9ybWF0LiBJIHRoZXJlZm9yZSByZXNwb25kIGlu
IHRoZSBlbmNvZGluZyB5b3UndmUgdXNlZC4NCg0KSSBhc3N1cmUgeW91IHRoYXQgdGhhdCBpcyBu
b3QgdGhlIGNhc2Ugb3IgSSB3b3VsZCBiZSBiYW5pc2hlZCBmcm9tDQpsaXN0cyBieSBub3cuIE91
dGxvb2sgaXMgZ2VuZXJhbGx5IGluY2FwYWJsZSBvZiBjb3JyZWN0bHkgc2VuZGluZw0KbWFpbHMg
dG8gbGlzdHMuIFRoZSByZXBseSBoZWFkZXIgYWJvdmUgaXMgb25lIGFzcGVjdCBvZiB0aGF0LiBU
aGUNCm90aGVyIHByb2JsZW0gaXMgeW91ciByZXBsaWVzIGRvbid0IGdldCB3cmFwcGVkIGFuZCBw
cmVmaXhlZCBwcm9wZXJseS4NClRoYXQgY291bGQgYmUgbXkgY2xpZW50IEkgZ3Vlc3MsIGJ1dCAq
YWxsKiBvdGhlciBtYWlscyBhcmUgZmluZS4NCg0KTXkgc2VudCBtYWlscyBoYXZlOg0KDQpDb250
ZW50LVR5cGU6IHRleHQvcGxhaW47IGNoYXJzZXQ9VVRGLTgNCkNvbnRlbnQtVHJhbnNmZXItRW5j
b2Rpbmc6IHF1b3RlZC1wcmludGFibGUNCg0KSUY6IFVubHVja2lseSwgT3V0bG9vayBpcyB3aGF0
IEkgYW0gc3VwcG9zZWQgdG8gdXNlLiBJIHBvc3QgcGF0Y2hlcyBmcm9tIHRoZSBVYnVudHUgVk0g
YnV0IEkgaGF2ZSB0aGUgY29tbWFuZCBsaW5lIGFjY2VzcyB0byBpdCBvbmx5Lg0KDQo+PiAtLS0t
LU9yaWdpbmFsIE1lc3NhZ2UtLS0tLQ0KPj4gRnJvbTogUm9iIEhlcnJpbmcgW21haWx0bzpyb2Jo
ZXJyaW5nMkBnbWFpbC5jb21dDQo+PiBTZW50OiBUaHVyc2RheSwgSnVuZSAxOCwgMjAxNSAxMTow
MyBBTQ0KPj4gVG86IElseWEgRmFlbnNvbg0KPj4gQ2M6IG1hcmNlbEBob2x0bWFubi5vcmc7IEFy
ZW5kIFZhbiBTcHJpZWw7IGRldmljZXRyZWVAdmdlci5rZXJuZWwub3JnOyBsaW51eC1ibHVldG9v
dGhAdmdlci5rZXJuZWwub3JnDQo+PiBTdWJqZWN0OiBSZTogRlc6IFtQQVRDSCB2NCAxLzRdIEJy
b2FkY29tIEJsdWV0b290aCBVQVJUIERldmljZSBUcmVlIGJpbmRpbmdzDQo+Pg0KPj4gT24gV2Vk
LCBKdW4gMTcsIDIwMTUgYXQgNjoxMSBQTSwgSWx5YSBGYWVuc29uIDxpZmFlbnNvbkBicm9hZGNv
bS5jb20+IHdyb3RlOg0KPj4+ICsgZGV2aWNldHJlZSBsaXN0cw0KPg0KPiBbLi4uXQ0KPg0KPj4+
IGRpZmYgLS1naXQgYS9Eb2N1bWVudGF0aW9uL2RldmljZXRyZWUvYmluZGluZ3MvbmV0L2JsdWV0
b290aC9idGJjbS50eHQgYi9Eb2N1bWVudGF0aW9uL2RldmljZXRyZWUvYmluZGluZ3MvbmV0L2Js
dWV0b290aC9idGJjbS50eHQNCj4+PiBuZXcgZmlsZSBtb2RlIDEwMDY0NA0KPj4+IGluZGV4IDAw
MDAwMDAuLjVkYmNkNTcNCj4+PiAtLS0gL2Rldi9udWxsDQo+Pj4gKysrIGIvRG9jdW1lbnRhdGlv
bi9kZXZpY2V0cmVlL2JpbmRpbmdzL25ldC9ibHVldG9vdGgvYnRiY20udHh0DQo+Pj4gQEAgLTAs
MCArMSw4NiBAQA0KPj4+ICtidGJjbQ0KPj4+ICstLS0tLS0NCj4+PiArDQo+Pj4gK1JlcXVpcmVk
IHByb3BlcnRpZXM6DQo+Pj4gKw0KPj4+ICsgICAgICAgLSBjb21wYXRpYmxlIDogbXVzdCBiZSAi
YnJjbSxicmNtLWJ0LXVhcnQiLg0KPj4NCj4+IFlvdSBuZWVkIHRvIGRlc2NyaWJlIHRoZSBjaGlw
LCBub3QgdGhlIGludGVyZmFjZS4NCj4+DQo+PiBJRjogVGhpcyBkcml2ZXIgaXMgZm9yIGFsbCBC
cm9hZGNvbSBCbHVldG9vdGggVUFSVCBiYXNlZCBjaGlwcy4NCj4NCj4gQlQgb25seSBjaGlwcz8g
TW9zdC9tYW55IEJyb2FkY29tIGNoaXBzIGFyZSBjb21ibyBjaGlwcy4gSSB1bmRlcnN0YW5kDQo+
IHRoZSBkcml2ZXIgZm9yIEJUIGlzICptb3N0bHkqIHNlcGFyYXRlIGZyb20gb3RoZXIgY2hpcCBm
dW5jdGlvbnMgbGlrZQ0KPiBXaUZpLCBHUFMgYW5kIE5GQywgYnV0IHRoZSBoL3cgaXMgYSBzaW5n
bGUgY2hpcC4gSSBzYXkgbW9zdCBiZWNhdXNlDQo+IGxpa2VseSB0aGVyZSBhcmUgc29tZSBwYXJ0
cyBzaGFyZWQ6IGEgdm9sdGFnZSByYWlsLCByZXNldCBsaW5lLCBvcg0KPiBwb3dlciBkb3duIGxp
bmUuIEkgdGhpbmsgc29tZSBjYW4gZG8gQlQgb3ZlciB0aGUgU0RJTyBpbnRlcmZhY2UgdG9vLA0K
PiBzbyB0aGUgaW50ZXJmYWNlIG1heSBiZSBzaGFyZWQuIFRoZSBEVCBpcyBhIGRlc2NyaXB0aW9u
IG9mIHRoZSBoL3cNCj4gKGkuZS4gd2hhdCBwYXJ0ICMgZm9yIGEgY2hpcCkgYW5kIG5vdCBhIGRy
aXZlciBkYXRhIHN0cnVjdHVyZS4gWW91DQo+IG5lZWQgdG8gZGVzY3JpYmUgdGhlIHdob2xlIGNo
aXAgaW4gdGhlIGJpbmRpbmcuIEl0IGlzIGEgTGludXggcHJvYmxlbQ0KPiBpZiB0aGVyZSBuZWVk
cyB0byBiZSBtdWx0aXBsZSBzZXBhcmF0ZSBkcml2ZXJzLg0KPg0KPiBJRjogRGVmaW5pbmcgY29t
cGxldGUgRFQgZGVzY3JpcHRpb24gZm9yIHRoZSBCcm9hZGNvbSBjb21ibyBjaGlwcyBmb3IgbXVs
dGlwbGUgaW50ZXJmYWNlcyBpcyB3ZWxsIGJleW9uZCB0aGUgc2NvcGUgb2Ygd2hhdCBJIGFtIGRv
aW5nLiBJIGp1c3QgbmVlZCB0byBkZWZpbmUgYSBEVCBub2RlIGZvciB0aGUgaW5wdXQgYW5kIG91
dHB1dCBHUElPcyBjb25uZWN0ZWQgdG8gdGhlIEJUIFVBUlQgY2hpcC4gQlQgbWF5IG9yIG1heSBu
b3QgYmUgcGFydCBvZiB0aGUgY29tYm8gY2hpcDogaXQgZG9lcyBub3QgcmVhbGx5IG1hdHRlciBm
b3IgdGhpcyBleGVyY2lzZS4gSSB0aG91Z2h0IEkgd291bGQgdGFrZSB0aGlzIG9wcG9ydHVuaXR5
IHRvIHBsYWNlIHNvbWUgQlQgZGV2aWNlIHBhcmFtZXRlcnMgaW50byB0aGF0IG5vZGUgYXMgd2Vs
bC4gSWYgeW91J3JlIG5vdCBjb21mb3J0YWJsZSB3aXRoIHRoaXMsIEkgY291bGQganVzdCBjYWxs
IGl0IGEgIkdQSU8gc2V0IiB0byBhdm9pZCBtZW50aW9uaW5nIEJUIGFuZCBVQVJUIGF0IGFsbCBi
dXQgaXQgd291bGQgbWFrZSBsaXR0bGUgc2Vuc2UuIFN0aWxsLCBJIGNvdWxkIGNvbnNpZGVyIGl0
LiBXb3VsZCB5b3UgaGF2ZSAiR1BJTyBzZXQiIHJlY29tbWVuZGF0aW9ucz8gQWx0ZXJuYXRpdmVs
eSwgTkZDIE1hcnZlbGwgY29kZSB5b3UncmUgcmVmZXJyaW5nIHRvIGhhcyBwYXJhbWV0ZXJzIGNv
bmZpZ3VyZWQgYXMgTGludXggbW9kdWxlIHBhcmFtZXRlcnMuIEkgY291bGQgZG8gdGhlIHNhbWUg
dG9vLCBhdm9pZGluZyB0aGlzIGRldmljZSB0cmVlIGRpc2N1c3Npb24uIExldCBtZSBrbm93Lg0K
Pg0KDQpJIGRvbid0IGNvbXBsZXRlbHkgZm9sbG93IHdoYXQgeW91IG1lYW4gYnkgIkdQSU8gc2V0
IiwgYnV0IEknbQ0KZ3Vlc3NpbmcgdGhhdCBpcyBub3QgdGhlIHJpZ2h0IHBhdGguDQoNCj4gR2Vu
ZXJhbGx5IHNwZWFraW5nIChwb250aWZpY2F0aW9uIGhhdCBvbiA6LSkpLCB3aGF0IHlvdSdyZSB0
cnlpbmcgdG8gZG8gKGRlc2NyaXB0aW9uIG9mIHRoZSB3aG9sZSBjaGlwKSBpcyB3ZWxsIGJleW9u
ZCB3aGF0IHNheSBBQ1BJIGhhcyBkb25lIChJIHdhcyBpbnZvbHZlZCBzb21lIGluIHRoZSBCVCBB
Q1BJIGV4ZXJjaXNlIGEgZmV3IHllYXJzIGFnbykuIEJUIFVBUlQgaW50ZXJmYWNlIGlzIGRlc2Ny
aWJlZCBpbiBBQ1BJIGluZGVwZW5kZW50bHkgb2Ygb3RoZXIgcGFydHMgb2YgdGhlIHNhbWUgY29t
Ym8gY2hpcC4gUmVxdWlyZW1lbnRzIGxpa2UgdGhhdCBzbG93IGRvd24gdGhlIERUIGRldmVsb3Bt
ZW50IGluIG15IG9waW5pb24gYXMgY29tcGFuaWVzIGFyZSB1bmRlcnN0YW5kYWJseSByZWx1Y3Rh
bnQgdG8gd29yayB3aXRoIHVucmVhbGlzdGljIGdvYWxzLiBFbmQgb2YgcG9udGlmaWNhdGlvbi4g
Oi0pDQo+DQoNCkFDUEkgYW5kIERUIGFyZSB2ZXJ5IGRpZmZlcmVudCBtb2RlbHMgaW4gdGVybXMg
b2YgYWJzdHJhY3Rpb24gYW5kDQpnb3Zlcm5hbmNlLiBJJ20gbm90IGdvaW5nIHRvIGhhc2ggdGhy
b3VnaCBhbGwgdGhlIGRldGFpbHMuDQoNCkknbSBub3QgbmVjZXNzYXJpbHkgc2F5aW5nIHdlIGhh
dmUgdG8gaGF2ZSBhIHNpbmdsZSBub2RlLCBidXQgdGhhdCBpcw0KbXkgZGVmYXVsdCBwb3NpdGlv
bi4gWW91IGhhdmUgY29udmluY2UgbWUgdGhhdCB0aGUgZnVuY3Rpb25zIGFyZQ0KY29tcGxldGVs
eSBpbmRlcGVuZGVudCBhbmQgSSBjYW5ub3QganVkZ2UgdGhhdCBpZiB5b3UgYXJlIGNvbXBsZXRl
bHkNCmlnbm9yaW5nIHRoZSBXaUZpIHBhcnQuIEZyb20gQnJvYWRjb20gY2hpcHMgSSd2ZSB3b3Jr
ZWQgd2l0aCwgdGhlDQpzdXBwbGllcyBhdCBsZWFzdCBhcmUgc2hhcmVkIChzb21ldGhpbmcgQUNQ
SSBkb2VzIG5vdCBleHBvc2UpLiBQZXJoYXBzDQp3ZSBjb3VsZCBmdWRnZSB0aGF0IGFuZCBqdXN0
IHJlcXVpcmUgdGhlIHNhbWUgc3VwcGx5IGhhcyB0byBiZQ0KY29ubmVjdGVkIHRvIGVhY2ggaGFs
Zi4gSSBzdGlsbCB3b3JyeSB0aGVyZSBjb3VsZCBiZSBvdGhlciBpbnRlcm5hbA0KaW50ZXItZGVw
ZW5kZW5jaWVzLiBQZXJoYXBzIEJUIHJlcXVpcmVzIHRoZSBTRElPIGNsb2NrIHRvIGJlIGFjdGl2
ZSBvcg0Kc29tZXRoaW5nIGxpa2UgdGhhdC4gTWF5YmUgbm90IG9uIEJyb2FkY29tIGNoaXBzLCBi
dXQgb24gb3RoZXIgdmVuZG9ycw0KYW5kIEkgaGF2ZSB0byBjYXJlIGFib3V0IHRoZW0gYWxsLg0K
DQpMZXQncyBzdGVwIGJhY2sgdG8gd2hhdCBJJ20gYXNraW5nIGZvcjoNCg0KLSBBIG1vcmUgc3Bl
Y2lmaWMgY29tcGF0aWJsZSBzdHJpbmcuIFRoaXMgc2hvdWxkIGluY2x1ZGUgdGhlIGNoaXANCm5h
bWUvbnVtYmVyLiBZb3UgbWF5IG5vdCBuZWVkIGl0IHRvZGF5LCBidXQgaXQgaXMgaW5zdXJhbmNl
IGluIGNhc2UNCnlvdSBkbyBmaW5kIGRpZmZlcmVuY2VzIGxhdHRlci4gVGhlIG9ubHkgaW1wYWN0
IGlzIHRoZSBtYXRjaCB0YWJsZSBpbg0KeW91ciBkcml2ZXIuIFlvdSBjYW4gYWxzbyBoYXZlIGEg
bGVzcyBzcGVjaWZpYyBjb21wYXRpYmxlIHN0cmluZyBpZg0KeW91IHdhbnQgdGhhdCB0aGUgZHJp
dmVyIGNhbiBtYXRjaCBvbi4NCg0KSUY6IE9rYXksIEkgY2FuIGNoYW5nZSB0aGF0Lg0KDQotIENo
YW5naW5nIHRoZSBsb2NhdGlvbiBvZiB0aGUgbm9kZS4gVGhlIG5vZGUgaGllcmFyY2h5IGltcGxp
Y2l0bHkNCmRlZmluZXMgY29ubmVjdGlvbnMuIFlvdSBoYXZlIGEgY29ubmVjdGlvbiBmcm9tIHRo
ZSBob3N0IFVBUlQgdG8gdGhlDQpCVCBkZXZpY2UuIFRoaXMgbmVlZHMgdG8gYmUgZGVzY3JpYmVk
LiBXaGV0aGVyIHNwbGl0dGluZyBCVCBhbmQgV2lGaQ0Kbm9kZXMgb3Igbm90LCBJJ3ZlIGFscmVh
ZHkgc2FpZCBpdCBwcm9iYWJseSBtYWtlcyB0aGUgbW9zdCBzZW5zZSB0bw0KcHV0IHRoaXMgdW5k
ZXIgdGhlIGhvc3QgdWFydCBub2RlLg0KDQpJRjogT2theSwgSSBoYXZlIGp1c3QgdHJpZWQgcGxh
Y2luZyBteSBub2RlIHVuZGVyIHRoZSBVQVJULiBUaGUgcGxhdGZvcm0gZHJpdmVyIHByb2JlIGlz
IG5vIGxvbmdlciBjYWxsZWQgdGhlbiB0aG91Z2guIFdoYXQgYW0gSSBkb2luZyB3cm9uZz8gUGFz
dGluZyB0aGUgcmVsZXZhbnQgc25pcHBldDoNCg0KSUY6ICZ1YXJ0MSB7DQpJRjogICAgICAgICBz
dGF0dXMgPSAib2theSI7DQpJRjogICAgICAgICAuLi4NCklGOiAgICAgICAgIGJjbTQzNTRfYnRf
dWFydDogYmNtNDM1NC1idC11YXJ0IHsNCklGOiAgICAgICAgICAgICAgICAgY29tcGF0aWJsZSA9
ICJicmNtLGJyY200MzU0LWJ0LXVhcnQiOw0KSUY6ICAgICAgICAgICAgICAgICBidC13YWtlLWdw
aW9zID0gPCZncGlvNCAzMCBHUElPX0FDVElWRV9ISUdIPjsNCklGOiAgICAgICAgICAgICAgICAg
Li4uDQpJRjogICAgICAgICB9Ow0KSUY6IH07DQoNCi0gU3BsaXR0aW5nIHRoZSBub2Rlcy4gSGVy
ZSB3ZSBhcmUgbG9va2luZyBhdCBkb2luZyBlaXRoZXI6DQoNCnNlcmlhbEAxMjM0IHsNCiAgY29t
cGF0aWJsZSA9ICJzb21lLXNvYy11YXJ0IjsNCg0KICBicmNtNDMzNDAgew0KICAgIGNvbXBhdGli
bGUgPSAiYnJjbSxicmNtNDMzNDAiOw0KICAgIHNkaW8taG9zdCA9IDwmc29jLXNkaG9zdD47DQog
ICAgLy8gQlQgcHJvcHMNCiAgICAvLyBXaUZpIHByb3BzDQogIH07DQp9Ow0KDQpPcjoNCg0Kc2Vy
aWFsQDEyMzQgew0KICBjb21wYXRpYmxlID0gInNvbWUtc29jLXVhcnQiOw0KDQogIGJyY200MzM0
MCB7DQogICAgY29tcGF0aWJsZSA9ICJicmNtLGJyY200MzM0MC1idCI7DQogICAgLy8gQlQgcHJv
cHMNCiAgfTsNCn07DQoNCm1tY0A1Njc4IHsNCiAgY29tcGF0aWJsZSA9ICJzb21lLXNvYy1zZGhj
aSI7DQoNCiAgYnJjbTQzMzQwQDAgew0KICAgIHJlZyA9IDwwPjsNCiAgICBjb21wYXRpYmxlID0g
ImJyY20sYnJjbTQzMzQwLXdpZmkiOw0KICAgIC8vIFdpRmkgcHJvcHMNCiAgfTsNCn07DQoNCk9y
IG1heWJlIGl0IGlzIHRoZSBsYXR0ZXIgZXhhbXBsZSBidXQgd2UganVzdCBhZGQgcGhhbmRsZSBs
aW5rcw0KYmV0d2VlbiB0aGUgMiBub2Rlcy4NCg0KV2UgaGF2ZW4ndCBldmVuIGNvbnNpZGVyZWQg
d2hhdCBoYXBwZW5zIHdoZW4gYSBjaGlwIGFsc28gaGFzIEZNLCBORkMsDQphbmQvb3IgR1BTLiBO
b3IgaGF2ZSB3ZSBjb25zaWRlcmVkIGhvdyB0byBkZXNjcmliZSB0aGUgYXVkaW8NCmNvbm5lY3Rp
b24gdG8gdGhlIGhvc3QgcHJvY2Vzc29yLCBidXQgd2UndmUgZ290IG5vdGhpbmcgY29tbW9uIGFu
ZA0KdGhhdCBjYW4gcHJvYmFibHkgY29tZSBsYXR0ZXIuDQoNCldlIG5lZWQgdG8gYWdyZWUgZmln
dXJpbmcgYWxsIHRoaXMgb3V0IGlzIG5lZWRlZC4gT3RoZXJ3aXNlLCB0aGlzDQp3aG9sZSBjb252
ZXJzYXRpb24gaXMgYSB3YXN0ZSBvZiB0aW1lLg0KDQpJRjogQXBwcmVjaWF0ZSB0aGUgZGV0YWls
ZWQgZWxhYm9yYXRpb25zLiBUaGUgbGF0dGVyIGV4YW1wbGUgd2l0aCBwaGFuZGxlIGxpbmtzIHNv
dW5kcyByZWFzb25hYmxlIHRvIG1lLiBJIGFtIGFmcmFpZCBJJ20gbm90IGluIGEgcG9zaXRpb24g
dG8gYWdyZWUgdG8gZXZlcnl0aGluZyB0aG91Z2ggYXMgSSdtIHJlc3BvbnNpYmxlIGZvciB0aGUg
QlQgb25seS4gQXJlbmQgVmFuIFNwcmllbCByZXByZXNlbnRpbmcgQnJvYWRjb20gV0xBTiBoYXMg
c3RhcnRlZCB0YWxraW5nIHRvIHlvdTogdGhhdCdzIGdvb2QuDQoNCj4+DQo+Pj4gKyAgICAgICAt
IHR0eSA6IHR0eSBkZXZpY2UgY29ubmVjdGVkIHRvIHRoaXMgQmx1ZXRvb3RoIGRldmljZS4NCj4+
DQo+PiAidHR5IiBpcyBhIGJpdCBvZiBhIExpbnV4aXNtIGFuZCAidHR5UzAiIGNlcnRhaW5seSBp
cy4gRnVydGhlciwgdGhlcmUNCj4+IGlzIG5vIGd1YXJhbnRlZSB3aGljaCB1YXJ0IGlzIGFzc2ln
bmVkIHR0eVMwLg0KPj4NCj4+IFRoaXMgc2hvdWxkIGJlIGEgcGhhbmRsZSB0byB0aGUgY29ubmVj
dGVkIHVhcnQgaWYgbm90IGEgc3ViIG5vZGUgb2YNCj4+IHRoZSB1YXJ0LiBUaGlzIGlzIGNvbXBs
aWNhdGVkIHNpbmNlIHRoZXNlIGNoaXBzIGhhdmUgbXVsdGlwbGUgaG9zdA0KPj4gY29ubmVjdGlv
bnMuIEl0IG5lZWRzIHRvIGdvIHVuZGVyIGVpdGhlciB1YXJ0IG9yIFNESU8gaG9zdCBhbmQgaGF2
ZSBhDQo+PiByZWZlcmVuY2UgYmFjayB0byB0aGUgb25lIGl0IGlzIG5vdCB1bmRlci4gR2l2ZW4g
dGhlIFNESU8gaW50ZXJmYWNlIGlzDQo+PiBkaXNjb3ZlcmFibGUgKGFsdGhvdWdoIHNpZGViYW5k
IGdwaW9zIGFuZCByZWd1bGF0b3JzIGFyZSBub3QpLCBJIHdvdWxkDQo+PiBwdXQgdGhpcyB1bmRl
ciB0aGUgdWFydCBub2RlIGFzIHRoYXQgaXMgbmV2ZXIgZGlzY292ZXJhYmxlLg0KPj4NCj4+IEFz
IEkndmUgbWVudGlvbmVkIHByZXZpb3VzbHksIHRoZXJlJ3Mgc2V2ZXJhbCBjYXNlcyBvZiBiaW5k
aW5ncyBmb3INCj4+IFVBUlQgc2xhdmUgZGV2aWNlcyBiZWluZyBwb3N0ZWQuIFRoaXMgYWxsIG5l
ZWRzIHRvIGJlIGNvb3JkaW5hdGVkIHRvDQo+PiB1c2UgYSBjb21tb24gc3RydWN0dXJlLg0KPj4N
Cj4+IElGOiBUaGlzIGRyaXZlciBkb2VzIG5vdCByZWFsbHkgYWNjZXNzIHRoZSBVQVJULiBJZiBq
dXN0IG5lZWRzIHRvIGhhdmUgYSBzdHJpbmcgb2Ygc29tZSBzb3J0IHRvIG1hcCBpbnN0YW5jZXMg
b2YgdGhlIEJsdWVaIHByb3RvY29sIGludG8gcGxhdGZvcm0gZGV2aWNlcyB0byBlbXBsb3kgdGhl
IHJpZ2h0IEdQSU9zIGFuZCBpbnRlcnJ1cHRzLiBJIGNvdWxkIHVzZSBhbnl0aGluZyB5b3UgcmVj
b21tZW5kIGF2YWlsYWJsZSB0aHJvdWdoIHRoZSB0dHlfc3RydWN0IGNvbWluZyB0byB0aGUgcHJv
dG9jb2wgZnJvbSB0aGUgQmx1ZVogbGluZSBkaXNjaXBsaW5lLiBNb3Jlb3ZlciwgZXZlcnkgZW5k
IHVzZXIgcGxhdGZvcm0gSSd2ZSBldmVyIGRlYWx0IHdpdGggaW4gMTYgeWVhcnMgb2Ygd29ya2lu
ZyB3aXRoIEJsdWV0b290aCBoYWQgYSBzaW5nbGUgQlQgVUFSVCBkZXZpY2UuIFNvIHRoZXNlIGFy
ZSByZWFsbHkgcmFyZSAodHlwaWNhbGx5IHRlc3QgcGxhdGZvcm1zKSBjYXNlcyBvbmx5LiBUaGUg
bWFwcGluZyBpcyBub3QgbmVlZGVkIGZvciBtb3N0IHBsYXRmb3JtcyBhdCBhbGwuIEkgc3VzcGVj
dCB0aGUgcmlnaHQgdGhpbmcgdG8gZG8gd291bGQgYmUgdG8gbWFrZSB0aGlzIHBhcmFtZXRlciBv
cHRpb25hbC4gVGhlIG1hcHBpbmcgd291bGQgYmUgZG9uZSBvbmx5IGlmIHRoZSBwYXJhbWV0ZXIg
aXMgcHJlc2VudC4gSSB3aWxsIHVzZSBhbnl0aGluZyB0dHlfc3RydWN0IGRlcml2ZWQgeW91IHNw
ZWNpZnkuIE1ha2VzIHNlbnNlPw0KPg0KPg0KPiBZb3UndmUgbWlzc2VkIG15IHBvaW50LiBJJ20g
bm90IHRhbGtpbmcgYWJvdXQgY29ubmVjdGluZyBtdWx0aXBsZQ0KPiBkZXZpY2VzIHRvIGEgVUFS
VCBhdCBvbmNlLiBUaGVyZSBhcmUgc2V2ZXJhbCBpbnN0YW5jZXMgb2YgcGVvcGxlDQo+IHRyeWlu
ZyB0byBhZGQgVUFSVCBjb25uZWN0ZWQgZGV2aWNlcyBpbnRvIERUWzFdWzJdLiBNeSBwb2ludCBp
cyB0aGVzZQ0KPiBkZXZpY2VzIGFsbCBuZWVkIHRvIGhhdmUgdGhlIERUIGJpbmRpbmcgZG9uZSBp
biBhIGNvbW1vbiB3YXkgYWNyb3NzDQo+IGRpZmZlcmVudCBwbGF0Zm9ybXMuIE90aGVyd2lzZSwg
d2UgY2FuIG5vdCBoYXZlIGNvbW1vbiBjb2RlIHRvIHBhcnNlDQo+IHRoZSBEVCBhbmQgZmluZCBk
ZXZpY2VzIGF0dGFjaGVkIHRvIGEgVUFSVC4NCj4NCj4gSUY6IENoYW5jZXMgYXJlIEkgd2FzIG5v
dCBjbGVhciBlbm91Z2guIEkgd2FzIG5vdCB0YWxraW5nIGFib3V0IGNvbm5lY3RpbmcgbXVsdGlw
bGUgZGV2aWNlcyB0byBhIFVBUlQuIEkgd2FzIHRhbGtpbmcgYWJvdXQgY29ubmVjdGluZyBvbmUg
QnJvYWRjb20gQlQgZGV2aWNlIHRvIG9uZSBzZXJpYWwgcG9ydCBhbmQgYW5vdGhlciBCcm9hZGNv
bSBCVCBkZXZpY2UgdG8gYW5vdGhlciBzZXJpYWwgcG9ydCAocmFyZSBlbm91Z2ggc2V0dXApLiBJ
IGRvIHVuZGVyc3RhbmQgeW91ciBnb2FscyB0aG91Z2guIEkgd291bGQgYmUgaGFwcHkgdG8gcGFy
dGljaXBhdGUgaW4gdGhhdCBleGVyY2lzZSAoc3ViamVjdCB0byB0aGUgbWFuYWdlbWVudCBhcHBy
b3ZhbCkgb25jZSBEVCBoYXMgcHVibGlzaGVkIHRoZSBVQVJUIGRldmljZSBwYXJhbWV0ZXJzIGFu
ZCB0aGUgTGludXggYmx1ZXRvb3RoLW5leHQgaGFzIHN1cHBvcnQgZm9yIERUIGVudW1lcmF0ZWQg
ZGV2aWNlcy4gSSBkb27igJl0IHNlZSBpdCBoYXBwZW5pbmcgc29vbiB0aG91Z2guIE1hcnZlbGwg
ZXhhbXBsZSB5b3UndmUgcmVmZXJyZWQgbWUgdG8gaGFzIG5vdGhpbmcgb2YgdGhlIHNvcnQuIFdo
YXQgZG8geW91IHRoaW5rIG9mIGFsbG93aW5nIHVzIHNvbWV0aGluZyB0byBzaGlwIG5vdyB3aXRo
IGFuIHVuZGVyc3RhbmRpbmcgdGhhdCB3ZSB3b3VsZCBzdXBwb3J0IHlvdXIgVUFSVCBlbnVtZXJh
dGVkIGRldmljZXMgb25jZSB0aGV5IGFyZSBwdWJsaXNoZWQ/DQoNCk9rYXkuIFNldmVyYWwgcGVv
cGxlIHdhbnQgdG8gZGVzY3JpYmUgYSBjb25uZWN0aW9uIGJldHdlZW4gYSBob3N0IHVhcnQNCmFu
ZCBhIGRldmljZSBjb25uZWN0ZWQgdG8gdGhlIHVhcnQgKEJULCBORkMsIEdQUywgZXRjLikuIFlv
dSBhcmUgZG9pbmcNCnRoaXMgd2l0aCB5b3VyICJ0dHkiIHByb3BlcnR5LiBNeSBnb2FsIGFuZCBy
ZXF1aXJlbWVudCBpcyB0aGF0IHRoaXMNCmNvbm5lY3Rpb24gYmUgZGVzY3JpYmVkIGluIERUIGlu
IHRoZSBzYW1lIHdheSByZWdhcmRsZXNzIG9mIHRoZSBkZXZpY2UNCmF0dGFjaGVkLiBKdXN0IGxp
a2UgYWxsIEkyQyBkZXZpY2UgY29ubmVjdGlvbnMgYXJlIGRlc2NyaWJlZCBieSBiZWluZw0KY2hp
bGQgbm9kZXMgdW5kZXIgdGhlIEkyQyBob3N0IHJlZ2FyZGxlc3Mgb2YgdGhlIHR5cGUgb2YgSTJD
IGRldmljZQ0KYXR0YWNoZWQuDQoNCklGOiBBbGwgZ29vZCBwb2ludHMsIFJvYi4gSSB3aWxsIGNl
cnRhaW5seSBnZXQgcmlkIG9mIHRoZSB0dHkgcHJvcGVydHkgaWYgSSBjYW4gbWFrZSB0aGUgY2hp
bGQgZGV2aWNlIGlkZWEgd29yay4gTXkgY29tcGxpY2F0aW9uIGlzIGluIHRoZSBuZWVkIHRvIG1h
cCBzYXkgdGhlIERUIGRldmljZSBwYXJlbnQgKFVBUlQpIGludG8gdGhlIHR0eV9zdHJ1Y3QgdXNl
ZCBieSB0aGUgTGludXggQmx1ZVogcHJvdG9jb2wuIEFueSBpZGVhcyBvbiBob3cgdG8gaW1wbGVt
ZW50IHRoYXQgPyBNYW55IHRoYW5rcyENCg0KUm9iDQo=
--
To unsubscribe from this list: send the line "unsubscribe linux-bluetooth" in

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

* RE: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-19 19:23   ` Fabio Estevam
@ 2015-06-19 20:40     ` Ilya Faenson
  0 siblings, 0 replies; 36+ messages in thread
From: Ilya Faenson @ 2015-06-19 20:40 UTC (permalink / raw)
  To: Fabio Estevam
  Cc: Marcel Holtmann, linux-bluetooth@vger.kernel.org,
	Arend Van Spriel

SGkgRmFiaW8sDQoNCi0tLS0tT3JpZ2luYWwgTWVzc2FnZS0tLS0tDQpGcm9tOiBGYWJpbyBFc3Rl
dmFtIFttYWlsdG86ZmVzdGV2YW1AZ21haWwuY29tXSANClNlbnQ6IEZyaWRheSwgSnVuZSAxOSwg
MjAxNSAzOjIzIFBNDQpUbzogSWx5YSBGYWVuc29uDQpDYzogTWFyY2VsIEhvbHRtYW5uOyBsaW51
eC1ibHVldG9vdGhAdmdlci5rZXJuZWwub3JnOyBBcmVuZCBWYW4gU3ByaWVsDQpTdWJqZWN0OiBS
ZTogW1BBVENIIHY0IDEvNF0gQnJvYWRjb20gQmx1ZXRvb3RoIFVBUlQgRGV2aWNlIFRyZWUgYmlu
ZGluZ3MNCg0KT24gV2VkLCBKdW4gMTcsIDIwMTUgYXQgNjozMCBQTSwgSWx5YSBGYWVuc29uIDxp
ZmFlbnNvbkBicm9hZGNvbS5jb20+IHdyb3RlOg0KDQo+ICtPcHRpb25hbCBwcm9wZXJ0aWVzOg0K
PiArDQo+ICsgIC0gYnQtaG9zdC13YWtlLWdwaW9zIDogYnQtaG9zdC13YWtlIGlucHV0IEdQSU8g
dG8gYmUgdXNlZCBhcyBhbiBpbnRlcnJ1cHQuDQo+ICsNCj4gKyAgLSBidC13YWtlLWdwaW9zIDog
YnQtd2FrZSBvdXRwdXQgR1BJTyB0byBiZSB1c2VkIHRvIHN1c3BlbmQgLyByZXN1bWUgZGV2aWNl
Lg0KPiArDQo+ICsgIC0gYnQtcmVnLW9uLWdwaW9zIDogcmVnLW9uIG91dHB1dCBHUElPIHRvIGJl
IHVzZWQgdG8gcG93ZXIgZGV2aWNlIG9uL29mZi4NCg0KU2hvdWxkbid0IHRoaXMgYmUgbW9kZWxs
ZWQgYXMgYSByZWd1bGF0b3IgaW5zdGVhZD8gV2hhdCBpZiB0aGUgYm9hcmQNCmRyaXZlcyBhIFBN
SUMgb3V0cHV0IHRvIHByb3ZpZGUgcG93ZXIgdG8gdGhlIEJUIGludGVyZmFjZT8NCg0KSUY6IEkg
dGhpbmsgdGhlIHJlZ3VsYXRvciB3b3VsZCBpbmRlZWQgYmUgYSBiZXR0ZXIgbmFtZSBmb3IgdGhl
ICJHUElPIHNldCIgaWRlYSBJIG1lbnRpb25lZCBpbiBhIHNlcGFyYXRlIG1lc3NhZ2UgdG8gUm9i
IEhlcnJpbmcuIDotKQ0KDQo=

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-19 19:20                                       ` Arend van Spriel
@ 2015-06-29 18:36                                           ` Arend van Spriel
  -1 siblings, 0 replies; 36+ messages in thread
From: Arend van Spriel @ 2015-06-29 18:36 UTC (permalink / raw)
  To: Rob Herring
  Cc: Ilya Faenson, marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

On 06/19/15 21:20, Arend van Spriel wrote:
> On 06/19/15 20:49, Rob Herring wrote:
>> On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel<arend-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>> wrote:
>>> On 06/19/15 17:47, Rob Herring wrote:
>>>>
>>>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>> wrote:
>>>>>
>>>>> Hi Rob.
>>>>>
>>>>> -----Original Message-----
>>>>> From: linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>>> [mailto:linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org] On Behalf Of Rob
>>>>> Herring
>>>>> Sent: Thursday, June 18, 2015 3:41 PM
>>>>> To: Ilya Faenson
>>>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>> bindings
>>>>>
>>>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>>> wrote:
>>>>>>
>>>>>> Hi Rob,
>>>>>
>>>>>
>>>>> Your emails are base64 encoded. They should be plain text for the
>>>>> list.
>>>>>
>>>>> IF: The Outlook is configured to respond in the sender's format. I
>>>>> therefore respond in the encoding you've used.
>>>>
>>>>
>>>> I assure you that that is not the case or I would be banished from
>>>> lists by now. Outlook is generally incapable of correctly sending
>>>> mails to lists. The reply header above is one aspect of that. The
>>>> other problem is your replies don't get wrapped and prefixed properly.
>>>> That could be my client I guess, but *all* other mails are fine.
>>>>
>>>> My sent mails have:
>>>>
>>>> Content-Type: text/plain; charset=UTF-8
>>>> Content-Transfer-Encoding: quoted-printable
>>>>
>>>>
>>>>>> -----Original Message-----
>>>>>> From: Rob Herring [mailto:robherring2-Re5JQEeQqe8AvxtiuMwx3w@public.gmane.org]
>>>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>>>> To: Ilya Faenson
>>>>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel;
>>>>>> devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>>>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>>> bindings
>>>>>>
>>>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>>>> wrote:
>>>>>>>
>>>>>>> + devicetree lists
>>>>>
>>>>>
>>>>> [...]
>>>>>
>>>>>>> diff --git
>>>>>>> a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>> new file mode 100644
>>>>>>> index 0000000..5dbcd57
>>>>>>> --- /dev/null
>>>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>> @@ -0,0 +1,86 @@
>>>>>>> +btbcm
>>>>>>> +------
>>>>>>> +
>>>>>>> +Required properties:
>>>>>>> +
>>>>>>> + - compatible : must be "brcm,brcm-bt-uart".
>>>>>>
>>>>>>
>>>>>> You need to describe the chip, not the interface.
>>>>>>
>>>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>>>
>>>>>
>>>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>>>> the driver for BT is *mostly* separate from other chip functions like
>>>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>>>> likely there are some parts shared: a voltage rail, reset line, or
>>>>> power down line. I think some can do BT over the SDIO interface too,
>>>>> so the interface may be shared. The DT is a description of the h/w
>>>>> (i.e. what part # for a chip) and not a driver data structure. You
>>>>> need to describe the whole chip in the binding. It is a Linux problem
>>>>> if there needs to be multiple separate drivers.
>>>>>
>>>>> IF: Defining complete DT description for the Broadcom combo chips for
>>>>> multiple interfaces is well beyond the scope of what I am doing. I
>>>>> just need
>>>>> to define a DT node for the input and output GPIOs connected to the
>>>>> BT UART
>>>>> chip. BT may or may not be part of the combo chip: it does not
>>>>> really matter
>>>>> for this exercise. I thought I would take this opportunity to place
>>>>> some BT
>>>>> device parameters into that node as well. If you're not comfortable
>>>>> with
>>>>> this, I could just call it a "GPIO set" to avoid mentioning BT and
>>>>> UART at
>>>>> all but it would make little sense. Still, I could consider it.
>>>>> Would you
>>>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code
>>>>> you're
>>>>> referring to has parameters configured as Linux module parameters.
>>>>> I could
>>>>> do the same too, avoiding this device tree discussion. Let me know.
>>>>>
>>>>
>>>> I don't completely follow what you mean by "GPIO set", but I'm
>>>> guessing that is not the right path.
>>>>
>>>>> Generally speaking (pontification hat on :-)), what you're trying
>>>>> to do
>>>>> (description of the whole chip) is well beyond what say ACPI has
>>>>> done (I was
>>>>> involved some in the BT ACPI exercise a few years ago). BT UART
>>>>> interface is
>>>>> described in ACPI independently of other parts of the same combo chip.
>>>>> Requirements like that slow down the DT development in my opinion as
>>>>> companies are understandably reluctant to work with unrealistic
>>>>> goals. End
>>>>> of pontification. :-)
>>>>>
>>>>
>>>> ACPI and DT are very different models in terms of abstraction and
>>>> governance. I'm not going to hash through all the details.
>>>>
>>>> I'm not necessarily saying we have to have a single node, but that is
>>>> my default position. You have convince me that the functions are
>>>> completely independent and I cannot judge that if you are completely
>>>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>>>> supplies at least are shared (something ACPI does not expose). Perhaps
>>>> we could fudge that and just require the same supply has to be
>>>> connected to each half. I still worry there could be other internal
>>>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>>>> something like that. Maybe not on Broadcom chips, but on other vendors
>>>> and I have to care about them all.
>>>
>>>
>>> All Broadcom combo chips that I know of have separate supplies, ie.
>>> wl-reg-on and bt-reg-on. There already is a binding present for the wifi
>>
>> GPIOs are not supplies. For the module I'm working with (43340 based)
>> there is a single VDDIO and VBAT supplies which are shared. Now
>> whether the module or the chip are tying things together, I don't
>> know. There is also a 32kHz clock input. Is that part of WiFi or BT?
>
> True and I see where you are going here. The 32kHz clock is input for
> low-power oscillator in the chip. That LPO provides clock for the
> interconnect in the chip so it is not part of wifi nor bt.

Hi Rob,

Haven't seen much follow up so how to move forward here. We could go for 
a devicetree node covering all functional entities on the device. 
However, we are making the chipset and users more often as not end up 
with a module that some manufacturer cooked up. So whether signals are 
optional or not is hard to say for us. Making them optional by default 
seems safest.

So could something like below work? Just wanted to know your opinion 
before moving in that direction.

bcm43341: {
	compatible: 'brcm,bcm43340';
	brcm,lpo-clock: <&32khz_clk>;
	:
	brcm_wifi: {
		compatible: "brcm,bcm4329-fmac";
		wifi-port: <&mmc3>;
		:
	}
	brcm_bt: {
		compatible: "brcm,bcm43xx-bt-uart";
		bt-port: <&uart1>;
		:
	}
	brcm_nfc: {
		compatible: "brcm,bcm43340-nfc";
		nfc-port: <&uart2>;
		:
	}
}

Regards,
Arend

>>> part. Not extending that may seem ignorant, but as wifi and bt can
>>> have a
>>> separate interface to the host (admittedly they could share SDIO
>>> interface,
>>> but they would be exposed as a separate SDIO function) I did not see a
>>> reason to object against a separate binding for BT. Whether wifi and
>>> bt are
>>> on the same device does not seem like something that must be
>>> expressed in
>>> DT. The physical state may help in determining DT bindings, but it
>>> should
>>> not be mandatory in my opinion.
>>
>> We don't need it in DT until we do. Soon as there is some some
>> interdependence, something in DT will be needed.
>
> Agree.
>
> Regards,
> Arend
> --
> To unsubscribe from this list: send the line "unsubscribe
> linux-bluetooth" in

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-06-29 18:36                                           ` Arend van Spriel
  0 siblings, 0 replies; 36+ messages in thread
From: Arend van Spriel @ 2015-06-29 18:36 UTC (permalink / raw)
  To: Rob Herring
  Cc: Ilya Faenson, marcel@holtmann.org, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

On 06/19/15 21:20, Arend van Spriel wrote:
> On 06/19/15 20:49, Rob Herring wrote:
>> On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel<arend@broadcom.com>
>> wrote:
>>> On 06/19/15 17:47, Rob Herring wrote:
>>>>
>>>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>> wrote:
>>>>>
>>>>> Hi Rob.
>>>>>
>>>>> -----Original Message-----
>>>>> From: linux-bluetooth-owner@vger.kernel.org
>>>>> [mailto:linux-bluetooth-owner@vger.kernel.org] On Behalf Of Rob
>>>>> Herring
>>>>> Sent: Thursday, June 18, 2015 3:41 PM
>>>>> To: Ilya Faenson
>>>>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org;
>>>>> linux-bluetooth@vger.kernel.org
>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>> bindings
>>>>>
>>>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>>> wrote:
>>>>>>
>>>>>> Hi Rob,
>>>>>
>>>>>
>>>>> Your emails are base64 encoded. They should be plain text for the
>>>>> list.
>>>>>
>>>>> IF: The Outlook is configured to respond in the sender's format. I
>>>>> therefore respond in the encoding you've used.
>>>>
>>>>
>>>> I assure you that that is not the case or I would be banished from
>>>> lists by now. Outlook is generally incapable of correctly sending
>>>> mails to lists. The reply header above is one aspect of that. The
>>>> other problem is your replies don't get wrapped and prefixed properly.
>>>> That could be my client I guess, but *all* other mails are fine.
>>>>
>>>> My sent mails have:
>>>>
>>>> Content-Type: text/plain; charset=UTF-8
>>>> Content-Transfer-Encoding: quoted-printable
>>>>
>>>>
>>>>>> -----Original Message-----
>>>>>> From: Rob Herring [mailto:robherring2@gmail.com]
>>>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>>>> To: Ilya Faenson
>>>>>> Cc: marcel@holtmann.org; Arend Van Spriel;
>>>>>> devicetree@vger.kernel.org;
>>>>>> linux-bluetooth@vger.kernel.org
>>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>>> bindings
>>>>>>
>>>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>>>> wrote:
>>>>>>>
>>>>>>> + devicetree lists
>>>>>
>>>>>
>>>>> [...]
>>>>>
>>>>>>> diff --git
>>>>>>> a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>> new file mode 100644
>>>>>>> index 0000000..5dbcd57
>>>>>>> --- /dev/null
>>>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>> @@ -0,0 +1,86 @@
>>>>>>> +btbcm
>>>>>>> +------
>>>>>>> +
>>>>>>> +Required properties:
>>>>>>> +
>>>>>>> + - compatible : must be "brcm,brcm-bt-uart".
>>>>>>
>>>>>>
>>>>>> You need to describe the chip, not the interface.
>>>>>>
>>>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>>>
>>>>>
>>>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>>>> the driver for BT is *mostly* separate from other chip functions like
>>>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>>>> likely there are some parts shared: a voltage rail, reset line, or
>>>>> power down line. I think some can do BT over the SDIO interface too,
>>>>> so the interface may be shared. The DT is a description of the h/w
>>>>> (i.e. what part # for a chip) and not a driver data structure. You
>>>>> need to describe the whole chip in the binding. It is a Linux problem
>>>>> if there needs to be multiple separate drivers.
>>>>>
>>>>> IF: Defining complete DT description for the Broadcom combo chips for
>>>>> multiple interfaces is well beyond the scope of what I am doing. I
>>>>> just need
>>>>> to define a DT node for the input and output GPIOs connected to the
>>>>> BT UART
>>>>> chip. BT may or may not be part of the combo chip: it does not
>>>>> really matter
>>>>> for this exercise. I thought I would take this opportunity to place
>>>>> some BT
>>>>> device parameters into that node as well. If you're not comfortable
>>>>> with
>>>>> this, I could just call it a "GPIO set" to avoid mentioning BT and
>>>>> UART at
>>>>> all but it would make little sense. Still, I could consider it.
>>>>> Would you
>>>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code
>>>>> you're
>>>>> referring to has parameters configured as Linux module parameters.
>>>>> I could
>>>>> do the same too, avoiding this device tree discussion. Let me know.
>>>>>
>>>>
>>>> I don't completely follow what you mean by "GPIO set", but I'm
>>>> guessing that is not the right path.
>>>>
>>>>> Generally speaking (pontification hat on :-)), what you're trying
>>>>> to do
>>>>> (description of the whole chip) is well beyond what say ACPI has
>>>>> done (I was
>>>>> involved some in the BT ACPI exercise a few years ago). BT UART
>>>>> interface is
>>>>> described in ACPI independently of other parts of the same combo chip.
>>>>> Requirements like that slow down the DT development in my opinion as
>>>>> companies are understandably reluctant to work with unrealistic
>>>>> goals. End
>>>>> of pontification. :-)
>>>>>
>>>>
>>>> ACPI and DT are very different models in terms of abstraction and
>>>> governance. I'm not going to hash through all the details.
>>>>
>>>> I'm not necessarily saying we have to have a single node, but that is
>>>> my default position. You have convince me that the functions are
>>>> completely independent and I cannot judge that if you are completely
>>>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>>>> supplies at least are shared (something ACPI does not expose). Perhaps
>>>> we could fudge that and just require the same supply has to be
>>>> connected to each half. I still worry there could be other internal
>>>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>>>> something like that. Maybe not on Broadcom chips, but on other vendors
>>>> and I have to care about them all.
>>>
>>>
>>> All Broadcom combo chips that I know of have separate supplies, ie.
>>> wl-reg-on and bt-reg-on. There already is a binding present for the wifi
>>
>> GPIOs are not supplies. For the module I'm working with (43340 based)
>> there is a single VDDIO and VBAT supplies which are shared. Now
>> whether the module or the chip are tying things together, I don't
>> know. There is also a 32kHz clock input. Is that part of WiFi or BT?
>
> True and I see where you are going here. The 32kHz clock is input for
> low-power oscillator in the chip. That LPO provides clock for the
> interconnect in the chip so it is not part of wifi nor bt.

Hi Rob,

Haven't seen much follow up so how to move forward here. We could go for 
a devicetree node covering all functional entities on the device. 
However, we are making the chipset and users more often as not end up 
with a module that some manufacturer cooked up. So whether signals are 
optional or not is hard to say for us. Making them optional by default 
seems safest.

So could something like below work? Just wanted to know your opinion 
before moving in that direction.

bcm43341: {
	compatible: 'brcm,bcm43340';
	brcm,lpo-clock: <&32khz_clk>;
	:
	brcm_wifi: {
		compatible: "brcm,bcm4329-fmac";
		wifi-port: <&mmc3>;
		:
	}
	brcm_bt: {
		compatible: "brcm,bcm43xx-bt-uart";
		bt-port: <&uart1>;
		:
	}
	brcm_nfc: {
		compatible: "brcm,bcm43340-nfc";
		nfc-port: <&uart2>;
		:
	}
}

Regards,
Arend

>>> part. Not extending that may seem ignorant, but as wifi and bt can
>>> have a
>>> separate interface to the host (admittedly they could share SDIO
>>> interface,
>>> but they would be exposed as a separate SDIO function) I did not see a
>>> reason to object against a separate binding for BT. Whether wifi and
>>> bt are
>>> on the same device does not seem like something that must be
>>> expressed in
>>> DT. The physical state may help in determining DT bindings, but it
>>> should
>>> not be mandatory in my opinion.
>>
>> We don't need it in DT until we do. Soon as there is some some
>> interdependence, something in DT will be needed.
>
> Agree.
>
> Regards,
> Arend
> --
> To unsubscribe from this list: send the line "unsubscribe
> linux-bluetooth" in

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
  2015-06-29 18:36                                           ` Arend van Spriel
@ 2015-07-02 18:26                                               ` Rob Herring
  -1 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-07-02 18:26 UTC (permalink / raw)
  To: Arend van Spriel, Grant Likely, Mark Rutland, Kumar Gala,
	Arnd Bergmann, Olof Johansson
  Cc: Ilya Faenson, marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org,
	devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org,
	linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org

+ a few more DT maintainers (and frequent reviewers) as this is a
common issue only affecting every single mobile platform.

On Mon, Jun 29, 2015 at 1:36 PM, Arend van Spriel <arend-dY08KVG/lbpWk0Htik3J/w@public.gmane.org> wrote:
> On 06/19/15 21:20, Arend van Spriel wrote:
>>
>> On 06/19/15 20:49, Rob Herring wrote:
>>>
>>> On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel<arend-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>> wrote:
>>>>
>>>> On 06/19/15 17:47, Rob Herring wrote:
>>>>>
>>>>>
>>>>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>>> wrote:
>>>>>>
>>>>>>
>>>>>> Hi Rob.
>>>>>>
>>>>>> -----Original Message-----
>>>>>> From: linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>>>> [mailto:linux-bluetooth-owner-u79uwXL29TY76Z2rM5mHXA@public.gmane.org] On Behalf Of Rob
>>>>>> Herring
>>>>>> Sent: Thursday, June 18, 2015 3:41 PM
>>>>>> To: Ilya Faenson
>>>>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel; devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>>>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>>> bindings
>>>>>>
>>>>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>>>> wrote:
>>>>>>>
>>>>>>>
>>>>>>> Hi Rob,
>>>>>>
>>>>>>
>>>>>>
>>>>>> Your emails are base64 encoded. They should be plain text for the
>>>>>> list.
>>>>>>
>>>>>> IF: The Outlook is configured to respond in the sender's format. I
>>>>>> therefore respond in the encoding you've used.
>>>>>
>>>>>
>>>>>
>>>>> I assure you that that is not the case or I would be banished from
>>>>> lists by now. Outlook is generally incapable of correctly sending
>>>>> mails to lists. The reply header above is one aspect of that. The
>>>>> other problem is your replies don't get wrapped and prefixed properly.
>>>>> That could be my client I guess, but *all* other mails are fine.
>>>>>
>>>>> My sent mails have:
>>>>>
>>>>> Content-Type: text/plain; charset=UTF-8
>>>>> Content-Transfer-Encoding: quoted-printable
>>>>>
>>>>>
>>>>>>> -----Original Message-----
>>>>>>> From: Rob Herring [mailto:robherring2-Re5JQEeQqe8AvxtiuMwx3w@public.gmane.org]
>>>>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>>>>> To: Ilya Faenson
>>>>>>> Cc: marcel-kz+m5ild9QBg9hUCZPvPmw@public.gmane.org; Arend Van Spriel;
>>>>>>> devicetree-u79uwXL29TY76Z2rM5mHXA@public.gmane.org;
>>>>>>> linux-bluetooth-u79uwXL29TY76Z2rM5mHXA@public.gmane.org
>>>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>>>> bindings
>>>>>>>
>>>>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
>>>>>>> wrote:
>>>>>>>>
>>>>>>>>
>>>>>>>> + devicetree lists
>>>>>>
>>>>>>
>>>>>>
>>>>>> [...]
>>>>>>
>>>>>>>> diff --git
>>>>>>>> a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>>> new file mode 100644
>>>>>>>> index 0000000..5dbcd57
>>>>>>>> --- /dev/null
>>>>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>>> @@ -0,0 +1,86 @@
>>>>>>>> +btbcm
>>>>>>>> +------
>>>>>>>> +
>>>>>>>> +Required properties:
>>>>>>>> +
>>>>>>>> + - compatible : must be "brcm,brcm-bt-uart".
>>>>>>>
>>>>>>>
>>>>>>>
>>>>>>> You need to describe the chip, not the interface.
>>>>>>>
>>>>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>>>>
>>>>>>
>>>>>>
>>>>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>>>>> the driver for BT is *mostly* separate from other chip functions like
>>>>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>>>>> likely there are some parts shared: a voltage rail, reset line, or
>>>>>> power down line. I think some can do BT over the SDIO interface too,
>>>>>> so the interface may be shared. The DT is a description of the h/w
>>>>>> (i.e. what part # for a chip) and not a driver data structure. You
>>>>>> need to describe the whole chip in the binding. It is a Linux problem
>>>>>> if there needs to be multiple separate drivers.
>>>>>>
>>>>>> IF: Defining complete DT description for the Broadcom combo chips for
>>>>>> multiple interfaces is well beyond the scope of what I am doing. I
>>>>>> just need
>>>>>> to define a DT node for the input and output GPIOs connected to the
>>>>>> BT UART
>>>>>> chip. BT may or may not be part of the combo chip: it does not
>>>>>> really matter
>>>>>> for this exercise. I thought I would take this opportunity to place
>>>>>> some BT
>>>>>> device parameters into that node as well. If you're not comfortable
>>>>>> with
>>>>>> this, I could just call it a "GPIO set" to avoid mentioning BT and
>>>>>> UART at
>>>>>> all but it would make little sense. Still, I could consider it.
>>>>>> Would you
>>>>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code
>>>>>> you're
>>>>>> referring to has parameters configured as Linux module parameters.
>>>>>> I could
>>>>>> do the same too, avoiding this device tree discussion. Let me know.
>>>>>>
>>>>>
>>>>> I don't completely follow what you mean by "GPIO set", but I'm
>>>>> guessing that is not the right path.
>>>>>
>>>>>> Generally speaking (pontification hat on :-)), what you're trying
>>>>>> to do
>>>>>> (description of the whole chip) is well beyond what say ACPI has
>>>>>> done (I was
>>>>>> involved some in the BT ACPI exercise a few years ago). BT UART
>>>>>> interface is
>>>>>> described in ACPI independently of other parts of the same combo chip.
>>>>>> Requirements like that slow down the DT development in my opinion as
>>>>>> companies are understandably reluctant to work with unrealistic
>>>>>> goals. End
>>>>>> of pontification. :-)
>>>>>>
>>>>>
>>>>> ACPI and DT are very different models in terms of abstraction and
>>>>> governance. I'm not going to hash through all the details.
>>>>>
>>>>> I'm not necessarily saying we have to have a single node, but that is
>>>>> my default position. You have convince me that the functions are
>>>>> completely independent and I cannot judge that if you are completely
>>>>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>>>>> supplies at least are shared (something ACPI does not expose). Perhaps
>>>>> we could fudge that and just require the same supply has to be
>>>>> connected to each half. I still worry there could be other internal
>>>>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>>>>> something like that. Maybe not on Broadcom chips, but on other vendors
>>>>> and I have to care about them all.
>>>>
>>>>
>>>>
>>>> All Broadcom combo chips that I know of have separate supplies, ie.
>>>> wl-reg-on and bt-reg-on. There already is a binding present for the wifi
>>>
>>>
>>> GPIOs are not supplies. For the module I'm working with (43340 based)
>>> there is a single VDDIO and VBAT supplies which are shared. Now
>>> whether the module or the chip are tying things together, I don't
>>> know. There is also a 32kHz clock input. Is that part of WiFi or BT?
>>
>>
>> True and I see where you are going here. The 32kHz clock is input for
>> low-power oscillator in the chip. That LPO provides clock for the
>> interconnect in the chip so it is not part of wifi nor bt.

We could handle this by routing clocks and regulators to every sub
node. A device with a shared GPIO (or any resource without
refcounting) would be a problem. Perhaps this is good enough. This
seemed to be the conclusion on earlier discussions[1].

Primarily, I just want to see the whole chip considered and thought
around any complications from shared resources. We can't just do the
easy part now and ignore the hard parts that cause changes later.

I'm not sure how we would handle a shared reset line. Perhaps the
first one to claim it wins control.

> Hi Rob,
>
> Haven't seen much follow up so how to move forward here.

Sorry, been (and still am) out on vacation.

> We could go for a
> devicetree node covering all functional entities on the device. However, we
> are making the chipset and users more often as not end up with a module that
> some manufacturer cooked up. So whether signals are optional or not is hard
> to say for us. Making them optional by default seems safest.
>
> So could something like below work? Just wanted to know your opinion before
> moving in that direction.

It does have the advantage of having the full chip described in one
place, but there are some issues.

> bcm43341: {
>         compatible: 'brcm,bcm43340';
>         brcm,lpo-clock: <&32khz_clk>;

What driver would handle this and instantiate the sub devices? An MFD driver?

If we place all the child nodes under their respective hosts and had a
chip/module level node separately, we would then potentially have
probe ordering issues (probably solvable though).

>         :
>         brcm_wifi: {
>                 compatible: "brcm,bcm4329-fmac";
>                 wifi-port: <&mmc3>;

This should be something generic like "mmc-parent".

This is a departure from how the wifi part is currently done. We could
take the stance that since there are no dts files actually using the
binding, we can change it breaking compatibility (if not upstream it
doesn't exist). Or we need to maintain both. Other combo chips such as
TI have the WiFi portion under SDIO host node.

The other issue potentially is does the SDIO host need to be able to
find the children easily. I think the power on the chip first so the
SDIO host can detect it issue is one example. We also have no way to
define which SDIO function this is. Putting the reg property here
would not make sense. So perhaps the phandle needs to go the other way
around having an mmc sub-node point to here.

So I think we need to keep the SDIO child node.

>                 :
>         }
>         brcm_bt: {
>                 compatible: "brcm,bcm43xx-bt-uart";
>                 bt-port: <&uart1>;

This should also be a generic name such as "uart". This needs to be
settled at wider scope of how we describe UART slave devices. It seems
to be a popular topic recently with yet another posting in the last
few days[2].

Thinking about different potential options now for a few hours, I
think we should just continue with having separate nodes for each
function under the respective host interface. The complicated cases
may just have to be solved with code rather than DT bindings.

Rob

>                 :
>         }
>         brcm_nfc: {
>                 compatible: "brcm,bcm43340-nfc";
>                 nfc-port: <&uart2>;
>                 :
>         }
> }
>

[1] http://lists.infradead.org/pipermail/linux-arm-kernel/2014-January/226343.html
[2] http://www.spinics.net/lists/linux-serial/msg18034.html

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

* Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings
@ 2015-07-02 18:26                                               ` Rob Herring
  0 siblings, 0 replies; 36+ messages in thread
From: Rob Herring @ 2015-07-02 18:26 UTC (permalink / raw)
  To: Arend van Spriel, Grant Likely, Mark Rutland, Kumar Gala,
	Arnd Bergmann, Olof Johansson
  Cc: Ilya Faenson, marcel@holtmann.org, devicetree@vger.kernel.org,
	linux-bluetooth@vger.kernel.org

+ a few more DT maintainers (and frequent reviewers) as this is a
common issue only affecting every single mobile platform.

On Mon, Jun 29, 2015 at 1:36 PM, Arend van Spriel <arend@broadcom.com> wrote:
> On 06/19/15 21:20, Arend van Spriel wrote:
>>
>> On 06/19/15 20:49, Rob Herring wrote:
>>>
>>> On Fri, Jun 19, 2015 at 12:06 PM, Arend van Spriel<arend@broadcom.com>
>>> wrote:
>>>>
>>>> On 06/19/15 17:47, Rob Herring wrote:
>>>>>
>>>>>
>>>>> On Thu, Jun 18, 2015 at 3:37 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>>> wrote:
>>>>>>
>>>>>>
>>>>>> Hi Rob.
>>>>>>
>>>>>> -----Original Message-----
>>>>>> From: linux-bluetooth-owner@vger.kernel.org
>>>>>> [mailto:linux-bluetooth-owner@vger.kernel.org] On Behalf Of Rob
>>>>>> Herring
>>>>>> Sent: Thursday, June 18, 2015 3:41 PM
>>>>>> To: Ilya Faenson
>>>>>> Cc: marcel@holtmann.org; Arend Van Spriel; devicetree@vger.kernel.org;
>>>>>> linux-bluetooth@vger.kernel.org
>>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>>> bindings
>>>>>>
>>>>>> On Thu, Jun 18, 2015 at 1:54 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>>>> wrote:
>>>>>>>
>>>>>>>
>>>>>>> Hi Rob,
>>>>>>
>>>>>>
>>>>>>
>>>>>> Your emails are base64 encoded. They should be plain text for the
>>>>>> list.
>>>>>>
>>>>>> IF: The Outlook is configured to respond in the sender's format. I
>>>>>> therefore respond in the encoding you've used.
>>>>>
>>>>>
>>>>>
>>>>> I assure you that that is not the case or I would be banished from
>>>>> lists by now. Outlook is generally incapable of correctly sending
>>>>> mails to lists. The reply header above is one aspect of that. The
>>>>> other problem is your replies don't get wrapped and prefixed properly.
>>>>> That could be my client I guess, but *all* other mails are fine.
>>>>>
>>>>> My sent mails have:
>>>>>
>>>>> Content-Type: text/plain; charset=UTF-8
>>>>> Content-Transfer-Encoding: quoted-printable
>>>>>
>>>>>
>>>>>>> -----Original Message-----
>>>>>>> From: Rob Herring [mailto:robherring2@gmail.com]
>>>>>>> Sent: Thursday, June 18, 2015 11:03 AM
>>>>>>> To: Ilya Faenson
>>>>>>> Cc: marcel@holtmann.org; Arend Van Spriel;
>>>>>>> devicetree@vger.kernel.org;
>>>>>>> linux-bluetooth@vger.kernel.org
>>>>>>> Subject: Re: FW: [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree
>>>>>>> bindings
>>>>>>>
>>>>>>> On Wed, Jun 17, 2015 at 6:11 PM, Ilya Faenson<ifaenson@broadcom.com>
>>>>>>> wrote:
>>>>>>>>
>>>>>>>>
>>>>>>>> + devicetree lists
>>>>>>
>>>>>>
>>>>>>
>>>>>> [...]
>>>>>>
>>>>>>>> diff --git
>>>>>>>> a/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>>> b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>>> new file mode 100644
>>>>>>>> index 0000000..5dbcd57
>>>>>>>> --- /dev/null
>>>>>>>> +++ b/Documentation/devicetree/bindings/net/bluetooth/btbcm.txt
>>>>>>>> @@ -0,0 +1,86 @@
>>>>>>>> +btbcm
>>>>>>>> +------
>>>>>>>> +
>>>>>>>> +Required properties:
>>>>>>>> +
>>>>>>>> + - compatible : must be "brcm,brcm-bt-uart".
>>>>>>>
>>>>>>>
>>>>>>>
>>>>>>> You need to describe the chip, not the interface.
>>>>>>>
>>>>>>> IF: This driver is for all Broadcom Bluetooth UART based chips.
>>>>>>
>>>>>>
>>>>>>
>>>>>> BT only chips? Most/many Broadcom chips are combo chips. I understand
>>>>>> the driver for BT is *mostly* separate from other chip functions like
>>>>>> WiFi, GPS and NFC, but the h/w is a single chip. I say most because
>>>>>> likely there are some parts shared: a voltage rail, reset line, or
>>>>>> power down line. I think some can do BT over the SDIO interface too,
>>>>>> so the interface may be shared. The DT is a description of the h/w
>>>>>> (i.e. what part # for a chip) and not a driver data structure. You
>>>>>> need to describe the whole chip in the binding. It is a Linux problem
>>>>>> if there needs to be multiple separate drivers.
>>>>>>
>>>>>> IF: Defining complete DT description for the Broadcom combo chips for
>>>>>> multiple interfaces is well beyond the scope of what I am doing. I
>>>>>> just need
>>>>>> to define a DT node for the input and output GPIOs connected to the
>>>>>> BT UART
>>>>>> chip. BT may or may not be part of the combo chip: it does not
>>>>>> really matter
>>>>>> for this exercise. I thought I would take this opportunity to place
>>>>>> some BT
>>>>>> device parameters into that node as well. If you're not comfortable
>>>>>> with
>>>>>> this, I could just call it a "GPIO set" to avoid mentioning BT and
>>>>>> UART at
>>>>>> all but it would make little sense. Still, I could consider it.
>>>>>> Would you
>>>>>> have "GPIO set" recommendations? Alternatively, NFC Marvell code
>>>>>> you're
>>>>>> referring to has parameters configured as Linux module parameters.
>>>>>> I could
>>>>>> do the same too, avoiding this device tree discussion. Let me know.
>>>>>>
>>>>>
>>>>> I don't completely follow what you mean by "GPIO set", but I'm
>>>>> guessing that is not the right path.
>>>>>
>>>>>> Generally speaking (pontification hat on :-)), what you're trying
>>>>>> to do
>>>>>> (description of the whole chip) is well beyond what say ACPI has
>>>>>> done (I was
>>>>>> involved some in the BT ACPI exercise a few years ago). BT UART
>>>>>> interface is
>>>>>> described in ACPI independently of other parts of the same combo chip.
>>>>>> Requirements like that slow down the DT development in my opinion as
>>>>>> companies are understandably reluctant to work with unrealistic
>>>>>> goals. End
>>>>>> of pontification. :-)
>>>>>>
>>>>>
>>>>> ACPI and DT are very different models in terms of abstraction and
>>>>> governance. I'm not going to hash through all the details.
>>>>>
>>>>> I'm not necessarily saying we have to have a single node, but that is
>>>>> my default position. You have convince me that the functions are
>>>>> completely independent and I cannot judge that if you are completely
>>>>> ignoring the WiFi part. From Broadcom chips I've worked with, the
>>>>> supplies at least are shared (something ACPI does not expose). Perhaps
>>>>> we could fudge that and just require the same supply has to be
>>>>> connected to each half. I still worry there could be other internal
>>>>> inter-dependencies. Perhaps BT requires the SDIO clock to be active or
>>>>> something like that. Maybe not on Broadcom chips, but on other vendors
>>>>> and I have to care about them all.
>>>>
>>>>
>>>>
>>>> All Broadcom combo chips that I know of have separate supplies, ie.
>>>> wl-reg-on and bt-reg-on. There already is a binding present for the wifi
>>>
>>>
>>> GPIOs are not supplies. For the module I'm working with (43340 based)
>>> there is a single VDDIO and VBAT supplies which are shared. Now
>>> whether the module or the chip are tying things together, I don't
>>> know. There is also a 32kHz clock input. Is that part of WiFi or BT?
>>
>>
>> True and I see where you are going here. The 32kHz clock is input for
>> low-power oscillator in the chip. That LPO provides clock for the
>> interconnect in the chip so it is not part of wifi nor bt.

We could handle this by routing clocks and regulators to every sub
node. A device with a shared GPIO (or any resource without
refcounting) would be a problem. Perhaps this is good enough. This
seemed to be the conclusion on earlier discussions[1].

Primarily, I just want to see the whole chip considered and thought
around any complications from shared resources. We can't just do the
easy part now and ignore the hard parts that cause changes later.

I'm not sure how we would handle a shared reset line. Perhaps the
first one to claim it wins control.

> Hi Rob,
>
> Haven't seen much follow up so how to move forward here.

Sorry, been (and still am) out on vacation.

> We could go for a
> devicetree node covering all functional entities on the device. However, we
> are making the chipset and users more often as not end up with a module that
> some manufacturer cooked up. So whether signals are optional or not is hard
> to say for us. Making them optional by default seems safest.
>
> So could something like below work? Just wanted to know your opinion before
> moving in that direction.

It does have the advantage of having the full chip described in one
place, but there are some issues.

> bcm43341: {
>         compatible: 'brcm,bcm43340';
>         brcm,lpo-clock: <&32khz_clk>;

What driver would handle this and instantiate the sub devices? An MFD driver?

If we place all the child nodes under their respective hosts and had a
chip/module level node separately, we would then potentially have
probe ordering issues (probably solvable though).

>         :
>         brcm_wifi: {
>                 compatible: "brcm,bcm4329-fmac";
>                 wifi-port: <&mmc3>;

This should be something generic like "mmc-parent".

This is a departure from how the wifi part is currently done. We could
take the stance that since there are no dts files actually using the
binding, we can change it breaking compatibility (if not upstream it
doesn't exist). Or we need to maintain both. Other combo chips such as
TI have the WiFi portion under SDIO host node.

The other issue potentially is does the SDIO host need to be able to
find the children easily. I think the power on the chip first so the
SDIO host can detect it issue is one example. We also have no way to
define which SDIO function this is. Putting the reg property here
would not make sense. So perhaps the phandle needs to go the other way
around having an mmc sub-node point to here.

So I think we need to keep the SDIO child node.

>                 :
>         }
>         brcm_bt: {
>                 compatible: "brcm,bcm43xx-bt-uart";
>                 bt-port: <&uart1>;

This should also be a generic name such as "uart". This needs to be
settled at wider scope of how we describe UART slave devices. It seems
to be a popular topic recently with yet another posting in the last
few days[2].

Thinking about different potential options now for a few hours, I
think we should just continue with having separate nodes for each
function under the respective host interface. The complicated cases
may just have to be solved with code rather than DT bindings.

Rob

>                 :
>         }
>         brcm_nfc: {
>                 compatible: "brcm,bcm43340-nfc";
>                 nfc-port: <&uart2>;
>                 :
>         }
> }
>

[1] http://lists.infradead.org/pipermail/linux-arm-kernel/2014-January/226343.html
[2] http://www.spinics.net/lists/linux-serial/msg18034.html

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

end of thread, other threads:[~2015-07-02 18:26 UTC | newest]

Thread overview: 36+ messages (download: mbox.gz / follow: Atom feed)
-- links below jump to the message on this page --
2015-06-17 21:30 [PATCH v4 0/4] Broadcom Bluetooth UART device driver Ilya Faenson
2015-06-17 21:30 ` [PATCH v4 1/4] Broadcom Bluetooth UART Device Tree bindings Ilya Faenson
2015-06-17 21:33   ` Arend van Spriel
     [not found]   ` <1434576658-20730-2-git-send-email-ifaenson-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
2015-06-17 23:11     ` FW: " Ilya Faenson
2015-06-17 23:11       ` Ilya Faenson
     [not found]       ` <E0D3336E15B58B4294723AC879BA5E942634F2-Wwdb2uEOBX8N93KskqRXH71+IgudQmzARxWJa1zDYLQ@public.gmane.org>
2015-06-18 15:02         ` Rob Herring
2015-06-18 15:02           ` Rob Herring
     [not found]           ` <CAL_JsqK9kup3sm3qgDLqtT8ajrN1ee6zfXwOoZqoq9cXQNwE_w-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
2015-06-18 18:54             ` Ilya Faenson
2015-06-18 18:54               ` Ilya Faenson
     [not found]               ` <E0D3336E15B58B4294723AC879BA5E94263E58-Wwdb2uEOBX8N93KskqRXH71+IgudQmzARxWJa1zDYLQ@public.gmane.org>
2015-06-18 19:41                 ` Rob Herring
2015-06-18 19:41                   ` Rob Herring
     [not found]                   ` <CAL_JsqJAUTjNehtr_Af93k71mdSREb9pLMoSyDTm1S42VkA2sQ-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
2015-06-18 20:37                     ` Ilya Faenson
2015-06-18 20:37                       ` Ilya Faenson
     [not found]                       ` <E0D3336E15B58B4294723AC879BA5E942640A3-Wwdb2uEOBX8N93KskqRXH71+IgudQmzARxWJa1zDYLQ@public.gmane.org>
2015-06-19 15:47                         ` Rob Herring
2015-06-19 15:47                           ` Rob Herring
     [not found]                           ` <CAL_JsqJKyj8sDwG82jb_CzXEDBN8aznR7eF5yTOiWruW8o3cng-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
2015-06-19 17:06                             ` Arend van Spriel
2015-06-19 17:06                               ` Arend van Spriel
     [not found]                               ` <55844C1E.8020301-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
2015-06-19 18:49                                 ` Rob Herring
2015-06-19 18:49                                   ` Rob Herring
     [not found]                                   ` <CAL_JsqLr7JZ9=i2XuWR0_FZDyxpDRwDS5dkSpzjKA-8V=-mpOw-JsoAwUIsXosN+BqQ9rBEUg@public.gmane.org>
2015-06-19 19:20                                     ` Arend van Spriel
2015-06-19 19:20                                       ` Arend van Spriel
     [not found]                                       ` <55846B7D.1060601-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
2015-06-29 18:36                                         ` Arend van Spriel
2015-06-29 18:36                                           ` Arend van Spriel
     [not found]                                           ` <55919023.200-dY08KVG/lbpWk0Htik3J/w@public.gmane.org>
2015-07-02 18:26                                             ` Rob Herring
2015-07-02 18:26                                               ` Rob Herring
2015-06-19 20:37                             ` Ilya Faenson
2015-06-19 20:37                               ` Ilya Faenson
2015-06-19 19:23   ` Fabio Estevam
2015-06-19 20:40     ` Ilya Faenson
2015-06-17 21:30 ` [PATCH v4 2/4] hci_uart: line discipline enhancements Ilya Faenson
2015-06-17 21:50   ` Marcel Holtmann
2015-06-17 21:53     ` Ilya Faenson
2015-06-18  9:46       ` Frederic Danis
2015-06-18 10:17         ` Marcel Holtmann
2015-06-17 21:30 ` [PATCH v4 3/4] btbcm_uart: Broadcom UART Platform Driver Ilya Faenson
2015-06-17 21:30 ` [PATCH v4 4/4] hci_bcm: Broadcom UART protocol enhancements Ilya Faenson

This is an external index of several public inboxes,
see mirroring instructions on how to clone and mirror
all data and code used by this external index.