2014-12-13 22:37:37

by Pavel Machek

[permalink] [raw]
Subject: bluetooth: Add hci_h4p driver

Add hci_h4p bluetooth driver to staging tree. This device is used
for example on Nokia N900 cell phone.

Signed-off-by: Pavel Machek <[email protected]>
Thanks-to: Sebastian Reichel <[email protected]>
Thanks-to: Joe Perches <[email protected]>

---


I'd prefer to resurect the driver in staging/ in order not to lose
history, but Marcel wanted to treat it as new submission, so I'm doing
that.

Firmware load was converted to hci_cmd_sync(). Unfortunately, the
firmware is needed after every open/close, so the setup mechanism does
not quite fit. (But code is now way cleaner).

Device tree bindings work for me, but they are not yet official and I
expect some more fun there.

Hacks surrounding bluetooth address were removed; this results in
working driver with address that is probably not unique.

HCI_QUIRK_RESET_ON_CLOSE will need to be investigated some more.

My notes say that Marcel wanted different filenames, but I'd need
advice exactly what filenames. I guess platform data supprort should
be removed altogether, rather than renamed.

Thanks,
Pavel

diff --git a/drivers/bluetooth/Kconfig b/drivers/bluetooth/Kconfig
index 4547dc2..0fc7d3a 100644
--- a/drivers/bluetooth/Kconfig
+++ b/drivers/bluetooth/Kconfig
@@ -243,4 +243,14 @@ config BT_WILINK
Say Y here to compile support for Texas Instrument's WiLink7 driver
into the kernel or say M to compile it as module (btwilink).

+config BT_NOKIA_H4P
+ tristate "HCI driver with H4 Nokia extensions"
+ depends on ARCH_OMAP
+ help
+ Bluetooth HCI driver with H4 extensions. This driver provides
+ support for H4+ Bluetooth chip with vendor-specific H4 extensions.
+
+ Say Y here to compile support for h4 extended devices into the kernel
+ or say M to compile it as module (btnokia_h4p).
+
endmenu
diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
index 9fe8a87..ec7074fe 100644
--- a/drivers/bluetooth/Makefile
+++ b/drivers/bluetooth/Makefile
@@ -31,4 +31,7 @@ hci_uart-$(CONFIG_BT_HCIUART_ATH3K) += hci_ath.o
hci_uart-$(CONFIG_BT_HCIUART_3WIRE) += hci_h5.o
hci_uart-objs := $(hci_uart-y)

+obj-$(CONFIG_BT_NOKIA_H4P) += hci_h4p.o
+hci_h4p-objs := nokia_core.o nokia_fw.o nokia_uart.o
+
ccflags-y += -D__CHECK_ENDIAN__
new file mode 100644
index 0000000..6445a99
--- /dev/null
+++ b/drivers/bluetooth/hci_h4p.h
@@ -0,0 +1,234 @@
+/*
+ * This file is part of Nokia H4P bluetooth driver
+ *
+ * Copyright (C) 2005-2008 Nokia Corporation.
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ */
+
+#ifndef __DRIVERS_BLUETOOTH_H4P_H
+#define __DRIVERS_BLUETOOTH_H4P_H
+
+#include <net/bluetooth/bluetooth.h>
+#include <net/bluetooth/hci_core.h>
+#include <net/bluetooth/hci.h>
+
+#include <linux/serial_reg.h>
+
+#define UART_SYSC_OMAP_RESET 0x03
+#define UART_SYSS_RESETDONE 0x01
+#define UART_OMAP_SCR_EMPTY_THR 0x08
+#define UART_OMAP_SCR_WAKEUP 0x10
+#define UART_OMAP_SSR_WAKEUP 0x02
+#define UART_OMAP_SSR_TXFULL 0x01
+
+#define UART_OMAP_SYSC_IDLEMODE 0x03
+#define UART_OMAP_SYSC_IDLEMASK (3 << UART_OMAP_SYSC_IDLEMODE)
+
+#define UART_OMAP_SYSC_FORCE_IDLE (0 << UART_OMAP_SYSC_IDLEMODE)
+#define UART_OMAP_SYSC_NO_IDLE (1 << UART_OMAP_SYSC_IDLEMODE)
+#define UART_OMAP_SYSC_SMART_IDLE (2 << UART_OMAP_SYSC_IDLEMODE)
+
+#define H4P_TRANSFER_MODE 1
+#define H4P_SCHED_TRANSFER_MODE 2
+#define H4P_ACTIVE_MODE 3
+
+struct h4p_info {
+ struct timer_list lazy_release;
+ struct hci_dev *hdev;
+ spinlock_t lock;
+
+ void __iomem *uart_base;
+ unsigned long uart_phys_base;
+ int irq;
+ struct device *dev;
+ u8 chip_type;
+ u8 bt_wakeup_gpio;
+ u8 host_wakeup_gpio;
+ u8 reset_gpio;
+ u8 reset_gpio_shared;
+ u8 bt_sysclk;
+ u8 man_id;
+ u8 ver_id;
+
+ struct sk_buff_head fw_queue;
+ struct sk_buff *alive_cmd_skb;
+ struct completion init_completion;
+ struct completion fw_completion;
+ struct completion test_completion;
+ int fw_error;
+ int init_error;
+
+ struct sk_buff_head txq;
+
+ struct sk_buff *rx_skb;
+ long rx_count;
+ unsigned long rx_state;
+ unsigned long garbage_bytes;
+
+ bdaddr_t bd_addr;
+ struct sk_buff_head *fw_q;
+
+ int pm_enabled;
+ int tx_enabled;
+ int autorts;
+ int rx_enabled;
+ unsigned long pm_flags;
+
+ int tx_clocks_en;
+ int rx_clocks_en;
+ spinlock_t clocks_lock;
+ struct clk *uart_iclk;
+ struct clk *uart_fclk;
+ atomic_t clk_users;
+ u16 dll;
+ u16 dlh;
+ u16 ier;
+ u16 mdr1;
+ u16 efr;
+
+ int initing;
+};
+
+struct h4p_radio_hdr {
+ u8 evt;
+ u8 dlen;
+} __packed;
+
+struct h4p_neg_hdr {
+ u8 dlen;
+} __packed;
+#define H4P_NEG_HDR_SIZE 1
+
+#define H4P_NEG_REQ 0x00
+#define H4P_NEG_ACK 0x20
+#define H4P_NEG_NAK 0x40
+
+#define H4P_PROTO_PKT 0x44
+#define H4P_PROTO_BYTE 0x4c
+
+#define H4P_ID_CSR 0x02
+#define H4P_ID_BCM2048 0x04
+#define H4P_ID_TI1271 0x31
+
+struct h4p_neg_cmd {
+ u8 ack;
+ u16 baud;
+ u16 unused1;
+ u8 proto;
+ u16 sys_clk;
+ u16 unused2;
+} __packed;
+
+struct h4p_neg_evt {
+ u8 ack;
+ u16 baud;
+ u16 unused1;
+ u8 proto;
+ u16 sys_clk;
+ u16 unused2;
+ u8 man_id;
+ u8 ver_id;
+} __packed;
+
+#define H4P_ALIVE_REQ 0x55
+#define H4P_ALIVE_RESP 0xcc
+
+struct h4p_alive_hdr {
+ u8 dlen;
+} __packed;
+#define H4P_ALIVE_HDR_SIZE 1
+
+struct h4p_alive_pkt {
+ u8 mid;
+ u8 unused;
+} __packed;
+
+#define MAX_BAUD_RATE 921600
+#define BC4_MAX_BAUD_RATE 3692300
+#define UART_CLOCK 48000000
+#define BT_INIT_DIVIDER 320
+#define BT_BAUDRATE_DIVIDER 384000000
+#define BT_SYSCLK_DIV 1000
+#define INIT_SPEED 120000
+
+#define H4_TYPE_SIZE 1
+#define H4_RADIO_HDR_SIZE 2
+
+/* H4+ packet types */
+#define H4_CMD_PKT 0x01
+#define H4_ACL_PKT 0x02
+#define H4_SCO_PKT 0x03
+#define H4_EVT_PKT 0x04
+#define H4_NEG_PKT 0x06
+#define H4_ALIVE_PKT 0x07
+#define H4_RADIO_PKT 0x08
+
+/* TX states */
+#define WAIT_FOR_PKT_TYPE 1
+#define WAIT_FOR_HEADER 2
+#define WAIT_FOR_DATA 3
+
+struct hci_fw_event {
+ struct hci_event_hdr hev;
+ struct hci_ev_cmd_complete cmd;
+ u8 status;
+} __packed;
+
+void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb);
+
+int h4p_send_alive_packet(struct h4p_info *info);
+
+int h4p_read_fw(struct h4p_info *info);
+int h4p_send_fw(struct h4p_info *info);
+void h4p_parse_fw_event(struct h4p_info *info, struct sk_buff *skb);
+
+static inline void h4p_outb(struct h4p_info *info, unsigned int offset, u8 val)
+{
+ __raw_writeb(val, info->uart_base + (offset << 2));
+}
+
+static inline u8 h4p_inb(struct h4p_info *info, unsigned int offset)
+{
+ u8 val;
+ val = __raw_readb(info->uart_base + (offset << 2));
+ return val;
+}
+
+static inline void h4p_set_rts(struct h4p_info *info, int active)
+{
+ u8 b;
+
+ b = h4p_inb(info, UART_MCR);
+ if (active)
+ b |= UART_MCR_RTS;
+ else
+ b &= ~UART_MCR_RTS;
+ h4p_outb(info, UART_MCR, b);
+}
+
+int h4p_wait_for_cts(struct h4p_info *info, int active, int timeout_ms);
+void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
+void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
+void h4p_change_speed(struct h4p_info *info, unsigned long speed);
+int h4p_reset_uart(struct h4p_info *info);
+void h4p_init_uart(struct h4p_info *info);
+void h4p_enable_tx(struct h4p_info *info);
+void h4p_store_regs(struct h4p_info *info);
+void h4p_restore_regs(struct h4p_info *info);
+void h4p_smart_idle(struct h4p_info *info, bool enable);
+
+#endif /* __DRIVERS_BLUETOOTH_H4P_H */
diff --git a/drivers/bluetooth/nokia_core.c b/drivers/bluetooth/nokia_core.c
new file mode 100644
index 0000000..ca9746d
--- /dev/null
+++ b/drivers/bluetooth/nokia_core.c
@@ -0,0 +1,1262 @@
+/*
+ * This file is part of Nokia H4P bluetooth driver
+ *
+ * Copyright (C) 2005-2008 Nokia Corporation.
+ * Copyright (C) 2014 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * Thanks to all the Nokia people that helped with this driver,
+ * including Ville Tervo and Roger Quadros.
+ *
+ * Power saving functionality was removed from this driver to make
+ * merging easier.
+ */
+
+/*
+insmod hci_h4p.ko && hciconfig hci0 up && hcitool inq && hciconfig hci0 down && hciconfig hci0 up && hcitool inq && rmmod hci_h4p
+
+*/
+
+#include <linux/module.h>
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/errno.h>
+#include <linux/delay.h>
+#include <linux/spinlock.h>
+#include <linux/serial_reg.h>
+#include <linux/skbuff.h>
+#include <linux/device.h>
+#include <linux/platform_device.h>
+#include <linux/clk.h>
+#include <linux/interrupt.h>
+#include <linux/gpio.h>
+#include <linux/of_gpio.h>
+#include <linux/of_irq.h>
+#include <linux/timer.h>
+#include <linux/kthread.h>
+#include <linux/io.h>
+#include <linux/completion.h>
+#include <linux/sizes.h>
+
+#include <net/bluetooth/bluetooth.h>
+#include <net/bluetooth/hci_core.h>
+#include <net/bluetooth/hci.h>
+
+#include <linux/platform_data/bt-nokia-h4p.h>
+
+#include "hci_h4p.h"
+
+#define BT_DBG(a...) do {} while(0)
+
+/* This should be used in function that cannot release clocks */
+static void h4p_set_clk(struct h4p_info *info, int *clock, int enable)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->clocks_lock, flags);
+ if (enable && !*clock) {
+ BT_DBG("Enabling %p", clock);
+ clk_prepare_enable(info->uart_fclk);
+ clk_prepare_enable(info->uart_iclk);
+ if (atomic_read(&info->clk_users) == 0)
+ h4p_restore_regs(info);
+ atomic_inc(&info->clk_users);
+ }
+
+ if (!enable && *clock) {
+ BT_DBG("Disabling %p", clock);
+ if (atomic_dec_and_test(&info->clk_users))
+ h4p_store_regs(info);
+ clk_disable_unprepare(info->uart_fclk);
+ clk_disable_unprepare(info->uart_iclk);
+ }
+
+ *clock = enable;
+ spin_unlock_irqrestore(&info->clocks_lock, flags);
+}
+
+static void h4p_lazy_clock_release(unsigned long data)
+{
+ struct h4p_info *info = (struct h4p_info *)data;
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->lock, flags);
+ if (!info->tx_enabled)
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+/* Power management functions */
+void h4p_smart_idle(struct h4p_info *info, bool enable)
+{
+ u8 v;
+
+ v = h4p_inb(info, UART_OMAP_SYSC);
+ v &= ~(UART_OMAP_SYSC_IDLEMASK);
+
+ if (enable)
+ v |= UART_OMAP_SYSC_SMART_IDLE;
+ else
+ v |= UART_OMAP_SYSC_NO_IDLE;
+
+ h4p_outb(info, UART_OMAP_SYSC, v);
+}
+
+static inline void h4p_schedule_pm(struct h4p_info *info)
+{
+}
+
+static void h4p_disable_tx(struct h4p_info *info)
+{
+ if (!info->pm_enabled)
+ return;
+
+ /* Re-enable smart-idle */
+ h4p_smart_idle(info, 1);
+
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ mod_timer(&info->lazy_release, jiffies + msecs_to_jiffies(100));
+ info->tx_enabled = 0;
+}
+
+void h4p_enable_tx_nopm(struct h4p_info *info)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->lock, flags);
+ h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
+ UART_IER_THRI);
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+void h4p_enable_tx(struct h4p_info *info)
+{
+ unsigned long flags;
+
+ if (!info->pm_enabled)
+ return;
+
+ h4p_schedule_pm(info);
+
+ spin_lock_irqsave(&info->lock, flags);
+ del_timer(&info->lazy_release);
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ info->tx_enabled = 1;
+ gpio_set_value(info->bt_wakeup_gpio, 1);
+ h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
+ UART_IER_THRI);
+ /*
+ * Disable smart-idle as UART TX interrupts
+ * are not wake-up capable
+ */
+ h4p_smart_idle(info, 0);
+
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+static void h4p_disable_rx(struct h4p_info *info)
+{
+ if (!info->pm_enabled)
+ return;
+
+ info->rx_enabled = 0;
+
+ if (h4p_inb(info, UART_LSR) & UART_LSR_DR)
+ return;
+
+ if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
+ return;
+
+ __h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
+ info->autorts = 0;
+ h4p_set_clk(info, &info->rx_clocks_en, 0);
+}
+
+static void h4p_enable_rx(struct h4p_info *info)
+{
+ if (!info->pm_enabled)
+ return;
+
+ h4p_schedule_pm(info);
+
+ h4p_set_clk(info, &info->rx_clocks_en, 1);
+ info->rx_enabled = 1;
+
+ if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
+ return;
+
+ __h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
+ info->autorts = 1;
+}
+
+void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb)
+{
+ skb_queue_tail(&info->txq, skb);
+ h4p_enable_tx_nopm(info);
+}
+
+/* Negotiation functions */
+int h4p_send_alive_packet(struct h4p_info *info)
+{
+ struct h4p_alive_hdr *hdr;
+ struct h4p_alive_pkt *pkt;
+ struct sk_buff *skb;
+ int len;
+
+ BT_DBG("Sending alive packet");
+
+ len = H4_TYPE_SIZE + sizeof(*hdr) + sizeof(*pkt);
+ skb = bt_skb_alloc(len, GFP_KERNEL);
+ if (!skb)
+ return -ENOMEM;
+
+ memset(skb->data, 0x00, len);
+ *skb_put(skb, 1) = H4_ALIVE_PKT;
+ hdr = (struct h4p_alive_hdr *)skb_put(skb, sizeof(*hdr));
+ hdr->dlen = sizeof(*pkt);
+ pkt = (struct h4p_alive_pkt *)skb_put(skb, sizeof(*pkt));
+ pkt->mid = H4P_ALIVE_REQ;
+
+ h4p_simple_send_frame(info, skb);
+
+ BT_DBG("Alive packet sent");
+
+ return 0;
+}
+
+static void h4p_alive_packet(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ struct h4p_alive_hdr *hdr;
+ struct h4p_alive_pkt *pkt;
+
+ BT_DBG("Received alive packet");
+ hdr = (struct h4p_alive_hdr *)skb->data;
+ if (hdr->dlen != sizeof(*pkt)) {
+ dev_err(info->dev, "Corrupted alive message\n");
+ info->init_error = -EIO;
+ goto finish_alive;
+ }
+
+ pkt = (struct h4p_alive_pkt *)skb_pull(skb, sizeof(*hdr));
+ if (pkt->mid != H4P_ALIVE_RESP) {
+ dev_err(info->dev, "Could not negotiate hci_h4p settings\n");
+ info->init_error = -EINVAL;
+ }
+
+finish_alive:
+ complete(&info->init_completion);
+ kfree_skb(skb);
+}
+
+static int h4p_send_negotiation(struct h4p_info *info)
+{
+ struct h4p_neg_cmd *neg_cmd;
+ struct h4p_neg_hdr *neg_hdr;
+ struct sk_buff *skb;
+ int err, len;
+ u16 sysclk = 38400;
+
+ printk("Sending negotiation..");
+ len = sizeof(*neg_cmd) + sizeof(*neg_hdr) + H4_TYPE_SIZE;
+
+ skb = bt_skb_alloc(len, GFP_KERNEL);
+ if (!skb)
+ return -ENOMEM;
+
+ memset(skb->data, 0x00, len);
+ *skb_put(skb, 1) = H4_NEG_PKT;
+ neg_hdr = (struct h4p_neg_hdr *)skb_put(skb, sizeof(*neg_hdr));
+ neg_cmd = (struct h4p_neg_cmd *)skb_put(skb, sizeof(*neg_cmd));
+
+ neg_hdr->dlen = sizeof(*neg_cmd);
+ neg_cmd->ack = H4P_NEG_REQ;
+ neg_cmd->baud = cpu_to_le16(BT_BAUDRATE_DIVIDER/MAX_BAUD_RATE);
+ neg_cmd->proto = H4P_PROTO_BYTE;
+ neg_cmd->sys_clk = cpu_to_le16(sysclk);
+
+ h4p_change_speed(info, INIT_SPEED);
+
+ h4p_set_rts(info, 1);
+ info->init_error = 0;
+ init_completion(&info->init_completion);
+
+ h4p_simple_send_frame(info, skb);
+
+ if (!wait_for_completion_interruptible_timeout(&info->init_completion,
+ msecs_to_jiffies(1000))) {
+ printk("h4p: negotiation did not return\n");
+ return -ETIMEDOUT;
+ }
+
+ if (info->init_error < 0)
+ return info->init_error;
+
+ /* Change to operational settings */
+ h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
+ h4p_set_rts(info, 0);
+ h4p_change_speed(info, MAX_BAUD_RATE);
+
+ err = h4p_wait_for_cts(info, 1, 100);
+ if (err < 0)
+ return err;
+
+ h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
+ init_completion(&info->init_completion);
+ err = h4p_send_alive_packet(info);
+
+ if (err < 0)
+ return err;
+
+ if (!wait_for_completion_interruptible_timeout(&info->init_completion,
+ msecs_to_jiffies(1000)))
+ return -ETIMEDOUT;
+
+ if (info->init_error < 0)
+ return info->init_error;
+
+ printk("Negotiation successful\n");
+ return 0;
+}
+
+static void h4p_negotiation_packet(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ struct h4p_neg_hdr *hdr;
+ struct h4p_neg_evt *evt;
+
+ hdr = (struct h4p_neg_hdr *)skb->data;
+ if (hdr->dlen != sizeof(*evt)) {
+ info->init_error = -EIO;
+ goto finish_neg;
+ }
+
+ evt = (struct h4p_neg_evt *)skb_pull(skb, sizeof(*hdr));
+
+ if (evt->ack != H4P_NEG_ACK) {
+ dev_err(info->dev, "Could not negotiate hci_h4p settings\n");
+ info->init_error = -EINVAL;
+ }
+
+ info->man_id = evt->man_id;
+ info->ver_id = evt->ver_id;
+ printk("Negotiation finished.\n");
+
+finish_neg:
+
+ complete(&info->init_completion);
+ kfree_skb(skb);
+}
+
+/* H4 packet handling functions */
+static int h4p_get_hdr_len(struct h4p_info *info, u8 pkt_type)
+{
+ long retval;
+
+ switch (pkt_type) {
+ case H4_EVT_PKT:
+ retval = HCI_EVENT_HDR_SIZE;
+ break;
+ case H4_ACL_PKT:
+ retval = HCI_ACL_HDR_SIZE;
+ break;
+ case H4_SCO_PKT:
+ retval = HCI_SCO_HDR_SIZE;
+ break;
+ case H4_NEG_PKT:
+ retval = H4P_NEG_HDR_SIZE;
+ break;
+ case H4_ALIVE_PKT:
+ retval = H4P_ALIVE_HDR_SIZE;
+ break;
+ case H4_RADIO_PKT:
+ retval = H4_RADIO_HDR_SIZE;
+ break;
+ default:
+ dev_err(info->dev, "Unknown H4 packet type 0x%.2x\n", pkt_type);
+ retval = -1;
+ break;
+ }
+
+ return retval;
+}
+
+static unsigned int h4p_get_data_len(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ long retval = -1;
+ struct hci_acl_hdr *acl_hdr;
+ struct hci_sco_hdr *sco_hdr;
+ struct hci_event_hdr *evt_hdr;
+ struct h4p_neg_hdr *neg_hdr;
+ struct h4p_alive_hdr *alive_hdr;
+ struct h4p_radio_hdr *radio_hdr;
+
+ switch (bt_cb(skb)->pkt_type) {
+ case H4_EVT_PKT:
+ evt_hdr = (struct hci_event_hdr *)skb->data;
+ retval = evt_hdr->plen;
+ break;
+ case H4_ACL_PKT:
+ acl_hdr = (struct hci_acl_hdr *)skb->data;
+ retval = le16_to_cpu(acl_hdr->dlen);
+ break;
+ case H4_SCO_PKT:
+ sco_hdr = (struct hci_sco_hdr *)skb->data;
+ retval = sco_hdr->dlen;
+ break;
+ case H4_RADIO_PKT:
+ radio_hdr = (struct h4p_radio_hdr *)skb->data;
+ retval = radio_hdr->dlen;
+ break;
+ case H4_NEG_PKT:
+ neg_hdr = (struct h4p_neg_hdr *)skb->data;
+ retval = neg_hdr->dlen;
+ break;
+ case H4_ALIVE_PKT:
+ alive_hdr = (struct h4p_alive_hdr *)skb->data;
+ retval = alive_hdr->dlen;
+ break;
+ }
+
+ return retval;
+}
+
+static inline void h4p_recv_frame(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ if (info->initing)
+ /*if (unlikely(!test_bit(HCI_RUNNING, &info->hdev->flags))) */ {
+ switch (bt_cb(skb)->pkt_type) {
+ case H4_NEG_PKT:
+ h4p_negotiation_packet(info, skb);
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ return;
+ case H4_ALIVE_PKT:
+ h4p_alive_packet(info, skb);
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ return;
+ }
+ }
+
+ hci_recv_frame(info->hdev, skb);
+ BT_DBG("Frame sent to upper layer");
+}
+
+static inline void h4p_handle_byte(struct h4p_info *info, u8 byte)
+{
+ switch (info->rx_state) {
+ case WAIT_FOR_PKT_TYPE:
+ bt_cb(info->rx_skb)->pkt_type = byte;
+ info->rx_count = h4p_get_hdr_len(info, byte);
+ if (info->rx_count < 0) {
+ info->hdev->stat.err_rx++;
+ kfree_skb(info->rx_skb);
+ info->rx_skb = NULL;
+ } else {
+ info->rx_state = WAIT_FOR_HEADER;
+ }
+ break;
+ case WAIT_FOR_HEADER:
+ info->rx_count--;
+ *skb_put(info->rx_skb, 1) = byte;
+ if (info->rx_count != 0)
+ break;
+ info->rx_count = h4p_get_data_len(info, info->rx_skb);
+ if (info->rx_count > skb_tailroom(info->rx_skb)) {
+ dev_err(info->dev, "frame too long\n");
+ info->garbage_bytes = info->rx_count
+ - skb_tailroom(info->rx_skb);
+ kfree_skb(info->rx_skb);
+ info->rx_skb = NULL;
+ break;
+ }
+ info->rx_state = WAIT_FOR_DATA;
+ break;
+ case WAIT_FOR_DATA:
+ info->rx_count--;
+ *skb_put(info->rx_skb, 1) = byte;
+ break;
+ default:
+ WARN_ON(1);
+ break;
+ }
+
+ if (info->rx_count == 0) {
+ /* H4+ devices should always send word aligned packets */
+ if (!(info->rx_skb->len % 2))
+ info->garbage_bytes++;
+ h4p_recv_frame(info, info->rx_skb);
+ info->rx_skb = NULL;
+ }
+}
+
+static void h4p_rx_tasklet(unsigned long data)
+{
+ u8 byte;
+ struct h4p_info *info = (struct h4p_info *)data;
+
+ BT_DBG("tasklet woke up");
+ BT_DBG("rx_tasklet woke up");
+
+ while (h4p_inb(info, UART_LSR) & UART_LSR_DR) {
+ byte = h4p_inb(info, UART_RX);
+ BT_DBG("[in: %02x]", byte);
+ if (info->garbage_bytes) {
+ info->garbage_bytes--;
+ continue;
+ }
+ if (info->rx_skb == NULL) {
+ info->rx_skb = bt_skb_alloc(HCI_MAX_FRAME_SIZE,
+ GFP_ATOMIC | GFP_DMA);
+ if (!info->rx_skb) {
+ dev_err(info->dev,
+ "No memory for new packet\n");
+ goto finish_rx;
+ }
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ info->rx_skb->dev = (void *)info->hdev;
+ }
+ info->hdev->stat.byte_rx++;
+ h4p_handle_byte(info, byte);
+ }
+
+ if (!info->rx_enabled) {
+ if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT &&
+ info->autorts) {
+ __h4p_set_auto_ctsrts(info, 0 , UART_EFR_RTS);
+ info->autorts = 0;
+ }
+ /* Flush posted write to avoid spurious interrupts */
+ h4p_inb(info, UART_OMAP_SCR);
+ h4p_set_clk(info, &info->rx_clocks_en, 0);
+ }
+
+finish_rx:
+ BT_DBG("rx_ended");
+}
+
+static void h4p_tx_tasklet(unsigned long data)
+{
+ unsigned int sent = 0;
+ struct sk_buff *skb;
+ struct h4p_info *info = (struct h4p_info *)data;
+
+ BT_DBG("tasklet woke up");
+ BT_DBG("tx_tasklet woke up");
+
+ if (info->autorts != info->rx_enabled) {
+ if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
+ if (info->autorts && !info->rx_enabled) {
+ __h4p_set_auto_ctsrts(info, 0,
+ UART_EFR_RTS);
+ info->autorts = 0;
+ }
+ if (!info->autorts && info->rx_enabled) {
+ __h4p_set_auto_ctsrts(info, 1,
+ UART_EFR_RTS);
+ info->autorts = 1;
+ }
+ } else {
+ h4p_outb(info, UART_OMAP_SCR,
+ h4p_inb(info, UART_OMAP_SCR) |
+ UART_OMAP_SCR_EMPTY_THR);
+ goto finish_tx;
+ }
+ }
+
+ skb = skb_dequeue(&info->txq);
+ if (!skb) {
+ /* No data in buffer */
+ BT_DBG("skb ready");
+ if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
+ h4p_outb(info, UART_IER,
+ h4p_inb(info, UART_IER) &
+ ~UART_IER_THRI);
+ h4p_inb(info, UART_OMAP_SCR);
+ h4p_disable_tx(info);
+ return;
+ }
+ h4p_outb(info, UART_OMAP_SCR,
+ h4p_inb(info, UART_OMAP_SCR) |
+ UART_OMAP_SCR_EMPTY_THR);
+ goto finish_tx;
+ }
+
+ /* Copy data to tx fifo */
+ while (!(h4p_inb(info, UART_OMAP_SSR) & UART_OMAP_SSR_TXFULL) &&
+ (sent < skb->len)) {
+ //printk("[Out: %02x]", skb->data[sent]);
+ //printk("%02x ", skb->data[sent]);
+ h4p_outb(info, UART_TX, skb->data[sent]);
+ sent++;
+ }
+
+ info->hdev->stat.byte_tx += sent;
+ if (skb->len == sent) {
+ kfree_skb(skb);
+ } else {
+ skb_pull(skb, sent);
+ skb_queue_head(&info->txq, skb);
+ }
+
+ h4p_outb(info, UART_OMAP_SCR, h4p_inb(info, UART_OMAP_SCR) &
+ ~UART_OMAP_SCR_EMPTY_THR);
+ h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
+ UART_IER_THRI);
+
+finish_tx:
+ /* Flush posted write to avoid spurious interrupts */
+ h4p_inb(info, UART_OMAP_SCR);
+
+}
+
+static irqreturn_t h4p_interrupt(int irq, void *data)
+{
+ struct h4p_info *info = (struct h4p_info *)data;
+ u8 iir, msr;
+ int ret;
+
+ ret = IRQ_NONE;
+
+ iir = h4p_inb(info, UART_IIR);
+ if (iir & UART_IIR_NO_INT)
+ return IRQ_HANDLED;
+
+ //BT_DBG("<%2x>", iir);
+
+ iir &= UART_IIR_ID;
+
+ if (iir == UART_IIR_MSI) {
+ msr = h4p_inb(info, UART_MSR);
+ ret = IRQ_HANDLED;
+ }
+ if (iir == UART_IIR_RLSI) {
+ h4p_inb(info, UART_RX);
+ h4p_inb(info, UART_LSR);
+ ret = IRQ_HANDLED;
+ }
+
+ if (iir == UART_IIR_RDI) {
+ h4p_rx_tasklet((unsigned long)data);
+ ret = IRQ_HANDLED;
+ }
+
+ if (iir == UART_IIR_THRI) {
+ h4p_tx_tasklet((unsigned long)data);
+ ret = IRQ_HANDLED;
+ }
+
+ return ret;
+}
+
+static irqreturn_t h4p_wakeup_interrupt(int irq, void *dev_inst)
+{
+ struct h4p_info *info = dev_inst;
+ int should_wakeup;
+ struct hci_dev *hdev;
+
+ BT_DBG("[wakeup irq]");
+
+ if (!info->hdev)
+ return IRQ_HANDLED;
+
+ should_wakeup = gpio_get_value(info->host_wakeup_gpio);
+ hdev = info->hdev;
+
+ if (!test_bit(HCI_RUNNING, &hdev->flags)) {
+ if (should_wakeup == 1)
+ complete_all(&info->test_completion);
+
+ printk("wakeup irq handled\n");
+
+ return IRQ_HANDLED;
+ }
+
+ BT_DBG("gpio interrupt %d", should_wakeup);
+
+ /* Check if wee have missed some interrupts */
+ if (info->rx_enabled == should_wakeup)
+ return IRQ_HANDLED;
+
+ if (should_wakeup)
+ h4p_enable_rx(info);
+ else
+ h4p_disable_rx(info);
+
+ return IRQ_HANDLED;
+}
+
+static inline void h4p_set_pm_limits(struct h4p_info *info, bool set)
+{
+ struct h4p_platform_data *bt_plat_data = info->dev->platform_data;
+
+ if (unlikely(!bt_plat_data || !bt_plat_data->set_pm_limits))
+ return;
+
+ if (set != !!test_bit(H4P_ACTIVE_MODE, &info->pm_flags)) {
+ bt_plat_data->set_pm_limits(info->dev, set);
+ if (set)
+ set_bit(H4P_ACTIVE_MODE, &info->pm_flags);
+ else
+ clear_bit(H4P_ACTIVE_MODE, &info->pm_flags);
+ BT_DBG("Change pm constraints to: %s", set ? "set" : "clear");
+ return;
+ }
+
+ BT_DBG("pm constraints remains: %s", set ? "set" : "clear");
+}
+
+static int h4p_reset(struct h4p_info *info)
+{
+ int err;
+
+ err = h4p_reset_uart(info);
+ if (err < 0) {
+ dev_err(info->dev, "Uart reset failed\n");
+ return err;
+ }
+ h4p_init_uart(info);
+ h4p_set_rts(info, 0);
+
+ gpio_set_value(info->reset_gpio, 0);
+ gpio_set_value(info->bt_wakeup_gpio, 1);
+ msleep(10);
+
+ if (gpio_get_value(info->host_wakeup_gpio) == 1) {
+ dev_err(info->dev, "host_wakeup_gpio not low\n");
+ return -EPROTO;
+ }
+
+ init_completion(&info->test_completion);
+ gpio_set_value(info->reset_gpio, 1);
+
+ if (!wait_for_completion_interruptible_timeout(&info->test_completion,
+ msecs_to_jiffies(100))) {
+ dev_err(info->dev, "wakeup test timed out\n");
+ complete_all(&info->test_completion);
+ return -EPROTO;
+ }
+
+ err = h4p_wait_for_cts(info, 1, 100);
+ if (err < 0) {
+ dev_err(info->dev, "No cts from bt chip\n");
+ return err;
+ }
+
+ h4p_set_rts(info, 1);
+
+ return 0;
+}
+
+/* hci callback functions */
+static int h4p_hci_flush(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+
+ skb_queue_purge(&info->txq);
+
+ return 0;
+}
+
+static int h4p_bt_wakeup_test(struct h4p_info *info)
+{
+ /*
+ * Test Sequence:
+ * Host de-asserts the BT_WAKE_UP line.
+ * Host polls the UART_CTS line, waiting for it to be de-asserted.
+ * Host asserts the BT_WAKE_UP line.
+ * Host polls the UART_CTS line, waiting for it to be asserted.
+ * Host de-asserts the BT_WAKE_UP line (allow the Bluetooth device to
+ * sleep).
+ * Host polls the UART_CTS line, waiting for it to be de-asserted.
+ */
+ int err;
+ int ret = -ECOMM;
+
+ if (!info)
+ return -EINVAL;
+
+ /* Disable wakeup interrupts */
+ disable_irq(gpio_to_irq(info->host_wakeup_gpio));
+
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ err = h4p_wait_for_cts(info, 0, 100);
+ if (err) {
+ dev_warn(info->dev,
+ "bt_wakeup_test: fail: CTS low timed out: %d\n",
+ err);
+ goto out;
+ }
+
+ gpio_set_value(info->bt_wakeup_gpio, 1);
+ err = h4p_wait_for_cts(info, 1, 100);
+ if (err) {
+ dev_warn(info->dev,
+ "bt_wakeup_test: fail: CTS high timed out: %d\n",
+ err);
+ goto out;
+ }
+
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ err = h4p_wait_for_cts(info, 0, 100);
+ if (err) {
+ dev_warn(info->dev,
+ "bt_wakeup_test: fail: CTS re-low timed out: %d\n",
+ err);
+ goto out;
+ }
+
+ ret = 0;
+
+out:
+
+ /* Re-enable wakeup interrupts */
+ enable_irq(gpio_to_irq(info->host_wakeup_gpio));
+
+ return ret;
+}
+
+static int h4p_setup(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+ int err;
+ unsigned long flags;
+
+ /*
+ * Disable smart-idle as UART TX interrupts
+ * are not wake-up capable
+ */
+ h4p_smart_idle(info, 0);
+
+ err = h4p_read_fw(info);
+ if (err < 0) {
+ dev_err(info->dev, "Cannot read firmware\n");
+ goto err_clean;
+ }
+
+ h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
+ h4p_set_rts(info, 0);
+ h4p_change_speed(info, BC4_MAX_BAUD_RATE);
+ h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
+
+ info->pm_enabled = 1;
+
+ err = h4p_bt_wakeup_test(info);
+ if (err < 0) {
+ dev_err(info->dev, "BT wakeup test failed.\n");
+ goto err_clean;
+ }
+
+ spin_lock_irqsave(&info->lock, flags);
+ info->rx_enabled = gpio_get_value(info->host_wakeup_gpio);
+ h4p_set_clk(info, &info->rx_clocks_en, info->rx_enabled);
+ spin_unlock_irqrestore(&info->lock, flags);
+
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+
+ kfree_skb(info->alive_cmd_skb);
+ info->alive_cmd_skb = NULL;
+ info->initing = 0;
+ return 0;
+
+err_clean:
+ printk("hci_setup: something failed, should do the clean up\n");
+ return err;
+}
+
+static int h4p_hci_setup(struct hci_dev *hdev)
+{
+ return 0;
+}
+
+static void hci_uninit(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+
+ h4p_reset_uart(info);
+ del_timer_sync(&info->lazy_release);
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+ h4p_set_clk(info, &info->rx_clocks_en, 0);
+ gpio_set_value(info->reset_gpio, 0);
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ kfree_skb(info->rx_skb);
+ info->rx_skb = NULL;
+}
+
+static int h4p_hci_open(struct hci_dev *hdev)
+{
+ struct h4p_info *info;
+ int err;
+
+ info = hci_get_drvdata(hdev);
+
+ if (test_bit(HCI_RUNNING, &hdev->flags))
+ return 0;
+
+ /* TI1271 has HW bug and boot up might fail. Original code retried
+ up to three times, but we removed TI1271 support. */
+
+ info->rx_enabled = 1;
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ info->rx_count = 0;
+ info->garbage_bytes = 0;
+ info->rx_skb = NULL;
+ info->pm_enabled = 0;
+ init_completion(&info->fw_completion);
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ h4p_set_clk(info, &info->rx_clocks_en, 1);
+
+ err = h4p_reset(info);
+ if (err < 0)
+ goto err_clean;
+
+ h4p_set_auto_ctsrts(info, 1, UART_EFR_CTS | UART_EFR_RTS);
+ info->autorts = 1;
+
+ info->initing = 1;
+ printk("hci_setup\n");
+
+ err = h4p_send_negotiation(info);
+ set_bit(HCI_RUNNING, &hdev->flags);
+#if 0
+ err = h4p_setup(hdev);
+ if (err < 0) {
+ printk("h4p setup failed\n");
+ goto err_clean;
+ }
+#endif
+
+ atomic_set(&hdev->cmd_cnt, 1);
+ set_bit(HCI_INIT, &hdev->flags);
+
+ return h4p_setup(hdev);
+
+err_clean:
+ printk("hci_open: something failed\n");
+ h4p_hci_flush(hdev);
+ hci_uninit(hdev);
+ kfree_skb(info->alive_cmd_skb);
+ info->alive_cmd_skb = NULL;
+
+ return err;
+}
+
+static int h4p_hci_close(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+
+ if (!test_and_clear_bit(HCI_RUNNING, &hdev->flags))
+ return 0;
+
+ h4p_hci_flush(hdev);
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ h4p_set_clk(info, &info->rx_clocks_en, 1);
+ hci_uninit(hdev);
+ return 0;
+}
+
+static int h4p_hci_send_frame(struct hci_dev *hdev, struct sk_buff *skb)
+{
+ struct h4p_info *info;
+ int err = 0;
+
+ BT_DBG("hci_send_frame: dev %p, skb %p\n", hdev, skb);
+
+ info = hci_get_drvdata(hdev);
+
+ if (!test_bit(HCI_RUNNING, &hdev->flags)) {
+ dev_warn(info->dev, "Frame for non-running device\n");
+ return -EIO;
+ }
+
+ switch (bt_cb(skb)->pkt_type) {
+ case HCI_COMMAND_PKT:
+ hdev->stat.cmd_tx++;
+ break;
+ case HCI_ACLDATA_PKT:
+ hdev->stat.acl_tx++;
+ break;
+ case HCI_SCODATA_PKT:
+ hdev->stat.sco_tx++;
+ break;
+ }
+
+ /* Push frame type to skb */
+ *skb_push(skb, 1) = (bt_cb(skb)->pkt_type);
+ /* We should always send word aligned data to h4+ devices */
+ if (skb->len % 2) {
+ err = skb_pad(skb, 1);
+ if (!err)
+ *skb_put(skb, 1) = 0x00;
+ }
+ if (err)
+ return err;
+
+ skb_queue_tail(&info->txq, skb);
+ if (!info->initing)
+ h4p_enable_tx(info);
+ else
+ h4p_enable_tx_nopm(info);
+
+ return 0;
+}
+
+static ssize_t h4p_hci_set_bdaddr(struct hci_dev *hdev, const bdaddr_t *bdaddr)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+
+ printk("Set bdaddr... %pMR\n", bdaddr);
+ return 0;
+}
+
+static int h4p_register_hdev(struct h4p_info *info)
+{
+ struct hci_dev *hdev;
+
+ /* Initialize and register HCI device */
+
+ hdev = hci_alloc_dev();
+ if (!hdev) {
+ dev_err(info->dev, "Can't allocate memory for device\n");
+ return -ENOMEM;
+ }
+ info->hdev = hdev;
+
+ hdev->bus = HCI_UART;
+ hci_set_drvdata(hdev, info);
+
+ hdev->open = h4p_hci_open;
+ hdev->setup = h4p_hci_setup;
+ hdev->close = h4p_hci_close;
+ hdev->flush = h4p_hci_flush;
+ hdev->send = h4p_hci_send_frame;
+ hdev->set_bdaddr = h4p_hci_set_bdaddr;
+
+ set_bit(HCI_QUIRK_RESET_ON_CLOSE, &hdev->quirks);
+
+ SET_HCIDEV_DEV(hdev, info->dev);
+
+ if (hci_register_dev(hdev) >= 0)
+ return 0;
+
+ dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
+ hci_free_dev(info->hdev);
+ return -ENODEV;
+}
+
+static int h4p_probe_pdata(struct platform_device *pdev, struct h4p_info *info,
+ struct h4p_platform_data *bt_plat_data)
+{
+ info->chip_type = bt_plat_data->chip_type;
+ info->bt_wakeup_gpio = bt_plat_data->bt_wakeup_gpio;
+ info->host_wakeup_gpio = bt_plat_data->host_wakeup_gpio;
+ info->reset_gpio = bt_plat_data->reset_gpio;
+ info->reset_gpio_shared = bt_plat_data->reset_gpio_shared;
+ info->bt_sysclk = bt_plat_data->bt_sysclk;
+
+ info->irq = bt_plat_data->uart_irq;
+ info->uart_base = devm_ioremap(&pdev->dev, bt_plat_data->uart_base,
+ SZ_2K);
+ info->uart_iclk = devm_clk_get(&pdev->dev, bt_plat_data->uart_iclk);
+ info->uart_fclk = devm_clk_get(&pdev->dev, bt_plat_data->uart_fclk);
+ return 0;
+}
+
+static int h4p_probe_dt(struct platform_device *pdev, struct h4p_info *info)
+{
+ struct device_node *node;
+ struct device_node *uart = pdev->dev.of_node;
+ u32 val;
+ struct resource *mem;
+
+ node = of_get_child_by_name(uart, "device");
+
+ if (!node)
+ return -ENODATA;
+
+ info->chip_type = 3; /* Bcm2048 */
+
+ if (of_property_read_u32(node, "bt-sysclk", &val)) return -EINVAL;
+ info->bt_sysclk = val;
+
+ info->reset_gpio = of_get_named_gpio(node, "reset-gpios", 0);
+ info->host_wakeup_gpio = of_get_named_gpio(node, "host-wakeup-gpios", 0);
+ info->bt_wakeup_gpio = of_get_named_gpio(node, "bluetooth-wakeup-gpios", 0);
+
+ if (!uart) {
+ dev_err(&pdev->dev, "UART link not provided\n");
+ return -EINVAL;
+ }
+
+ info->irq = irq_of_parse_and_map(uart, 0);
+
+ mem = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ info->uart_base = devm_ioremap_resource(&pdev->dev, mem);
+
+ info->uart_iclk = of_clk_get_by_name(uart, "ick");
+ info->uart_fclk = of_clk_get_by_name(uart, "fck");
+
+ printk("DT: have neccessary data\n");
+ return 0;
+}
+
+
+static int h4p_probe(struct platform_device *pdev)
+{
+
+ struct h4p_info *info;
+ int err;
+
+ dev_info(&pdev->dev, "Registering HCI H4P device\n");
+ info = devm_kzalloc(&pdev->dev, sizeof(struct h4p_info),
+ GFP_KERNEL);
+ if (!info)
+ return -ENOMEM;
+
+ info->dev = &pdev->dev;
+ info->tx_enabled = 1;
+ info->rx_enabled = 1;
+ spin_lock_init(&info->lock);
+ spin_lock_init(&info->clocks_lock);
+ skb_queue_head_init(&info->txq);
+
+ if (pdev->dev.platform_data) {
+ err = h4p_probe_pdata(pdev, info, pdev->dev.platform_data);
+ } else {
+ err = h4p_probe_dt(pdev, info);
+ }
+ if (err) {
+ dev_err(&pdev->dev, "Could not get Bluetooth config data\n");
+ return -ENODATA;
+ }
+
+ printk("base/irq gpio: %lx/%d/%d\n",
+ info->uart_base, info->irq);
+ printk("RESET/BTWU/HOSTWU gpio: %d/%d/%d\n",
+ info->reset_gpio, info->bt_wakeup_gpio, info->host_wakeup_gpio);
+ printk("chip type, sysclk: %d/%d\n", info->chip_type, info->bt_sysclk);
+ printk("clock i/f: %lx/%lx\n", info->uart_iclk, info->uart_fclk);
+
+ init_completion(&info->test_completion);
+ complete_all(&info->test_completion);
+
+ err = devm_gpio_request_one(&pdev->dev, info->reset_gpio,
+ GPIOF_OUT_INIT_LOW, "bt_reset");
+ if (err < 0) {
+ dev_err(&pdev->dev, "Cannot get GPIO line %d\n",
+ info->reset_gpio);
+ return err;
+ }
+
+ err = devm_gpio_request_one(&pdev->dev, info->bt_wakeup_gpio,
+ GPIOF_OUT_INIT_LOW, "bt_wakeup");
+ if (err < 0) {
+ dev_err(info->dev, "Cannot get GPIO line 0x%d",
+ info->bt_wakeup_gpio);
+ return err;
+ }
+
+ err = devm_gpio_request_one(&pdev->dev, info->host_wakeup_gpio,
+ GPIOF_DIR_IN, "host_wakeup");
+ if (err < 0) {
+ dev_err(info->dev, "Cannot get GPIO line %d",
+ info->host_wakeup_gpio);
+ return err;
+ }
+
+ err = devm_request_irq(&pdev->dev, info->irq, h4p_interrupt,
+ IRQF_DISABLED, "hci_h4p", info);
+ if (err < 0) {
+ dev_err(info->dev, "hci_h4p: unable to get IRQ %d\n",
+ info->irq);
+ return err;
+ }
+
+ err = devm_request_irq(&pdev->dev, gpio_to_irq(info->host_wakeup_gpio),
+ h4p_wakeup_interrupt, IRQF_TRIGGER_FALLING |
+ IRQF_TRIGGER_RISING | IRQF_DISABLED,
+ "h4p_wkup", info);
+ if (err < 0) {
+ dev_err(info->dev, "hci_h4p: unable to get wakeup IRQ %d\n",
+ gpio_to_irq(info->host_wakeup_gpio));
+ return err;
+ }
+
+ err = irq_set_irq_wake(gpio_to_irq(info->host_wakeup_gpio), 1);
+ if (err < 0) {
+ dev_err(info->dev, "hci_h4p: unable to set wakeup for IRQ %d\n",
+ gpio_to_irq(info->host_wakeup_gpio));
+ return err;
+ }
+
+ init_timer_deferrable(&info->lazy_release);
+ info->lazy_release.function = h4p_lazy_clock_release;
+ info->lazy_release.data = (unsigned long)info;
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ printk("resetting uart....\n");
+ err = h4p_reset_uart(info);
+ printk("reset ok....\n");
+ if (err < 0)
+ return err;
+ gpio_set_value(info->reset_gpio, 0);
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+
+ platform_set_drvdata(pdev, info);
+
+ if (h4p_register_hdev(info) < 0) {
+ dev_err(info->dev, "failed to register hci_h4p hci device\n");
+ return -EINVAL;
+ }
+
+ return 0;
+}
+
+static int h4p_remove(struct platform_device *pdev)
+{
+ struct h4p_info *info;
+
+ info = platform_get_drvdata(pdev);
+
+ h4p_hci_close(info->hdev);
+ hci_unregister_dev(info->hdev);
+ hci_free_dev(info->hdev);
+
+ return 0;
+}
+
+static const struct of_device_id h4p_of_match[] = {
+ { .compatible = "brcm,uart,bcm2048" },
+ {},
+};
+MODULE_DEVICE_TABLE(of, h4p_of_match);
+
+static struct platform_driver h4p_driver = {
+ .probe = h4p_probe,
+ .remove = h4p_remove,
+ .driver = {
+ .name = "disabled" "hci_h4p",
+ .owner = THIS_MODULE,
+ .of_match_table = of_match_ptr(h4p_of_match),
+ },
+};
+
+module_platform_driver(h4p_driver);
+
+MODULE_ALIAS("platform:hci_h4p");
+MODULE_DESCRIPTION("Bluetooth h4 driver with nokia extensions");
+MODULE_LICENSE("GPL");
+MODULE_AUTHOR("Ville Tervo");
diff --git a/drivers/bluetooth/nokia_fw-bcm.c b/drivers/bluetooth/nokia_fw-bcm.c
new file mode 100644
index 0000000..fd88727
--- /dev/null
+++ b/drivers/bluetooth/nokia_fw-bcm.c
@@ -0,0 +1,27 @@
+/*
+ * This file is part of Nokia H4P bluetooth driver
+ *
+ * Copyright (C) 2005-2008 Nokia Corporation.
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ */
+
+#include <linux/skbuff.h>
+#include <linux/delay.h>
+#include <linux/serial_reg.h>
+
+#include "hci_h4p.h"
+
diff --git a/drivers/bluetooth/nokia_fw.c b/drivers/bluetooth/nokia_fw.c
new file mode 100644
index 0000000..7b6a750
--- /dev/null
+++ b/drivers/bluetooth/nokia_fw.c
@@ -0,0 +1,105 @@
+/*
+ * This file is part of hci_h4p bluetooth driver
+ *
+ * Copyright (C) 2005-2008 Nokia Corporation.
+ * Copyright (C) 2014 Pavel Machek <[email protected]>
+ *
+ * Contact: Ville Tervo <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ */
+
+#include <linux/module.h>
+#include <linux/skbuff.h>
+#include <linux/firmware.h>
+#include <linux/clk.h>
+
+#include <net/bluetooth/bluetooth.h>
+
+#include "hci_h4p.h"
+
+#define FW_NAME_BCM2048 "bcmfw.bin"
+
+#define BT_DBG printk
+
+
+/* Read fw. Return length of the command. If no more commands in
+ * fw 0 is returned. In error case return value is negative.
+ */
+int h4p_read_fw(struct h4p_info *info)
+{
+ int num = 0;
+ int fw_pos = 0;
+ struct sk_buff *skb;
+ const struct firmware *fw_entry = NULL;
+ int err = -ENOENT;
+ unsigned int cmd_len = 0;
+
+ err = request_firmware(&fw_entry, FW_NAME_BCM2048, info->dev);
+ if (err != 0 || !fw_entry)
+ return err;
+
+ while(1) {
+ int cmd, len;
+
+ fw_pos += cmd_len;
+
+ if (fw_pos >= fw_entry->size)
+ break;
+
+ if (fw_pos + 2 > fw_entry->size) {
+ dev_err(info->dev, "Corrupted firmware image 1\n");
+ err = -EMSGSIZE;
+ break;
+ }
+
+ cmd_len = fw_entry->data[fw_pos++];
+ cmd_len += fw_entry->data[fw_pos++] << 8;
+ if (cmd_len == 0)
+ break;
+
+ if (fw_pos + cmd_len > fw_entry->size) {
+ dev_err(info->dev, "Corrupted firmware image 2\n");
+ err = -EMSGSIZE;
+ break;
+ }
+
+ /* Skip first two packets */
+ if (++num <= 2)
+ continue;
+
+ /* Note that this is timing-critical. If sending packets takes too
+ long, initialization will fail. */
+ printk("Packet %d...", num);
+
+ cmd = fw_entry->data[fw_pos+1];
+ cmd += fw_entry->data[fw_pos+2] << 8;
+ len = fw_entry->data[fw_pos+3];
+ printk("cmd %x, len %d.", cmd, len);
+
+ skb = __hci_cmd_sync(info->hdev, cmd, len, fw_entry->data+fw_pos+4, 500);
+ if (IS_ERR(skb)) {
+ dev_err(info->dev, "...sending cmd failed %d\n", PTR_ERR(skb));
+ err = -EIO;
+ break;
+ }
+ }
+
+ release_firmware(fw_entry);
+ return err;
+}
+
+MODULE_FIRMWARE(FW_NAME_BCM2048);
diff --git a/drivers/bluetooth/nokia_uart.c b/drivers/bluetooth/nokia_uart.c
new file mode 100644
index 0000000..2cae639
--- /dev/null
+++ b/drivers/bluetooth/nokia_uart.c
@@ -0,0 +1,179 @@
+/*
+ * This file is part of Nokia H4P bluetooth driver
+ *
+ * Copyright (C) 2005, 2006 Nokia Corporation.
+ * Copyright (C) 2014 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ */
+
+#include <linux/delay.h>
+#include <linux/clk.h>
+
+#include <linux/io.h>
+
+#include "hci_h4p.h"
+
+
+
+int h4p_wait_for_cts(struct h4p_info *info, int active,
+ int timeout_ms)
+{
+ unsigned long timeout;
+ int state;
+
+ timeout = jiffies + msecs_to_jiffies(timeout_ms);
+ for (;;) {
+ state = h4p_inb(info, UART_MSR) & UART_MSR_CTS;
+ if (active) {
+ if (state)
+ return 0;
+ } else {
+ if (!state)
+ return 0;
+ }
+ if (time_after(jiffies, timeout))
+ return -ETIMEDOUT;
+ msleep(1);
+ }
+}
+
+void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)
+{
+ u8 lcr, b;
+
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, 0xbf);
+ b = h4p_inb(info, UART_EFR);
+ if (on)
+ b |= which;
+ else
+ b &= ~which;
+ h4p_outb(info, UART_EFR, b);
+ h4p_outb(info, UART_LCR, lcr);
+}
+
+void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->lock, flags);
+ __h4p_set_auto_ctsrts(info, on, which);
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+void h4p_change_speed(struct h4p_info *info, unsigned long speed)
+{
+ unsigned int divisor;
+ u8 lcr, mdr1;
+
+ BT_DBG("Setting speed %lu", speed);
+
+ if (speed >= 460800) {
+ divisor = UART_CLOCK / 13 / speed;
+ mdr1 = 3;
+ } else {
+ divisor = UART_CLOCK / 16 / speed;
+ mdr1 = 0;
+ }
+
+ /* Make sure UART mode is disabled */
+ h4p_outb(info, UART_OMAP_MDR1, 7);
+
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, UART_LCR_DLAB); /* Set DLAB */
+ h4p_outb(info, UART_DLL, divisor & 0xff); /* Set speed */
+ h4p_outb(info, UART_DLM, divisor >> 8);
+ h4p_outb(info, UART_LCR, lcr);
+
+ /* Make sure UART mode is enabled */
+ h4p_outb(info, UART_OMAP_MDR1, mdr1);
+}
+
+int h4p_reset_uart(struct h4p_info *info)
+{
+ int count = 0;
+
+ /* Reset the UART */
+ h4p_outb(info, UART_OMAP_SYSC, UART_SYSC_OMAP_RESET);
+ while (!(h4p_inb(info, UART_OMAP_SYSS) & UART_SYSS_RESETDONE)) {
+ if (count++ > 100) {
+ dev_err(info->dev, "hci_h4p: UART reset timeout\n");
+ return -ENODEV;
+ }
+ udelay(1);
+ }
+
+ return 0;
+}
+
+void h4p_store_regs(struct h4p_info *info)
+{
+ u16 lcr = 0;
+
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, 0xBF);
+ info->dll = h4p_inb(info, UART_DLL);
+ info->dlh = h4p_inb(info, UART_DLM);
+ info->efr = h4p_inb(info, UART_EFR);
+ h4p_outb(info, UART_LCR, lcr);
+ info->mdr1 = h4p_inb(info, UART_OMAP_MDR1);
+ info->ier = h4p_inb(info, UART_IER);
+}
+
+void h4p_restore_regs(struct h4p_info *info)
+{
+ u16 lcr = 0;
+
+ h4p_init_uart(info);
+
+ h4p_outb(info, UART_OMAP_MDR1, 7);
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, 0xBF);
+ h4p_outb(info, UART_DLL, info->dll); /* Set speed */
+ h4p_outb(info, UART_DLM, info->dlh);
+ h4p_outb(info, UART_EFR, info->efr);
+ h4p_outb(info, UART_LCR, lcr);
+ h4p_outb(info, UART_OMAP_MDR1, info->mdr1);
+ h4p_outb(info, UART_IER, info->ier);
+}
+
+void h4p_init_uart(struct h4p_info *info)
+{
+ u8 mcr, efr;
+
+ /* Enable and setup FIFO */
+ h4p_outb(info, UART_OMAP_MDR1, 0x00);
+
+ h4p_outb(info, UART_LCR, 0xbf);
+ efr = h4p_inb(info, UART_EFR);
+ h4p_outb(info, UART_EFR, UART_EFR_ECB);
+ h4p_outb(info, UART_LCR, UART_LCR_DLAB);
+ mcr = h4p_inb(info, UART_MCR);
+ h4p_outb(info, UART_MCR, UART_MCR_TCRTLR);
+ h4p_outb(info, UART_FCR, UART_FCR_ENABLE_FIFO |
+ UART_FCR_CLEAR_RCVR | UART_FCR_CLEAR_XMIT |
+ (3 << 6) | (0 << 4));
+ h4p_outb(info, UART_LCR, 0xbf);
+ h4p_outb(info, UART_TI752_TLR, 0xed);
+ h4p_outb(info, UART_TI752_TCR, 0xef);
+ h4p_outb(info, UART_EFR, efr);
+ h4p_outb(info, UART_LCR, UART_LCR_DLAB);
+ h4p_outb(info, UART_MCR, 0x00);
+ h4p_outb(info, UART_LCR, UART_LCR_WLEN8);
+ h4p_outb(info, UART_IER, UART_IER_RDI);
+ h4p_outb(info, UART_OMAP_SYSC, (1 << 0) | (1 << 2) | (2 << 3));
+}
diff --git a/include/linux/platform_data/bt-nokia-h4p.h b/include/linux/platform_data/bt-nokia-h4p.h
index 30d169d..c1a7e64 100644
--- a/include/linux/platform_data/bt-nokia-h4p.h
+++ b/include/linux/platform_data/bt-nokia-h4p.h
@@ -21,9 +21,9 @@


/**
- * struct hci_h4p_platform data - hci_h4p Platform data structure
+ * struct h4p_platform data - hci_h4p Platform data structure
*/
-struct hci_h4p_platform_data {
+struct h4p_platform_data {
int chip_type;
int bt_sysclk;
unsigned int bt_wakeup_gpio;

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html


2014-12-13 23:30:19

by Marcel Holtmann

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi Pavel,

> Add hci_h4p bluetooth driver to staging tree. This device is used
> for example on Nokia N900 cell phone.
>
> Signed-off-by: Pavel Machek <[email protected]>
> Thanks-to: Sebastian Reichel <[email protected]>
> Thanks-to: Joe Perches <[email protected]>
>
> ---
>
>
> I'd prefer to resurect the driver in staging/ in order not to lose
> history, but Marcel wanted to treat it as new submission, so I'm doing
> that.

that history is in linux.git now for all times. No need to repeat it. I rather not play around with that again. Lets get a minimal driver merged so we can give people something to improve.

>
> Firmware load was converted to hci_cmd_sync(). Unfortunately, the
> firmware is needed after every open/close, so the setup mechanism does
> not quite fit. (But code is now way cleaner).

What is the reason for that? Does it mean that the device will always loose all its settings when powering it down. Do we know why that is that way and can we maybe change it?

If there is no way around this, we can introduce a quirk that will always run hdev->setup. However if the device keeps forgetting all settings all the time, that means it will also keep forgetting its address. So that power on procedure will be wasting time. We would need to check if we can make it so that it only has unconfigured state once and then keeps remembering the address even if we have to re-program it every time.

> Device tree bindings work for me, but they are not yet official and I
> expect some more fun there.
>
> Hacks surrounding bluetooth address were removed; this results in
> working driver with address that is probably not unique.

Just set HCI_QUIRK_INVALID_BDADDR and let someone deal with that in userspace. You can use the btmgmt public-addr command for testing.

In the end someone needs to write a small tool that users mgmt interface and listens for unconfigured controllers, reads the address from whatever storage it is, uses the Set Public Address command and that is it.

On the kernel side you need to add hdev->set_bdaddr support. For the Broadcom based devices you can copy it from the btusb.c driver.

> HCI_QUIRK_RESET_ON_CLOSE will need to be investigated some more.

Why was that needed again? If the device loses power anyway, then that seems wasteful. Also the core changed to make sure it resets all settings on power down correctly.

> My notes say that Marcel wanted different filenames, but I'd need
> advice exactly what filenames. I guess platform data supprort should
> be removed altogether, rather than renamed.

Yes, the platform support should go away. This should be purely based on DT.

Can you also start using git format-patch so that patches get a diffstat.

Regards

Marcel

2014-12-13 23:51:35

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!

> > My notes say that Marcel wanted different filenames, but I'd need
> > advice exactly what filenames. I guess platform data supprort should
> > be removed altogether, rather than renamed.
>
> Yes, the platform support should go away. This should be purely based on DT.
>
> Can you also start using git format-patch so that patches get a diffstat.

So the rest of filenames look ok?
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-14 00:07:49

by Marcel Holtmann

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi Pavel,

>>> My notes say that Marcel wanted different filenames, but I'd need
>>> advice exactly what filenames. I guess platform data supprort should
>>> be removed altogether, rather than renamed.
>>
>> Yes, the platform support should go away. This should be purely based on DT.
>>
>> Can you also start using git format-patch so that patches get a diffstat.
>
> So the rest of filenames look ok?

I have not looked at the patch or the filenames at all.

Regards

Marcel

2014-12-14 09:48:07

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

On Sun 2014-12-14 01:07:42, Marcel Holtmann wrote:
> Hi Pavel,
>
> >>> My notes say that Marcel wanted different filenames, but I'd need
> >>> advice exactly what filenames. I guess platform data supprort should
> >>> be removed altogether, rather than renamed.
> >>
> >> Yes, the platform support should go away. This should be purely based on DT.
> >>
> >> Can you also start using git format-patch so that patches get a diffstat.
> >
> > So the rest of filenames look ok?
>
> I have not looked at the patch or the filenames at all.

Ok, so here's diffstat. Can you take a look?

Thanks,
Pavel

drivers/bluetooth/Kconfig | 10
drivers/bluetooth/Makefile | 3
drivers/bluetooth/hci_h4p.h | 234 +++++
drivers/bluetooth/nokia_core.c | 1262 +++++++++++++++++++++++++++++
drivers/bluetooth/nokia_fw-bcm.c | 27
drivers/bluetooth/nokia_fw.c | 105 ++
drivers/bluetooth/nokia_uart.c | 179 ++++
include/linux/platform_data/bt-nokia-h4p.h | 4
8 files changed, 1822 insertions(+), 2 deletions(-)

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-14 10:40:36

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

On Sun 2014-12-14 00:30:13, Marcel Holtmann wrote:
> Hi Pavel,
>
> > Add hci_h4p bluetooth driver to staging tree. This device is used
> > for example on Nokia N900 cell phone.
> >
> > Signed-off-by: Pavel Machek <[email protected]>
> > Thanks-to: Sebastian Reichel <[email protected]>
> > Thanks-to: Joe Perches <[email protected]>
> >
> > ---
> >
> >
> > I'd prefer to resurect the driver in staging/ in order not to lose
> > history, but Marcel wanted to treat it as new submission, so I'm doing
> > that.
>
> that history is in linux.git now for all times. No need to repeat it. I rather not play around with that again. Lets get a minimal driver merged so we can give people something to improve.
>

We will merge minimum version. Still I'd like complete history for
credits and bisect and easy ability to diff original and minimum
version.

> > Firmware load was converted to hci_cmd_sync(). Unfortunately, the
> > firmware is needed after every open/close, so the setup mechanism does
> > not quite fit. (But code is now way cleaner).
>
> What is the reason for that? Does it mean that the device will always loose all its settings when powering it down. Do we know why that is that way and can we maybe change it?
>
> If there is no way around this, we can introduce a quirk that will always run hdev->setup. However if the device keeps forgetting all settings all the time, that means it will also keep forgetting its address. So that power on procedure will be wasting time. We would need to check if we can make it so that it only has unconfigured state once and then keeps remembering the address even if we have to re-program it every time.
>
> > Device tree bindings work for me, but they are not yet official and I
> > expect some more fun there.
> >
> > Hacks surrounding bluetooth address were removed; this results in
> > working driver with address that is probably not unique.
>
> Just set HCI_QUIRK_INVALID_BDADDR and let someone deal with that in
> userspace. You can use the btmgmt public-addr command for testing.

What command would that be? Do I need some new versions of tools?

root@n900:/my/modules# man hciconfig
(don't see anything relevant).
root@n900:/my/modules# btmgmt
-bash: btmgmt: command not found
root@n900:/my/modules# apt-cache search btmgmt
root@n900:/my/modules#

> On the kernel side you need to add hdev->set_bdaddr support. For the Broadcom based devices you can copy it from the btusb.c driver.
>

I tried doing that from setup, but either command failed or it killed
hte kernel.

> > HCI_QUIRK_RESET_ON_CLOSE will need to be investigated some more.
>
> Why was that needed again? If the device loses power anyway, then that seems wasteful. Also the core changed to make sure it resets all settings on power down correctly.
>

Ok.

> > My notes say that Marcel wanted different filenames, but I'd need
> > advice exactly what filenames. I guess platform data supprort should
> > be removed altogether, rather than renamed.
>
> Yes, the platform support should go away. This should be purely based on DT.
>
> Can you also start using git format-patch so that patches get a diffstat.

I can do diffstat manually for you, git format-patch does not fit my
workflow.

Thanks,
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-14 11:16:28

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

On Sun 2014-12-14 00:30:13, Marcel Holtmann wrote:
> Hi Pavel,
>
> > Add hci_h4p bluetooth driver to staging tree. This device is used
> > for example on Nokia N900 cell phone.
> >
> > Signed-off-by: Pavel Machek <[email protected]>
> > Thanks-to: Sebastian Reichel <[email protected]>
> > Thanks-to: Joe Perches <[email protected]>
> >
> > ---
> >
> >
> > I'd prefer to resurect the driver in staging/ in order not to lose
> > history, but Marcel wanted to treat it as new submission, so I'm doing
> > that.
>
> that history is in linux.git now for all times. No need to repeat it. I rather not play around with that again. Lets get a minimal driver merged so we can give people something to improve.
>
> >
> > Firmware load was converted to hci_cmd_sync(). Unfortunately, the
> > firmware is needed after every open/close, so the setup mechanism does
> > not quite fit. (But code is now way cleaner).
>
> What is the reason for that? Does it mean that the device will always loose all its settings when powering it down. Do we know why that is that way and can we maybe change it?
>
> If there is no way around this, we can introduce a quirk that will always run hdev->setup. However if the device keeps forgetting all settings all the time, that means it will also keep forgetting its address. So that power on procedure will be wasting time. We would need to check if we can make it so that it only has unconfigured state once and then keeps remembering the address even if we have to re-program it every time.
>
> > Device tree bindings work for me, but they are not yet official and I
> > expect some more fun there.
> >
> > Hacks surrounding bluetooth address were removed; this results in
> > working driver with address that is probably not unique.
>
> Just set HCI_QUIRK_INVALID_BDADDR and let someone deal with that in
>userspace. You can use the btmgmt public-addr command for testing.

Hmm. So I installed bluez-5.36, then libudev-dev, then libical-dev,
libreadline-dev. I'm glad I have debian and not maemo, and nfsroot and
not limited flash. I had to turn off systemd support.

It still compiles..
Pavel

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-14 13:19:55

by Bastien Nocera

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

On Sun, 2014-12-14 at 11:40 +0100, Pavel Machek wrote:
> On Sun 2014-12-14 00:30:13, Marcel Holtmann wrote:
> > Hi Pavel,
> >
> > > Add hci_h4p bluetooth driver to staging tree. This device is used
> > > for example on Nokia N900 cell phone.
> > >
> > > Signed-off-by: Pavel Machek <[email protected]>
> > > Thanks-to: Sebastian Reichel <[email protected]>
> > > Thanks-to: Joe Perches <[email protected]>
> > >
> > > ---
> > >
> > >
> > > I'd prefer to resurect the driver in staging/ in order not to lose
> > > history, but Marcel wanted to treat it as new submission, so I'm doing
> > > that.
> >
> > that history is in linux.git now for all times. No need to repeat it. I rather not play around with that again. Lets get a minimal driver merged so we can give people something to improve.
> >
>
> We will merge minimum version. Still I'd like complete history for
> credits and bisect and easy ability to diff original and minimum
> version.

FWIW, I found that developing the driver outside of the main kernel tree
for merge is the best way to keep a history that's not too interesting
in the kernel tree.

Something like:
https://github.com/hadess/gt9xx
will allow small reversible commits, make it easy to branch for testing
(say a bug crops up, create a branch, fix the bug, get somebody to test
it, merge to master, and copy/paste the files to the upstream git tree
for inclusion).

Of course, in your case you might need to create a backport for the
whole bluetooth sub-system, as it uses internal API, which makes it
harder. But it's still viable for large cleanups, and pre-merge changes
while keeping history.

2014-12-14 19:21:33

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!


> > Hacks surrounding bluetooth address were removed; this results in
> > working driver with address that is probably not unique.
>
> Just set HCI_QUIRK_INVALID_BDADDR and let someone deal with that in userspace. You can use the btmgmt public-addr command for testing.
>

Ok, it took me a while to figure out that --enable-experimental is
needed.

Then help was playing tricks with me:

For more information on the usage of each command use:
btmgmt <command> --help
root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr --help
Set Public Address for hci0 failed with status 0x0b (Rejected)
root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr
Usage: btmgmt public-addr <address>


root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr 01:02:03:04:05:06
Set Public Address for hci0 failed with status 0x0b (Rejected)

Hmm. Since setting public address only works when interface is down,
and we lose all the settings during up, this does not work at all,
right?

Anyway, you might want to apply this to lessen the confusion.

diff -ur bluez-5.26.ofic/tools/btmgmt.c bluez-5.26/tools/btmgmt.c
--- bluez-5.26.ofic/tools/btmgmt.c 2014-12-14 12:32:19.742595000 +0100
+++ bluez-5.26/tools/btmgmt.c 2014-12-14 20:06:40.432497000 +0100
@@ -2603,7 +2603,7 @@

static void static_addr_usage(void)
{
- printf("Usage: btmgmt static-addr <address>\n");
+ printf("Usage: btmgmt static-addr ??:??:??:??:??:??\n");
}

static void cmd_static_addr(struct mgmt *mgmt, uint16_t index,
@@ -2660,7 +2660,8 @@
struct mgmt_cp_set_public_address cp;

if (argc < 2) {
- printf("Usage: btmgmt public-addr <address>\n");
+ printf("Usage: btmgmt public-addr ??:??:??:??:??:??\n"
+ "Note: interface must be down for this to work\n");
exit(EXIT_FAILURE);
}

@@ -2934,7 +2935,7 @@

static void add_device_usage(void)
{
- printf("Usage: btmgmt add-device [-a action] [-t type] <address>\n");
+ printf("Usage: btmgmt add-device [-a action] [-t type] ??:??:??:??:??:??\n");
}

static struct option add_device_options[] = {
@@ -3007,7 +3008,7 @@

static void del_device_usage(void)
{
- printf("Usage: btmgmt del-device [-t type] <address>\n");
+ printf("Usage: btmgmt del-device [-t type] ??:??:??:??:??:??\n");
}

static struct option del_device_options[] = {
@@ -3153,7 +3154,7 @@

printf("\n"
"For more information on the usage of each command use:\n"
- "\tbtmgmt <command> --help\n" );
+ "\tbtmgmt <command>\n" );
}

static struct option main_options[] = {
Only in bluez-5.26/tools: btmgmt.c~


--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-14 20:28:23

by Marcel Holtmann

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi Pavel,

>>> Hacks surrounding bluetooth address were removed; this results in
>>> working driver with address that is probably not unique.
>>
>> Just set HCI_QUIRK_INVALID_BDADDR and let someone deal with that in userspace. You can use the btmgmt public-addr command for testing.
>>
>
> Ok, it took me a while to figure out that --enable-experimental is
> needed.
>
> Then help was playing tricks with me:
>
> For more information on the usage of each command use:
> btmgmt <command> --help
> root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr --help
> Set Public Address for hci0 failed with status 0x0b (Rejected)
> root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr
> Usage: btmgmt public-addr <address>

that is indeed confusing. Something went wrong with that tool. Just keep in mind that tool is just for internal testing by the developers. Someone would still need to write a proper integration with listening for the appropriate events and dig out the actual address from the memory location.

> root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr 01:02:03:04:05:06
> Set Public Address for hci0 failed with status 0x0b (Rejected)
>
> Hmm. Since setting public address only works when interface is down,
> and we lose all the settings during up, this does not work at all,
> right?

It does keep it. The address is stored in hdev->public_addr which is actually different from hdev->bdaddr which is the current address in use.

However I am not sure that hdev->set_bdaddr is executed again. Same as hdev->setup is not executed twice. The controller loosing all states is something we have not yet encountered. At least not while the hci_dev stays around.

I wonder if the drastic power off might be better hooked into a platform RFKILL switch. And with that you would just unregister hci_dev and re-register it when the RFKILL switch is unblocked.

The other option is to introduce a quirk that allows running hdev->setup and hdev->set_bdaddr all the time when you bring up your device.

Another alternate idea for getting something upstream for testing is to ignore the whole firmware loading in the kernel and bring up the controller with HCI_QUIRK_EXTERNAL_CONFIG. Doing that would allow you to do bette testing and evolve the driver in small tests.

So what this quirk does is that the hci_dev comes up unconfigured. So mgmt interface will only show it as unconfigured controller. However you can open it with HCI User Channel and run all HCI commands manually. That is what src/shared/hci.[ch] is good at. Once you are done, you just flip the switch via btmgmt ext-config and then the kernel goes and treats it as fully configured.

Regards

Marcel

2014-12-14 21:52:57

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!

> > Firmware load was converted to hci_cmd_sync(). Unfortunately, the
> > firmware is needed after every open/close, so the setup mechanism does
> > not quite fit. (But code is now way cleaner).
>
> What is the reason for that? Does it mean that the device will always loose all its settings when powering it down. Do we know why that is that way and can we maybe change it?
>

Well, on hci_close(), original code asserts reset GPIO. I guess that
clears everything... I got it working with that removed, and it means
I can set the address the normal way. What are implications for power
consumption... I'm not sure at this point. Lets worry about that
later.
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-14 22:41:44

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!

> >>> Hacks surrounding bluetooth address were removed; this results in
> >>> working driver with address that is probably not unique.
> >>
> >> Just set HCI_QUIRK_INVALID_BDADDR and let someone deal with that in userspace. You can use the btmgmt public-addr command for testing.
> >>
> >
> > Ok, it took me a while to figure out that --enable-experimental is
> > needed.
> >
> > Then help was playing tricks with me:
> >
> > For more information on the usage of each command use:
> > btmgmt <command> --help
> > root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr --help
> > Set Public Address for hci0 failed with status 0x0b (Rejected)
> > root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr
> > Usage: btmgmt public-addr <address>
>
> that is indeed confusing. Something went wrong with that tool. Just keep in mind that tool is just for internal testing by the developers. Someone would still need to write a proper integration with listening for the appropriate events and dig out the actual address from the memory location.
>

You have patch that helps that issues in the email :-).

> > root@n900:/my/bluez-5.26/tools# ./btmgmt public-addr 01:02:03:04:05:06
> > Set Public Address for hci0 failed with status 0x0b (Rejected)
> >
> > Hmm. Since setting public address only works when interface is down,
> > and we lose all the settings during up, this does not work at all,
> > right?
>
> It does keep it. The address is stored in hdev->public_addr which is actually different from hdev->bdaddr which is the current address in use.
>
> However I am not sure that hdev->set_bdaddr is executed again. Same
> as hdev->setup is not executed twice. The controller loosing all
> states is something we have not yet encountered. At least not
> while the hci_dev stays around.

It looks like that's the exact issue. It seems to me like set_bdaddr
is actually called while the device is "down".

> I wonder if the drastic power off might be better hooked into a
> platform RFKILL switch. And with that you would just unregister
> hci_dev and re-register it when the RFKILL switch is unblocked.

Ok, so kernel currently wants bluetooth out of reset at

> The other option is to introduce a quirk that allows running hdev->setup and hdev->set_bdaddr all the time when you bring up your device.
>
> Another alternate idea for getting something upstream for testing is to ignore the whole firmware loading in the kernel and bring up the controller with HCI_QUIRK_EXTERNAL_CONFIG. Doing that would allow you to do bette testing and evolve the driver in small tests.
>

Actually, firmware loading is _not_ the biggest problem. That is
pretty self-contained now.

I guess I should just configure it at probe time, put it into reset
during rmmod, keep it out of reset otherwise, and see how it works.

Thanks,

Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-15 10:02:02

by Oliver Neukum

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi,

a few remarks about possible issues.

Regards
Oliver

> +static int h4p_send_negotiation(struct h4p_info *info)
> +{
> + struct h4p_neg_cmd *neg_cmd;
> + struct h4p_neg_hdr *neg_hdr;
> + struct sk_buff *skb;
> + int err, len;
> + u16 sysclk = 38400;
> +
> + printk("Sending negotiation..");
> + len = sizeof(*neg_cmd) + sizeof(*neg_hdr) + H4_TYPE_SIZE;
> +
> + skb = bt_skb_alloc(len, GFP_KERNEL);
> + if (!skb)
> + return -ENOMEM;
> +
> + memset(skb->data, 0x00, len);
> + *skb_put(skb, 1) = H4_NEG_PKT;
> + neg_hdr = (struct h4p_neg_hdr *)skb_put(skb, sizeof(*neg_hdr));
> + neg_cmd = (struct h4p_neg_cmd *)skb_put(skb, sizeof(*neg_cmd));
> +
> + neg_hdr->dlen = sizeof(*neg_cmd);
> + neg_cmd->ack = H4P_NEG_REQ;
> + neg_cmd->baud = cpu_to_le16(BT_BAUDRATE_DIVIDER/MAX_BAUD_RATE);
> + neg_cmd->proto = H4P_PROTO_BYTE;
> + neg_cmd->sys_clk = cpu_to_le16(sysclk);
> +
> + h4p_change_speed(info, INIT_SPEED);
> +
> + h4p_set_rts(info, 1);
> + info->init_error = 0;
> + init_completion(&info->init_completion);
> +
> + h4p_simple_send_frame(info, skb);
> +
> + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> + msecs_to_jiffies(1000))) {
> + printk("h4p: negotiation did not return\n");

Memory leak in the error case

> + return -ETIMEDOUT;
> + }
> +
> + if (info->init_error < 0)
> + return info->init_error;
> +
> + /* Change to operational settings */
> + h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
> + h4p_set_rts(info, 0);
> + h4p_change_speed(info, MAX_BAUD_RATE);
> +
> + err = h4p_wait_for_cts(info, 1, 100);
> + if (err < 0)
> + return err;
> +
> + h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
> + init_completion(&info->init_completion);
> + err = h4p_send_alive_packet(info);
> +
> + if (err < 0)
> + return err;
> +
> + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> + msecs_to_jiffies(1000)))
> + return -ETIMEDOUT;
> +
> + if (info->init_error < 0)
> + return info->init_error;
> +
> + printk("Negotiation successful\n");
> + return 0;
> +}



> +static unsigned int h4p_get_data_len(struct h4p_info *info,
> + struct sk_buff *skb)
> +{
> + long retval = -1;
> + struct hci_acl_hdr *acl_hdr;
> + struct hci_sco_hdr *sco_hdr;
> + struct hci_event_hdr *evt_hdr;
> + struct h4p_neg_hdr *neg_hdr;
> + struct h4p_alive_hdr *alive_hdr;
> + struct h4p_radio_hdr *radio_hdr;
> +
> + switch (bt_cb(skb)->pkt_type) {
> + case H4_EVT_PKT:
> + evt_hdr = (struct hci_event_hdr *)skb->data;
> + retval = evt_hdr->plen;
> + break;
> + case H4_ACL_PKT:
> + acl_hdr = (struct hci_acl_hdr *)skb->data;
> + retval = le16_to_cpu(acl_hdr->dlen);

Could you explain, why only this needs endianness converted?

> + break;
> + case H4_SCO_PKT:
> + sco_hdr = (struct hci_sco_hdr *)skb->data;
> + retval = sco_hdr->dlen;
> + break;
> + case H4_RADIO_PKT:
> + radio_hdr = (struct h4p_radio_hdr *)skb->data;
> + retval = radio_hdr->dlen;
> + break;
> + case H4_NEG_PKT:
> + neg_hdr = (struct h4p_neg_hdr *)skb->data;
> + retval = neg_hdr->dlen;
> + break;
> + case H4_ALIVE_PKT:
> + alive_hdr = (struct h4p_alive_hdr *)skb->data;
> + retval = alive_hdr->dlen;
> + break;
> + }
> +
> + return retval;
> +}



> +static void h4p_rx_tasklet(unsigned long data)
> +{
> + u8 byte;
> + struct h4p_info *info = (struct h4p_info *)data;
> +
> + BT_DBG("tasklet woke up");
> + BT_DBG("rx_tasklet woke up");

Isn't this a bit redundant?

> +
> + while (h4p_inb(info, UART_LSR) & UART_LSR_DR) {
> + byte = h4p_inb(info, UART_RX);
> + BT_DBG("[in: %02x]", byte);
> + if (info->garbage_bytes) {
> + info->garbage_bytes--;
> + continue;
> + }
> + if (info->rx_skb == NULL) {
> + info->rx_skb = bt_skb_alloc(HCI_MAX_FRAME_SIZE,
> + GFP_ATOMIC | GFP_DMA);
> + if (!info->rx_skb) {
> + dev_err(info->dev,
> + "No memory for new packet\n");
> + goto finish_rx;
> + }
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + info->rx_skb->dev = (void *)info->hdev;
> + }
> + info->hdev->stat.byte_rx++;
> + h4p_handle_byte(info, byte);
> + }
> +
> + if (!info->rx_enabled) {
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT &&
> + info->autorts) {
> + __h4p_set_auto_ctsrts(info, 0 , UART_EFR_RTS);
> + info->autorts = 0;
> + }
> + /* Flush posted write to avoid spurious interrupts */
> + h4p_inb(info, UART_OMAP_SCR);
> + h4p_set_clk(info, &info->rx_clocks_en, 0);
> + }
> +
> +finish_rx:
> + BT_DBG("rx_ended");
> +}
> +
> +static void h4p_tx_tasklet(unsigned long data)
> +{
> + unsigned int sent = 0;
> + struct sk_buff *skb;
> + struct h4p_info *info = (struct h4p_info *)data;
> +
> + BT_DBG("tasklet woke up");
> + BT_DBG("tx_tasklet woke up");

Doubled?

> + if (info->autorts != info->rx_enabled) {
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
> + if (info->autorts && !info->rx_enabled) {
> + __h4p_set_auto_ctsrts(info, 0,
> + UART_EFR_RTS);
> + info->autorts = 0;
> + }
> + if (!info->autorts && info->rx_enabled) {
> + __h4p_set_auto_ctsrts(info, 1,
> + UART_EFR_RTS);
> + info->autorts = 1;
> + }
> + } else {
> + h4p_outb(info, UART_OMAP_SCR,
> + h4p_inb(info, UART_OMAP_SCR) |
> + UART_OMAP_SCR_EMPTY_THR);
> + goto finish_tx;
> + }
> + }
> +
> + skb = skb_dequeue(&info->txq);
> + if (!skb) {
> + /* No data in buffer */
> + BT_DBG("skb ready");
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
> + h4p_outb(info, UART_IER,
> + h4p_inb(info, UART_IER) &
> + ~UART_IER_THRI);
> + h4p_inb(info, UART_OMAP_SCR);
> + h4p_disable_tx(info);
> + return;
> + }
> + h4p_outb(info, UART_OMAP_SCR,
> + h4p_inb(info, UART_OMAP_SCR) |
> + UART_OMAP_SCR_EMPTY_THR);
> + goto finish_tx;
> + }
> +
> + /* Copy data to tx fifo */
> + while (!(h4p_inb(info, UART_OMAP_SSR) & UART_OMAP_SSR_TXFULL) &&
> + (sent < skb->len)) {
> + //printk("[Out: %02x]", skb->data[sent]);
> + //printk("%02x ", skb->data[sent]);
> + h4p_outb(info, UART_TX, skb->data[sent]);
> + sent++;
> + }
> +
> + info->hdev->stat.byte_tx += sent;
> + if (skb->len == sent) {
> + kfree_skb(skb);
> + } else {
> + skb_pull(skb, sent);
> + skb_queue_head(&info->txq, skb);
> + }
> +
> + h4p_outb(info, UART_OMAP_SCR, h4p_inb(info, UART_OMAP_SCR) &
> + ~UART_OMAP_SCR_EMPTY_THR);
> + h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
> + UART_IER_THRI);
> +
> +finish_tx:
> + /* Flush posted write to avoid spurious interrupts */
> + h4p_inb(info, UART_OMAP_SCR);
> +
> +}


















2014-12-15 12:10:30

by Marcel Holtmann

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi Pavel,

> diff --git a/drivers/bluetooth/Kconfig b/drivers/bluetooth/Kconfig
> index 4547dc2..0fc7d3a 100644
> --- a/drivers/bluetooth/Kconfig
> +++ b/drivers/bluetooth/Kconfig
> @@ -243,4 +243,14 @@ config BT_WILINK
> Say Y here to compile support for Texas Instrument's WiLink7 driver
> into the kernel or say M to compile it as module (btwilink).
>
> +config BT_NOKIA_H4P
> + tristate "HCI driver with H4 Nokia extensions"
> + depends on ARCH_OMAP

this dependency needs to go away. The actual loading and detection of the driver should purely be based on DT. All OMAP specific details should not really be part of the Bluetooth driver.

> + help
> + Bluetooth HCI driver with H4 extensions. This driver provides
> + support for H4+ Bluetooth chip with vendor-specific H4 extensions.
> +
> + Say Y here to compile support for h4 extended devices into the kernel
> + or say M to compile it as module (btnokia_h4p).
> +
> endmenu
> diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
> index 9fe8a87..ec7074fe 100644
> --- a/drivers/bluetooth/Makefile
> +++ b/drivers/bluetooth/Makefile
> @@ -31,4 +31,7 @@ hci_uart-$(CONFIG_BT_HCIUART_ATH3K) += hci_ath.o
> hci_uart-$(CONFIG_BT_HCIUART_3WIRE) += hci_h5.o
> hci_uart-objs := $(hci_uart-y)
>
> +obj-$(CONFIG_BT_NOKIA_H4P) += hci_h4p.o
> +hci_h4p-objs := nokia_core.o nokia_fw.o nokia_uart.o
> +

We are moving away from calling drivers hci_ since that is a bit too generic. Just call the the driver object nokia_h4p.o for now.

> ccflags-y += -D__CHECK_ENDIAN__
> new file mode 100644
> index 0000000..6445a99
> --- /dev/null
> +++ b/drivers/bluetooth/hci_h4p.h

this should be nokia_h4p.h then.

> @@ -0,0 +1,234 @@
> +/*
> + * This file is part of Nokia H4P bluetooth driver
> + *
> + * Copyright (C) 2005-2008 Nokia Corporation.
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + */
> +
> +#ifndef __DRIVERS_BLUETOOTH_H4P_H
> +#define __DRIVERS_BLUETOOTH_H4P_H

Skip these circular inclusion protection checks. The header file is local and you know what you are doing.

> +
> +#include <net/bluetooth/bluetooth.h>
> +#include <net/bluetooth/hci_core.h>
> +#include <net/bluetooth/hci.h>
> +
> +#include <linux/serial_reg.h>
> +
> +#define UART_SYSC_OMAP_RESET 0x03
> +#define UART_SYSS_RESETDONE 0x01
> +#define UART_OMAP_SCR_EMPTY_THR 0x08
> +#define UART_OMAP_SCR_WAKEUP 0x10
> +#define UART_OMAP_SSR_WAKEUP 0x02
> +#define UART_OMAP_SSR_TXFULL 0x01
> +
> +#define UART_OMAP_SYSC_IDLEMODE 0x03
> +#define UART_OMAP_SYSC_IDLEMASK (3 << UART_OMAP_SYSC_IDLEMODE)
> +
> +#define UART_OMAP_SYSC_FORCE_IDLE (0 << UART_OMAP_SYSC_IDLEMODE)
> +#define UART_OMAP_SYSC_NO_IDLE (1 << UART_OMAP_SYSC_IDLEMODE)
> +#define UART_OMAP_SYSC_SMART_IDLE (2 << UART_OMAP_SYSC_IDLEMODE)
> +
> +#define H4P_TRANSFER_MODE 1
> +#define H4P_SCHED_TRANSFER_MODE 2
> +#define H4P_ACTIVE_MODE 3
> +
> +struct h4p_info {
> + struct timer_list lazy_release;
> + struct hci_dev *hdev;
> + spinlock_t lock;
> +
> + void __iomem *uart_base;
> + unsigned long uart_phys_base;
> + int irq;
> + struct device *dev;
> + u8 chip_type;
> + u8 bt_wakeup_gpio;
> + u8 host_wakeup_gpio;
> + u8 reset_gpio;
> + u8 reset_gpio_shared;
> + u8 bt_sysclk;
> + u8 man_id;
> + u8 ver_id;
> +
> + struct sk_buff_head fw_queue;
> + struct sk_buff *alive_cmd_skb;
> + struct completion init_completion;
> + struct completion fw_completion;
> + struct completion test_completion;
> + int fw_error;
> + int init_error;
> +
> + struct sk_buff_head txq;
> +
> + struct sk_buff *rx_skb;
> + long rx_count;
> + unsigned long rx_state;
> + unsigned long garbage_bytes;
> +
> + bdaddr_t bd_addr;

Remove this one. Let the core handle any BD_ADDR related details.

> + struct sk_buff_head *fw_q;
> +
> + int pm_enabled;
> + int tx_enabled;
> + int autorts;
> + int rx_enabled;
> + unsigned long pm_flags;
> +
> + int tx_clocks_en;
> + int rx_clocks_en;
> + spinlock_t clocks_lock;
> + struct clk *uart_iclk;
> + struct clk *uart_fclk;
> + atomic_t clk_users;
> + u16 dll;
> + u16 dlh;
> + u16 ier;
> + u16 mdr1;
> + u16 efr;
> +
> + int initing;
> +};
> +
> +struct h4p_radio_hdr {
> + u8 evt;
> + u8 dlen;
> +} __packed;
> +
> +struct h4p_neg_hdr {
> + u8 dlen;
> +} __packed;
> +#define H4P_NEG_HDR_SIZE 1
> +
> +#define H4P_NEG_REQ 0x00
> +#define H4P_NEG_ACK 0x20
> +#define H4P_NEG_NAK 0x40
> +
> +#define H4P_PROTO_PKT 0x44
> +#define H4P_PROTO_BYTE 0x4c
> +
> +#define H4P_ID_CSR 0x02
> +#define H4P_ID_BCM2048 0x04
> +#define H4P_ID_TI1271 0x31
> +
> +struct h4p_neg_cmd {
> + u8 ack;
> + u16 baud;
> + u16 unused1;
> + u8 proto;
> + u16 sys_clk;
> + u16 unused2;
> +} __packed;
> +
> +struct h4p_neg_evt {
> + u8 ack;
> + u16 baud;
> + u16 unused1;
> + u8 proto;
> + u16 sys_clk;
> + u16 unused2;
> + u8 man_id;
> + u8 ver_id;
> +} __packed;
> +
> +#define H4P_ALIVE_REQ 0x55
> +#define H4P_ALIVE_RESP 0xcc
> +
> +struct h4p_alive_hdr {
> + u8 dlen;
> +} __packed;
> +#define H4P_ALIVE_HDR_SIZE 1
> +
> +struct h4p_alive_pkt {
> + u8 mid;
> + u8 unused;
> +} __packed;
> +
> +#define MAX_BAUD_RATE 921600
> +#define BC4_MAX_BAUD_RATE 3692300
> +#define UART_CLOCK 48000000
> +#define BT_INIT_DIVIDER 320
> +#define BT_BAUDRATE_DIVIDER 384000000
> +#define BT_SYSCLK_DIV 1000
> +#define INIT_SPEED 120000
> +
> +#define H4_TYPE_SIZE 1
> +#define H4_RADIO_HDR_SIZE 2
> +
> +/* H4+ packet types */
> +#define H4_CMD_PKT 0x01
> +#define H4_ACL_PKT 0x02
> +#define H4_SCO_PKT 0x03
> +#define H4_EVT_PKT 0x04
> +#define H4_NEG_PKT 0x06
> +#define H4_ALIVE_PKT 0x07
> +#define H4_RADIO_PKT 0x08
> +
> +/* TX states */
> +#define WAIT_FOR_PKT_TYPE 1
> +#define WAIT_FOR_HEADER 2
> +#define WAIT_FOR_DATA 3
> +
> +struct hci_fw_event {
> + struct hci_event_hdr hev;
> + struct hci_ev_cmd_complete cmd;
> + u8 status;
> +} __packed;
> +
> +void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb);
> +
> +int h4p_send_alive_packet(struct h4p_info *info);
> +
> +int h4p_read_fw(struct h4p_info *info);
> +int h4p_send_fw(struct h4p_info *info);
> +void h4p_parse_fw_event(struct h4p_info *info, struct sk_buff *skb);
> +
> +static inline void h4p_outb(struct h4p_info *info, unsigned int offset, u8 val)
> +{
> + __raw_writeb(val, info->uart_base + (offset << 2));
> +}
> +
> +static inline u8 h4p_inb(struct h4p_info *info, unsigned int offset)
> +{
> + u8 val;
> + val = __raw_readb(info->uart_base + (offset << 2));
> + return val;
> +}
> +
> +static inline void h4p_set_rts(struct h4p_info *info, int active)
> +{
> + u8 b;
> +
> + b = h4p_inb(info, UART_MCR);
> + if (active)
> + b |= UART_MCR_RTS;
> + else
> + b &= ~UART_MCR_RTS;
> + h4p_outb(info, UART_MCR, b);
> +}
> +
> +int h4p_wait_for_cts(struct h4p_info *info, int active, int timeout_ms);
> +void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
> +void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
> +void h4p_change_speed(struct h4p_info *info, unsigned long speed);
> +int h4p_reset_uart(struct h4p_info *info);
> +void h4p_init_uart(struct h4p_info *info);
> +void h4p_enable_tx(struct h4p_info *info);
> +void h4p_store_regs(struct h4p_info *info);
> +void h4p_restore_regs(struct h4p_info *info);
> +void h4p_smart_idle(struct h4p_info *info, bool enable);
> +
> +#endif /* __DRIVERS_BLUETOOTH_H4P_H */
> diff --git a/drivers/bluetooth/nokia_core.c b/drivers/bluetooth/nokia_core.c
> new file mode 100644
> index 0000000..ca9746d
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_core.c
> @@ -0,0 +1,1262 @@
> +/*
> + * This file is part of Nokia H4P bluetooth driver
> + *
> + * Copyright (C) 2005-2008 Nokia Corporation.
> + * Copyright (C) 2014 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + * Thanks to all the Nokia people that helped with this driver,
> + * including Ville Tervo and Roger Quadros.
> + *
> + * Power saving functionality was removed from this driver to make
> + * merging easier.
> + */
> +
> +/*
> +insmod hci_h4p.ko && hciconfig hci0 up && hcitool inq && hciconfig hci0 down && hciconfig hci0 up && hcitool inq && rmmod hci_h4p
> +
> +*/

This command should not be in the source.

> +
> +#include <linux/module.h>
> +#include <linux/kernel.h>
> +#include <linux/init.h>
> +#include <linux/errno.h>
> +#include <linux/delay.h>
> +#include <linux/spinlock.h>
> +#include <linux/serial_reg.h>
> +#include <linux/skbuff.h>
> +#include <linux/device.h>
> +#include <linux/platform_device.h>
> +#include <linux/clk.h>
> +#include <linux/interrupt.h>
> +#include <linux/gpio.h>
> +#include <linux/of_gpio.h>
> +#include <linux/of_irq.h>
> +#include <linux/timer.h>
> +#include <linux/kthread.h>
> +#include <linux/io.h>
> +#include <linux/completion.h>
> +#include <linux/sizes.h>
> +
> +#include <net/bluetooth/bluetooth.h>
> +#include <net/bluetooth/hci_core.h>
> +#include <net/bluetooth/hci.h>
> +
> +#include <linux/platform_data/bt-nokia-h4p.h>

We need to move towards DT and not platform data.

> +
> +#include "hci_h4p.h"
> +
> +#define BT_DBG(a...) do {} while(0)

Why is this needed? BT_DBG is hooked up with dynamic debug.

> +
> +/* This should be used in function that cannot release clocks */
> +static void h4p_set_clk(struct h4p_info *info, int *clock, int enable)
> +{
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->clocks_lock, flags);
> + if (enable && !*clock) {
> + BT_DBG("Enabling %p", clock);
> + clk_prepare_enable(info->uart_fclk);
> + clk_prepare_enable(info->uart_iclk);
> + if (atomic_read(&info->clk_users) == 0)
> + h4p_restore_regs(info);
> + atomic_inc(&info->clk_users);
> + }
> +
> + if (!enable && *clock) {
> + BT_DBG("Disabling %p", clock);
> + if (atomic_dec_and_test(&info->clk_users))
> + h4p_store_regs(info);
> + clk_disable_unprepare(info->uart_fclk);
> + clk_disable_unprepare(info->uart_iclk);
> + }
> +
> + *clock = enable;
> + spin_unlock_irqrestore(&info->clocks_lock, flags);
> +}
> +
> +static void h4p_lazy_clock_release(unsigned long data)
> +{
> + struct h4p_info *info = (struct h4p_info *)data;
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->lock, flags);
> + if (!info->tx_enabled)
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +/* Power management functions */
> +void h4p_smart_idle(struct h4p_info *info, bool enable)
> +{
> + u8 v;
> +
> + v = h4p_inb(info, UART_OMAP_SYSC);
> + v &= ~(UART_OMAP_SYSC_IDLEMASK);
> +
> + if (enable)
> + v |= UART_OMAP_SYSC_SMART_IDLE;
> + else
> + v |= UART_OMAP_SYSC_NO_IDLE;
> +
> + h4p_outb(info, UART_OMAP_SYSC, v);
> +}
> +
> +static inline void h4p_schedule_pm(struct h4p_info *info)
> +{
> +}
> +
> +static void h4p_disable_tx(struct h4p_info *info)
> +{
> + if (!info->pm_enabled)
> + return;
> +
> + /* Re-enable smart-idle */
> + h4p_smart_idle(info, 1);
> +
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + mod_timer(&info->lazy_release, jiffies + msecs_to_jiffies(100));
> + info->tx_enabled = 0;
> +}
> +
> +void h4p_enable_tx_nopm(struct h4p_info *info)
> +{
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->lock, flags);
> + h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
> + UART_IER_THRI);
> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +void h4p_enable_tx(struct h4p_info *info)
> +{
> + unsigned long flags;
> +
> + if (!info->pm_enabled)
> + return;
> +
> + h4p_schedule_pm(info);
> +
> + spin_lock_irqsave(&info->lock, flags);
> + del_timer(&info->lazy_release);
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + info->tx_enabled = 1;
> + gpio_set_value(info->bt_wakeup_gpio, 1);
> + h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
> + UART_IER_THRI);
> + /*
> + * Disable smart-idle as UART TX interrupts
> + * are not wake-up capable
> + */
> + h4p_smart_idle(info, 0);
> +
> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +static void h4p_disable_rx(struct h4p_info *info)
> +{
> + if (!info->pm_enabled)
> + return;
> +
> + info->rx_enabled = 0;
> +
> + if (h4p_inb(info, UART_LSR) & UART_LSR_DR)
> + return;
> +
> + if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
> + return;
> +
> + __h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
> + info->autorts = 0;
> + h4p_set_clk(info, &info->rx_clocks_en, 0);
> +}
> +
> +static void h4p_enable_rx(struct h4p_info *info)
> +{
> + if (!info->pm_enabled)
> + return;
> +
> + h4p_schedule_pm(info);
> +
> + h4p_set_clk(info, &info->rx_clocks_en, 1);
> + info->rx_enabled = 1;
> +
> + if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
> + return;
> +
> + __h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
> + info->autorts = 1;
> +}
> +
> +void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb)
> +{
> + skb_queue_tail(&info->txq, skb);
> + h4p_enable_tx_nopm(info);
> +}
> +
> +/* Negotiation functions */
> +int h4p_send_alive_packet(struct h4p_info *info)
> +{
> + struct h4p_alive_hdr *hdr;
> + struct h4p_alive_pkt *pkt;
> + struct sk_buff *skb;
> + int len;
> +
> + BT_DBG("Sending alive packet");
> +
> + len = H4_TYPE_SIZE + sizeof(*hdr) + sizeof(*pkt);
> + skb = bt_skb_alloc(len, GFP_KERNEL);
> + if (!skb)
> + return -ENOMEM;
> +
> + memset(skb->data, 0x00, len);
> + *skb_put(skb, 1) = H4_ALIVE_PKT;
> + hdr = (struct h4p_alive_hdr *)skb_put(skb, sizeof(*hdr));
> + hdr->dlen = sizeof(*pkt);
> + pkt = (struct h4p_alive_pkt *)skb_put(skb, sizeof(*pkt));
> + pkt->mid = H4P_ALIVE_REQ;
> +
> + h4p_simple_send_frame(info, skb);
> +
> + BT_DBG("Alive packet sent");
> +
> + return 0;
> +}
> +
> +static void h4p_alive_packet(struct h4p_info *info,
> + struct sk_buff *skb)
> +{
> + struct h4p_alive_hdr *hdr;
> + struct h4p_alive_pkt *pkt;
> +
> + BT_DBG("Received alive packet");
> + hdr = (struct h4p_alive_hdr *)skb->data;
> + if (hdr->dlen != sizeof(*pkt)) {
> + dev_err(info->dev, "Corrupted alive message\n");
> + info->init_error = -EIO;
> + goto finish_alive;
> + }
> +
> + pkt = (struct h4p_alive_pkt *)skb_pull(skb, sizeof(*hdr));
> + if (pkt->mid != H4P_ALIVE_RESP) {
> + dev_err(info->dev, "Could not negotiate hci_h4p settings\n");
> + info->init_error = -EINVAL;
> + }
> +
> +finish_alive:
> + complete(&info->init_completion);
> + kfree_skb(skb);
> +}
> +
> +static int h4p_send_negotiation(struct h4p_info *info)
> +{
> + struct h4p_neg_cmd *neg_cmd;
> + struct h4p_neg_hdr *neg_hdr;
> + struct sk_buff *skb;
> + int err, len;
> + u16 sysclk = 38400;
> +
> + printk("Sending negotiation..");
> + len = sizeof(*neg_cmd) + sizeof(*neg_hdr) + H4_TYPE_SIZE;
> +
> + skb = bt_skb_alloc(len, GFP_KERNEL);
> + if (!skb)
> + return -ENOMEM;
> +
> + memset(skb->data, 0x00, len);
> + *skb_put(skb, 1) = H4_NEG_PKT;
> + neg_hdr = (struct h4p_neg_hdr *)skb_put(skb, sizeof(*neg_hdr));
> + neg_cmd = (struct h4p_neg_cmd *)skb_put(skb, sizeof(*neg_cmd));
> +
> + neg_hdr->dlen = sizeof(*neg_cmd);
> + neg_cmd->ack = H4P_NEG_REQ;
> + neg_cmd->baud = cpu_to_le16(BT_BAUDRATE_DIVIDER/MAX_BAUD_RATE);
> + neg_cmd->proto = H4P_PROTO_BYTE;
> + neg_cmd->sys_clk = cpu_to_le16(sysclk);
> +
> + h4p_change_speed(info, INIT_SPEED);
> +
> + h4p_set_rts(info, 1);
> + info->init_error = 0;
> + init_completion(&info->init_completion);
> +
> + h4p_simple_send_frame(info, skb);
> +
> + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> + msecs_to_jiffies(1000))) {
> + printk("h4p: negotiation did not return\n");
> + return -ETIMEDOUT;
> + }
> +
> + if (info->init_error < 0)
> + return info->init_error;
> +
> + /* Change to operational settings */
> + h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
> + h4p_set_rts(info, 0);
> + h4p_change_speed(info, MAX_BAUD_RATE);
> +
> + err = h4p_wait_for_cts(info, 1, 100);
> + if (err < 0)
> + return err;
> +
> + h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
> + init_completion(&info->init_completion);
> + err = h4p_send_alive_packet(info);
> +
> + if (err < 0)
> + return err;
> +
> + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> + msecs_to_jiffies(1000)))
> + return -ETIMEDOUT;
> +
> + if (info->init_error < 0)
> + return info->init_error;
> +
> + printk("Negotiation successful\n");
> + return 0;
> +}
> +
> +static void h4p_negotiation_packet(struct h4p_info *info,
> + struct sk_buff *skb)
> +{
> + struct h4p_neg_hdr *hdr;
> + struct h4p_neg_evt *evt;
> +
> + hdr = (struct h4p_neg_hdr *)skb->data;
> + if (hdr->dlen != sizeof(*evt)) {
> + info->init_error = -EIO;
> + goto finish_neg;
> + }
> +
> + evt = (struct h4p_neg_evt *)skb_pull(skb, sizeof(*hdr));
> +
> + if (evt->ack != H4P_NEG_ACK) {
> + dev_err(info->dev, "Could not negotiate hci_h4p settings\n");
> + info->init_error = -EINVAL;
> + }
> +
> + info->man_id = evt->man_id;
> + info->ver_id = evt->ver_id;
> + printk("Negotiation finished.\n");
> +
> +finish_neg:
> +
> + complete(&info->init_completion);
> + kfree_skb(skb);
> +}
> +
> +/* H4 packet handling functions */
> +static int h4p_get_hdr_len(struct h4p_info *info, u8 pkt_type)
> +{
> + long retval;
> +
> + switch (pkt_type) {
> + case H4_EVT_PKT:
> + retval = HCI_EVENT_HDR_SIZE;
> + break;
> + case H4_ACL_PKT:
> + retval = HCI_ACL_HDR_SIZE;
> + break;
> + case H4_SCO_PKT:
> + retval = HCI_SCO_HDR_SIZE;
> + break;
> + case H4_NEG_PKT:
> + retval = H4P_NEG_HDR_SIZE;
> + break;
> + case H4_ALIVE_PKT:
> + retval = H4P_ALIVE_HDR_SIZE;
> + break;
> + case H4_RADIO_PKT:
> + retval = H4_RADIO_HDR_SIZE;
> + break;
> + default:
> + dev_err(info->dev, "Unknown H4 packet type 0x%.2x\n", pkt_type);
> + retval = -1;
> + break;
> + }
> +
> + return retval;
> +}
> +
> +static unsigned int h4p_get_data_len(struct h4p_info *info,
> + struct sk_buff *skb)
> +{
> + long retval = -1;
> + struct hci_acl_hdr *acl_hdr;
> + struct hci_sco_hdr *sco_hdr;
> + struct hci_event_hdr *evt_hdr;
> + struct h4p_neg_hdr *neg_hdr;
> + struct h4p_alive_hdr *alive_hdr;
> + struct h4p_radio_hdr *radio_hdr;
> +
> + switch (bt_cb(skb)->pkt_type) {
> + case H4_EVT_PKT:
> + evt_hdr = (struct hci_event_hdr *)skb->data;
> + retval = evt_hdr->plen;
> + break;
> + case H4_ACL_PKT:
> + acl_hdr = (struct hci_acl_hdr *)skb->data;
> + retval = le16_to_cpu(acl_hdr->dlen);
> + break;
> + case H4_SCO_PKT:
> + sco_hdr = (struct hci_sco_hdr *)skb->data;
> + retval = sco_hdr->dlen;
> + break;
> + case H4_RADIO_PKT:
> + radio_hdr = (struct h4p_radio_hdr *)skb->data;
> + retval = radio_hdr->dlen;
> + break;
> + case H4_NEG_PKT:
> + neg_hdr = (struct h4p_neg_hdr *)skb->data;
> + retval = neg_hdr->dlen;
> + break;
> + case H4_ALIVE_PKT:
> + alive_hdr = (struct h4p_alive_hdr *)skb->data;
> + retval = alive_hdr->dlen;
> + break;
> + }
> +
> + return retval;
> +}
> +
> +static inline void h4p_recv_frame(struct h4p_info *info,
> + struct sk_buff *skb)
> +{
> + if (info->initing)
> + /*if (unlikely(!test_bit(HCI_RUNNING, &info->hdev->flags))) */ {
> + switch (bt_cb(skb)->pkt_type) {
> + case H4_NEG_PKT:
> + h4p_negotiation_packet(info, skb);
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + return;
> + case H4_ALIVE_PKT:
> + h4p_alive_packet(info, skb);
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + return;
> + }
> + }
> +
> + hci_recv_frame(info->hdev, skb);
> + BT_DBG("Frame sent to upper layer");
> +}
> +
> +static inline void h4p_handle_byte(struct h4p_info *info, u8 byte)
> +{
> + switch (info->rx_state) {
> + case WAIT_FOR_PKT_TYPE:
> + bt_cb(info->rx_skb)->pkt_type = byte;
> + info->rx_count = h4p_get_hdr_len(info, byte);
> + if (info->rx_count < 0) {
> + info->hdev->stat.err_rx++;
> + kfree_skb(info->rx_skb);
> + info->rx_skb = NULL;
> + } else {
> + info->rx_state = WAIT_FOR_HEADER;
> + }
> + break;
> + case WAIT_FOR_HEADER:
> + info->rx_count--;
> + *skb_put(info->rx_skb, 1) = byte;
> + if (info->rx_count != 0)
> + break;
> + info->rx_count = h4p_get_data_len(info, info->rx_skb);
> + if (info->rx_count > skb_tailroom(info->rx_skb)) {
> + dev_err(info->dev, "frame too long\n");
> + info->garbage_bytes = info->rx_count
> + - skb_tailroom(info->rx_skb);
> + kfree_skb(info->rx_skb);
> + info->rx_skb = NULL;
> + break;
> + }
> + info->rx_state = WAIT_FOR_DATA;
> + break;
> + case WAIT_FOR_DATA:
> + info->rx_count--;
> + *skb_put(info->rx_skb, 1) = byte;
> + break;
> + default:
> + WARN_ON(1);
> + break;
> + }
> +
> + if (info->rx_count == 0) {
> + /* H4+ devices should always send word aligned packets */
> + if (!(info->rx_skb->len % 2))
> + info->garbage_bytes++;
> + h4p_recv_frame(info, info->rx_skb);

The h4p_recv_frame should maybe done inline here since it only handles 2 exception packets. Also to make it easy, just leave the function if (info->rx_count).

This packet processing feels like a bit of spaghetti code. I think that is better handled in a proper function that goes through it and not with many tiny sub functions.

> + info->rx_skb = NULL;
> + }
> +}
> +
> +static void h4p_rx_tasklet(unsigned long data)
> +{
> + u8 byte;
> + struct h4p_info *info = (struct h4p_info *)data;
> +
> + BT_DBG("tasklet woke up");
> + BT_DBG("rx_tasklet woke up");
> +
> + while (h4p_inb(info, UART_LSR) & UART_LSR_DR) {
> + byte = h4p_inb(info, UART_RX);
> + BT_DBG("[in: %02x]", byte);
> + if (info->garbage_bytes) {
> + info->garbage_bytes--;
> + continue;
> + }
> + if (info->rx_skb == NULL) {
> + info->rx_skb = bt_skb_alloc(HCI_MAX_FRAME_SIZE,
> + GFP_ATOMIC | GFP_DMA);
> + if (!info->rx_skb) {
> + dev_err(info->dev,
> + "No memory for new packet\n");
> + goto finish_rx;
> + }
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + info->rx_skb->dev = (void *)info->hdev;
> + }
> + info->hdev->stat.byte_rx++;
> + h4p_handle_byte(info, byte);
> + }
> +
> + if (!info->rx_enabled) {
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT &&
> + info->autorts) {
> + __h4p_set_auto_ctsrts(info, 0 , UART_EFR_RTS);
> + info->autorts = 0;
> + }
> + /* Flush posted write to avoid spurious interrupts */
> + h4p_inb(info, UART_OMAP_SCR);
> + h4p_set_clk(info, &info->rx_clocks_en, 0);
> + }
> +
> +finish_rx:
> + BT_DBG("rx_ended");
> +}
> +
> +static void h4p_tx_tasklet(unsigned long data)
> +{
> + unsigned int sent = 0;
> + struct sk_buff *skb;
> + struct h4p_info *info = (struct h4p_info *)data;
> +
> + BT_DBG("tasklet woke up");
> + BT_DBG("tx_tasklet woke up");
> +
> + if (info->autorts != info->rx_enabled) {
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
> + if (info->autorts && !info->rx_enabled) {
> + __h4p_set_auto_ctsrts(info, 0,
> + UART_EFR_RTS);
> + info->autorts = 0;
> + }
> + if (!info->autorts && info->rx_enabled) {
> + __h4p_set_auto_ctsrts(info, 1,
> + UART_EFR_RTS);
> + info->autorts = 1;
> + }
> + } else {
> + h4p_outb(info, UART_OMAP_SCR,
> + h4p_inb(info, UART_OMAP_SCR) |
> + UART_OMAP_SCR_EMPTY_THR);
> + goto finish_tx;
> + }
> + }
> +
> + skb = skb_dequeue(&info->txq);
> + if (!skb) {
> + /* No data in buffer */
> + BT_DBG("skb ready");
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
> + h4p_outb(info, UART_IER,
> + h4p_inb(info, UART_IER) &
> + ~UART_IER_THRI);
> + h4p_inb(info, UART_OMAP_SCR);
> + h4p_disable_tx(info);
> + return;
> + }
> + h4p_outb(info, UART_OMAP_SCR,
> + h4p_inb(info, UART_OMAP_SCR) |
> + UART_OMAP_SCR_EMPTY_THR);
> + goto finish_tx;
> + }
> +
> + /* Copy data to tx fifo */
> + while (!(h4p_inb(info, UART_OMAP_SSR) & UART_OMAP_SSR_TXFULL) &&
> + (sent < skb->len)) {
> + //printk("[Out: %02x]", skb->data[sent]);
> + //printk("%02x ", skb->data[sent]);
> + h4p_outb(info, UART_TX, skb->data[sent]);
> + sent++;
> + }
> +
> + info->hdev->stat.byte_tx += sent;
> + if (skb->len == sent) {
> + kfree_skb(skb);
> + } else {
> + skb_pull(skb, sent);
> + skb_queue_head(&info->txq, skb);
> + }
> +
> + h4p_outb(info, UART_OMAP_SCR, h4p_inb(info, UART_OMAP_SCR) &
> + ~UART_OMAP_SCR_EMPTY_THR);
> + h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
> + UART_IER_THRI);
> +
> +finish_tx:
> + /* Flush posted write to avoid spurious interrupts */
> + h4p_inb(info, UART_OMAP_SCR);
> +
> +}
> +
> +static irqreturn_t h4p_interrupt(int irq, void *data)
> +{
> + struct h4p_info *info = (struct h4p_info *)data;
> + u8 iir, msr;
> + int ret;
> +
> + ret = IRQ_NONE;
> +
> + iir = h4p_inb(info, UART_IIR);
> + if (iir & UART_IIR_NO_INT)
> + return IRQ_HANDLED;
> +
> + //BT_DBG("<%2x>", iir);
> +
> + iir &= UART_IIR_ID;
> +
> + if (iir == UART_IIR_MSI) {
> + msr = h4p_inb(info, UART_MSR);
> + ret = IRQ_HANDLED;
> + }
> + if (iir == UART_IIR_RLSI) {
> + h4p_inb(info, UART_RX);
> + h4p_inb(info, UART_LSR);
> + ret = IRQ_HANDLED;
> + }
> +
> + if (iir == UART_IIR_RDI) {
> + h4p_rx_tasklet((unsigned long)data);
> + ret = IRQ_HANDLED;
> + }
> +
> + if (iir == UART_IIR_THRI) {
> + h4p_tx_tasklet((unsigned long)data);
> + ret = IRQ_HANDLED;
> + }
> +
> + return ret;
> +}
> +
> +static irqreturn_t h4p_wakeup_interrupt(int irq, void *dev_inst)
> +{
> + struct h4p_info *info = dev_inst;
> + int should_wakeup;
> + struct hci_dev *hdev;
> +
> + BT_DBG("[wakeup irq]");
> +
> + if (!info->hdev)
> + return IRQ_HANDLED;
> +
> + should_wakeup = gpio_get_value(info->host_wakeup_gpio);
> + hdev = info->hdev;
> +
> + if (!test_bit(HCI_RUNNING, &hdev->flags)) {
> + if (should_wakeup == 1)
> + complete_all(&info->test_completion);
> +
> + printk("wakeup irq handled\n");
> +
> + return IRQ_HANDLED;
> + }
> +
> + BT_DBG("gpio interrupt %d", should_wakeup);
> +
> + /* Check if wee have missed some interrupts */
> + if (info->rx_enabled == should_wakeup)
> + return IRQ_HANDLED;
> +
> + if (should_wakeup)
> + h4p_enable_rx(info);
> + else
> + h4p_disable_rx(info);
> +
> + return IRQ_HANDLED;
> +}
> +
> +static inline void h4p_set_pm_limits(struct h4p_info *info, bool set)
> +{
> + struct h4p_platform_data *bt_plat_data = info->dev->platform_data;
> +
> + if (unlikely(!bt_plat_data || !bt_plat_data->set_pm_limits))
> + return;
> +
> + if (set != !!test_bit(H4P_ACTIVE_MODE, &info->pm_flags)) {

I wonder what is the difference between x != !!y and x == !y or how many negations are really need.

> + bt_plat_data->set_pm_limits(info->dev, set);
> + if (set)
> + set_bit(H4P_ACTIVE_MODE, &info->pm_flags);
> + else
> + clear_bit(H4P_ACTIVE_MODE, &info->pm_flags);
> + BT_DBG("Change pm constraints to: %s", set ? "set" : "clear");
> + return;
> + }
> +
> + BT_DBG("pm constraints remains: %s", set ? "set" : "clear");
> +}
> +
> +static int h4p_reset(struct h4p_info *info)
> +{
> + int err;
> +
> + err = h4p_reset_uart(info);
> + if (err < 0) {
> + dev_err(info->dev, "Uart reset failed\n");
> + return err;
> + }
> + h4p_init_uart(info);
> + h4p_set_rts(info, 0);
> +
> + gpio_set_value(info->reset_gpio, 0);
> + gpio_set_value(info->bt_wakeup_gpio, 1);
> + msleep(10);
> +
> + if (gpio_get_value(info->host_wakeup_gpio) == 1) {
> + dev_err(info->dev, "host_wakeup_gpio not low\n");
> + return -EPROTO;
> + }
> +
> + init_completion(&info->test_completion);
> + gpio_set_value(info->reset_gpio, 1);
> +
> + if (!wait_for_completion_interruptible_timeout(&info->test_completion,
> + msecs_to_jiffies(100))) {
> + dev_err(info->dev, "wakeup test timed out\n");
> + complete_all(&info->test_completion);
> + return -EPROTO;
> + }
> +
> + err = h4p_wait_for_cts(info, 1, 100);
> + if (err < 0) {
> + dev_err(info->dev, "No cts from bt chip\n");
> + return err;
> + }
> +
> + h4p_set_rts(info, 1);
> +
> + return 0;
> +}
> +
> +/* hci callback functions */
> +static int h4p_hci_flush(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> +
> + skb_queue_purge(&info->txq);
> +
> + return 0;
> +}
> +
> +static int h4p_bt_wakeup_test(struct h4p_info *info)
> +{
> + /*
> + * Test Sequence:
> + * Host de-asserts the BT_WAKE_UP line.
> + * Host polls the UART_CTS line, waiting for it to be de-asserted.
> + * Host asserts the BT_WAKE_UP line.
> + * Host polls the UART_CTS line, waiting for it to be asserted.
> + * Host de-asserts the BT_WAKE_UP line (allow the Bluetooth device to
> + * sleep).
> + * Host polls the UART_CTS line, waiting for it to be de-asserted.
> + */
> + int err;
> + int ret = -ECOMM;
> +
> + if (!info)
> + return -EINVAL;
> +
> + /* Disable wakeup interrupts */
> + disable_irq(gpio_to_irq(info->host_wakeup_gpio));
> +
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + err = h4p_wait_for_cts(info, 0, 100);
> + if (err) {
> + dev_warn(info->dev,
> + "bt_wakeup_test: fail: CTS low timed out: %d\n",
> + err);
> + goto out;
> + }
> +
> + gpio_set_value(info->bt_wakeup_gpio, 1);
> + err = h4p_wait_for_cts(info, 1, 100);
> + if (err) {
> + dev_warn(info->dev,
> + "bt_wakeup_test: fail: CTS high timed out: %d\n",
> + err);
> + goto out;
> + }
> +
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + err = h4p_wait_for_cts(info, 0, 100);
> + if (err) {
> + dev_warn(info->dev,
> + "bt_wakeup_test: fail: CTS re-low timed out: %d\n",
> + err);
> + goto out;
> + }
> +
> + ret = 0;
> +
> +out:
> +
> + /* Re-enable wakeup interrupts */
> + enable_irq(gpio_to_irq(info->host_wakeup_gpio));
> +
> + return ret;
> +}
> +
> +static int h4p_setup(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> + int err;
> + unsigned long flags;
> +
> + /*
> + * Disable smart-idle as UART TX interrupts
> + * are not wake-up capable
> + */
> + h4p_smart_idle(info, 0);
> +
> + err = h4p_read_fw(info);
> + if (err < 0) {
> + dev_err(info->dev, "Cannot read firmware\n");
> + goto err_clean;
> + }
> +
> + h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
> + h4p_set_rts(info, 0);
> + h4p_change_speed(info, BC4_MAX_BAUD_RATE);
> + h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
> +
> + info->pm_enabled = 1;
> +
> + err = h4p_bt_wakeup_test(info);
> + if (err < 0) {
> + dev_err(info->dev, "BT wakeup test failed.\n");
> + goto err_clean;
> + }
> +
> + spin_lock_irqsave(&info->lock, flags);
> + info->rx_enabled = gpio_get_value(info->host_wakeup_gpio);
> + h4p_set_clk(info, &info->rx_clocks_en, info->rx_enabled);
> + spin_unlock_irqrestore(&info->lock, flags);
> +
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> +
> + kfree_skb(info->alive_cmd_skb);
> + info->alive_cmd_skb = NULL;
> + info->initing = 0;
> + return 0;
> +
> +err_clean:
> + printk("hci_setup: something failed, should do the clean up\n");
> + return err;
> +}
> +
> +static int h4p_hci_setup(struct hci_dev *hdev)
> +{
> + return 0;
> +}

If you do not use it, then there is no point in including it. The core will do the right thing if you leave it out.

> +
> +static void hci_uninit(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> +
> + h4p_reset_uart(info);
> + del_timer_sync(&info->lazy_release);
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> + h4p_set_clk(info, &info->rx_clocks_en, 0);
> + gpio_set_value(info->reset_gpio, 0);
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + kfree_skb(info->rx_skb);
> + info->rx_skb = NULL;
> +}
> +
> +static int h4p_hci_open(struct hci_dev *hdev)
> +{
> + struct h4p_info *info;
> + int err;
> +
> + info = hci_get_drvdata(hdev);

Fold this into the variable declaration.

> +
> + if (test_bit(HCI_RUNNING, &hdev->flags))
> + return 0;
> +
> + /* TI1271 has HW bug and boot up might fail. Original code retried
> + up to three times, but we removed TI1271 support. */

Comment coding style needs to be correct.

> +
> + info->rx_enabled = 1;
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + info->rx_count = 0;
> + info->garbage_bytes = 0;
> + info->rx_skb = NULL;
> + info->pm_enabled = 0;
> + init_completion(&info->fw_completion);
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + h4p_set_clk(info, &info->rx_clocks_en, 1);
> +
> + err = h4p_reset(info);
> + if (err < 0)
> + goto err_clean;
> +
> + h4p_set_auto_ctsrts(info, 1, UART_EFR_CTS | UART_EFR_RTS);
> + info->autorts = 1;
> +
> + info->initing = 1;
> + printk("hci_setup\n");
> +
> + err = h4p_send_negotiation(info);
> + set_bit(HCI_RUNNING, &hdev->flags);
> +#if 0
> + err = h4p_setup(hdev);
> + if (err < 0) {
> + printk("h4p setup failed\n");
> + goto err_clean;
> + }
> +#endif
> +
> + atomic_set(&hdev->cmd_cnt, 1);
> + set_bit(HCI_INIT, &hdev->flags);
> +
> + return h4p_setup(hdev);
> +
> +err_clean:
> + printk("hci_open: something failed\n");
> + h4p_hci_flush(hdev);
> + hci_uninit(hdev);
> + kfree_skb(info->alive_cmd_skb);
> + info->alive_cmd_skb = NULL;
> +
> + return err;
> +}
> +
> +static int h4p_hci_close(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> +
> + if (!test_and_clear_bit(HCI_RUNNING, &hdev->flags))
> + return 0;
> +
> + h4p_hci_flush(hdev);
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + h4p_set_clk(info, &info->rx_clocks_en, 1);
> + hci_uninit(hdev);
> + return 0;
> +}
> +
> +static int h4p_hci_send_frame(struct hci_dev *hdev, struct sk_buff *skb)
> +{
> + struct h4p_info *info;
> + int err = 0;
> +
> + BT_DBG("hci_send_frame: dev %p, skb %p\n", hdev, skb);
> +
> + info = hci_get_drvdata(hdev);

Same as above and for all other cases as well.

> +
> + if (!test_bit(HCI_RUNNING, &hdev->flags)) {
> + dev_warn(info->dev, "Frame for non-running device\n");
> + return -EIO;
> + }
> +
> + switch (bt_cb(skb)->pkt_type) {
> + case HCI_COMMAND_PKT:
> + hdev->stat.cmd_tx++;
> + break;
> + case HCI_ACLDATA_PKT:
> + hdev->stat.acl_tx++;
> + break;
> + case HCI_SCODATA_PKT:
> + hdev->stat.sco_tx++;
> + break;
> + }
> +
> + /* Push frame type to skb */
> + *skb_push(skb, 1) = (bt_cb(skb)->pkt_type);
> + /* We should always send word aligned data to h4+ devices */
> + if (skb->len % 2) {
> + err = skb_pad(skb, 1);
> + if (!err)
> + *skb_put(skb, 1) = 0x00;
> + }
> + if (err)
> + return err;
> +
> + skb_queue_tail(&info->txq, skb);
> + if (!info->initing)
> + h4p_enable_tx(info);
> + else
> + h4p_enable_tx_nopm(info);
> +
> + return 0;
> +}
> +
> +static ssize_t h4p_hci_set_bdaddr(struct hci_dev *hdev, const bdaddr_t *bdaddr)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> +
> + printk("Set bdaddr... %pMR\n", bdaddr);
> + return 0;
> +}
> +
> +static int h4p_register_hdev(struct h4p_info *info)
> +{
> + struct hci_dev *hdev;
> +
> + /* Initialize and register HCI device */
> +
> + hdev = hci_alloc_dev();
> + if (!hdev) {
> + dev_err(info->dev, "Can't allocate memory for device\n");
> + return -ENOMEM;
> + }
> + info->hdev = hdev;
> +
> + hdev->bus = HCI_UART;
> + hci_set_drvdata(hdev, info);
> +
> + hdev->open = h4p_hci_open;
> + hdev->setup = h4p_hci_setup;
> + hdev->close = h4p_hci_close;
> + hdev->flush = h4p_hci_flush;
> + hdev->send = h4p_hci_send_frame;
> + hdev->set_bdaddr = h4p_hci_set_bdaddr;
> +
> + set_bit(HCI_QUIRK_RESET_ON_CLOSE, &hdev->quirks);

Not sure why this one is needed. So that needs to be figured out.

And you want to set the QUIRK_INVALID_BADDR. At least you want to do that in the final submission.

> +
> + SET_HCIDEV_DEV(hdev, info->dev);
> +
> + if (hci_register_dev(hdev) >= 0)
> + return 0;
> +
> + dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
> + hci_free_dev(info->hdev);
> + return -ENODEV;
> +}

And normally this is folded into the probe handling and not in a separate function.

> +
> +static int h4p_probe_pdata(struct platform_device *pdev, struct h4p_info *info,
> + struct h4p_platform_data *bt_plat_data)
> +{
> + info->chip_type = bt_plat_data->chip_type;
> + info->bt_wakeup_gpio = bt_plat_data->bt_wakeup_gpio;
> + info->host_wakeup_gpio = bt_plat_data->host_wakeup_gpio;
> + info->reset_gpio = bt_plat_data->reset_gpio;
> + info->reset_gpio_shared = bt_plat_data->reset_gpio_shared;
> + info->bt_sysclk = bt_plat_data->bt_sysclk;
> +
> + info->irq = bt_plat_data->uart_irq;
> + info->uart_base = devm_ioremap(&pdev->dev, bt_plat_data->uart_base,
> + SZ_2K);
> + info->uart_iclk = devm_clk_get(&pdev->dev, bt_plat_data->uart_iclk);
> + info->uart_fclk = devm_clk_get(&pdev->dev, bt_plat_data->uart_fclk);
> + return 0;
> +}
> +
> +static int h4p_probe_dt(struct platform_device *pdev, struct h4p_info *info)
> +{
> + struct device_node *node;
> + struct device_node *uart = pdev->dev.of_node;
> + u32 val;
> + struct resource *mem;
> +
> + node = of_get_child_by_name(uart, "device");
> +
> + if (!node)
> + return -ENODATA;
> +
> + info->chip_type = 3; /* Bcm2048 */
> +
> + if (of_property_read_u32(node, "bt-sysclk", &val)) return -EINVAL;
> + info->bt_sysclk = val;
> +
> + info->reset_gpio = of_get_named_gpio(node, "reset-gpios", 0);
> + info->host_wakeup_gpio = of_get_named_gpio(node, "host-wakeup-gpios", 0);
> + info->bt_wakeup_gpio = of_get_named_gpio(node, "bluetooth-wakeup-gpios", 0);
> +
> + if (!uart) {
> + dev_err(&pdev->dev, "UART link not provided\n");
> + return -EINVAL;
> + }
> +
> + info->irq = irq_of_parse_and_map(uart, 0);
> +
> + mem = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + info->uart_base = devm_ioremap_resource(&pdev->dev, mem);
> +
> + info->uart_iclk = of_clk_get_by_name(uart, "ick");
> + info->uart_fclk = of_clk_get_by_name(uart, "fck");
> +
> + printk("DT: have neccessary data\n");
> + return 0;
> +}
> +
> +
> +static int h4p_probe(struct platform_device *pdev)
> +{
> +
> + struct h4p_info *info;
> + int err;
> +
> + dev_info(&pdev->dev, "Registering HCI H4P device\n");
> + info = devm_kzalloc(&pdev->dev, sizeof(struct h4p_info),
> + GFP_KERNEL);
> + if (!info)
> + return -ENOMEM;
> +
> + info->dev = &pdev->dev;
> + info->tx_enabled = 1;
> + info->rx_enabled = 1;
> + spin_lock_init(&info->lock);
> + spin_lock_init(&info->clocks_lock);
> + skb_queue_head_init(&info->txq);
> +
> + if (pdev->dev.platform_data) {
> + err = h4p_probe_pdata(pdev, info, pdev->dev.platform_data);
> + } else {
> + err = h4p_probe_dt(pdev, info);
> + }
> + if (err) {
> + dev_err(&pdev->dev, "Could not get Bluetooth config data\n");
> + return -ENODATA;
> + }
> +
> + printk("base/irq gpio: %lx/%d/%d\n",
> + info->uart_base, info->irq);
> + printk("RESET/BTWU/HOSTWU gpio: %d/%d/%d\n",
> + info->reset_gpio, info->bt_wakeup_gpio, info->host_wakeup_gpio);
> + printk("chip type, sysclk: %d/%d\n", info->chip_type, info->bt_sysclk);
> + printk("clock i/f: %lx/%lx\n", info->uart_iclk, info->uart_fclk);
> +
> + init_completion(&info->test_completion);
> + complete_all(&info->test_completion);
> +
> + err = devm_gpio_request_one(&pdev->dev, info->reset_gpio,
> + GPIOF_OUT_INIT_LOW, "bt_reset");
> + if (err < 0) {
> + dev_err(&pdev->dev, "Cannot get GPIO line %d\n",
> + info->reset_gpio);
> + return err;
> + }
> +
> + err = devm_gpio_request_one(&pdev->dev, info->bt_wakeup_gpio,
> + GPIOF_OUT_INIT_LOW, "bt_wakeup");
> + if (err < 0) {
> + dev_err(info->dev, "Cannot get GPIO line 0x%d",
> + info->bt_wakeup_gpio);
> + return err;
> + }
> +
> + err = devm_gpio_request_one(&pdev->dev, info->host_wakeup_gpio,
> + GPIOF_DIR_IN, "host_wakeup");
> + if (err < 0) {
> + dev_err(info->dev, "Cannot get GPIO line %d",
> + info->host_wakeup_gpio);
> + return err;
> + }
> +
> + err = devm_request_irq(&pdev->dev, info->irq, h4p_interrupt,
> + IRQF_DISABLED, "hci_h4p", info);
> + if (err < 0) {
> + dev_err(info->dev, "hci_h4p: unable to get IRQ %d\n",
> + info->irq);
> + return err;
> + }
> +
> + err = devm_request_irq(&pdev->dev, gpio_to_irq(info->host_wakeup_gpio),
> + h4p_wakeup_interrupt, IRQF_TRIGGER_FALLING |
> + IRQF_TRIGGER_RISING | IRQF_DISABLED,
> + "h4p_wkup", info);
> + if (err < 0) {
> + dev_err(info->dev, "hci_h4p: unable to get wakeup IRQ %d\n",
> + gpio_to_irq(info->host_wakeup_gpio));
> + return err;
> + }
> +
> + err = irq_set_irq_wake(gpio_to_irq(info->host_wakeup_gpio), 1);
> + if (err < 0) {
> + dev_err(info->dev, "hci_h4p: unable to set wakeup for IRQ %d\n",
> + gpio_to_irq(info->host_wakeup_gpio));
> + return err;
> + }
> +
> + init_timer_deferrable(&info->lazy_release);
> + info->lazy_release.function = h4p_lazy_clock_release;
> + info->lazy_release.data = (unsigned long)info;
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + printk("resetting uart....\n");
> + err = h4p_reset_uart(info);
> + printk("reset ok....\n");

I would really prefer that you either use BT_* print functions here or dev_* ones.

> + if (err < 0)
> + return err;
> + gpio_set_value(info->reset_gpio, 0);
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> +
> + platform_set_drvdata(pdev, info);
> +
> + if (h4p_register_hdev(info) < 0) {
> + dev_err(info->dev, "failed to register hci_h4p hci device\n");
> + return -EINVAL;
> + }
> +
> + return 0;
> +}
> +
> +static int h4p_remove(struct platform_device *pdev)
> +{
> + struct h4p_info *info;
> +
> + info = platform_get_drvdata(pdev);
> +
> + h4p_hci_close(info->hdev);
> + hci_unregister_dev(info->hdev);
> + hci_free_dev(info->hdev);
> +
> + return 0;
> +}
> +
> +static const struct of_device_id h4p_of_match[] = {
> + { .compatible = "brcm,uart,bcm2048" },
> + {},
> +};
> +MODULE_DEVICE_TABLE(of, h4p_of_match);
> +
> +static struct platform_driver h4p_driver = {
> + .probe = h4p_probe,
> + .remove = h4p_remove,
> + .driver = {
> + .name = "disabled" "hci_h4p",
> + .owner = THIS_MODULE,
> + .of_match_table = of_match_ptr(h4p_of_match),
> + },
> +};
> +
> +module_platform_driver(h4p_driver);
> +
> +MODULE_ALIAS("platform:hci_h4p");
> +MODULE_DESCRIPTION("Bluetooth h4 driver with nokia extensions");
> +MODULE_LICENSE("GPL");
> +MODULE_AUTHOR("Ville Tervo");
> diff --git a/drivers/bluetooth/nokia_fw-bcm.c b/drivers/bluetooth/nokia_fw-bcm.c
> new file mode 100644
> index 0000000..fd88727
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_fw-bcm.c
> @@ -0,0 +1,27 @@
> +/*
> + * This file is part of Nokia H4P bluetooth driver
> + *
> + * Copyright (C) 2005-2008 Nokia Corporation.
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + */
> +
> +#include <linux/skbuff.h>
> +#include <linux/delay.h>
> +#include <linux/serial_reg.h>
> +
> +#include "hci_h4p.h"
> +
> diff --git a/drivers/bluetooth/nokia_fw.c b/drivers/bluetooth/nokia_fw.c
> new file mode 100644
> index 0000000..7b6a750
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_fw.c
> @@ -0,0 +1,105 @@
> +/*
> + * This file is part of hci_h4p bluetooth driver
> + *
> + * Copyright (C) 2005-2008 Nokia Corporation.
> + * Copyright (C) 2014 Pavel Machek <[email protected]>
> + *
> + * Contact: Ville Tervo <[email protected]>

Since he no longer works for Nokia, this email will bounce. Might just take it out as well.

> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + */
> +
> +#include <linux/module.h>
> +#include <linux/skbuff.h>
> +#include <linux/firmware.h>
> +#include <linux/clk.h>
> +
> +#include <net/bluetooth/bluetooth.h>
> +
> +#include "hci_h4p.h"
> +
> +#define FW_NAME_BCM2048 "bcmfw.bin"

I have the feeling, we really want to put that into "nokia/bcmfw.bin" since all these firmwares were special releases made for Nokia.

> +
> +#define BT_DBG printk

I do not get these re-declartions.

> +
> +
> +/* Read fw. Return length of the command. If no more commands in
> + * fw 0 is returned. In error case return value is negative.
> + */
> +int h4p_read_fw(struct h4p_info *info)
> +{
> + int num = 0;
> + int fw_pos = 0;
> + struct sk_buff *skb;
> + const struct firmware *fw_entry = NULL;
> + int err = -ENOENT;
> + unsigned int cmd_len = 0;
> +
> + err = request_firmware(&fw_entry, FW_NAME_BCM2048, info->dev);
> + if (err != 0 || !fw_entry)
> + return err;

I think that checking for err < 0 is plenty here.

> +
> + while(1) {

while (1) or while (true)

> + int cmd, len;
> +
> + fw_pos += cmd_len;
> +
> + if (fw_pos >= fw_entry->size)
> + break;
> +
> + if (fw_pos + 2 > fw_entry->size) {
> + dev_err(info->dev, "Corrupted firmware image 1\n");
> + err = -EMSGSIZE;
> + break;
> + }
> +
> + cmd_len = fw_entry->data[fw_pos++];
> + cmd_len += fw_entry->data[fw_pos++] << 8;
> + if (cmd_len == 0)
> + break;
> +
> + if (fw_pos + cmd_len > fw_entry->size) {
> + dev_err(info->dev, "Corrupted firmware image 2\n");
> + err = -EMSGSIZE;
> + break;
> + }
> +
> + /* Skip first two packets */
> + if (++num <= 2)
> + continue;
> +
> + /* Note that this is timing-critical. If sending packets takes too
> + long, initialization will fail. */
> + printk("Packet %d...", num);
> +
> + cmd = fw_entry->data[fw_pos+1];
> + cmd += fw_entry->data[fw_pos+2] << 8;
> + len = fw_entry->data[fw_pos+3];
> + printk("cmd %x, len %d.", cmd, len);
> +
> + skb = __hci_cmd_sync(info->hdev, cmd, len, fw_entry->data+fw_pos+4, 500);
> + if (IS_ERR(skb)) {
> + dev_err(info->dev, "...sending cmd failed %d\n", PTR_ERR(skb));
> + err = -EIO;
> + break;
> + }
> + }
> +
> + release_firmware(fw_entry);
> + return err;
> +}
> +
> +MODULE_FIRMWARE(FW_NAME_BCM2048);
> diff --git a/drivers/bluetooth/nokia_uart.c b/drivers/bluetooth/nokia_uart.c
> new file mode 100644
> index 0000000..2cae639
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_uart.c
> @@ -0,0 +1,179 @@
> +/*
> + * This file is part of Nokia H4P bluetooth driver
> + *
> + * Copyright (C) 2005, 2006 Nokia Corporation.
> + * Copyright (C) 2014 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + */
> +
> +#include <linux/delay.h>
> +#include <linux/clk.h>
> +
> +#include <linux/io.h>
> +
> +#include "hci_h4p.h"
> +
> +
> +

Why is this a separate file? And if so, why not all UART specific details are in this file. Including bunch of the defines you have in the header.

> +int h4p_wait_for_cts(struct h4p_info *info, int active,
> + int timeout_ms)
> +{
> + unsigned long timeout;
> + int state;
> +
> + timeout = jiffies + msecs_to_jiffies(timeout_ms);
> + for (;;) {
> + state = h4p_inb(info, UART_MSR) & UART_MSR_CTS;
> + if (active) {
> + if (state)
> + return 0;
> + } else {
> + if (!state)
> + return 0;
> + }
> + if (time_after(jiffies, timeout))
> + return -ETIMEDOUT;
> + msleep(1);
> + }
> +}
> +
> +void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)
> +{
> + u8 lcr, b;
> +
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, 0xbf);
> + b = h4p_inb(info, UART_EFR);
> + if (on)
> + b |= which;
> + else
> + b &= ~which;
> + h4p_outb(info, UART_EFR, b);
> + h4p_outb(info, UART_LCR, lcr);
> +}
> +
> +void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)
> +{
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->lock, flags);
> + __h4p_set_auto_ctsrts(info, on, which);
> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +void h4p_change_speed(struct h4p_info *info, unsigned long speed)
> +{
> + unsigned int divisor;
> + u8 lcr, mdr1;
> +
> + BT_DBG("Setting speed %lu", speed);
> +
> + if (speed >= 460800) {
> + divisor = UART_CLOCK / 13 / speed;
> + mdr1 = 3;
> + } else {
> + divisor = UART_CLOCK / 16 / speed;
> + mdr1 = 0;
> + }
> +
> + /* Make sure UART mode is disabled */
> + h4p_outb(info, UART_OMAP_MDR1, 7);
> +
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, UART_LCR_DLAB); /* Set DLAB */
> + h4p_outb(info, UART_DLL, divisor & 0xff); /* Set speed */
> + h4p_outb(info, UART_DLM, divisor >> 8);
> + h4p_outb(info, UART_LCR, lcr);
> +
> + /* Make sure UART mode is enabled */
> + h4p_outb(info, UART_OMAP_MDR1, mdr1);
> +}
> +
> +int h4p_reset_uart(struct h4p_info *info)
> +{
> + int count = 0;
> +
> + /* Reset the UART */
> + h4p_outb(info, UART_OMAP_SYSC, UART_SYSC_OMAP_RESET);
> + while (!(h4p_inb(info, UART_OMAP_SYSS) & UART_SYSS_RESETDONE)) {
> + if (count++ > 100) {
> + dev_err(info->dev, "hci_h4p: UART reset timeout\n");
> + return -ENODEV;
> + }
> + udelay(1);
> + }
> +
> + return 0;
> +}
> +
> +void h4p_store_regs(struct h4p_info *info)
> +{
> + u16 lcr = 0;
> +
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, 0xBF);
> + info->dll = h4p_inb(info, UART_DLL);
> + info->dlh = h4p_inb(info, UART_DLM);
> + info->efr = h4p_inb(info, UART_EFR);
> + h4p_outb(info, UART_LCR, lcr);
> + info->mdr1 = h4p_inb(info, UART_OMAP_MDR1);
> + info->ier = h4p_inb(info, UART_IER);
> +}
> +
> +void h4p_restore_regs(struct h4p_info *info)
> +{
> + u16 lcr = 0;
> +
> + h4p_init_uart(info);
> +
> + h4p_outb(info, UART_OMAP_MDR1, 7);
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, 0xBF);
> + h4p_outb(info, UART_DLL, info->dll); /* Set speed */
> + h4p_outb(info, UART_DLM, info->dlh);
> + h4p_outb(info, UART_EFR, info->efr);
> + h4p_outb(info, UART_LCR, lcr);
> + h4p_outb(info, UART_OMAP_MDR1, info->mdr1);
> + h4p_outb(info, UART_IER, info->ier);
> +}
> +
> +void h4p_init_uart(struct h4p_info *info)
> +{
> + u8 mcr, efr;
> +
> + /* Enable and setup FIFO */
> + h4p_outb(info, UART_OMAP_MDR1, 0x00);
> +
> + h4p_outb(info, UART_LCR, 0xbf);
> + efr = h4p_inb(info, UART_EFR);
> + h4p_outb(info, UART_EFR, UART_EFR_ECB);
> + h4p_outb(info, UART_LCR, UART_LCR_DLAB);
> + mcr = h4p_inb(info, UART_MCR);
> + h4p_outb(info, UART_MCR, UART_MCR_TCRTLR);
> + h4p_outb(info, UART_FCR, UART_FCR_ENABLE_FIFO |
> + UART_FCR_CLEAR_RCVR | UART_FCR_CLEAR_XMIT |
> + (3 << 6) | (0 << 4));
> + h4p_outb(info, UART_LCR, 0xbf);
> + h4p_outb(info, UART_TI752_TLR, 0xed);
> + h4p_outb(info, UART_TI752_TCR, 0xef);
> + h4p_outb(info, UART_EFR, efr);
> + h4p_outb(info, UART_LCR, UART_LCR_DLAB);
> + h4p_outb(info, UART_MCR, 0x00);
> + h4p_outb(info, UART_LCR, UART_LCR_WLEN8);
> + h4p_outb(info, UART_IER, UART_IER_RDI);
> + h4p_outb(info, UART_OMAP_SYSC, (1 << 0) | (1 << 2) | (2 << 3));
> +}
> diff --git a/include/linux/platform_data/bt-nokia-h4p.h b/include/linux/platform_data/bt-nokia-h4p.h
> index 30d169d..c1a7e64 100644
> --- a/include/linux/platform_data/bt-nokia-h4p.h
> +++ b/include/linux/platform_data/bt-nokia-h4p.h
> @@ -21,9 +21,9 @@
>
>
> /**
> - * struct hci_h4p_platform data - hci_h4p Platform data structure
> + * struct h4p_platform data - hci_h4p Platform data structure
> */
> -struct hci_h4p_platform_data {
> +struct h4p_platform_data {
> int chip_type;
> int bt_sysclk;
> unsigned int bt_wakeup_gpio;

And this just needs to ultimately go away. We need to get this as DT detail.

Regards

Marcel

2014-12-18 19:32:00

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!

> > + h4p_simple_send_frame(info, skb);
> > +
> > + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> > + msecs_to_jiffies(1000))) {
> > + printk("h4p: negotiation did not return\n");
>
> Memory leak in the error case

And memory leak in the normal case, too, no? Fixed.

> > + case H4_ACL_PKT:
> > + acl_hdr = (struct hci_acl_hdr *)skb->data;
> > + retval = le16_to_cpu(acl_hdr->dlen);
>
> Could you explain, why only this needs endianness converted?

This one is 16 bit, the others I checked are 8 bit.

> > +static void h4p_rx_tasklet(unsigned long data)
> > +{
> > + u8 byte;
> > + struct h4p_info *info = (struct h4p_info *)data;
> > +
> > + BT_DBG("tasklet woke up");
> > + BT_DBG("rx_tasklet woke up");
>
> Isn't this a bit redundant?

Fixed.

> > + struct sk_buff *skb;
> > + struct h4p_info *info = (struct h4p_info *)data;
> > +
> > + BT_DBG("tasklet woke up");
> > + BT_DBG("tx_tasklet woke up");
>
> Doubled?

Fixed.

Thanks,
Pavel

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-18 20:10:48

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!
On Thu 2014-12-18 20:31:53, Pavel Machek wrote:
> Hi!
>
> > > + h4p_simple_send_frame(info, skb);
> > > +
> > > + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> > > + msecs_to_jiffies(1000))) {
> > > + printk("h4p: negotiation did not return\n");
> >
> > Memory leak in the error case
>
> And memory leak in the normal case, too, no? Fixed.

Actually, no, h4p_simple_send_frame passes skb to network stack, and
it should free it as neccessary.

Pavel

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-19 09:50:08

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!

> And you want to set the QUIRK_INVALID_BADDR. At least you want to do that in the final submission.
>

Ok, I found out that I can do it and result works, provided that I do
hciconfig hci0 up/down first.

I have trouble understanding... h4p_hci_open() seems to be called as
soon as I insmod the driver. Who does that? Is it some kind of udev
magic?

...
> > +#include "hci_h4p.h"
> > +
> > +#define BT_DBG(a...) do {} while(0)
>
> Why is this needed? BT_DBG is hooked up with dynamic debug.
...

I did all the changes as requested. Thanks. I did't see harm in
include guards, but I removed them; it is not important.

> > + if (info->rx_count == 0) {
> > + /* H4+ devices should always send word aligned packets */
> > + if (!(info->rx_skb->len % 2))
> > + info->garbage_bytes++;
> > + h4p_recv_frame(info, info->rx_skb);
>
> The h4p_recv_frame should maybe done inline here since it only handles 2 exception packets. Also to make it easy, just leave the function if (info->rx_count).
>
> This packet processing feels like a bit of spaghetti code. I think that is better handled in a proper function that goes through it and not with many tiny sub functions.
>

Well, CodingStyle says something about functions that should be kept
short... And when manually inlined, the inner function would have to
be made less readable, as it uses return to shortcut processing.


To use __hci_cmd_sync()

> > +
> > + SET_HCIDEV_DEV(hdev, info->dev);
> > +
> > + if (hci_register_dev(hdev) >= 0)
> > + return 0;
> > +
> > + dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
> > + hci_free_dev(info->hdev);
> > + return -ENODEV;
> > +}
>
> And normally this is folded into the probe handling and not in a
> separate function.

The probe function is too long, already...

> > +#include <linux/delay.h>
> > +#include <linux/clk.h>
> > +
> > +#include <linux/io.h>
> > +
> > +#include "hci_h4p.h"
>
> Why is this a separate file? And if so, why not all UART specific details are in this file. Including bunch of the defines you have in the header.
>

Well, you wanted less global functions, so I moved some as inlines to
headers. I guess I can merge nokia_core and nokia_uart if really wanted.

I did rest of requested changes.

Thanks,
Pavel

--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-19 09:58:47

by Marcel Holtmann

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi Pavel,

>> And you want to set the QUIRK_INVALID_BADDR. At least you want to do that in the final submission.
>>
>
> Ok, I found out that I can do it and result works, provided that I do
> hciconfig hci0 up/down first.

that should not be the case. Actually hciconfig uses old ioctl. A full Bluetooth system running bluetoothd (from BlueZ 5) will never use any old ioctl. Only an old system (BlueZ 4) will use ioctl.

> I have trouble understanding... h4p_hci_open() seems to be called as
> soon as I insmod the driver. Who does that? Is it some kind of udev
> magic?

As soon as you do hci_register_dev, it will bring up the device and run the basic initialization. That is needed to get the address, version information and features. Otherwise the mgmt interface can not work. We need basic information about the device.

So what the kernel will do internally when you find a device is bring it up, get the basics and then bring it back down (in case nobody uses it). See hci_power_on work.

> ...
>>> +#include "hci_h4p.h"
>>> +
>>> +#define BT_DBG(a...) do {} while(0)
>>
>> Why is this needed? BT_DBG is hooked up with dynamic debug.
> ...
>
> I did all the changes as requested. Thanks. I did't see harm in
> include guards, but I removed them; it is not important.

There is no harm in including the guards. We just don't do it for internal files. And thus if anyone tries to be sneaky and build circular inclusion they will fall flat on their faces. That is the only reason.

>
>>> + if (info->rx_count == 0) {
>>> + /* H4+ devices should always send word aligned packets */
>>> + if (!(info->rx_skb->len % 2))
>>> + info->garbage_bytes++;
>>> + h4p_recv_frame(info, info->rx_skb);
>>
>> The h4p_recv_frame should maybe done inline here since it only handles 2 exception packets. Also to make it easy, just leave the function if (info->rx_count).
>>
>> This packet processing feels like a bit of spaghetti code. I think that is better handled in a proper function that goes through it and not with many tiny sub functions.
>>
>
> Well, CodingStyle says something about functions that should be kept
> short... And when manually inlined, the inner function would have to
> be made less readable, as it uses return to shortcut processing.

It also should not make me have to follow 3 functions to figure out what it is actually doing.

>
>
> To use __hci_cmd_sync()
>
>>> +
>>> + SET_HCIDEV_DEV(hdev, info->dev);
>>> +
>>> + if (hci_register_dev(hdev) >= 0)
>>> + return 0;
>>> +
>>> + dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
>>> + hci_free_dev(info->hdev);
>>> + return -ENODEV;
>>> +}
>>
>> And normally this is folded into the probe handling and not in a
>> separate function.
>
> The probe function is too long, already...

Have you compared it to other functions. Normally probe() functions in general are all pretty long since they have to do tons of stuff. Having all in one function means you can read through it at once.

>
>>> +#include <linux/delay.h>
>>> +#include <linux/clk.h>
>>> +
>>> +#include <linux/io.h>
>>> +
>>> +#include "hci_h4p.h"
>>
>> Why is this a separate file? And if so, why not all UART specific details are in this file. Including bunch of the defines you have in the header.
>>
>
> Well, you wanted less global functions, so I moved some as inlines to
> headers. I guess I can merge nokia_core and nokia_uart if really wanted.

Would this become easier when some of the OMAP specific stuff is moved out of this driver? If that is possible.

Regards

Marcel

2014-12-20 15:48:55

by Pavel Machek

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi!

> > I have trouble understanding... h4p_hci_open() seems to be called as
> > soon as I insmod the driver. Who does that? Is it some kind of udev
> > magic?
>
> As soon as you do hci_register_dev, it will bring up the device and run the basic initialization. That is needed to get the address, version information and features. Otherwise the mgmt interface can not work. We need basic information about the device.
>
> So what the kernel will do internally when you find a device is bring it up, get the basics and then bring it back down (in case nobody uses it). See hci_power_on work.
>

Aha, slightly unexpected, but it matches observations. Good.

> > To use __hci_cmd_sync()
> >
> >>> +
> >>> + SET_HCIDEV_DEV(hdev, info->dev);
> >>> +
> >>> + if (hci_register_dev(hdev) >= 0)
> >>> + return 0;
> >>> +
> >>> + dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
> >>> + hci_free_dev(info->hdev);
> >>> + return -ENODEV;
> >>> +}
> >>
> >> And normally this is folded into the probe handling and not in a
> >> separate function.
> >
> > The probe function is too long, already...
>
> Have you compared it to other functions. Normally probe() functions in general are all pretty long since they have to do tons of stuff. Having all in one function means you can read through it at once.
>

Ok.

> >>> +#include "hci_h4p.h"
> >>
> >> Why is this a separate file? And if so, why not all UART specific details are in this file. Including bunch of the defines you have in the header.
> >>
> >
> > Well, you wanted less global functions, so I moved some as inlines to
> > headers. I guess I can merge nokia_core and nokia_uart if really wanted.
>
> Would this become easier when some of the OMAP specific stuff is moved out of this driver? If that is possible.
>

Yes, I can investigate further cleanups. But original plan was to
merge it and then clean up the rest. Could we do that, please?

Thanks,
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-20 20:23:21

by Pavel Machek

[permalink] [raw]
Subject: [PATCH] bluetooth: Add hci_h4p driver


Add hci_h4p bluetooth driver. This device is used for example on Nokia N900 cell phone.

Signed-off-by: Pavel Machek <[email protected]>
Thanks-to: Sebastian Reichel <[email protected]>
Thanks-to: Joe Perches <[email protected]>

---

Please apply,

Pavel

diff --git a/drivers/bluetooth/Kconfig b/drivers/bluetooth/Kconfig
index 4547dc2..268b1a6 100644
--- a/drivers/bluetooth/Kconfig
+++ b/drivers/bluetooth/Kconfig
@@ -243,4 +243,13 @@ config BT_WILINK
Say Y here to compile support for Texas Instrument's WiLink7 driver
into the kernel or say M to compile it as module (btwilink).

+config BT_NOKIA_H4P
+ tristate "HCI driver with H4 Nokia extensions"
+ help
+ Bluetooth HCI driver with H4 extensions. This driver provides
+ support for H4+ Bluetooth chip with vendor-specific H4 extensions.
+
+ Say Y here to compile support for h4 extended devices into the kernel
+ or say M to compile it as module (btnokia_h4p).
+
endmenu
diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
index 9fe8a87..624ef3fc 100644
--- a/drivers/bluetooth/Makefile
+++ b/drivers/bluetooth/Makefile
@@ -31,4 +31,7 @@ hci_uart-$(CONFIG_BT_HCIUART_ATH3K) += hci_ath.o
hci_uart-$(CONFIG_BT_HCIUART_3WIRE) += hci_h5.o
hci_uart-objs := $(hci_uart-y)

+obj-$(CONFIG_BT_NOKIA_H4P) += nokia_h4p.o
+nokia_h4p-objs := nokia_core.o nokia_fw.o nokia_uart.o
+
ccflags-y += -D__CHECK_ENDIAN__
diff --git a/drivers/bluetooth/nokia_core.c b/drivers/bluetooth/nokia_core.c
new file mode 100644
index 0000000..163531e
--- /dev/null
+++ b/drivers/bluetooth/nokia_core.c
@@ -0,0 +1,1188 @@
+/*
+ * This file is part of Nokia H4P bluetooth driver
+ *
+ * Copyright (C) 2005-2008 Nokia Corporation.
+ * Copyright (C) 2014 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ * Thanks to all the Nokia people that helped with this driver,
+ * including Ville Tervo and Roger Quadros.
+ *
+ * Power saving functionality was removed from this driver to make
+ * merging easier.
+ */
+
+#include <linux/module.h>
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/errno.h>
+#include <linux/delay.h>
+#include <linux/spinlock.h>
+#include <linux/serial_reg.h>
+#include <linux/skbuff.h>
+#include <linux/device.h>
+#include <linux/platform_device.h>
+#include <linux/clk.h>
+#include <linux/interrupt.h>
+#include <linux/gpio.h>
+#include <linux/of_gpio.h>
+#include <linux/of_irq.h>
+#include <linux/timer.h>
+#include <linux/kthread.h>
+#include <linux/io.h>
+#include <linux/completion.h>
+#include <linux/sizes.h>
+
+#include <net/bluetooth/bluetooth.h>
+#include <net/bluetooth/hci_core.h>
+#include <net/bluetooth/hci.h>
+
+#include "nokia_h4p.h"
+
+#undef TEST
+
+static int hw_inited = 0;
+
+/* This should be used in function that cannot release clocks */
+static void h4p_set_clk(struct h4p_info *info, int *clock, int enable)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->clocks_lock, flags);
+ if (enable && !*clock) {
+ BT_DBG("Enabling %p", clock);
+ clk_prepare_enable(info->uart_fclk);
+ clk_prepare_enable(info->uart_iclk);
+ if (atomic_read(&info->clk_users) == 0)
+ h4p_restore_regs(info);
+ atomic_inc(&info->clk_users);
+ }
+
+ if (!enable && *clock) {
+ BT_DBG("Disabling %p", clock);
+ if (atomic_dec_and_test(&info->clk_users))
+ h4p_store_regs(info);
+ clk_disable_unprepare(info->uart_fclk);
+ clk_disable_unprepare(info->uart_iclk);
+ }
+
+ *clock = enable;
+ spin_unlock_irqrestore(&info->clocks_lock, flags);
+}
+
+static void h4p_lazy_clock_release(unsigned long data)
+{
+ struct h4p_info *info = (struct h4p_info *)data;
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->lock, flags);
+ if (!info->tx_enabled)
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+/* Power management functions */
+void h4p_smart_idle(struct h4p_info *info, bool enable)
+{
+ u8 v;
+
+ v = h4p_inb(info, UART_OMAP_SYSC);
+ v &= ~(UART_OMAP_SYSC_IDLEMASK);
+
+ if (enable)
+ v |= UART_OMAP_SYSC_SMART_IDLE;
+ else
+ v |= UART_OMAP_SYSC_NO_IDLE;
+
+ h4p_outb(info, UART_OMAP_SYSC, v);
+}
+
+static inline void h4p_schedule_pm(struct h4p_info *info)
+{
+}
+
+static void h4p_disable_tx(struct h4p_info *info)
+{
+ if (!info->pm_enabled)
+ return;
+
+ /* Re-enable smart-idle */
+ h4p_smart_idle(info, 1);
+
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ mod_timer(&info->lazy_release, jiffies + msecs_to_jiffies(100));
+ info->tx_enabled = 0;
+}
+
+void h4p_enable_tx_nopm(struct h4p_info *info)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->lock, flags);
+ h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
+ UART_IER_THRI);
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+void h4p_enable_tx(struct h4p_info *info)
+{
+ unsigned long flags;
+
+ if (!info->pm_enabled)
+ return;
+
+ h4p_schedule_pm(info);
+
+ spin_lock_irqsave(&info->lock, flags);
+ del_timer(&info->lazy_release);
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ info->tx_enabled = 1;
+ gpio_set_value(info->bt_wakeup_gpio, 1);
+ h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
+ UART_IER_THRI);
+ /*
+ * Disable smart-idle as UART TX interrupts
+ * are not wake-up capable
+ */
+ h4p_smart_idle(info, 0);
+
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+static void h4p_disable_rx(struct h4p_info *info)
+{
+ if (!info->pm_enabled)
+ return;
+
+ info->rx_enabled = 0;
+
+ if (h4p_inb(info, UART_LSR) & UART_LSR_DR)
+ return;
+
+ if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
+ return;
+
+ __h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
+ info->autorts = 0;
+ h4p_set_clk(info, &info->rx_clocks_en, 0);
+}
+
+static void h4p_enable_rx(struct h4p_info *info)
+{
+ if (!info->pm_enabled)
+ return;
+
+ h4p_schedule_pm(info);
+
+ h4p_set_clk(info, &info->rx_clocks_en, 1);
+ info->rx_enabled = 1;
+
+ if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
+ return;
+
+ __h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
+ info->autorts = 1;
+}
+
+void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb)
+{
+ skb_queue_tail(&info->txq, skb);
+ h4p_enable_tx_nopm(info);
+}
+
+/* Negotiation functions */
+int h4p_send_alive_packet(struct h4p_info *info)
+{
+ struct h4p_alive_hdr *hdr;
+ struct h4p_alive_pkt *pkt;
+ struct sk_buff *skb;
+ int len;
+
+ BT_DBG("Sending alive packet");
+
+ len = H4_TYPE_SIZE + sizeof(*hdr) + sizeof(*pkt);
+ skb = bt_skb_alloc(len, GFP_KERNEL);
+ if (!skb)
+ return -ENOMEM;
+
+ memset(skb->data, 0x00, len);
+ *skb_put(skb, 1) = H4_ALIVE_PKT;
+ hdr = (struct h4p_alive_hdr *)skb_put(skb, sizeof(*hdr));
+ hdr->dlen = sizeof(*pkt);
+ pkt = (struct h4p_alive_pkt *)skb_put(skb, sizeof(*pkt));
+ pkt->mid = H4P_ALIVE_REQ;
+
+ h4p_simple_send_frame(info, skb);
+
+ BT_DBG("Alive packet sent");
+
+ return 0;
+}
+
+static void h4p_alive_packet(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ struct h4p_alive_hdr *hdr;
+ struct h4p_alive_pkt *pkt;
+
+ BT_DBG("Received alive packet");
+ hdr = (struct h4p_alive_hdr *)skb->data;
+ if (hdr->dlen != sizeof(*pkt)) {
+ dev_err(info->dev, "Corrupted alive message\n");
+ info->init_error = -EIO;
+ goto finish_alive;
+ }
+
+ pkt = (struct h4p_alive_pkt *)skb_pull(skb, sizeof(*hdr));
+ if (pkt->mid != H4P_ALIVE_RESP) {
+ dev_err(info->dev, "Could not negotiate nokia_h4p settings\n");
+ info->init_error = -EINVAL;
+ }
+
+finish_alive:
+ complete(&info->init_completion);
+ kfree_skb(skb);
+}
+
+static int h4p_send_negotiation(struct h4p_info *info)
+{
+ struct h4p_neg_cmd *neg_cmd;
+ struct h4p_neg_hdr *neg_hdr;
+ struct sk_buff *skb;
+ int err, len;
+ u16 sysclk = 38400;
+
+ printk("Sending negotiation..");
+ len = sizeof(*neg_cmd) + sizeof(*neg_hdr) + H4_TYPE_SIZE;
+
+ skb = bt_skb_alloc(len, GFP_KERNEL);
+ if (!skb)
+ return -ENOMEM;
+
+ memset(skb->data, 0x00, len);
+ *skb_put(skb, 1) = H4_NEG_PKT;
+ neg_hdr = (struct h4p_neg_hdr *)skb_put(skb, sizeof(*neg_hdr));
+ neg_cmd = (struct h4p_neg_cmd *)skb_put(skb, sizeof(*neg_cmd));
+
+ neg_hdr->dlen = sizeof(*neg_cmd);
+ neg_cmd->ack = H4P_NEG_REQ;
+ neg_cmd->baud = cpu_to_le16(BT_BAUDRATE_DIVIDER/MAX_BAUD_RATE);
+ neg_cmd->proto = H4P_PROTO_BYTE;
+ neg_cmd->sys_clk = cpu_to_le16(sysclk);
+
+ h4p_change_speed(info, INIT_SPEED);
+
+ h4p_set_rts(info, 1);
+ info->init_error = 0;
+ init_completion(&info->init_completion);
+
+ h4p_simple_send_frame(info, skb);
+
+ if (!wait_for_completion_interruptible_timeout(&info->init_completion,
+ msecs_to_jiffies(1000))) {
+ printk("h4p: negotiation did not return\n");
+ return -ETIMEDOUT;
+ }
+
+ if (info->init_error < 0)
+ return info->init_error;
+
+ /* Change to operational settings */
+ h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
+ h4p_set_rts(info, 0);
+ h4p_change_speed(info, MAX_BAUD_RATE);
+
+ err = h4p_wait_for_cts(info, 1, 100);
+ if (err < 0)
+ return err;
+
+ h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
+ init_completion(&info->init_completion);
+ err = h4p_send_alive_packet(info);
+
+ if (err < 0)
+ return err;
+
+ if (!wait_for_completion_interruptible_timeout(&info->init_completion,
+ msecs_to_jiffies(1000)))
+ return -ETIMEDOUT;
+
+ if (info->init_error < 0)
+ return info->init_error;
+
+ printk("Negotiation successful\n");
+ return 0;
+}
+
+static void h4p_negotiation_packet(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ struct h4p_neg_hdr *hdr;
+ struct h4p_neg_evt *evt;
+
+ hdr = (struct h4p_neg_hdr *)skb->data;
+ if (hdr->dlen != sizeof(*evt)) {
+ info->init_error = -EIO;
+ goto finish_neg;
+ }
+
+ evt = (struct h4p_neg_evt *)skb_pull(skb, sizeof(*hdr));
+
+ if (evt->ack != H4P_NEG_ACK) {
+ dev_err(info->dev, "Could not negotiate nokia_h4p settings\n");
+ info->init_error = -EINVAL;
+ }
+
+ info->man_id = evt->man_id;
+ info->ver_id = evt->ver_id;
+ printk("Negotiation finished.\n");
+
+finish_neg:
+
+ complete(&info->init_completion);
+ kfree_skb(skb);
+}
+
+/* H4 packet handling functions */
+static int h4p_get_hdr_len(struct h4p_info *info, u8 pkt_type)
+{
+ long retval;
+
+ switch (pkt_type) {
+ case H4_EVT_PKT:
+ retval = HCI_EVENT_HDR_SIZE;
+ break;
+ case H4_ACL_PKT:
+ retval = HCI_ACL_HDR_SIZE;
+ break;
+ case H4_SCO_PKT:
+ retval = HCI_SCO_HDR_SIZE;
+ break;
+ case H4_NEG_PKT:
+ retval = H4P_NEG_HDR_SIZE;
+ break;
+ case H4_ALIVE_PKT:
+ retval = H4P_ALIVE_HDR_SIZE;
+ break;
+ case H4_RADIO_PKT:
+ retval = H4_RADIO_HDR_SIZE;
+ break;
+ default:
+ dev_err(info->dev, "Unknown H4 packet type 0x%.2x\n", pkt_type);
+ retval = -1;
+ break;
+ }
+
+ return retval;
+}
+
+static unsigned int h4p_get_data_len(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ long retval = -1;
+ struct hci_acl_hdr *acl_hdr;
+ struct hci_sco_hdr *sco_hdr;
+ struct hci_event_hdr *evt_hdr;
+ struct h4p_neg_hdr *neg_hdr;
+ struct h4p_alive_hdr *alive_hdr;
+ struct h4p_radio_hdr *radio_hdr;
+
+ switch (bt_cb(skb)->pkt_type) {
+ case H4_EVT_PKT:
+ evt_hdr = (struct hci_event_hdr *)skb->data;
+ retval = evt_hdr->plen;
+ break;
+ case H4_ACL_PKT:
+ acl_hdr = (struct hci_acl_hdr *)skb->data;
+ retval = le16_to_cpu(acl_hdr->dlen);
+ break;
+ case H4_SCO_PKT:
+ sco_hdr = (struct hci_sco_hdr *)skb->data;
+ retval = sco_hdr->dlen;
+ break;
+ case H4_RADIO_PKT:
+ radio_hdr = (struct h4p_radio_hdr *)skb->data;
+ retval = radio_hdr->dlen;
+ break;
+ case H4_NEG_PKT:
+ neg_hdr = (struct h4p_neg_hdr *)skb->data;
+ retval = neg_hdr->dlen;
+ break;
+ case H4_ALIVE_PKT:
+ alive_hdr = (struct h4p_alive_hdr *)skb->data;
+ retval = alive_hdr->dlen;
+ break;
+ }
+
+ return retval;
+}
+
+static inline void h4p_recv_frame(struct h4p_info *info,
+ struct sk_buff *skb)
+{
+ if (info->initing) {
+ switch (bt_cb(skb)->pkt_type) {
+ case H4_NEG_PKT:
+ h4p_negotiation_packet(info, skb);
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ return;
+ case H4_ALIVE_PKT:
+ h4p_alive_packet(info, skb);
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ return;
+ }
+ }
+
+ hci_recv_frame(info->hdev, skb);
+ BT_DBG("Frame sent to upper layer");
+}
+
+static inline void h4p_handle_byte(struct h4p_info *info, u8 byte)
+{
+ switch (info->rx_state) {
+ case WAIT_FOR_PKT_TYPE:
+ bt_cb(info->rx_skb)->pkt_type = byte;
+ info->rx_count = h4p_get_hdr_len(info, byte);
+ if (info->rx_count < 0) {
+ info->hdev->stat.err_rx++;
+ kfree_skb(info->rx_skb);
+ info->rx_skb = NULL;
+ } else {
+ info->rx_state = WAIT_FOR_HEADER;
+ }
+ break;
+ case WAIT_FOR_HEADER:
+ info->rx_count--;
+ *skb_put(info->rx_skb, 1) = byte;
+ if (info->rx_count != 0)
+ break;
+ info->rx_count = h4p_get_data_len(info, info->rx_skb);
+ if (info->rx_count > skb_tailroom(info->rx_skb)) {
+ dev_err(info->dev, "frame too long\n");
+ info->garbage_bytes = info->rx_count
+ - skb_tailroom(info->rx_skb);
+ kfree_skb(info->rx_skb);
+ info->rx_skb = NULL;
+ break;
+ }
+ info->rx_state = WAIT_FOR_DATA;
+ break;
+ case WAIT_FOR_DATA:
+ info->rx_count--;
+ *skb_put(info->rx_skb, 1) = byte;
+ break;
+ default:
+ WARN_ON(1);
+ break;
+ }
+
+ if (info->rx_count == 0) {
+ /* H4+ devices should always send word aligned packets */
+ if (!(info->rx_skb->len % 2))
+ info->garbage_bytes++;
+ h4p_recv_frame(info, info->rx_skb);
+ info->rx_skb = NULL;
+ }
+}
+
+static void h4p_rx_tasklet(unsigned long data)
+{
+ u8 byte;
+ struct h4p_info *info = (struct h4p_info *)data;
+
+ BT_DBG("rx_tasklet woke up");
+
+ while (h4p_inb(info, UART_LSR) & UART_LSR_DR) {
+ byte = h4p_inb(info, UART_RX);
+ BT_DBG("[in: %02x]", byte);
+ if (info->garbage_bytes) {
+ info->garbage_bytes--;
+ continue;
+ }
+ if (info->rx_skb == NULL) {
+ info->rx_skb = bt_skb_alloc(HCI_MAX_FRAME_SIZE,
+ GFP_ATOMIC | GFP_DMA);
+ if (!info->rx_skb) {
+ dev_err(info->dev,
+ "No memory for new packet\n");
+ goto finish_rx;
+ }
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ info->rx_skb->dev = (void *)info->hdev;
+ }
+ info->hdev->stat.byte_rx++;
+ h4p_handle_byte(info, byte);
+ }
+
+ if (!info->rx_enabled) {
+ if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT &&
+ info->autorts) {
+ __h4p_set_auto_ctsrts(info, 0 , UART_EFR_RTS);
+ info->autorts = 0;
+ }
+ /* Flush posted write to avoid spurious interrupts */
+ h4p_inb(info, UART_OMAP_SCR);
+ h4p_set_clk(info, &info->rx_clocks_en, 0);
+ }
+
+finish_rx:
+ BT_DBG("rx_ended");
+}
+
+static void h4p_tx_tasklet(unsigned long data)
+{
+ unsigned int sent = 0;
+ struct sk_buff *skb;
+ struct h4p_info *info = (struct h4p_info *)data;
+
+ BT_DBG("tx_tasklet woke up");
+
+ if (info->autorts != info->rx_enabled) {
+ if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
+ if (info->autorts && !info->rx_enabled) {
+ __h4p_set_auto_ctsrts(info, 0,
+ UART_EFR_RTS);
+ info->autorts = 0;
+ }
+ if (!info->autorts && info->rx_enabled) {
+ __h4p_set_auto_ctsrts(info, 1,
+ UART_EFR_RTS);
+ info->autorts = 1;
+ }
+ } else {
+ h4p_outb(info, UART_OMAP_SCR,
+ h4p_inb(info, UART_OMAP_SCR) |
+ UART_OMAP_SCR_EMPTY_THR);
+ goto finish_tx;
+ }
+ }
+
+ skb = skb_dequeue(&info->txq);
+ if (!skb) {
+ /* No data in buffer */
+ BT_DBG("skb ready");
+ if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
+ h4p_outb(info, UART_IER,
+ h4p_inb(info, UART_IER) &
+ ~UART_IER_THRI);
+ h4p_inb(info, UART_OMAP_SCR);
+ h4p_disable_tx(info);
+ return;
+ }
+ h4p_outb(info, UART_OMAP_SCR,
+ h4p_inb(info, UART_OMAP_SCR) |
+ UART_OMAP_SCR_EMPTY_THR);
+ goto finish_tx;
+ }
+
+ /* Copy data to tx fifo */
+ while (!(h4p_inb(info, UART_OMAP_SSR) & UART_OMAP_SSR_TXFULL) &&
+ (sent < skb->len)) {
+ BT_DBG("%02x ", skb->data[sent]);
+ h4p_outb(info, UART_TX, skb->data[sent]);
+ sent++;
+ }
+
+ info->hdev->stat.byte_tx += sent;
+ if (skb->len == sent) {
+ kfree_skb(skb);
+ } else {
+ skb_pull(skb, sent);
+ skb_queue_head(&info->txq, skb);
+ }
+
+ h4p_outb(info, UART_OMAP_SCR, h4p_inb(info, UART_OMAP_SCR) &
+ ~UART_OMAP_SCR_EMPTY_THR);
+ h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
+ UART_IER_THRI);
+
+finish_tx:
+ /* Flush posted write to avoid spurious interrupts */
+ h4p_inb(info, UART_OMAP_SCR);
+
+}
+
+static irqreturn_t h4p_interrupt(int irq, void *data)
+{
+ struct h4p_info *info = (struct h4p_info *)data;
+ u8 iir, msr;
+ int ret;
+
+ ret = IRQ_NONE;
+
+ iir = h4p_inb(info, UART_IIR);
+ if (iir & UART_IIR_NO_INT)
+ return IRQ_HANDLED;
+
+ iir &= UART_IIR_ID;
+
+ if (iir == UART_IIR_MSI) {
+ msr = h4p_inb(info, UART_MSR);
+ ret = IRQ_HANDLED;
+ }
+ if (iir == UART_IIR_RLSI) {
+ h4p_inb(info, UART_RX);
+ h4p_inb(info, UART_LSR);
+ ret = IRQ_HANDLED;
+ }
+
+ if (iir == UART_IIR_RDI) {
+ h4p_rx_tasklet((unsigned long)data);
+ ret = IRQ_HANDLED;
+ }
+
+ if (iir == UART_IIR_THRI) {
+ h4p_tx_tasklet((unsigned long)data);
+ ret = IRQ_HANDLED;
+ }
+
+ return ret;
+}
+
+static irqreturn_t h4p_wakeup_interrupt(int irq, void *dev_inst)
+{
+ struct h4p_info *info = dev_inst;
+ int should_wakeup;
+ struct hci_dev *hdev;
+
+ BT_DBG("[wakeup irq]");
+
+ if (!info->hdev)
+ return IRQ_HANDLED;
+
+ should_wakeup = gpio_get_value(info->host_wakeup_gpio);
+ hdev = info->hdev;
+
+ if (info->initing) {
+ if (should_wakeup == 1)
+ complete_all(&info->test_completion);
+
+ printk("wakeup irq handled\n");
+
+ return IRQ_HANDLED;
+ }
+
+ BT_DBG("gpio interrupt %d", should_wakeup);
+
+ /* Check if we have missed some interrupts */
+ if (info->rx_enabled == should_wakeup)
+ return IRQ_HANDLED;
+
+ if (should_wakeup)
+ h4p_enable_rx(info);
+ else
+ h4p_disable_rx(info);
+
+ return IRQ_HANDLED;
+}
+
+static int h4p_reset(struct h4p_info *info)
+{
+ int err;
+
+ err = h4p_reset_uart(info);
+ if (err < 0) {
+ dev_err(info->dev, "Uart reset failed\n");
+ return err;
+ }
+ h4p_init_uart(info);
+ h4p_set_rts(info, 0);
+
+ gpio_set_value(info->reset_gpio, 0);
+ gpio_set_value(info->bt_wakeup_gpio, 1);
+ msleep(10);
+
+ if (gpio_get_value(info->host_wakeup_gpio) == 1) {
+ dev_err(info->dev, "host_wakeup_gpio not low\n");
+ return -EPROTO;
+ }
+
+ init_completion(&info->test_completion);
+ gpio_set_value(info->reset_gpio, 1);
+
+ if (!wait_for_completion_interruptible_timeout(&info->test_completion,
+ msecs_to_jiffies(100))) {
+ dev_err(info->dev, "wakeup test timed out\n");
+ complete_all(&info->test_completion);
+ return -EPROTO;
+ }
+
+ err = h4p_wait_for_cts(info, 1, 100);
+ if (err < 0) {
+ dev_err(info->dev, "No cts from bt chip\n");
+ return err;
+ }
+
+ h4p_set_rts(info, 1);
+
+ return 0;
+}
+
+/* hci callback functions */
+static int h4p_hci_flush(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+
+ skb_queue_purge(&info->txq);
+
+ return 0;
+}
+
+static int h4p_bt_wakeup_test(struct h4p_info *info)
+{
+ /*
+ * Test Sequence:
+ * Host de-asserts the BT_WAKE_UP line.
+ * Host polls the UART_CTS line, waiting for it to be de-asserted.
+ * Host asserts the BT_WAKE_UP line.
+ * Host polls the UART_CTS line, waiting for it to be asserted.
+ * Host de-asserts the BT_WAKE_UP line (allow the Bluetooth device to
+ * sleep).
+ * Host polls the UART_CTS line, waiting for it to be de-asserted.
+ */
+ int err;
+ int ret = -ECOMM;
+
+ if (!info)
+ return -EINVAL;
+
+ /* Disable wakeup interrupts */
+ disable_irq(gpio_to_irq(info->host_wakeup_gpio));
+
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ err = h4p_wait_for_cts(info, 0, 100);
+ if (err) {
+ dev_warn(info->dev,
+ "bt_wakeup_test: fail: CTS low timed out: %d\n",
+ err);
+ goto out;
+ }
+
+ gpio_set_value(info->bt_wakeup_gpio, 1);
+ err = h4p_wait_for_cts(info, 1, 100);
+ if (err) {
+ dev_warn(info->dev,
+ "bt_wakeup_test: fail: CTS high timed out: %d\n",
+ err);
+ goto out;
+ }
+
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ err = h4p_wait_for_cts(info, 0, 100);
+ if (err) {
+ dev_warn(info->dev,
+ "bt_wakeup_test: fail: CTS re-low timed out: %d\n",
+ err);
+ goto out;
+ }
+
+ ret = 0;
+
+out:
+
+ /* Re-enable wakeup interrupts */
+ enable_irq(gpio_to_irq(info->host_wakeup_gpio));
+
+ return ret;
+}
+
+static int h4p_hci_set_bdaddr(struct hci_dev *hdev, const bdaddr_t *bdaddr)
+{
+ struct sk_buff *skb;
+ long ret;
+
+ printk("Set bdaddr... %pMR\n", bdaddr);
+
+ skb = __hci_cmd_sync(hdev, 0xfc01, 6, bdaddr, HCI_INIT_TIMEOUT);
+ if (IS_ERR(skb)) {
+ ret = PTR_ERR(skb);
+ BT_ERR("%s: BCM: Change address command failed (%ld)",
+ hdev->name, ret);
+ return ret;
+ }
+ kfree_skb(skb);
+
+ return 0;
+}
+
+static void h4p_deinit(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+
+ h4p_hci_flush(hdev);
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ h4p_set_clk(info, &info->rx_clocks_en, 1);
+ h4p_reset_uart(info);
+ del_timer_sync(&info->lazy_release);
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+ h4p_set_clk(info, &info->rx_clocks_en, 0);
+ gpio_set_value(info->reset_gpio, 0);
+ gpio_set_value(info->bt_wakeup_gpio, 0);
+ kfree_skb(info->rx_skb);
+ info->rx_skb = NULL;
+}
+
+static int h4p_setup(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+ int err;
+ unsigned long flags;
+
+ /* TI1271 has HW bug and boot up might fail. Nokia retried up to 3x. */
+
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ h4p_set_clk(info, &info->rx_clocks_en, 1);
+
+ if (!hw_inited) {
+ h4p_set_auto_ctsrts(info, 1, UART_EFR_CTS | UART_EFR_RTS);
+ info->autorts = 1;
+
+ info->initing = 1;
+ printk("hci_setup\n");
+
+ err = h4p_send_negotiation(info);
+ if (err < 0)
+ goto err_clean;
+ }
+
+ /*
+ * Disable smart-idle as UART TX interrupts
+ * are not wake-up capable
+ */
+ h4p_smart_idle(info, 0);
+
+ err = h4p_read_fw(info);
+ if (err < 0) {
+ dev_err(info->dev, "Cannot read firmware\n");
+ goto err_clean;
+ }
+
+
+ h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
+ h4p_set_rts(info, 0);
+ h4p_change_speed(info, BC4_MAX_BAUD_RATE);
+ h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
+
+ info->pm_enabled = 1;
+
+ err = h4p_bt_wakeup_test(info);
+ if (err < 0) {
+ dev_err(info->dev, "BT wakeup test failed.\n");
+ goto err_clean;
+ }
+
+ spin_lock_irqsave(&info->lock, flags);
+ info->rx_enabled = gpio_get_value(info->host_wakeup_gpio);
+ h4p_set_clk(info, &info->rx_clocks_en, info->rx_enabled);
+ spin_unlock_irqrestore(&info->lock, flags);
+
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+
+ info->initing = 0;
+ hw_inited = 1;
+ return 0;
+
+err_clean:
+ printk("hci_setup: something failed, should do the clean up\n");
+ h4p_hci_flush(hdev);
+ h4p_deinit(hdev);
+ return err;
+}
+
+static int h4p_hci_setup(struct hci_dev *hdev)
+{
+ return h4p_setup(hdev);
+}
+
+
+static int h4p_boot(struct hci_dev *hdev)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+ int err;
+
+ info->rx_enabled = 1;
+ info->rx_state = WAIT_FOR_PKT_TYPE;
+ info->rx_count = 0;
+ info->garbage_bytes = 0;
+ info->rx_skb = NULL;
+ info->pm_enabled = 0;
+ init_completion(&info->fw_completion);
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+ h4p_set_clk(info, &info->rx_clocks_en, 1);
+
+ err = h4p_reset(info);
+ return err;
+}
+
+static int h4p_hci_open(struct hci_dev *hdev)
+{
+ set_bit(HCI_RUNNING, &hdev->flags);
+ return 0;
+}
+
+static int h4p_hci_close(struct hci_dev *hdev)
+{
+ clear_bit(HCI_RUNNING, &hdev->flags);
+ return 0;
+}
+
+static int h4p_hci_send_frame(struct hci_dev *hdev, struct sk_buff *skb)
+{
+ struct h4p_info *info = hci_get_drvdata(hdev);
+ int err = 0;
+
+ BT_DBG("hci_send_frame: dev %p, skb %p\n", hdev, skb);
+
+ if (!test_bit(HCI_RUNNING, &hdev->flags)) {
+ dev_warn(info->dev, "Frame for non-running device\n");
+ return -EIO;
+ }
+
+ switch (bt_cb(skb)->pkt_type) {
+ case HCI_COMMAND_PKT:
+ hdev->stat.cmd_tx++;
+ break;
+ case HCI_ACLDATA_PKT:
+ hdev->stat.acl_tx++;
+ break;
+ case HCI_SCODATA_PKT:
+ hdev->stat.sco_tx++;
+ break;
+ }
+
+ /* Push frame type to skb */
+ *skb_push(skb, 1) = (bt_cb(skb)->pkt_type);
+ /* We should always send word aligned data to h4+ devices */
+ if (skb->len % 2) {
+ err = skb_pad(skb, 1);
+ if (!err)
+ *skb_put(skb, 1) = 0x00;
+ }
+ if (err)
+ return err;
+
+ skb_queue_tail(&info->txq, skb);
+ if (!info->initing)
+ h4p_enable_tx(info);
+ else
+ h4p_enable_tx_nopm(info);
+
+ return 0;
+}
+
+static int h4p_probe_dt(struct platform_device *pdev, struct h4p_info *info)
+{
+ struct device_node *node;
+ struct device_node *uart = pdev->dev.of_node;
+ u32 val;
+ struct resource *mem;
+
+ node = of_get_child_by_name(uart, "device");
+
+ if (!node)
+ return -ENODATA;
+
+ info->chip_type = 3; /* Bcm2048 */
+
+ if (of_property_read_u32(node, "bt-sysclk", &val)) return -EINVAL;
+ info->bt_sysclk = val;
+
+ info->reset_gpio = of_get_named_gpio(node, "reset-gpios", 0);
+ info->host_wakeup_gpio = of_get_named_gpio(node, "host-wakeup-gpios", 0);
+ info->bt_wakeup_gpio = of_get_named_gpio(node, "bluetooth-wakeup-gpios", 0);
+
+ if (!uart) {
+ dev_err(&pdev->dev, "UART link not provided\n");
+ return -EINVAL;
+ }
+
+ info->irq = irq_of_parse_and_map(uart, 0);
+
+ mem = platform_get_resource(pdev, IORESOURCE_MEM, 0);
+ info->uart_base = devm_ioremap_resource(&pdev->dev, mem);
+
+ info->uart_iclk = of_clk_get_by_name(uart, "ick");
+ info->uart_fclk = of_clk_get_by_name(uart, "fck");
+
+ printk("DT: have neccessary data\n");
+ return 0;
+}
+
+
+static int h4p_probe(struct platform_device *pdev)
+{
+ struct hci_dev *hdev;
+ struct h4p_info *info;
+ int err;
+
+ dev_info(&pdev->dev, "Registering HCI H4P device\n");
+ info = devm_kzalloc(&pdev->dev, sizeof(struct h4p_info),
+ GFP_KERNEL);
+ if (!info)
+ return -ENOMEM;
+
+ info->dev = &pdev->dev;
+ info->tx_enabled = 1;
+ info->rx_enabled = 1;
+ spin_lock_init(&info->lock);
+ spin_lock_init(&info->clocks_lock);
+ skb_queue_head_init(&info->txq);
+
+ err = h4p_probe_dt(pdev, info);
+ if (err) {
+ dev_err(&pdev->dev, "Could not get Bluetooth config data\n");
+ return -ENODATA;
+ }
+
+ BT_DBG("base/irq gpio: %p/%d",
+ info->uart_base, info->irq);
+ BT_DBG("RESET/BTWU/HOSTWU gpio: %d/%d/%d",
+ info->reset_gpio, info->bt_wakeup_gpio, info->host_wakeup_gpio);
+ BT_DBG("chip type, sysclk: %d/%d", info->chip_type, info->bt_sysclk);
+ BT_DBG("clock i/f: %p/%p", info->uart_iclk, info->uart_fclk);
+
+ init_completion(&info->test_completion);
+ complete_all(&info->test_completion);
+
+ err = devm_gpio_request_one(&pdev->dev, info->reset_gpio,
+ GPIOF_OUT_INIT_LOW, "bt_reset");
+ if (err < 0) {
+ dev_err(&pdev->dev, "Cannot get GPIO line %d\n",
+ info->reset_gpio);
+ return err;
+ }
+
+ err = devm_gpio_request_one(&pdev->dev, info->bt_wakeup_gpio,
+ GPIOF_OUT_INIT_LOW, "bt_wakeup");
+ if (err < 0) {
+ dev_err(info->dev, "Cannot get GPIO line 0x%d",
+ info->bt_wakeup_gpio);
+ return err;
+ }
+
+ err = devm_gpio_request_one(&pdev->dev, info->host_wakeup_gpio,
+ GPIOF_DIR_IN, "host_wakeup");
+ if (err < 0) {
+ dev_err(info->dev, "Cannot get GPIO line %d",
+ info->host_wakeup_gpio);
+ return err;
+ }
+
+ err = devm_request_irq(&pdev->dev, info->irq, h4p_interrupt,
+ IRQF_DISABLED, "nokia_h4p", info);
+ if (err < 0) {
+ dev_err(info->dev, "nokia_h4p: unable to get IRQ %d\n",
+ info->irq);
+ return err;
+ }
+
+ err = devm_request_irq(&pdev->dev, gpio_to_irq(info->host_wakeup_gpio),
+ h4p_wakeup_interrupt, IRQF_TRIGGER_FALLING |
+ IRQF_TRIGGER_RISING | IRQF_DISABLED,
+ "h4p_wkup", info);
+ if (err < 0) {
+ dev_err(info->dev, "nokia_h4p: unable to get wakeup IRQ %d\n",
+ gpio_to_irq(info->host_wakeup_gpio));
+ return err;
+ }
+
+ err = irq_set_irq_wake(gpio_to_irq(info->host_wakeup_gpio), 1);
+ if (err < 0) {
+ dev_err(info->dev, "nokia_h4p: unable to set wakeup for IRQ %d\n",
+ gpio_to_irq(info->host_wakeup_gpio));
+ return err;
+ }
+
+ init_timer_deferrable(&info->lazy_release);
+ info->lazy_release.function = h4p_lazy_clock_release;
+ info->lazy_release.data = (unsigned long)info;
+ h4p_set_clk(info, &info->tx_clocks_en, 1);
+
+ err = h4p_reset_uart(info);
+ if (err < 0)
+ return err;
+
+ gpio_set_value(info->reset_gpio, 0);
+ h4p_set_clk(info, &info->tx_clocks_en, 0);
+
+ platform_set_drvdata(pdev, info);
+
+ /* Initialize and register HCI device */
+
+ hdev = hci_alloc_dev();
+ if (!hdev) {
+ dev_err(info->dev, "Can't allocate memory for device\n");
+ return -ENOMEM;
+ }
+ info->hdev = hdev;
+
+ hdev->bus = HCI_UART;
+ hci_set_drvdata(hdev, info);
+
+ hdev->open = h4p_hci_open;
+ hdev->setup = h4p_hci_setup;
+ hdev->close = h4p_hci_close;
+ hdev->flush = h4p_hci_flush;
+ hdev->send = h4p_hci_send_frame;
+ hdev->set_bdaddr = h4p_hci_set_bdaddr;
+
+#ifndef TEST
+ set_bit(HCI_QUIRK_INVALID_BDADDR, &hdev->quirks);
+#endif
+ SET_HCIDEV_DEV(hdev, info->dev);
+
+ if (hci_register_dev(hdev) >= 0)
+ return h4p_boot(hdev);
+
+ dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
+ hci_free_dev(info->hdev);
+ return -ENODEV;
+}
+
+static int h4p_remove(struct platform_device *pdev)
+{
+ struct h4p_info *info = platform_get_drvdata(pdev);
+
+ h4p_hci_close(info->hdev);
+ h4p_deinit(info->hdev);
+ hci_unregister_dev(info->hdev);
+ hci_free_dev(info->hdev);
+
+ return 0;
+}
+
+static const struct of_device_id h4p_of_match[] = {
+ { .compatible = "brcm,uart,bcm2048" },
+ {},
+};
+MODULE_DEVICE_TABLE(of, h4p_of_match);
+
+static struct platform_driver h4p_driver = {
+ .probe = h4p_probe,
+ .remove = h4p_remove,
+ .driver = {
+ .name = "disabled" "nokia_h4p",
+ .owner = THIS_MODULE,
+ .of_match_table = of_match_ptr(h4p_of_match),
+ },
+};
+
+module_platform_driver(h4p_driver);
+
+MODULE_ALIAS("platform:nokia_h4p");
+MODULE_DESCRIPTION("Bluetooth h4 driver with nokia extensions");
+MODULE_LICENSE("GPL");
+MODULE_AUTHOR("Ville Tervo");
diff --git a/drivers/bluetooth/nokia_fw.c b/drivers/bluetooth/nokia_fw.c
new file mode 100644
index 0000000..80e4385
--- /dev/null
+++ b/drivers/bluetooth/nokia_fw.c
@@ -0,0 +1,101 @@
+/*
+ * This file is part of nokia_h4p bluetooth driver
+ *
+ * Copyright (C) 2005-2008 Nokia Corporation.
+ * Copyright (C) 2014 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ */
+
+#define DEBUG
+#include <linux/module.h>
+#include <linux/skbuff.h>
+#include <linux/firmware.h>
+#include <linux/clk.h>
+
+#include <net/bluetooth/bluetooth.h>
+
+#include "nokia_h4p.h"
+
+#define FW_NAME_BCM2048 "nokia/bcmfw.bin"
+
+/* Read fw. Return length of the command. If no more commands in
+ * fw 0 is returned. In error case return value is negative.
+ */
+int h4p_read_fw(struct h4p_info *info)
+{
+ int num = 0;
+ int fw_pos = 0;
+ struct sk_buff *skb;
+ const struct firmware *fw_entry = NULL;
+ int err = -ENOENT;
+ unsigned int cmd_len = 0;
+
+ err = request_firmware(&fw_entry, FW_NAME_BCM2048, info->dev);
+ if (err != 0)
+ return err;
+
+ while (1) {
+ int cmd, len;
+
+ fw_pos += cmd_len;
+
+ if (fw_pos >= fw_entry->size)
+ break;
+
+ if (fw_pos + 2 > fw_entry->size) {
+ dev_err(info->dev, "Corrupted firmware image 1\n");
+ err = -EMSGSIZE;
+ break;
+ }
+
+ cmd_len = fw_entry->data[fw_pos++];
+ cmd_len += fw_entry->data[fw_pos++] << 8;
+ if (cmd_len == 0)
+ break;
+
+ if (fw_pos + cmd_len > fw_entry->size) {
+ dev_err(info->dev, "Corrupted firmware image 2\n");
+ err = -EMSGSIZE;
+ break;
+ }
+
+ /* Skip first two packets */
+ if (++num <= 2)
+ continue;
+
+ /* Note that this is timing-critical. If sending packets takes too
+ long, initialization will fail. */
+ printk("Packet %d...", num);
+
+ cmd = fw_entry->data[fw_pos+1];
+ cmd += fw_entry->data[fw_pos+2] << 8;
+ len = fw_entry->data[fw_pos+3];
+ printk("cmd %x, len %d.", cmd, len);
+
+ skb = __hci_cmd_sync(info->hdev, cmd, len, fw_entry->data+fw_pos+4, 500);
+ if (IS_ERR(skb)) {
+ dev_err(info->dev, "...sending cmd failed %ld\n", PTR_ERR(skb));
+ err = -EIO;
+ break;
+ }
+ }
+
+ release_firmware(fw_entry);
+ return err;
+}
+
+MODULE_FIRMWARE(FW_NAME_BCM2048);
diff --git a/drivers/bluetooth/nokia_h4p.h b/drivers/bluetooth/nokia_h4p.h
new file mode 100644
index 0000000..312c61c
--- /dev/null
+++ b/drivers/bluetooth/nokia_h4p.h
@@ -0,0 +1,228 @@
+/*
+ * This file is part of Nokia H4P bluetooth driver
+ *
+ * Copyright (C) 2005-2008 Nokia Corporation.
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ */
+
+#include <net/bluetooth/bluetooth.h>
+#include <net/bluetooth/hci_core.h>
+#include <net/bluetooth/hci.h>
+
+#include <linux/serial_reg.h>
+
+#define UART_SYSC_OMAP_RESET 0x03
+#define UART_SYSS_RESETDONE 0x01
+#define UART_OMAP_SCR_EMPTY_THR 0x08
+#define UART_OMAP_SCR_WAKEUP 0x10
+#define UART_OMAP_SSR_WAKEUP 0x02
+#define UART_OMAP_SSR_TXFULL 0x01
+
+#define UART_OMAP_SYSC_IDLEMODE 0x03
+#define UART_OMAP_SYSC_IDLEMASK (3 << UART_OMAP_SYSC_IDLEMODE)
+
+#define UART_OMAP_SYSC_FORCE_IDLE (0 << UART_OMAP_SYSC_IDLEMODE)
+#define UART_OMAP_SYSC_NO_IDLE (1 << UART_OMAP_SYSC_IDLEMODE)
+#define UART_OMAP_SYSC_SMART_IDLE (2 << UART_OMAP_SYSC_IDLEMODE)
+
+#define H4P_TRANSFER_MODE 1
+#define H4P_SCHED_TRANSFER_MODE 2
+#define H4P_ACTIVE_MODE 3
+
+struct h4p_info {
+ struct timer_list lazy_release;
+ struct hci_dev *hdev;
+ spinlock_t lock;
+
+ void __iomem *uart_base;
+ unsigned long uart_phys_base;
+ int irq;
+ struct device *dev;
+ u8 chip_type;
+ u8 bt_wakeup_gpio;
+ u8 host_wakeup_gpio;
+ u8 reset_gpio;
+ u8 reset_gpio_shared;
+ u8 bt_sysclk;
+ u8 man_id;
+ u8 ver_id;
+
+ struct sk_buff_head fw_queue;
+ struct sk_buff *alive_cmd_skb;
+ struct completion init_completion;
+ struct completion fw_completion;
+ struct completion test_completion;
+ int fw_error;
+ int init_error;
+
+ struct sk_buff_head txq;
+
+ struct sk_buff *rx_skb;
+ long rx_count;
+ unsigned long rx_state;
+ unsigned long garbage_bytes;
+
+ struct sk_buff_head *fw_q;
+
+ int pm_enabled;
+ int tx_enabled;
+ int autorts;
+ int rx_enabled;
+ unsigned long pm_flags;
+
+ int tx_clocks_en;
+ int rx_clocks_en;
+ spinlock_t clocks_lock;
+ struct clk *uart_iclk;
+ struct clk *uart_fclk;
+ atomic_t clk_users;
+ u16 dll;
+ u16 dlh;
+ u16 ier;
+ u16 mdr1;
+ u16 efr;
+
+ int initing;
+};
+
+struct h4p_radio_hdr {
+ u8 evt;
+ u8 dlen;
+} __packed;
+
+struct h4p_neg_hdr {
+ u8 dlen;
+} __packed;
+#define H4P_NEG_HDR_SIZE 1
+
+#define H4P_NEG_REQ 0x00
+#define H4P_NEG_ACK 0x20
+#define H4P_NEG_NAK 0x40
+
+#define H4P_PROTO_PKT 0x44
+#define H4P_PROTO_BYTE 0x4c
+
+#define H4P_ID_CSR 0x02
+#define H4P_ID_BCM2048 0x04
+#define H4P_ID_TI1271 0x31
+
+struct h4p_neg_cmd {
+ u8 ack;
+ u16 baud;
+ u16 unused1;
+ u8 proto;
+ u16 sys_clk;
+ u16 unused2;
+} __packed;
+
+struct h4p_neg_evt {
+ u8 ack;
+ u16 baud;
+ u16 unused1;
+ u8 proto;
+ u16 sys_clk;
+ u16 unused2;
+ u8 man_id;
+ u8 ver_id;
+} __packed;
+
+#define H4P_ALIVE_REQ 0x55
+#define H4P_ALIVE_RESP 0xcc
+
+struct h4p_alive_hdr {
+ u8 dlen;
+} __packed;
+#define H4P_ALIVE_HDR_SIZE 1
+
+struct h4p_alive_pkt {
+ u8 mid;
+ u8 unused;
+} __packed;
+
+#define MAX_BAUD_RATE 921600
+#define BC4_MAX_BAUD_RATE 3692300
+#define UART_CLOCK 48000000
+#define BT_INIT_DIVIDER 320
+#define BT_BAUDRATE_DIVIDER 384000000
+#define BT_SYSCLK_DIV 1000
+#define INIT_SPEED 120000
+
+#define H4_TYPE_SIZE 1
+#define H4_RADIO_HDR_SIZE 2
+
+/* H4+ packet types */
+#define H4_CMD_PKT 0x01
+#define H4_ACL_PKT 0x02
+#define H4_SCO_PKT 0x03
+#define H4_EVT_PKT 0x04
+#define H4_NEG_PKT 0x06
+#define H4_ALIVE_PKT 0x07
+#define H4_RADIO_PKT 0x08
+
+/* TX states */
+#define WAIT_FOR_PKT_TYPE 1
+#define WAIT_FOR_HEADER 2
+#define WAIT_FOR_DATA 3
+
+struct hci_fw_event {
+ struct hci_event_hdr hev;
+ struct hci_ev_cmd_complete cmd;
+ u8 status;
+} __packed;
+
+void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb);
+
+int h4p_send_alive_packet(struct h4p_info *info);
+
+int h4p_read_fw(struct h4p_info *info);
+int h4p_send_fw(struct h4p_info *info);
+void h4p_parse_fw_event(struct h4p_info *info, struct sk_buff *skb);
+
+static inline void h4p_outb(struct h4p_info *info, unsigned int offset, u8 val)
+{
+ __raw_writeb(val, info->uart_base + (offset << 2));
+}
+
+static inline u8 h4p_inb(struct h4p_info *info, unsigned int offset)
+{
+ u8 val;
+ val = __raw_readb(info->uart_base + (offset << 2));
+ return val;
+}
+
+static inline void h4p_set_rts(struct h4p_info *info, int active)
+{
+ u8 b;
+
+ b = h4p_inb(info, UART_MCR);
+ if (active)
+ b |= UART_MCR_RTS;
+ else
+ b &= ~UART_MCR_RTS;
+ h4p_outb(info, UART_MCR, b);
+}
+
+int h4p_wait_for_cts(struct h4p_info *info, int active, int timeout_ms);
+void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
+void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
+void h4p_change_speed(struct h4p_info *info, unsigned long speed);
+int h4p_reset_uart(struct h4p_info *info);
+void h4p_init_uart(struct h4p_info *info);
+void h4p_enable_tx(struct h4p_info *info);
+void h4p_store_regs(struct h4p_info *info);
+void h4p_restore_regs(struct h4p_info *info);
+void h4p_smart_idle(struct h4p_info *info, bool enable);
diff --git a/drivers/bluetooth/nokia_uart.c b/drivers/bluetooth/nokia_uart.c
new file mode 100644
index 0000000..d95683a
--- /dev/null
+++ b/drivers/bluetooth/nokia_uart.c
@@ -0,0 +1,179 @@
+/*
+ * This file is part of Nokia H4P bluetooth driver
+ *
+ * Copyright (C) 2005, 2006 Nokia Corporation.
+ * Copyright (C) 2014 Pavel Machek <[email protected]>
+ *
+ * This program is free software; you can redistribute it and/or
+ * modify it under the terms of the GNU General Public License
+ * version 2 as published by the Free Software Foundation.
+ *
+ * This program is distributed in the hope that it will be useful, but
+ * WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ * General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program; if not, write to the Free Software
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
+ * 02110-1301 USA
+ *
+ */
+
+#include <linux/delay.h>
+#include <linux/clk.h>
+
+#include <linux/io.h>
+
+#include "nokia_h4p.h"
+
+
+
+int h4p_wait_for_cts(struct h4p_info *info, int active,
+ int timeout_ms)
+{
+ unsigned long timeout;
+ int state;
+
+ timeout = jiffies + msecs_to_jiffies(timeout_ms);
+ for (;;) {
+ state = h4p_inb(info, UART_MSR) & UART_MSR_CTS;
+ if (active) {
+ if (state)
+ return 0;
+ } else {
+ if (!state)
+ return 0;
+ }
+ if (time_after(jiffies, timeout))
+ return -ETIMEDOUT;
+ msleep(1);
+ }
+}
+
+void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)
+{
+ u8 lcr, b;
+
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, 0xbf);
+ b = h4p_inb(info, UART_EFR);
+ if (on)
+ b |= which;
+ else
+ b &= ~which;
+ h4p_outb(info, UART_EFR, b);
+ h4p_outb(info, UART_LCR, lcr);
+}
+
+void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)
+{
+ unsigned long flags;
+
+ spin_lock_irqsave(&info->lock, flags);
+ __h4p_set_auto_ctsrts(info, on, which);
+ spin_unlock_irqrestore(&info->lock, flags);
+}
+
+void h4p_change_speed(struct h4p_info *info, unsigned long speed)
+{
+ unsigned int divisor;
+ u8 lcr, mdr1;
+
+ BT_DBG("Setting speed %lu", speed);
+
+ if (speed >= 460800) {
+ divisor = UART_CLOCK / 13 / speed;
+ mdr1 = 3;
+ } else {
+ divisor = UART_CLOCK / 16 / speed;
+ mdr1 = 0;
+ }
+
+ /* Make sure UART mode is disabled */
+ h4p_outb(info, UART_OMAP_MDR1, 7);
+
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, UART_LCR_DLAB); /* Set DLAB */
+ h4p_outb(info, UART_DLL, divisor & 0xff); /* Set speed */
+ h4p_outb(info, UART_DLM, divisor >> 8);
+ h4p_outb(info, UART_LCR, lcr);
+
+ /* Make sure UART mode is enabled */
+ h4p_outb(info, UART_OMAP_MDR1, mdr1);
+}
+
+int h4p_reset_uart(struct h4p_info *info)
+{
+ int count = 0;
+
+ /* Reset the UART */
+ h4p_outb(info, UART_OMAP_SYSC, UART_SYSC_OMAP_RESET);
+ while (!(h4p_inb(info, UART_OMAP_SYSS) & UART_SYSS_RESETDONE)) {
+ if (count++ > 100) {
+ dev_err(info->dev, "nokia_h4p: UART reset timeout\n");
+ return -ENODEV;
+ }
+ udelay(1);
+ }
+
+ return 0;
+}
+
+void h4p_store_regs(struct h4p_info *info)
+{
+ u16 lcr = 0;
+
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, 0xBF);
+ info->dll = h4p_inb(info, UART_DLL);
+ info->dlh = h4p_inb(info, UART_DLM);
+ info->efr = h4p_inb(info, UART_EFR);
+ h4p_outb(info, UART_LCR, lcr);
+ info->mdr1 = h4p_inb(info, UART_OMAP_MDR1);
+ info->ier = h4p_inb(info, UART_IER);
+}
+
+void h4p_restore_regs(struct h4p_info *info)
+{
+ u16 lcr = 0;
+
+ h4p_init_uart(info);
+
+ h4p_outb(info, UART_OMAP_MDR1, 7);
+ lcr = h4p_inb(info, UART_LCR);
+ h4p_outb(info, UART_LCR, 0xBF);
+ h4p_outb(info, UART_DLL, info->dll); /* Set speed */
+ h4p_outb(info, UART_DLM, info->dlh);
+ h4p_outb(info, UART_EFR, info->efr);
+ h4p_outb(info, UART_LCR, lcr);
+ h4p_outb(info, UART_OMAP_MDR1, info->mdr1);
+ h4p_outb(info, UART_IER, info->ier);
+}
+
+void h4p_init_uart(struct h4p_info *info)
+{
+ u8 mcr, efr;
+
+ /* Enable and setup FIFO */
+ h4p_outb(info, UART_OMAP_MDR1, 0x00);
+
+ h4p_outb(info, UART_LCR, 0xbf);
+ efr = h4p_inb(info, UART_EFR);
+ h4p_outb(info, UART_EFR, UART_EFR_ECB);
+ h4p_outb(info, UART_LCR, UART_LCR_DLAB);
+ mcr = h4p_inb(info, UART_MCR);
+ h4p_outb(info, UART_MCR, UART_MCR_TCRTLR);
+ h4p_outb(info, UART_FCR, UART_FCR_ENABLE_FIFO |
+ UART_FCR_CLEAR_RCVR | UART_FCR_CLEAR_XMIT |
+ (3 << 6) | (0 << 4));
+ h4p_outb(info, UART_LCR, 0xbf);
+ h4p_outb(info, UART_TI752_TLR, 0xed);
+ h4p_outb(info, UART_TI752_TCR, 0xef);
+ h4p_outb(info, UART_EFR, efr);
+ h4p_outb(info, UART_LCR, UART_LCR_DLAB);
+ h4p_outb(info, UART_MCR, 0x00);
+ h4p_outb(info, UART_LCR, UART_LCR_WLEN8);
+ h4p_outb(info, UART_IER, UART_IER_RDI);
+ h4p_outb(info, UART_OMAP_SYSC, (1 << 0) | (1 << 2) | (2 << 3));
+}



--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-20 20:43:18

by Paul Bolle

[permalink] [raw]
Subject: Re: [PATCH] bluetooth: Add hci_h4p driver

Pavel,

On Sat, 2014-12-20 at 21:23 +0100, Pavel Machek wrote:
> --- a/drivers/bluetooth/Kconfig
> +++ b/drivers/bluetooth/Kconfig
> @@ -243,4 +243,13 @@ config BT_WILINK
> Say Y here to compile support for Texas Instrument's WiLink7 driver
> into the kernel or say M to compile it as module (btwilink).
>
> +config BT_NOKIA_H4P
> + tristate "HCI driver with H4 Nokia extensions"
> + help
> + Bluetooth HCI driver with H4 extensions. This driver provides
> + support for H4+ Bluetooth chip with vendor-specific H4 extensions.
> +
> + Say Y here to compile support for h4 extended devices into the kernel
> + or say M to compile it as module (btnokia_h4p).

Will this module be called btnokia_h4p or ...

> +
> endmenu
> diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
> index 9fe8a87..624ef3fc 100644
> --- a/drivers/bluetooth/Makefile
> +++ b/drivers/bluetooth/Makefile
> @@ -31,4 +31,7 @@ hci_uart-$(CONFIG_BT_HCIUART_ATH3K) += hci_ath.o
> hci_uart-$(CONFIG_BT_HCIUART_3WIRE) += hci_h5.o
> hci_uart-objs := $(hci_uart-y)
>
> +obj-$(CONFIG_BT_NOKIA_H4P) += nokia_h4p.o

... nokia_h4p?

> +nokia_h4p-objs := nokia_core.o nokia_fw.o nokia_uart.o
> +
> ccflags-y += -D__CHECK_ENDIAN__

Or did I miss some make magic here?

Thanks,


Paul Bolle

2014-12-20 23:35:59

by Marcel Holtmann

[permalink] [raw]
Subject: Re: [PATCH] bluetooth: Add hci_h4p driver

Hi Pavel,

> Add hci_h4p bluetooth driver. This device is used for example on Nokia N900 cell phone.

the driver is called nokia_h4p. And you could be a little bit more verbose here explaining where the driver came from.

>
> Signed-off-by: Pavel Machek <[email protected]>
> Thanks-to: Sebastian Reichel <[email protected]>
> Thanks-to: Joe Perches <[email protected]>
>
> ---
>
> Please apply,

If you refuse to use git check-patch, then manually include a diffstat.

>
> Pavel
>
> diff --git a/drivers/bluetooth/Kconfig b/drivers/bluetooth/Kconfig
> index 4547dc2..268b1a6 100644
> --- a/drivers/bluetooth/Kconfig
> +++ b/drivers/bluetooth/Kconfig
> @@ -243,4 +243,13 @@ config BT_WILINK
> Say Y here to compile support for Texas Instrument's WiLink7 driver
> into the kernel or say M to compile it as module (btwilink).
>
> +config BT_NOKIA_H4P
> + tristate "HCI driver with H4 Nokia extensions"

Lets call this "Nokia H4+ Extensions (H4P) driver"

I prefer if the driver list looks at least a bit clean. So that vendor drivers that with the vendor name in their description.

> + help
> + Bluetooth HCI driver with H4 extensions. This driver provides
> + support for H4+ Bluetooth chip with vendor-specific H4 extensions.

Mention here that the current version supports the Broadcom based version found in the Nokia N900.

> +
> + Say Y here to compile support for h4 extended devices into the kernel
> + or say M to compile it as module (btnokia_h4p).

Module name is nokia_h4p

> +
> endmenu
> diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
> index 9fe8a87..624ef3fc 100644
> --- a/drivers/bluetooth/Makefile
> +++ b/drivers/bluetooth/Makefile
> @@ -31,4 +31,7 @@ hci_uart-$(CONFIG_BT_HCIUART_ATH3K) += hci_ath.o
> hci_uart-$(CONFIG_BT_HCIUART_3WIRE) += hci_h5.o
> hci_uart-objs := $(hci_uart-y)
>
> +obj-$(CONFIG_BT_NOKIA_H4P) += nokia_h4p.o

We use tabs and not spaces here.

Also add an extra empty line between the driver field and the list of objects.

> +nokia_h4p-objs := nokia_core.o nokia_fw.o nokia_uart.o
> +

And unless something changed in kbuild, this is nokia_h4p-y :=. Similar to all the other multi file drivers we have.

> ccflags-y += -D__CHECK_ENDIAN__
> diff --git a/drivers/bluetooth/nokia_core.c b/drivers/bluetooth/nokia_core.c
> new file mode 100644
> index 0000000..163531e
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_core.c
> @@ -0,0 +1,1188 @@
> +/*
> + * This file is part of Nokia H4P bluetooth driver
> + *
> + * Copyright (C) 2005-2008 Nokia Corporation.
> + * Copyright (C) 2014 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + * Thanks to all the Nokia people that helped with this driver,
> + * including Ville Tervo and Roger Quadros.
> + *
> + * Power saving functionality was removed from this driver to make
> + * merging easier.
> + */
> +
> +#include <linux/module.h>
> +#include <linux/kernel.h>
> +#include <linux/init.h>
> +#include <linux/errno.h>
> +#include <linux/delay.h>
> +#include <linux/spinlock.h>
> +#include <linux/serial_reg.h>
> +#include <linux/skbuff.h>
> +#include <linux/device.h>
> +#include <linux/platform_device.h>
> +#include <linux/clk.h>
> +#include <linux/interrupt.h>
> +#include <linux/gpio.h>
> +#include <linux/of_gpio.h>
> +#include <linux/of_irq.h>
> +#include <linux/timer.h>
> +#include <linux/kthread.h>
> +#include <linux/io.h>
> +#include <linux/completion.h>
> +#include <linux/sizes.h>
> +
> +#include <net/bluetooth/bluetooth.h>
> +#include <net/bluetooth/hci_core.h>
> +#include <net/bluetooth/hci.h>
> +
> +#include "nokia_h4p.h"
> +
> +#undef TEST

What is the TEST undef doing here?

> +
> +static int hw_inited = 0;
> +
> +/* This should be used in function that cannot release clocks */
> +static void h4p_set_clk(struct h4p_info *info, int *clock, int enable)

Lets start using bool enable here.

> +{
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->clocks_lock, flags);
> + if (enable && !*clock) {
> + BT_DBG("Enabling %p", clock);
> + clk_prepare_enable(info->uart_fclk);
> + clk_prepare_enable(info->uart_iclk);
> + if (atomic_read(&info->clk_users) == 0)
> + h4p_restore_regs(info);
> + atomic_inc(&info->clk_users);
> + }
> +
> + if (!enable && *clock) {
> + BT_DBG("Disabling %p", clock);
> + if (atomic_dec_and_test(&info->clk_users))
> + h4p_store_regs(info);
> + clk_disable_unprepare(info->uart_fclk);
> + clk_disable_unprepare(info->uart_iclk);
> + }
> +
> + *clock = enable;
> + spin_unlock_irqrestore(&info->clocks_lock, flags);
> +}
> +
> +static void h4p_lazy_clock_release(unsigned long data)
> +{

What is the reason this is unsigned long and not just struct h4p_info?

> + struct h4p_info *info = (struct h4p_info *)data;
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->lock, flags);
> + if (!info->tx_enabled)
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +/* Power management functions */
> +void h4p_smart_idle(struct h4p_info *info, bool enable)
> +{
> + u8 v;
> +
> + v = h4p_inb(info, UART_OMAP_SYSC);
> + v &= ~(UART_OMAP_SYSC_IDLEMASK);
> +
> + if (enable)
> + v |= UART_OMAP_SYSC_SMART_IDLE;
> + else
> + v |= UART_OMAP_SYSC_NO_IDLE;
> +
> + h4p_outb(info, UART_OMAP_SYSC, v);
> +}
> +
> +static inline void h4p_schedule_pm(struct h4p_info *info)
> +{
> +}
> +
> +static void h4p_disable_tx(struct h4p_info *info)
> +{
> + if (!info->pm_enabled)
> + return;
> +
> + /* Re-enable smart-idle */
> + h4p_smart_idle(info, 1);
> +
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + mod_timer(&info->lazy_release, jiffies + msecs_to_jiffies(100));

How many lazy_release functions do you have? Why is this a callback anyway. If not needed, then please simplify this.

> + info->tx_enabled = 0;

If used as bool, then I prefer bool and start using false here.

> +}
> +
> +void h4p_enable_tx_nopm(struct h4p_info *info)
> +{
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->lock, flags);
> + h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
> + UART_IER_THRI);

You need to align this with h4p_inb so that you can tell where it belongs to.

Or just read it into a value and then store the ORed value.

> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +void h4p_enable_tx(struct h4p_info *info)
> +{
> + unsigned long flags;
> +
> + if (!info->pm_enabled)
> + return;
> +
> + h4p_schedule_pm(info);
> +
> + spin_lock_irqsave(&info->lock, flags);
> + del_timer(&info->lazy_release);
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + info->tx_enabled = 1;

bool?

> + gpio_set_value(info->bt_wakeup_gpio, 1);
> + h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
> + UART_IER_THRI);

Same as above. This needs proper alignment. Or just two calls.

> + /*
> + * Disable smart-idle as UART TX interrupts
> + * are not wake-up capable
> + */

Comment style follows the net comment style.

/* foo
* bar
*/

> + h4p_smart_idle(info, 0);
> +
> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +static void h4p_disable_rx(struct h4p_info *info)
> +{
> + if (!info->pm_enabled)
> + return;
> +
> + info->rx_enabled = 0;

bool?

> +
> + if (h4p_inb(info, UART_LSR) & UART_LSR_DR)
> + return;
> +
> + if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
> + return;
> +
> + __h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
> + info->autorts = 0;
> + h4p_set_clk(info, &info->rx_clocks_en, 0);
> +}
> +
> +static void h4p_enable_rx(struct h4p_info *info)
> +{
> + if (!info->pm_enabled)
> + return;
> +
> + h4p_schedule_pm(info);
> +
> + h4p_set_clk(info, &info->rx_clocks_en, 1);

true instead of 1?

> + info->rx_enabled = 1;

bool?

> +
> + if (!(h4p_inb(info, UART_LSR) & UART_LSR_TEMT))
> + return;
> +
> + __h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);

true instead of 1?

> + info->autorts = 1;

bool?

> +}
> +
> +void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb)
> +{
> + skb_queue_tail(&info->txq, skb);
> + h4p_enable_tx_nopm(info);
> +}
> +
> +/* Negotiation functions */
> +int h4p_send_alive_packet(struct h4p_info *info)
> +{
> + struct h4p_alive_hdr *hdr;
> + struct h4p_alive_pkt *pkt;
> + struct sk_buff *skb;
> + int len;
> +
> + BT_DBG("Sending alive packet");
> +
> + len = H4_TYPE_SIZE + sizeof(*hdr) + sizeof(*pkt);
> + skb = bt_skb_alloc(len, GFP_KERNEL);
> + if (!skb)
> + return -ENOMEM;
> +
> + memset(skb->data, 0x00, len);

What is this memset for? We really never do that in any of the other drivers.

> + *skb_put(skb, 1) = H4_ALIVE_PKT;
> + hdr = (struct h4p_alive_hdr *)skb_put(skb, sizeof(*hdr));
> + hdr->dlen = sizeof(*pkt);
> + pkt = (struct h4p_alive_pkt *)skb_put(skb, sizeof(*pkt));
> + pkt->mid = H4P_ALIVE_REQ;
> +
> + h4p_simple_send_frame(info, skb);
> +
> + BT_DBG("Alive packet sent");
> +
> + return 0;
> +}
> +
> +static void h4p_alive_packet(struct h4p_info *info,
> + struct sk_buff *skb)

Proper alignment according to the net coding style please.

> +{
> + struct h4p_alive_hdr *hdr;
> + struct h4p_alive_pkt *pkt;
> +
> + BT_DBG("Received alive packet");

Normally we have empty lines before and after the BT_DBUG in the function.

> + hdr = (struct h4p_alive_hdr *)skb->data;
> + if (hdr->dlen != sizeof(*pkt)) {
> + dev_err(info->dev, "Corrupted alive message\n");
> + info->init_error = -EIO;
> + goto finish_alive;
> + }
> +
> + pkt = (struct h4p_alive_pkt *)skb_pull(skb, sizeof(*hdr));
> + if (pkt->mid != H4P_ALIVE_RESP) {
> + dev_err(info->dev, "Could not negotiate nokia_h4p settings\n");
> + info->init_error = -EINVAL;
> + }
> +
> +finish_alive:
> + complete(&info->init_completion);
> + kfree_skb(skb);
> +}
> +
> +static int h4p_send_negotiation(struct h4p_info *info)
> +{
> + struct h4p_neg_cmd *neg_cmd;
> + struct h4p_neg_hdr *neg_hdr;
> + struct sk_buff *skb;
> + int err, len;
> + u16 sysclk = 38400;
> +
> + printk("Sending negotiation..");

Should be a BT_DBG.

> + len = sizeof(*neg_cmd) + sizeof(*neg_hdr) + H4_TYPE_SIZE;
> +
> + skb = bt_skb_alloc(len, GFP_KERNEL);
> + if (!skb)
> + return -ENOMEM;
> +
> + memset(skb->data, 0x00, len);
> + *skb_put(skb, 1) = H4_NEG_PKT;
> + neg_hdr = (struct h4p_neg_hdr *)skb_put(skb, sizeof(*neg_hdr));
> + neg_cmd = (struct h4p_neg_cmd *)skb_put(skb, sizeof(*neg_cmd));
> +
> + neg_hdr->dlen = sizeof(*neg_cmd);
> + neg_cmd->ack = H4P_NEG_REQ;
> + neg_cmd->baud = cpu_to_le16(BT_BAUDRATE_DIVIDER/MAX_BAUD_RATE);
> + neg_cmd->proto = H4P_PROTO_BYTE;
> + neg_cmd->sys_clk = cpu_to_le16(sysclk);
> +
> + h4p_change_speed(info, INIT_SPEED);
> +
> + h4p_set_rts(info, 1);
> + info->init_error = 0;
> + init_completion(&info->init_completion);
> +
> + h4p_simple_send_frame(info, skb);
> +
> + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> + msecs_to_jiffies(1000))) {
> + printk("h4p: negotiation did not return\n");

sounds like a BT_ERR to me.

> + return -ETIMEDOUT;
> + }
> +
> + if (info->init_error < 0)
> + return info->init_error;
> +
> + /* Change to operational settings */
> + h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
> + h4p_set_rts(info, 0);
> + h4p_change_speed(info, MAX_BAUD_RATE);
> +
> + err = h4p_wait_for_cts(info, 1, 100);
> + if (err < 0)
> + return err;
> +
> + h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
> + init_completion(&info->init_completion);
> + err = h4p_send_alive_packet(info);
> +

No extra empty line here.

> + if (err < 0)
> + return err;
> +
> + if (!wait_for_completion_interruptible_timeout(&info->init_completion,
> + msecs_to_jiffies(1000)))

The alignment of the indentation is wrong.

> + return -ETIMEDOUT;
> +
> + if (info->init_error < 0)
> + return info->init_error;
> +
> + printk("Negotiation successful\n");

BT_DBG.

> + return 0;
> +}
> +
> +static void h4p_negotiation_packet(struct h4p_info *info,
> + struct sk_buff *skb)

Indentation.

Please just get this right since I most likely miss a few in the review.

> +{
> + struct h4p_neg_hdr *hdr;
> + struct h4p_neg_evt *evt;
> +
> + hdr = (struct h4p_neg_hdr *)skb->data;
> + if (hdr->dlen != sizeof(*evt)) {
> + info->init_error = -EIO;
> + goto finish_neg;
> + }
> +
> + evt = (struct h4p_neg_evt *)skb_pull(skb, sizeof(*hdr));
> +
> + if (evt->ack != H4P_NEG_ACK) {
> + dev_err(info->dev, "Could not negotiate nokia_h4p settings\n");
> + info->init_error = -EINVAL;
> + }
> +
> + info->man_id = evt->man_id;
> + info->ver_id = evt->ver_id;
> + printk("Negotiation finished.\n");

BT_DBG.

> +
> +finish_neg:
> +

This extra empty line here is not needed.

> + complete(&info->init_completion);
> + kfree_skb(skb);
> +}
> +
> +/* H4 packet handling functions */
> +static int h4p_get_hdr_len(struct h4p_info *info, u8 pkt_type)
> +{
> + long retval;

I do not get why retval is long and function returns int.

> +
> + switch (pkt_type) {
> + case H4_EVT_PKT:
> + retval = HCI_EVENT_HDR_SIZE;
> + break;
> + case H4_ACL_PKT:
> + retval = HCI_ACL_HDR_SIZE;
> + break;
> + case H4_SCO_PKT:
> + retval = HCI_SCO_HDR_SIZE;
> + break;
> + case H4_NEG_PKT:
> + retval = H4P_NEG_HDR_SIZE;
> + break;
> + case H4_ALIVE_PKT:
> + retval = H4P_ALIVE_HDR_SIZE;
> + break;
> + case H4_RADIO_PKT:
> + retval = H4_RADIO_HDR_SIZE;
> + break;
> + default:
> + dev_err(info->dev, "Unknown H4 packet type 0x%.2x\n", pkt_type);
> + retval = -1;
> + break;
> + }
> +
> + return retval;
> +}
> +
> +static unsigned int h4p_get_data_len(struct h4p_info *info,
> + struct sk_buff *skb)

Indentation.

> +{
> + long retval = -1;

use a default label in the switch statement instead of assigning the variable.

And again, why long if the return value is unsigned int.

> + struct hci_acl_hdr *acl_hdr;
> + struct hci_sco_hdr *sco_hdr;
> + struct hci_event_hdr *evt_hdr;
> + struct h4p_neg_hdr *neg_hdr;
> + struct h4p_alive_hdr *alive_hdr;
> + struct h4p_radio_hdr *radio_hdr;
> +
> + switch (bt_cb(skb)->pkt_type) {
> + case H4_EVT_PKT:
> + evt_hdr = (struct hci_event_hdr *)skb->data;
> + retval = evt_hdr->plen;
> + break;
> + case H4_ACL_PKT:
> + acl_hdr = (struct hci_acl_hdr *)skb->data;
> + retval = le16_to_cpu(acl_hdr->dlen);
> + break;
> + case H4_SCO_PKT:
> + sco_hdr = (struct hci_sco_hdr *)skb->data;
> + retval = sco_hdr->dlen;
> + break;
> + case H4_RADIO_PKT:
> + radio_hdr = (struct h4p_radio_hdr *)skb->data;
> + retval = radio_hdr->dlen;
> + break;
> + case H4_NEG_PKT:
> + neg_hdr = (struct h4p_neg_hdr *)skb->data;
> + retval = neg_hdr->dlen;
> + break;
> + case H4_ALIVE_PKT:
> + alive_hdr = (struct h4p_alive_hdr *)skb->data;
> + retval = alive_hdr->dlen;
> + break;
> + }
> +
> + return retval;
> +}
> +
> +static inline void h4p_recv_frame(struct h4p_info *info,
> + struct sk_buff *skb)

Indentation.

> +{
> + if (info->initing) {

So "initing" is not even an English word. Can use something that makes actually some sense.

> + switch (bt_cb(skb)->pkt_type) {
> + case H4_NEG_PKT:
> + h4p_negotiation_packet(info, skb);
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + return;
> + case H4_ALIVE_PKT:
> + h4p_alive_packet(info, skb);
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + return;
> + }
> + }
> +
> + hci_recv_frame(info->hdev, skb);
> + BT_DBG("Frame sent to upper layer");
> +}
> +
> +static inline void h4p_handle_byte(struct h4p_info *info, u8 byte)
> +{
> + switch (info->rx_state) {
> + case WAIT_FOR_PKT_TYPE:
> + bt_cb(info->rx_skb)->pkt_type = byte;
> + info->rx_count = h4p_get_hdr_len(info, byte);

And I looked, info->rx_count is long. I do not get this variable classification. If this is used as state machine sync, then long is overkill. Bluetooth HCI packets will never be that long (pun intended)

> + if (info->rx_count < 0) {
> + info->hdev->stat.err_rx++;
> + kfree_skb(info->rx_skb);
> + info->rx_skb = NULL;
> + } else {
> + info->rx_state = WAIT_FOR_HEADER;
> + }
> + break;
> + case WAIT_FOR_HEADER:
> + info->rx_count--;
> + *skb_put(info->rx_skb, 1) = byte;
> + if (info->rx_count != 0)
> + break;
> + info->rx_count = h4p_get_data_len(info, info->rx_skb);
> + if (info->rx_count > skb_tailroom(info->rx_skb)) {
> + dev_err(info->dev, "frame too long\n");
> + info->garbage_bytes = info->rx_count
> + - skb_tailroom(info->rx_skb);
> + kfree_skb(info->rx_skb);
> + info->rx_skb = NULL;
> + break;
> + }
> + info->rx_state = WAIT_FOR_DATA;
> + break;
> + case WAIT_FOR_DATA:
> + info->rx_count--;
> + *skb_put(info->rx_skb, 1) = byte;
> + break;
> + default:
> + WARN_ON(1);
> + break;
> + }
> +
> + if (info->rx_count == 0) {
> + /* H4+ devices should always send word aligned packets */
> + if (!(info->rx_skb->len % 2))
> + info->garbage_bytes++;
> + h4p_recv_frame(info, info->rx_skb);

I still do not get why the functionality of h4p_recv_frame is not just inlined here.

And more importantly, are we doing something about this word alignment here. What are these garbage_bytes for?

> + info->rx_skb = NULL;
> + }
> +}
> +
> +static void h4p_rx_tasklet(unsigned long data)
> +{
> + u8 byte;
> + struct h4p_info *info = (struct h4p_info *)data;

Swap these two around.

> +
> + BT_DBG("rx_tasklet woke up");
> +
> + while (h4p_inb(info, UART_LSR) & UART_LSR_DR) {
> + byte = h4p_inb(info, UART_RX);
> + BT_DBG("[in: %02x]", byte);
> + if (info->garbage_bytes) {
> + info->garbage_bytes--;
> + continue;
> + }
> + if (info->rx_skb == NULL) {

if (!info->rx_skb) {

> + info->rx_skb = bt_skb_alloc(HCI_MAX_FRAME_SIZE,
> + GFP_ATOMIC | GFP_DMA);
> + if (!info->rx_skb) {
> + dev_err(info->dev,
> + "No memory for new packet\n");
> + goto finish_rx;
> + }
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + info->rx_skb->dev = (void *)info->hdev;
> + }
> + info->hdev->stat.byte_rx++;
> + h4p_handle_byte(info, byte);
> + }
> +
> + if (!info->rx_enabled) {
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT &&
> + info->autorts) {

Indentation and please use extra ( ) to make clear what you want.

if ((h4p_inb(..) & UART_...)
info->autocrts) {

> + __h4p_set_auto_ctsrts(info, 0 , UART_EFR_RTS);
> + info->autorts = 0;

bool?

> + }
> + /* Flush posted write to avoid spurious interrupts */
> + h4p_inb(info, UART_OMAP_SCR);
> + h4p_set_clk(info, &info->rx_clocks_en, 0);

bool?

I think we have a of int where using bool + false/true would make the code a lot easier to read. Since I most likely will miss a few, please fix them all up.

> + }
> +
> +finish_rx:
> + BT_DBG("rx_ended");
> +}
> +
> +static void h4p_tx_tasklet(unsigned long data)
> +{
> + unsigned int sent = 0;
> + struct sk_buff *skb;
> + struct h4p_info *info = (struct h4p_info *)data;

The variable assignment from the function parameters should be always first. So swap it with the sent variable.

> +
> + BT_DBG("tx_tasklet woke up");
> +
> + if (info->autorts != info->rx_enabled) {
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
> + if (info->autorts && !info->rx_enabled) {
> + __h4p_set_auto_ctsrts(info, 0,
> + UART_EFR_RTS);

Alignment.

> + info->autorts = 0;
> + }
> + if (!info->autorts && info->rx_enabled) {
> + __h4p_set_auto_ctsrts(info, 1,
> + UART_EFR_RTS);

Alignment.

> + info->autorts = 1;
> + }
> + } else {
> + h4p_outb(info, UART_OMAP_SCR,
> + h4p_inb(info, UART_OMAP_SCR) |
> + UART_OMAP_SCR_EMPTY_THR);

Alignment.

> + goto finish_tx;
> + }
> + }
> +
> + skb = skb_dequeue(&info->txq);
> + if (!skb) {
> + /* No data in buffer */
> + BT_DBG("skb ready");
> + if (h4p_inb(info, UART_LSR) & UART_LSR_TEMT) {
> + h4p_outb(info, UART_IER,
> + h4p_inb(info, UART_IER) &
> + ~UART_IER_THRI);

Alignment.

> + h4p_inb(info, UART_OMAP_SCR);
> + h4p_disable_tx(info);
> + return;
> + }
> + h4p_outb(info, UART_OMAP_SCR,
> + h4p_inb(info, UART_OMAP_SCR) |
> + UART_OMAP_SCR_EMPTY_THR);

Alignment.

> + goto finish_tx;
> + }
> +
> + /* Copy data to tx fifo */
> + while (!(h4p_inb(info, UART_OMAP_SSR) & UART_OMAP_SSR_TXFULL) &&
> + (sent < skb->len)) {
> + BT_DBG("%02x ", skb->data[sent]);
> + h4p_outb(info, UART_TX, skb->data[sent]);
> + sent++;
> + }
> +
> + info->hdev->stat.byte_tx += sent;
> + if (skb->len == sent) {
> + kfree_skb(skb);
> + } else {
> + skb_pull(skb, sent);
> + skb_queue_head(&info->txq, skb);
> + }
> +
> + h4p_outb(info, UART_OMAP_SCR, h4p_inb(info, UART_OMAP_SCR) &
> + ~UART_OMAP_SCR_EMPTY_THR);

Alignment.

> + h4p_outb(info, UART_IER, h4p_inb(info, UART_IER) |
> + UART_IER_THRI);

Alignment.

I really get the feeling read the value into a variable and then using it would make this more readable.

> +
> +finish_tx:
> + /* Flush posted write to avoid spurious interrupts */
> + h4p_inb(info, UART_OMAP_SCR);
> +
> +}
> +
> +static irqreturn_t h4p_interrupt(int irq, void *data)
> +{
> + struct h4p_info *info = (struct h4p_info *)data;
> + u8 iir, msr;
> + int ret;
> +
> + ret = IRQ_NONE;
> +
> + iir = h4p_inb(info, UART_IIR);
> + if (iir & UART_IIR_NO_INT)
> + return IRQ_HANDLED;
> +
> + iir &= UART_IIR_ID;
> +
> + if (iir == UART_IIR_MSI) {
> + msr = h4p_inb(info, UART_MSR);
> + ret = IRQ_HANDLED;
> + }
> + if (iir == UART_IIR_RLSI) {
> + h4p_inb(info, UART_RX);
> + h4p_inb(info, UART_LSR);
> + ret = IRQ_HANDLED;
> + }
> +
> + if (iir == UART_IIR_RDI) {
> + h4p_rx_tasklet((unsigned long)data);
> + ret = IRQ_HANDLED;
> + }
> +
> + if (iir == UART_IIR_THRI) {
> + h4p_tx_tasklet((unsigned long)data);
> + ret = IRQ_HANDLED;
> + }
> +
> + return ret;
> +}
> +
> +static irqreturn_t h4p_wakeup_interrupt(int irq, void *dev_inst)
> +{
> + struct h4p_info *info = dev_inst;
> + int should_wakeup;
> + struct hci_dev *hdev;
> +
> + BT_DBG("[wakeup irq]");
> +
> + if (!info->hdev)
> + return IRQ_HANDLED;
> +
> + should_wakeup = gpio_get_value(info->host_wakeup_gpio);
> + hdev = info->hdev;

Are you using hdev here at all?

> +
> + if (info->initing) {
> + if (should_wakeup == 1)
> + complete_all(&info->test_completion);
> +
> + printk("wakeup irq handled\n");

We are not using printk directly. Sounds like BT_DBG to me.
> +
> + return IRQ_HANDLED;
> + }
> +
> + BT_DBG("gpio interrupt %d", should_wakeup);
> +
> + /* Check if we have missed some interrupts */
> + if (info->rx_enabled == should_wakeup)
> + return IRQ_HANDLED;
> +
> + if (should_wakeup)
> + h4p_enable_rx(info);
> + else
> + h4p_disable_rx(info);
> +
> + return IRQ_HANDLED;
> +}
> +
> +static int h4p_reset(struct h4p_info *info)
> +{
> + int err;
> +
> + err = h4p_reset_uart(info);
> + if (err < 0) {
> + dev_err(info->dev, "Uart reset failed\n");
> + return err;
> + }
> + h4p_init_uart(info);
> + h4p_set_rts(info, 0);
> +
> + gpio_set_value(info->reset_gpio, 0);
> + gpio_set_value(info->bt_wakeup_gpio, 1);
> + msleep(10);
> +
> + if (gpio_get_value(info->host_wakeup_gpio) == 1) {
> + dev_err(info->dev, "host_wakeup_gpio not low\n");
> + return -EPROTO;
> + }
> +
> + init_completion(&info->test_completion);
> + gpio_set_value(info->reset_gpio, 1);
> +
> + if (!wait_for_completion_interruptible_timeout(&info->test_completion,
> + msecs_to_jiffies(100))) {
> + dev_err(info->dev, "wakeup test timed out\n");
> + complete_all(&info->test_completion);
> + return -EPROTO;
> + }
> +
> + err = h4p_wait_for_cts(info, 1, 100);
> + if (err < 0) {
> + dev_err(info->dev, "No cts from bt chip\n");
> + return err;
> + }
> +
> + h4p_set_rts(info, 1);
> +
> + return 0;
> +}
> +
> +/* hci callback functions */
> +static int h4p_hci_flush(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> +
> + skb_queue_purge(&info->txq);
> +
> + return 0;
> +}
> +
> +static int h4p_bt_wakeup_test(struct h4p_info *info)
> +{
> + /*
> + * Test Sequence:
> + * Host de-asserts the BT_WAKE_UP line.
> + * Host polls the UART_CTS line, waiting for it to be de-asserted.
> + * Host asserts the BT_WAKE_UP line.
> + * Host polls the UART_CTS line, waiting for it to be asserted.
> + * Host de-asserts the BT_WAKE_UP line (allow the Bluetooth device to
> + * sleep).
> + * Host polls the UART_CTS line, waiting for it to be de-asserted.
> + */
> + int err;
> + int ret = -ECOMM;

This is confusing. err and ret? Can we just use one.

> +
> + if (!info)
> + return -EINVAL;
> +
> + /* Disable wakeup interrupts */
> + disable_irq(gpio_to_irq(info->host_wakeup_gpio));
> +
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + err = h4p_wait_for_cts(info, 0, 100);
> + if (err) {
> + dev_warn(info->dev,
> + "bt_wakeup_test: fail: CTS low timed out: %d\n",
> + err);

Alignment.

> + goto out;
> + }
> +
> + gpio_set_value(info->bt_wakeup_gpio, 1);
> + err = h4p_wait_for_cts(info, 1, 100);
> + if (err) {
> + dev_warn(info->dev,
> + "bt_wakeup_test: fail: CTS high timed out: %d\n",
> + err);

Alignment.

> + goto out;
> + }
> +
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + err = h4p_wait_for_cts(info, 0, 100);
> + if (err) {
> + dev_warn(info->dev,
> + "bt_wakeup_test: fail: CTS re-low timed out: %d\n",
> + err);
> + goto out;
> + }
> +
> + ret = 0;
> +
> +out:
> +
> + /* Re-enable wakeup interrupts */
> + enable_irq(gpio_to_irq(info->host_wakeup_gpio));
> +
> + return ret;
> +}
> +
> +static int h4p_hci_set_bdaddr(struct hci_dev *hdev, const bdaddr_t *bdaddr)
> +{
> + struct sk_buff *skb;
> + long ret;
> +
> + printk("Set bdaddr... %pMR\n", bdaddr);

BT_DBG or BT_INFO if you want it printed out all the time.

> +
> + skb = __hci_cmd_sync(hdev, 0xfc01, 6, bdaddr, HCI_INIT_TIMEOUT);
> + if (IS_ERR(skb)) {
> + ret = PTR_ERR(skb);
> + BT_ERR("%s: BCM: Change address command failed (%ld)",
> + hdev->name, ret);
> + return ret;
> + }
> + kfree_skb(skb);
> +
> + return 0;
> +}
> +
> +static void h4p_deinit(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> +
> + h4p_hci_flush(hdev);
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + h4p_set_clk(info, &info->rx_clocks_en, 1);
> + h4p_reset_uart(info);
> + del_timer_sync(&info->lazy_release);
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> + h4p_set_clk(info, &info->rx_clocks_en, 0);
> + gpio_set_value(info->reset_gpio, 0);
> + gpio_set_value(info->bt_wakeup_gpio, 0);
> + kfree_skb(info->rx_skb);
> + info->rx_skb = NULL;
> +}
> +
> +static int h4p_setup(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> + int err;
> + unsigned long flags;
> +
> + /* TI1271 has HW bug and boot up might fail. Nokia retried up to 3x. */

But this is for the Broadcom based devices. So this comment is not really useful here.

> +
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + h4p_set_clk(info, &info->rx_clocks_en, 1);
> +
> + if (!hw_inited) {

So this magic global variable is a no go. I know that nobody has two of these devices installed, but we are just not doing that. Period.

And on a side not, "inited" is not a real word either. Please pick proper variable names.

> + h4p_set_auto_ctsrts(info, 1, UART_EFR_CTS | UART_EFR_RTS);
> + info->autorts = 1;
> +
> + info->initing = 1;
> + printk("hci_setup\n");

BT_DBG.

> +
> + err = h4p_send_negotiation(info);
> + if (err < 0)
> + goto err_clean;
> + }
> +
> + /*
> + * Disable smart-idle as UART TX interrupts
> + * are not wake-up capable
> + */
> + h4p_smart_idle(info, 0);
> +
> + err = h4p_read_fw(info);
> + if (err < 0) {
> + dev_err(info->dev, "Cannot read firmware\n");
> + goto err_clean;
> + }
> +
> +
> + h4p_set_auto_ctsrts(info, 0, UART_EFR_RTS);
> + h4p_set_rts(info, 0);
> + h4p_change_speed(info, BC4_MAX_BAUD_RATE);
> + h4p_set_auto_ctsrts(info, 1, UART_EFR_RTS);
> +
> + info->pm_enabled = 1;
> +
> + err = h4p_bt_wakeup_test(info);
> + if (err < 0) {
> + dev_err(info->dev, "BT wakeup test failed.\n");
> + goto err_clean;
> + }
> +
> + spin_lock_irqsave(&info->lock, flags);
> + info->rx_enabled = gpio_get_value(info->host_wakeup_gpio);
> + h4p_set_clk(info, &info->rx_clocks_en, info->rx_enabled);
> + spin_unlock_irqrestore(&info->lock, flags);
> +
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> +
> + info->initing = 0;
> + hw_inited = 1;
> + return 0;
> +
> +err_clean:
> + printk("hci_setup: something failed, should do the clean up\n");

BT_ERR.

> + h4p_hci_flush(hdev);
> + h4p_deinit(hdev);
> + return err;
> +}
> +
> +static int h4p_hci_setup(struct hci_dev *hdev)
> +{
> + return h4p_setup(hdev);

Why are we doing this?

This also seems wrong. You should enable the hardware within the probe function that registers the hci_dev or from a rfkill switch. Not from the hdev->setup callback. This callback is for running HCI commands that handle firmware loading and general configuration of the controller over HCI. If it is not HCI based, then it does belong there.

Messing with the flow of how what the core thinks you are doing is just dangerous.

> +}
> +
> +

No double empty lines.

> +static int h4p_boot(struct hci_dev *hdev)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> + int err;
> +
> + info->rx_enabled = 1;
> + info->rx_state = WAIT_FOR_PKT_TYPE;
> + info->rx_count = 0;
> + info->garbage_bytes = 0;
> + info->rx_skb = NULL;
> + info->pm_enabled = 0;
> + init_completion(&info->fw_completion);
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> + h4p_set_clk(info, &info->rx_clocks_en, 1);
> +
> + err = h4p_reset(info);
> + return err;
> +}
> +
> +static int h4p_hci_open(struct hci_dev *hdev)
> +{
> + set_bit(HCI_RUNNING, &hdev->flags);
> + return 0;
> +}
> +
> +static int h4p_hci_close(struct hci_dev *hdev)
> +{
> + clear_bit(HCI_RUNNING, &hdev->flags);
> + return 0;
> +}
> +
> +static int h4p_hci_send_frame(struct hci_dev *hdev, struct sk_buff *skb)
> +{
> + struct h4p_info *info = hci_get_drvdata(hdev);
> + int err = 0;
> +
> + BT_DBG("hci_send_frame: dev %p, skb %p\n", hdev, skb);

BT_DBG does not need \n.

> +
> + if (!test_bit(HCI_RUNNING, &hdev->flags)) {
> + dev_warn(info->dev, "Frame for non-running device\n");
> + return -EIO;
> + }

Can we just return -EBUSY and no extra warning like all the other drivers do.

> +
> + switch (bt_cb(skb)->pkt_type) {
> + case HCI_COMMAND_PKT:
> + hdev->stat.cmd_tx++;
> + break;
> + case HCI_ACLDATA_PKT:
> + hdev->stat.acl_tx++;
> + break;
> + case HCI_SCODATA_PKT:
> + hdev->stat.sco_tx++;
> + break;
> + }
> +
> + /* Push frame type to skb */
> + *skb_push(skb, 1) = (bt_cb(skb)->pkt_type);

What are the extra ( ) for?

> + /* We should always send word aligned data to h4+ devices */
> + if (skb->len % 2) {
> + err = skb_pad(skb, 1);
> + if (!err)
> + *skb_put(skb, 1) = 0x00;
> + }
> + if (err)
> + return err;

This is crazy code.

if (skb->len % 2) {
if (!skb_pad(skb, 1)
return -ENOMEM;
*skb_put(skb, 1) = 0x00;
}

> +
> + skb_queue_tail(&info->txq, skb);
> + if (!info->initing)
> + h4p_enable_tx(info);
> + else
> + h4p_enable_tx_nopm(info);
> +
> + return 0;
> +}
> +
> +static int h4p_probe_dt(struct platform_device *pdev, struct h4p_info *info)
> +{
> + struct device_node *node;
> + struct device_node *uart = pdev->dev.of_node;
> + u32 val;
> + struct resource *mem;
> +
> + node = of_get_child_by_name(uart, "device");
> +
> + if (!node)
> + return -ENODATA;
> +
> + info->chip_type = 3; /* Bcm2048 */
> +
> + if (of_property_read_u32(node, "bt-sysclk", &val)) return -EINVAL;

Two lines please.

> + info->bt_sysclk = val;
> +
> + info->reset_gpio = of_get_named_gpio(node, "reset-gpios", 0);
> + info->host_wakeup_gpio = of_get_named_gpio(node, "host-wakeup-gpios", 0);
> + info->bt_wakeup_gpio = of_get_named_gpio(node, "bluetooth-wakeup-gpios", 0);
> +
> + if (!uart) {
> + dev_err(&pdev->dev, "UART link not provided\n");
> + return -EINVAL;
> + }
> +
> + info->irq = irq_of_parse_and_map(uart, 0);
> +
> + mem = platform_get_resource(pdev, IORESOURCE_MEM, 0);
> + info->uart_base = devm_ioremap_resource(&pdev->dev, mem);
> +
> + info->uart_iclk = of_clk_get_by_name(uart, "ick");
> + info->uart_fclk = of_clk_get_by_name(uart, "fck");
> +
> + printk("DT: have neccessary data\n");
> + return 0;
> +}
> +
> +
> +static int h4p_probe(struct platform_device *pdev)
> +{
> + struct hci_dev *hdev;
> + struct h4p_info *info;
> + int err;
> +
> + dev_info(&pdev->dev, "Registering HCI H4P device\n");
> + info = devm_kzalloc(&pdev->dev, sizeof(struct h4p_info),
> + GFP_KERNEL);

Indentation.

> + if (!info)
> + return -ENOMEM;
> +
> + info->dev = &pdev->dev;
> + info->tx_enabled = 1;
> + info->rx_enabled = 1;
> + spin_lock_init(&info->lock);
> + spin_lock_init(&info->clocks_lock);
> + skb_queue_head_init(&info->txq);
> +
> + err = h4p_probe_dt(pdev, info);
> + if (err) {
> + dev_err(&pdev->dev, "Could not get Bluetooth config data\n");
> + return -ENODATA;
> + }
> +
> + BT_DBG("base/irq gpio: %p/%d",
> + info->uart_base, info->irq);
> + BT_DBG("RESET/BTWU/HOSTWU gpio: %d/%d/%d",
> + info->reset_gpio, info->bt_wakeup_gpio, info->host_wakeup_gpio);
> + BT_DBG("chip type, sysclk: %d/%d", info->chip_type, info->bt_sysclk);
> + BT_DBG("clock i/f: %p/%p", info->uart_iclk, info->uart_fclk);
> +
> + init_completion(&info->test_completion);
> + complete_all(&info->test_completion);
> +
> + err = devm_gpio_request_one(&pdev->dev, info->reset_gpio,
> + GPIOF_OUT_INIT_LOW, "bt_reset");
> + if (err < 0) {
> + dev_err(&pdev->dev, "Cannot get GPIO line %d\n",
> + info->reset_gpio);
> + return err;
> + }
> +
> + err = devm_gpio_request_one(&pdev->dev, info->bt_wakeup_gpio,
> + GPIOF_OUT_INIT_LOW, "bt_wakeup");
> + if (err < 0) {
> + dev_err(info->dev, "Cannot get GPIO line 0x%d",
> + info->bt_wakeup_gpio);
> + return err;
> + }
> +
> + err = devm_gpio_request_one(&pdev->dev, info->host_wakeup_gpio,
> + GPIOF_DIR_IN, "host_wakeup");
> + if (err < 0) {
> + dev_err(info->dev, "Cannot get GPIO line %d",
> + info->host_wakeup_gpio);
> + return err;
> + }
> +
> + err = devm_request_irq(&pdev->dev, info->irq, h4p_interrupt,
> + IRQF_DISABLED, "nokia_h4p", info);
> + if (err < 0) {
> + dev_err(info->dev, "nokia_h4p: unable to get IRQ %d\n",
> + info->irq);
> + return err;
> + }
> +
> + err = devm_request_irq(&pdev->dev, gpio_to_irq(info->host_wakeup_gpio),
> + h4p_wakeup_interrupt, IRQF_TRIGGER_FALLING |
> + IRQF_TRIGGER_RISING | IRQF_DISABLED,
> + "h4p_wkup", info);

Indentation.

> + if (err < 0) {
> + dev_err(info->dev, "nokia_h4p: unable to get wakeup IRQ %d\n",
> + gpio_to_irq(info->host_wakeup_gpio));

Indentation.

> + return err;
> + }
> +
> + err = irq_set_irq_wake(gpio_to_irq(info->host_wakeup_gpio), 1);
> + if (err < 0) {
> + dev_err(info->dev, "nokia_h4p: unable to set wakeup for IRQ %d\n",
> + gpio_to_irq(info->host_wakeup_gpio));

Indentation.

> + return err;
> + }
> +
> + init_timer_deferrable(&info->lazy_release);
> + info->lazy_release.function = h4p_lazy_clock_release;
> + info->lazy_release.data = (unsigned long)info;
> + h4p_set_clk(info, &info->tx_clocks_en, 1);
> +
> + err = h4p_reset_uart(info);
> + if (err < 0)
> + return err;
> +
> + gpio_set_value(info->reset_gpio, 0);
> + h4p_set_clk(info, &info->tx_clocks_en, 0);
> +
> + platform_set_drvdata(pdev, info);
> +
> + /* Initialize and register HCI device */
> +
> + hdev = hci_alloc_dev();
> + if (!hdev) {
> + dev_err(info->dev, "Can't allocate memory for device\n");
> + return -ENOMEM;
> + }
> + info->hdev = hdev;
> +
> + hdev->bus = HCI_UART;
> + hci_set_drvdata(hdev, info);
> +
> + hdev->open = h4p_hci_open;
> + hdev->setup = h4p_hci_setup;
> + hdev->close = h4p_hci_close;
> + hdev->flush = h4p_hci_flush;
> + hdev->send = h4p_hci_send_frame;
> + hdev->set_bdaddr = h4p_hci_set_bdaddr;
> +
> +#ifndef TEST
> + set_bit(HCI_QUIRK_INVALID_BDADDR, &hdev->quirks);
> +#endif

That needs to go away. It should be set by default actually when I merge the driver upstream.

You can introduce a module parameter like "use_default_bdaddr", but the default needs to be that we set this flag.

And lets face it, the distros running on the N900 need to start solving the problem of programming the BD_ADDR into the Bluetooth core.

> + SET_HCIDEV_DEV(hdev, info->dev);
> +
> + if (hci_register_dev(hdev) >= 0)
> + return h4p_boot(hdev);

Lets error out here like all the other drivers do.

> +
> + dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
> + hci_free_dev(info->hdev);
> + return -ENODEV;

There is an extra empty space at the end of the line, look for these and fix them. I am really not the janitor here.

> +}
> +
> +static int h4p_remove(struct platform_device *pdev)
> +{
> + struct h4p_info *info = platform_get_drvdata(pdev);
> +
> + h4p_hci_close(info->hdev);
> + h4p_deinit(info->hdev);
> + hci_unregister_dev(info->hdev);
> + hci_free_dev(info->hdev);
> +
> + return 0;
> +}
> +
> +static const struct of_device_id h4p_of_match[] = {
> + { .compatible = "brcm,uart,bcm2048" },
> + {},
> +};
> +MODULE_DEVICE_TABLE(of, h4p_of_match);
> +
> +static struct platform_driver h4p_driver = {
> + .probe = h4p_probe,
> + .remove = h4p_remove,
> + .driver = {
> + .name = "disabled" "nokia_h4p",
> + .owner = THIS_MODULE,
> + .of_match_table = of_match_ptr(h4p_of_match),
> + },
> +};

This one can not be const?

> +
> +module_platform_driver(h4p_driver);
> +
> +MODULE_ALIAS("platform:nokia_h4p");
> +MODULE_DESCRIPTION("Bluetooth h4 driver with nokia extensions");

s/h4/H4/

> +MODULE_LICENSE("GPL");
> +MODULE_AUTHOR("Ville Tervo");
> diff --git a/drivers/bluetooth/nokia_fw.c b/drivers/bluetooth/nokia_fw.c
> new file mode 100644
> index 0000000..80e4385
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_fw.c
> @@ -0,0 +1,101 @@
> +/*
> + * This file is part of nokia_h4p bluetooth driver
> + *
> + * Copyright (C) 2005-2008 Nokia Corporation.
> + * Copyright (C) 2014 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + */
> +
> +#define DEBUG

Why?

> +#include <linux/module.h>
> +#include <linux/skbuff.h>
> +#include <linux/firmware.h>
> +#include <linux/clk.h>
> +
> +#include <net/bluetooth/bluetooth.h>
> +
> +#include "nokia_h4p.h"
> +
> +#define FW_NAME_BCM2048 "nokia/bcmfw.bin"
> +
> +/* Read fw. Return length of the command. If no more commands in
> + * fw 0 is returned. In error case return value is negative.
> + */
> +int h4p_read_fw(struct h4p_info *info)
> +{
> + int num = 0;
> + int fw_pos = 0;
> + struct sk_buff *skb;
> + const struct firmware *fw_entry = NULL;
> + int err = -ENOENT;
> + unsigned int cmd_len = 0;
> +
> + err = request_firmware(&fw_entry, FW_NAME_BCM2048, info->dev);
> + if (err != 0)
> + return err;
> +
> + while (1) {
> + int cmd, len;
> +
> + fw_pos += cmd_len;
> +
> + if (fw_pos >= fw_entry->size)
> + break;
> +
> + if (fw_pos + 2 > fw_entry->size) {
> + dev_err(info->dev, "Corrupted firmware image 1\n");
> + err = -EMSGSIZE;
> + break;
> + }
> +
> + cmd_len = fw_entry->data[fw_pos++];
> + cmd_len += fw_entry->data[fw_pos++] << 8;
> + if (cmd_len == 0)
> + break;
> +
> + if (fw_pos + cmd_len > fw_entry->size) {
> + dev_err(info->dev, "Corrupted firmware image 2\n");

Still not like the 1 and 2 in the error message. They make no sense. There is no image 1 and no image 2. It is a single image.

> + err = -EMSGSIZE;
> + break;
> + }
> +
> + /* Skip first two packets */
> + if (++num <= 2)
> + continue;
> +
> + /* Note that this is timing-critical. If sending packets takes too
> + long, initialization will fail. */
> + printk("Packet %d...", num);
> +
> + cmd = fw_entry->data[fw_pos+1];
> + cmd += fw_entry->data[fw_pos+2] << 8;
> + len = fw_entry->data[fw_pos+3];
> + printk("cmd %x, len %d.", cmd, len);
> +
> + skb = __hci_cmd_sync(info->hdev, cmd, len, fw_entry->data+fw_pos+4, 500);
> + if (IS_ERR(skb)) {
> + dev_err(info->dev, "...sending cmd failed %ld\n", PTR_ERR(skb));
> + err = -EIO;
> + break;
> + }
> + }
> +
> + release_firmware(fw_entry);
> + return err;
> +}
> +
> +MODULE_FIRMWARE(FW_NAME_BCM2048);
> diff --git a/drivers/bluetooth/nokia_h4p.h b/drivers/bluetooth/nokia_h4p.h
> new file mode 100644
> index 0000000..312c61c
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_h4p.h
> @@ -0,0 +1,228 @@
> +/*
> + * This file is part of Nokia H4P bluetooth driver
> + *
> + * Copyright (C) 2005-2008 Nokia Corporation.
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + */
> +
> +#include <net/bluetooth/bluetooth.h>
> +#include <net/bluetooth/hci_core.h>
> +#include <net/bluetooth/hci.h>
> +
> +#include <linux/serial_reg.h>
> +
> +#define UART_SYSC_OMAP_RESET 0x03
> +#define UART_SYSS_RESETDONE 0x01
> +#define UART_OMAP_SCR_EMPTY_THR 0x08
> +#define UART_OMAP_SCR_WAKEUP 0x10
> +#define UART_OMAP_SSR_WAKEUP 0x02
> +#define UART_OMAP_SSR_TXFULL 0x01
> +
> +#define UART_OMAP_SYSC_IDLEMODE 0x03
> +#define UART_OMAP_SYSC_IDLEMASK (3 << UART_OMAP_SYSC_IDLEMODE)
> +
> +#define UART_OMAP_SYSC_FORCE_IDLE (0 << UART_OMAP_SYSC_IDLEMODE)
> +#define UART_OMAP_SYSC_NO_IDLE (1 << UART_OMAP_SYSC_IDLEMODE)
> +#define UART_OMAP_SYSC_SMART_IDLE (2 << UART_OMAP_SYSC_IDLEMODE)
> +
> +#define H4P_TRANSFER_MODE 1
> +#define H4P_SCHED_TRANSFER_MODE 2
> +#define H4P_ACTIVE_MODE 3
> +
> +struct h4p_info {
> + struct timer_list lazy_release;
> + struct hci_dev *hdev;
> + spinlock_t lock;
> +
> + void __iomem *uart_base;
> + unsigned long uart_phys_base;
> + int irq;
> + struct device *dev;
> + u8 chip_type;
> + u8 bt_wakeup_gpio;
> + u8 host_wakeup_gpio;
> + u8 reset_gpio;
> + u8 reset_gpio_shared;
> + u8 bt_sysclk;
> + u8 man_id;
> + u8 ver_id;
> +
> + struct sk_buff_head fw_queue;
> + struct sk_buff *alive_cmd_skb;
> + struct completion init_completion;
> + struct completion fw_completion;
> + struct completion test_completion;
> + int fw_error;
> + int init_error;
> +
> + struct sk_buff_head txq;
> +
> + struct sk_buff *rx_skb;
> + long rx_count;
> + unsigned long rx_state;
> + unsigned long garbage_bytes;
> +
> + struct sk_buff_head *fw_q;
> +
> + int pm_enabled;
> + int tx_enabled;
> + int autorts;
> + int rx_enabled;
> + unsigned long pm_flags;
> +
> + int tx_clocks_en;
> + int rx_clocks_en;
> + spinlock_t clocks_lock;
> + struct clk *uart_iclk;
> + struct clk *uart_fclk;
> + atomic_t clk_users;
> + u16 dll;
> + u16 dlh;
> + u16 ier;
> + u16 mdr1;
> + u16 efr;
> +
> + int initing;
> +};
> +
> +struct h4p_radio_hdr {
> + u8 evt;
> + u8 dlen;
> +} __packed;
> +
> +struct h4p_neg_hdr {
> + u8 dlen;
> +} __packed;
> +#define H4P_NEG_HDR_SIZE 1
> +
> +#define H4P_NEG_REQ 0x00
> +#define H4P_NEG_ACK 0x20
> +#define H4P_NEG_NAK 0x40
> +
> +#define H4P_PROTO_PKT 0x44
> +#define H4P_PROTO_BYTE 0x4c
> +
> +#define H4P_ID_CSR 0x02
> +#define H4P_ID_BCM2048 0x04
> +#define H4P_ID_TI1271 0x31
> +
> +struct h4p_neg_cmd {
> + u8 ack;
> + u16 baud;
> + u16 unused1;
> + u8 proto;
> + u16 sys_clk;
> + u16 unused2;

If these are little endian, the __le16 here. And most likely also __u8

> +} __packed;
> +
> +struct h4p_neg_evt {
> + u8 ack;
> + u16 baud;
> + u16 unused1;
> + u8 proto;
> + u16 sys_clk;
> + u16 unused2;
> + u8 man_id;
> + u8 ver_id;
> +} __packed;
> +
> +#define H4P_ALIVE_REQ 0x55
> +#define H4P_ALIVE_RESP 0xcc
> +
> +struct h4p_alive_hdr {
> + u8 dlen;
> +} __packed;
> +#define H4P_ALIVE_HDR_SIZE 1
> +
> +struct h4p_alive_pkt {
> + u8 mid;
> + u8 unused;
> +} __packed;
> +
> +#define MAX_BAUD_RATE 921600
> +#define BC4_MAX_BAUD_RATE 3692300
> +#define UART_CLOCK 48000000
> +#define BT_INIT_DIVIDER 320
> +#define BT_BAUDRATE_DIVIDER 384000000
> +#define BT_SYSCLK_DIV 1000
> +#define INIT_SPEED 120000
> +
> +#define H4_TYPE_SIZE 1
> +#define H4_RADIO_HDR_SIZE 2
> +
> +/* H4+ packet types */
> +#define H4_CMD_PKT 0x01
> +#define H4_ACL_PKT 0x02
> +#define H4_SCO_PKT 0x03
> +#define H4_EVT_PKT 0x04
> +#define H4_NEG_PKT 0x06
> +#define H4_ALIVE_PKT 0x07
> +#define H4_RADIO_PKT 0x08
> +
> +/* TX states */
> +#define WAIT_FOR_PKT_TYPE 1
> +#define WAIT_FOR_HEADER 2
> +#define WAIT_FOR_DATA 3
> +
> +struct hci_fw_event {
> + struct hci_event_hdr hev;
> + struct hci_ev_cmd_complete cmd;
> + u8 status;
> +} __packed;

Is this actually used.

> +
> +void h4p_simple_send_frame(struct h4p_info *info, struct sk_buff *skb);

I have no idea why this is public in the first place.

> +
> +int h4p_send_alive_packet(struct h4p_info *info);
> +

Same here.

> +int h4p_read_fw(struct h4p_info *info);
> +int h4p_send_fw(struct h4p_info *info);

This one does not even exist.

> +void h4p_parse_fw_event(struct h4p_info *info, struct sk_buff *skb);

And neither does this one.

Seriously here, why do I have to play janitor and look all these up :(

> +
> +static inline void h4p_outb(struct h4p_info *info, unsigned int offset, u8 val)
> +{
> + __raw_writeb(val, info->uart_base + (offset << 2));
> +}
> +
> +static inline u8 h4p_inb(struct h4p_info *info, unsigned int offset)
> +{
> + u8 val;
> + val = __raw_readb(info->uart_base + (offset << 2));
> + return val;
> +}
> +
> +static inline void h4p_set_rts(struct h4p_info *info, int active)
> +{
> + u8 b;
> +
> + b = h4p_inb(info, UART_MCR);
> + if (active)
> + b |= UART_MCR_RTS;
> + else
> + b &= ~UART_MCR_RTS;
> + h4p_outb(info, UART_MCR, b);
> +}
> +
> +int h4p_wait_for_cts(struct h4p_info *info, int active, int timeout_ms);
> +void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
> +void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which);
> +void h4p_change_speed(struct h4p_info *info, unsigned long speed);
> +int h4p_reset_uart(struct h4p_info *info);
> +void h4p_init_uart(struct h4p_info *info);
> +void h4p_enable_tx(struct h4p_info *info);
> +void h4p_store_regs(struct h4p_info *info);
> +void h4p_restore_regs(struct h4p_info *info);
> +void h4p_smart_idle(struct h4p_info *info, bool enable);
> diff --git a/drivers/bluetooth/nokia_uart.c b/drivers/bluetooth/nokia_uart.c
> new file mode 100644
> index 0000000..d95683a
> --- /dev/null
> +++ b/drivers/bluetooth/nokia_uart.c
> @@ -0,0 +1,179 @@
> +/*
> + * This file is part of Nokia H4P bluetooth driver
> + *
> + * Copyright (C) 2005, 2006 Nokia Corporation.
> + * Copyright (C) 2014 Pavel Machek <[email protected]>
> + *
> + * This program is free software; you can redistribute it and/or
> + * modify it under the terms of the GNU General Public License
> + * version 2 as published by the Free Software Foundation.
> + *
> + * This program is distributed in the hope that it will be useful, but
> + * WITHOUT ANY WARRANTY; without even the implied warranty of
> + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
> + * General Public License for more details.
> + *
> + * You should have received a copy of the GNU General Public License
> + * along with this program; if not, write to the Free Software
> + * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA
> + * 02110-1301 USA
> + *
> + */
> +
> +#include <linux/delay.h>
> +#include <linux/clk.h>
> +
> +#include <linux/io.h>
> +
> +#include "nokia_h4p.h"
> +
> +
> +

Single empty line.

> +int h4p_wait_for_cts(struct h4p_info *info, int active,
> + int timeout_ms)

Indentation and bool for active.

> +{
> + unsigned long timeout;
> + int state;
> +
> + timeout = jiffies + msecs_to_jiffies(timeout_ms);
> + for (;;) {
> + state = h4p_inb(info, UART_MSR) & UART_MSR_CTS;
> + if (active) {
> + if (state)
> + return 0;
> + } else {
> + if (!state)
> + return 0;
> + }

if (active == !!state)
return 0;

> + if (time_after(jiffies, timeout))
> + return -ETIMEDOUT;
> + msleep(1);
> + }
> +}
> +
> +void __h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)
> +{

bool for on.

> + u8 lcr, b;
> +
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, 0xbf);
> + b = h4p_inb(info, UART_EFR);
> + if (on)
> + b |= which;
> + else
> + b &= ~which;
> + h4p_outb(info, UART_EFR, b);
> + h4p_outb(info, UART_LCR, lcr);
> +}
> +
> +void h4p_set_auto_ctsrts(struct h4p_info *info, int on, u8 which)

bool for on.

> +{
> + unsigned long flags;
> +
> + spin_lock_irqsave(&info->lock, flags);
> + __h4p_set_auto_ctsrts(info, on, which);
> + spin_unlock_irqrestore(&info->lock, flags);
> +}
> +
> +void h4p_change_speed(struct h4p_info *info, unsigned long speed)
> +{
> + unsigned int divisor;
> + u8 lcr, mdr1;
> +
> + BT_DBG("Setting speed %lu", speed);
> +
> + if (speed >= 460800) {
> + divisor = UART_CLOCK / 13 / speed;
> + mdr1 = 3;
> + } else {
> + divisor = UART_CLOCK / 16 / speed;
> + mdr1 = 0;
> + }
> +
> + /* Make sure UART mode is disabled */
> + h4p_outb(info, UART_OMAP_MDR1, 7);
> +
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, UART_LCR_DLAB); /* Set DLAB */
> + h4p_outb(info, UART_DLL, divisor & 0xff); /* Set speed */
> + h4p_outb(info, UART_DLM, divisor >> 8);
> + h4p_outb(info, UART_LCR, lcr);
> +
> + /* Make sure UART mode is enabled */
> + h4p_outb(info, UART_OMAP_MDR1, mdr1);
> +}
> +
> +int h4p_reset_uart(struct h4p_info *info)
> +{
> + int count = 0;
> +
> + /* Reset the UART */
> + h4p_outb(info, UART_OMAP_SYSC, UART_SYSC_OMAP_RESET);
> + while (!(h4p_inb(info, UART_OMAP_SYSS) & UART_SYSS_RESETDONE)) {
> + if (count++ > 100) {
> + dev_err(info->dev, "nokia_h4p: UART reset timeout\n");
> + return -ENODEV;
> + }
> + udelay(1);
> + }
> +
> + return 0;
> +}
> +
> +void h4p_store_regs(struct h4p_info *info)
> +{
> + u16 lcr = 0;
> +
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, 0xBF);
> + info->dll = h4p_inb(info, UART_DLL);
> + info->dlh = h4p_inb(info, UART_DLM);
> + info->efr = h4p_inb(info, UART_EFR);
> + h4p_outb(info, UART_LCR, lcr);
> + info->mdr1 = h4p_inb(info, UART_OMAP_MDR1);
> + info->ier = h4p_inb(info, UART_IER);
> +}
> +
> +void h4p_restore_regs(struct h4p_info *info)
> +{
> + u16 lcr = 0;
> +
> + h4p_init_uart(info);
> +
> + h4p_outb(info, UART_OMAP_MDR1, 7);
> + lcr = h4p_inb(info, UART_LCR);
> + h4p_outb(info, UART_LCR, 0xBF);
> + h4p_outb(info, UART_DLL, info->dll); /* Set speed */
> + h4p_outb(info, UART_DLM, info->dlh);
> + h4p_outb(info, UART_EFR, info->efr);
> + h4p_outb(info, UART_LCR, lcr);
> + h4p_outb(info, UART_OMAP_MDR1, info->mdr1);
> + h4p_outb(info, UART_IER, info->ier);
> +}
> +
> +void h4p_init_uart(struct h4p_info *info)
> +{
> + u8 mcr, efr;
> +
> + /* Enable and setup FIFO */
> + h4p_outb(info, UART_OMAP_MDR1, 0x00);
> +
> + h4p_outb(info, UART_LCR, 0xbf);
> + efr = h4p_inb(info, UART_EFR);
> + h4p_outb(info, UART_EFR, UART_EFR_ECB);
> + h4p_outb(info, UART_LCR, UART_LCR_DLAB);
> + mcr = h4p_inb(info, UART_MCR);
> + h4p_outb(info, UART_MCR, UART_MCR_TCRTLR);
> + h4p_outb(info, UART_FCR, UART_FCR_ENABLE_FIFO |
> + UART_FCR_CLEAR_RCVR | UART_FCR_CLEAR_XMIT |
> + (3 << 6) | (0 << 4));
> + h4p_outb(info, UART_LCR, 0xbf);
> + h4p_outb(info, UART_TI752_TLR, 0xed);
> + h4p_outb(info, UART_TI752_TCR, 0xef);
> + h4p_outb(info, UART_EFR, efr);
> + h4p_outb(info, UART_LCR, UART_LCR_DLAB);
> + h4p_outb(info, UART_MCR, 0x00);
> + h4p_outb(info, UART_LCR, UART_LCR_WLEN8);
> + h4p_outb(info, UART_IER, UART_IER_RDI);
> + h4p_outb(info, UART_OMAP_SYSC, (1 << 0) | (1 << 2) | (2 << 3));
> +}

And you should run sparse before submitting patches.

CHECK drivers/bluetooth/nokia_core.c
drivers/bluetooth/nokia_core.c:130:6: warning: symbol 'h4p_enable_tx_nopm' was not declared. Should it be static?
drivers/bluetooth/nokia_core.c:282:23: warning: incorrect type in assignment (different base types)
drivers/bluetooth/nokia_core.c:282:23: expected unsigned short [unsigned] [usertype] baud
drivers/bluetooth/nokia_core.c:282:23: got restricted __le16 [usertype] <noident>
drivers/bluetooth/nokia_core.c:284:26: warning: incorrect type in assignment (different base types)
drivers/bluetooth/nokia_core.c:284:26: expected unsigned short [unsigned] [usertype] sys_clk
drivers/bluetooth/nokia_core.c:284:26: got restricted __le16 [usertype] <noident>

Regards

Marcel

2014-12-20 23:39:37

by Marcel Holtmann

[permalink] [raw]
Subject: Re: bluetooth: Add hci_h4p driver

Hi Pavel,

>>> I have trouble understanding... h4p_hci_open() seems to be called as
>>> soon as I insmod the driver. Who does that? Is it some kind of udev
>>> magic?
>>
>> As soon as you do hci_register_dev, it will bring up the device and run the basic initialization. That is needed to get the address, version information and features. Otherwise the mgmt interface can not work. We need basic information about the device.
>>
>> So what the kernel will do internally when you find a device is bring it up, get the basics and then bring it back down (in case nobody uses it). See hci_power_on work.
>>
>
> Aha, slightly unexpected, but it matches observations. Good.

we are at Bluetooth 4.2 specification now. Thinks got a lot more complicated these days.

>
>>> To use __hci_cmd_sync()
>>>
>>>>> +
>>>>> + SET_HCIDEV_DEV(hdev, info->dev);
>>>>> +
>>>>> + if (hci_register_dev(hdev) >= 0)
>>>>> + return 0;
>>>>> +
>>>>> + dev_err(info->dev, "hci_register failed %s.\n", hdev->name);
>>>>> + hci_free_dev(info->hdev);
>>>>> + return -ENODEV;
>>>>> +}
>>>>
>>>> And normally this is folded into the probe handling and not in a
>>>> separate function.
>>>
>>> The probe function is too long, already...
>>
>> Have you compared it to other functions. Normally probe() functions in general are all pretty long since they have to do tons of stuff. Having all in one function means you can read through it at once.
>>
>
> Ok.
>
>>>>> +#include "hci_h4p.h"
>>>>
>>>> Why is this a separate file? And if so, why not all UART specific details are in this file. Including bunch of the defines you have in the header.
>>>>
>>>
>>> Well, you wanted less global functions, so I moved some as inlines to
>>> headers. I guess I can merge nokia_core and nokia_uart if really wanted.
>>
>> Would this become easier when some of the OMAP specific stuff is moved out of this driver? If that is possible.
>>
>
> Yes, I can investigate further cleanups. But original plan was to
> merge it and then clean up the rest. Could we do that, please?

You need to fix all these small details. There are tons of whitespace damages, indentation issues, trailing whitespaces and what not. Even if they were in the original driver to begin this, they can not be in a driver submitted these days.

Regards

Marcel

2014-12-23 12:00:53

by Pavel Machek

[permalink] [raw]
Subject: Re: [PATCH] bluetooth: Add hci_h4p driver

Hi!

> > + /* We should always send word aligned data to h4+ devices */
> > + if (skb->len % 2) {
> > + err = skb_pad(skb, 1);
> > + if (!err)
> > + *skb_put(skb, 1) = 0x00;
> > + }
> > + if (err)
> > + return err;
>
> This is crazy code.
>
> if (skb->len % 2) {
> if (!skb_pad(skb, 1)
> return -ENOMEM;
> *skb_put(skb, 1) = 0x00;
> }

This does not work, it needs to be if (skb_pad())... and it does not
propagate error value. Took me few boots to debug, as I still can't
scroll back after kernel crash...
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html

2014-12-23 12:41:09

by Pavel Machek

[permalink] [raw]
Subject: Re: [PATCH] bluetooth: Add hci_h4p driver

Hi!

> > Add hci_h4p bluetooth driver. This device is used for example on Nokia N900 cell phone.
>
> the driver is called nokia_h4p. And you could be a little bit more verbose here explaining where the driver came from.


> > Signed-off-by: Pavel Machek <[email protected]>
> > Thanks-to: Sebastian Reichel <[email protected]>
> > Thanks-to: Joe Perches <[email protected]>
> >
> > ---
> >
> > Please apply,
>
> If you refuse to use git check-patch, then manually include a
> diffstat.

> > +#include "nokia_h4p.h"
> > +
> > +#undef TEST
>
> What is the TEST undef doing here?

Waiting to be removed. I did, and cleaned the other small stuff.

> > +static void h4p_lazy_clock_release(unsigned long data)
> > +{
>
> What is the reason this is unsigned long and not just struct h4p_info?

That's what struct timer_list expects.

> > +static void h4p_disable_tx(struct h4p_info *info)
> > +{
> > + if (!info->pm_enabled)
> > + return;
> > +
> > + /* Re-enable smart-idle */
> > + h4p_smart_idle(info, 1);
> > +
> > + gpio_set_value(info->bt_wakeup_gpio, 0);
> > + mod_timer(&info->lazy_release, jiffies + msecs_to_jiffies(100));
>
> How many lazy_release functions do you have? Why is this a callback anyway. If not needed, then please simplify this.
>

You don't want to spend power trying to save power, that's why it is
done lazily.

> > +static unsigned int h4p_get_data_len(struct h4p_info *info,
> > + struct sk_buff *skb)
>
> Indentation.

I'm not sure what indentation you want here. net/ uses different
coding style, not a consistent one, and it is not documented. I tried

static unsigned int
h4p_get_data_len(struct h4p_info *info, struct sk_buff *skb)

as seen net/.

> > + if (info->rx_count == 0) {
> > + /* H4+ devices should always send word aligned packets */
> > + if (!(info->rx_skb->len % 2))
> > + info->garbage_bytes++;
> > + h4p_recv_frame(info, info->rx_skb);
>
> I still do not get why the functionality of h4p_recv_frame is not
> just inlined here.

I took a look at h4p_recv_frame, and decided it would hurt the
readability due to control flow.

> And more importantly, are we doing something about this word alignment here. What are these garbage_bytes for?
>

For skipping and completely ignoring bytes, see h4p_rx_tasklet.

> > + h4p_hci_flush(hdev);
> > + h4p_deinit(hdev);
> > + return err;
> > +}
> > +
> > +static int h4p_hci_setup(struct hci_dev *hdev)
> > +{
> > + return h4p_setup(hdev);
>
> Why are we doing this?

Removed indirection.

> This also seems wrong. You should enable the hardware within the probe function that registers the hci_dev or from a rfkill switch. Not from the hdev->setup callback. This callback is for running HCI commands that handle firmware loading and general configuration of the controller over HCI. If it is not HCI based, then it does belong there.
>

I tried that, and spent really lot of time trying to get something
working and clear, and this is the best match I could find. Problem is
I need skb_queue_tail() to send management frames, too.

> > +struct h4p_neg_cmd {
> > + u8 ack;
> > + u16 baud;
> > + u16 unused1;
> > + u8 proto;
> > + u16 sys_clk;
> > + u16 unused2;
>
> If these are little endian, the __le16 here. And most likely also
> __u8

Why would I want to do __u8? This is kernel code, no need to make it
more ugly with __s. (And yes, you have patch to remove some extra __s
from bluetooth core in your inbox.).

> > +void h4p_parse_fw_event(struct h4p_info *info, struct sk_buff *skb);
>
> And neither does this one.
>
> Seriously here, why do I have to play janitor and look all these up
> :(

It has something to do with vetoing staging merge, and mixing cleanups
with "big" changes. Getting "rewrite this because it does not work" is
fair, getting "to these 1000 cleanups and oh btw you have to rewrite
it because XYZ" does not work as well. Plus, consistent coding style
between net/ and rest of kernel would help. Sorry about that, and
trust me, it sucks on my side, too.

static struct platform_driver can't be const, because rest of kernel
does not expect that and it causes warnings.

> > + h4p_outb(info, UART_LCR, UART_LCR_WLEN8);
> > + h4p_outb(info, UART_IER, UART_IER_RDI);
> > + h4p_outb(info, UART_OMAP_SYSC, (1 << 0) | (1 << 2) | (2 << 3));
> > +}
>
> And you should run sparse before submitting patches.
>
> CHECK drivers/bluetooth/nokia_core.c
> drivers/bluetooth/nokia_core.c:130:6: warning: symbol 'h4p_enable_tx_nopm' was not declared. Should it be static?
> drivers/bluetooth/nokia_core.c:282:23: warning: incorrect type in assignment (different base types)
> drivers/bluetooth/nokia_core.c:282:23: expected unsigned short [unsigned] [usertype] baud
> drivers/bluetooth/nokia_core.c:282:23: got restricted __le16 [usertype] <noident>
> drivers/bluetooth/nokia_core.c:284:26: warning: incorrect type in assignment (different base types)
> drivers/bluetooth/nokia_core.c:284:26: expected unsigned short [unsigned] [usertype] sys_clk
> drivers/bluetooth/nokia_core.c:284:26: got restricted __le16 [usertype] <noident>
>

make C=... does not seem to work well with cross-compilation. AFAICT
these should be due to missing static and le16 annotations, should be
fixed.

Best regards,
Pavel
--
(english) http://www.livejournal.com/~pavelmachek
(cesky, pictures) http://atrey.karlin.mff.cuni.cz/~pavel/picture/horses/blog.html