From: Ganapathi Bhat <[email protected]>
This patch implement firmware download feature for
Marvell Bluetooth devices. If firmware is already
downloaded, it will skip downloading.
Signed-off-by: Ganapathi Bhat <[email protected]>
Signed-off-by: Amitkumar Karwar <[email protected]>
---
drivers/bluetooth/Kconfig | 10 +
drivers/bluetooth/Makefile | 1 +
drivers/bluetooth/btmrvl.h | 38 +++
drivers/bluetooth/hci_ldisc.c | 15 +-
drivers/bluetooth/hci_mrvl.c | 645 ++++++++++++++++++++++++++++++++++++++++++
drivers/bluetooth/hci_uart.h | 13 +-
6 files changed, 720 insertions(+), 2 deletions(-)
create mode 100644 drivers/bluetooth/btmrvl.h
create mode 100644 drivers/bluetooth/hci_mrvl.c
diff --git a/drivers/bluetooth/Kconfig b/drivers/bluetooth/Kconfig
index ec6af15..836f1c9 100644
--- a/drivers/bluetooth/Kconfig
+++ b/drivers/bluetooth/Kconfig
@@ -169,6 +169,16 @@ config BT_HCIUART_QCA
Say Y here to compile support for QCA protocol.
+config BT_HCIUART_MRVL
+ bool "Marvell protocol support"
+ depends on BT_HCIUART
+ help
+ Marvell is serial protocol for communication between Bluetooth
+ device and host. This protocol is required for most Marvell Bluetooth
+ devices with UART interface.
+
+ Say Y here to compile support for HCI MRVL protocol.
+
config BT_HCIBCM203X
tristate "HCI BCM203x USB driver"
depends on USB
diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
index 07c9cf3..f7cb408 100644
--- a/drivers/bluetooth/Makefile
+++ b/drivers/bluetooth/Makefile
@@ -36,6 +36,7 @@ hci_uart-$(CONFIG_BT_HCIUART_3WIRE) += hci_h5.o
hci_uart-$(CONFIG_BT_HCIUART_INTEL) += hci_intel.o
hci_uart-$(CONFIG_BT_HCIUART_BCM) += hci_bcm.o
hci_uart-$(CONFIG_BT_HCIUART_QCA) += hci_qca.o
+hci_uart-$(CONFIG_BT_HCIUART_MRVL) += hci_mrvl.o
hci_uart-objs := $(hci_uart-y)
ccflags-y += -D__CHECK_ENDIAN__
diff --git a/drivers/bluetooth/btmrvl.h b/drivers/bluetooth/btmrvl.h
new file mode 100644
index 0000000..6517cdd
--- /dev/null
+++ b/drivers/bluetooth/btmrvl.h
@@ -0,0 +1,38 @@
+/* Bluetooth support for Marvell devices
+ *
+ * Copyright (C) 2016, Marvell International Ltd.
+ *
+ * This software file (the "File") is distributed by Marvell International
+ * Ltd. under the terms of the GNU General Public License Version 2, June 1991
+ * (the "License"). You may use, redistribute and/or modify this File in
+ * accordance with the terms and conditions of the License, a copy of which
+ * is available on the worldwide web at
+ * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt.
+ *
+ * THE FILE IS DISTRIBUTED AS-IS, WITHOUT WARRANTY OF ANY KIND, AND THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY OR FITNESS FOR A PARTICULAR PURPOSE
+ * ARE EXPRESSLY DISCLAIMED. The License provides additional details about
+ * this warranty disclaimer.
+ */
+
+struct fw_data {
+ wait_queue_head_t init_wait_q __aligned(4);
+ u8 wait_fw;
+ int next_len;
+ u8 five_bytes[5];
+ u8 next_index;
+ u8 last_ack;
+ u8 expected_ack;
+ u8 fw_loaded;
+ struct ktermios old_termios;
+};
+
+#define MRVL_WAIT_TIMEOUT 12000
+#define MRVL_MAX_FW_BLOCK_SIZE 1024
+#define MRVL_MAX_RETRY_SEND 12
+#define MRVL_DNLD_DELAY 100
+#define MRVL_ACK 0x5A
+#define MRVL_NAK 0xBF
+#define MRVL_HDR_REQ_FW 0xA5
+#define MRVL_HDR_CHIP_VER 0xAA
+#define MRVL_HCI_OP_SET_BAUD 0xFC09
diff --git a/drivers/bluetooth/hci_ldisc.c b/drivers/bluetooth/hci_ldisc.c
index 73202624..737a09f 100644
--- a/drivers/bluetooth/hci_ldisc.c
+++ b/drivers/bluetooth/hci_ldisc.c
@@ -163,7 +163,14 @@ restart:
}
hci_uart_tx_complete(hu, hci_skb_pkt_type(skb));
- kfree_skb(skb);
+#ifdef CONFIG_BT_HCIUART_MRVL
+ if (hu->proto->id == HCI_UART_MRVL &&
+ !test_bit(HCI_UART_DNLD_FW, &hu->flags)) {
+#endif
+ kfree_skb(skb);
+#ifdef CONFIG_BT_HCIUART_MRVL
+ }
+#endif
}
if (test_bit(HCI_UART_TX_WAKEUP, &hu->tx_state))
@@ -805,6 +812,9 @@ static int __init hci_uart_init(void)
qca_init();
#endif
+#ifdef CONFIG_BT_HCIUART_MRVL
+ mrvl_init();
+#endif
return 0;
}
@@ -836,6 +846,9 @@ static void __exit hci_uart_exit(void)
#ifdef CONFIG_BT_HCIUART_QCA
qca_deinit();
#endif
+#ifdef CONFIG_BT_HCIUART_MRVL
+ mrvl_deinit();
+#endif
/* Release tty registration of line discipline */
err = tty_unregister_ldisc(N_HCI);
diff --git a/drivers/bluetooth/hci_mrvl.c b/drivers/bluetooth/hci_mrvl.c
new file mode 100644
index 0000000..0072b1b
--- /dev/null
+++ b/drivers/bluetooth/hci_mrvl.c
@@ -0,0 +1,645 @@
+/* Bluetooth HCI UART driver for Marvell devices
+ *
+ * Copyright (C) 2016, Marvell International Ltd.
+ *
+ * Acknowledgements:
+ * This file is based on hci_h4.c, which was written
+ * by Maxim Krasnyansky and Marcel Holtmann.
+ *
+ * This software file (the "File") is distributed by Marvell International
+ * Ltd. under the terms of the GNU General Public License Version 2, June 1991
+ * (the "License"). You may use, redistribute and/or modify this File in
+ * accordance with the terms and conditions of the License, a copy of which
+ * is available on the worldwide web at
+ * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt.
+ *
+ * THE FILE IS DISTRIBUTED AS-IS, WITHOUT WARRANTY OF ANY KIND, AND THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY OR FITNESS FOR A PARTICULAR PURPOSE
+ * ARE EXPRESSLY DISCLAIMED. The License provides additional details about
+ * this warranty disclaimer.
+ */
+
+#include <linux/module.h>
+
+#include <linux/kernel.h>
+#include <linux/init.h>
+#include <linux/types.h>
+#include <linux/fcntl.h>
+#include <linux/interrupt.h>
+#include <linux/ptrace.h>
+#include <linux/poll.h>
+
+#include <linux/slab.h>
+#include <linux/tty.h>
+#include <linux/errno.h>
+#include <linux/string.h>
+#include <linux/signal.h>
+#include <linux/ioctl.h>
+#include <linux/skbuff.h>
+#include <asm/unaligned.h>
+
+#include <net/bluetooth/bluetooth.h>
+#include <net/bluetooth/hci_core.h>
+
+#include "hci_uart.h"
+#include <linux/proc_fs.h>
+#include "btmrvl.h"
+#include <linux/firmware.h>
+#include <linux/version.h>
+
+struct mrvl_data {
+ struct sk_buff *rx_skb;
+ struct sk_buff_head txq;
+ struct fw_data *fwdata;
+};
+
+static char helper_name[128];
+static char fw_name[128];
+
+static int mrvl_init_fw_data(struct hci_uart *hu);
+static int mrvl_recv_frame(struct hci_dev *hdev, struct sk_buff *skb);
+
+/* Initialize protocol */
+static int mrvl_open(struct hci_uart *hu)
+{
+ struct mrvl_data *mrvl;
+
+ BT_DBG("hu %p", hu);
+
+ mrvl = kzalloc(sizeof(*mrvl), GFP_KERNEL);
+ if (!mrvl)
+ return -ENOMEM;
+
+ skb_queue_head_init(&mrvl->txq);
+ hu->priv = mrvl;
+
+ return 0;
+}
+
+/* Flush protocol data */
+static int mrvl_flush(struct hci_uart *hu)
+{
+ struct mrvl_data *mrvl = hu->priv;
+
+ BT_DBG("hu %p", hu);
+
+ skb_queue_purge(&mrvl->txq);
+
+ return 0;
+}
+
+/* Close protocol */
+static int mrvl_close(struct hci_uart *hu)
+{
+ struct mrvl_data *mrvl = hu->priv;
+
+ BT_DBG("hu %p", hu);
+
+ skb_queue_purge(&mrvl->txq);
+ kfree_skb(mrvl->rx_skb);
+ kfree(mrvl->fwdata);
+ hu->priv = NULL;
+ kfree(mrvl);
+
+ return 0;
+}
+
+/* Enqueue frame for transmittion (padding, crc, etc) */
+static int mrvl_enqueue(struct hci_uart *hu, struct sk_buff *skb)
+{
+ struct mrvl_data *mrvl = hu->priv;
+
+ if (test_bit(HCI_UART_DNLD_FW, &hu->flags))
+ return -EBUSY;
+
+ BT_DBG("hu %p skb %p", hu, skb);
+
+ /* Prepend skb with frame type */
+ memcpy(skb_push(skb, 1), &hci_skb_pkt_type(skb), 1);
+ skb_queue_tail(&mrvl->txq, skb);
+
+ return 0;
+}
+
+static const struct h4_recv_pkt mrvl_recv_pkts[] = {
+ { H4_RECV_ACL, .recv = hci_recv_frame },
+ { H4_RECV_SCO, .recv = hci_recv_frame },
+ { H4_RECV_EVENT, .recv = mrvl_recv_frame },
+};
+
+static int mrvl_recv_frame(struct hci_dev *hdev, struct sk_buff *skb)
+{
+ int ret;
+
+ ret = hci_recv_frame(hdev, skb);
+
+ return ret;
+}
+
+/* Receive data */
+static int mrvl_recv(struct hci_uart *hu, const void *data, int count)
+{
+ struct mrvl_data *mrvl = hu->priv;
+
+ if (test_bit(HCI_UART_DNLD_FW, &hu->flags)) {
+ hci_uart_recv_data(hu, (u8 *)data, count);
+ return 0;
+ }
+
+ if (!test_bit(HCI_UART_REGISTERED, &hu->flags))
+ return -EUNATCH;
+
+ mrvl->rx_skb = h4_recv_buf(hu->hdev, mrvl->rx_skb, data, count,
+ mrvl_recv_pkts, ARRAY_SIZE(mrvl_recv_pkts));
+ if (IS_ERR(mrvl->rx_skb)) {
+ int err = PTR_ERR(mrvl->rx_skb);
+
+ BT_ERR("%s: Frame reassembly failed (%d)", hu->hdev->name, err);
+ mrvl->rx_skb = NULL;
+ return err;
+ }
+
+ return count;
+}
+
+static struct sk_buff *mrvl_dequeue(struct hci_uart *hu)
+{
+ struct mrvl_data *mrvl = hu->priv;
+
+ return skb_dequeue(&mrvl->txq);
+}
+
+static int mrvl_setup(struct hci_uart *hu)
+{
+ mrvl_init_fw_data(hu);
+ set_bit(HCI_UART_DNLD_FW, &hu->flags);
+
+ return hci_uart_dnld_fw(hu);
+}
+
+static const struct hci_uart_proto mrvlp = {
+ .id = HCI_UART_MRVL,
+ .name = "MRVL",
+ .open = mrvl_open,
+ .close = mrvl_close,
+ .recv = mrvl_recv,
+ .enqueue = mrvl_enqueue,
+ .dequeue = mrvl_dequeue,
+ .flush = mrvl_flush,
+ .setup = mrvl_setup,
+};
+
+int __init mrvl_init(void)
+{
+ return hci_uart_register_proto(&mrvlp);
+}
+
+int __exit mrvl_deinit(void)
+{
+ return hci_uart_unregister_proto(&mrvlp);
+}
+
+static int get_cts(struct tty_struct *tty)
+{
+ u32 state;
+
+ if (tty->ops->tiocmget) {
+ state = tty->ops->tiocmget(tty);
+ if (state & TIOCM_CTS) {
+ BT_DBG("CTS is low\n");
+ return 1;
+ }
+ BT_DBG("CTS is high\n");
+ return 0;
+ }
+ return -1;
+}
+
+static int mrvl_init_fw_data(struct hci_uart *hu)
+{
+ struct fw_data *fwdata;
+ struct mrvl_data *mrvl = hu->priv;
+
+ fwdata = kzalloc(sizeof(*fwdata), GFP_KERNEL);
+
+ if (!fwdata) {
+ BT_ERR("Can't allocate firmware data\n");
+ return -ENOMEM;
+ }
+
+ mrvl->fwdata = fwdata;
+ fwdata->fw_loaded = 0;
+
+ init_waitqueue_head(&fwdata->init_wait_q);
+
+ return 0;
+}
+
+/* Wait for the header from device */
+static int mrvl_wait_for_hdr(struct hci_uart *hu, u8 header)
+{
+ struct mrvl_data *mrvl = hu->priv;
+ struct fw_data *fw_data = mrvl->fwdata;
+
+ fw_data->expected_ack = header;
+ fw_data->wait_fw = 0;
+
+ if (!wait_event_interruptible_timeout(fw_data->init_wait_q,
+ fw_data->wait_fw,
+ ((MRVL_WAIT_TIMEOUT) * HZ / 1000))) {
+ BT_ERR("TIMEOUT, waiting for:0x%x\n", fw_data->expected_ack);
+ return -1;
+ }
+
+ return 0;
+}
+
+/* Send bytes to device */
+static int mrvl_send_data(struct hci_uart *hu, struct sk_buff *skb)
+{
+ int retry = 0;
+ int skb_len;
+
+ skb_len = skb->len;
+ while (retry < MRVL_MAX_RETRY_SEND) {
+ hu->tx_skb = skb;
+ hci_uart_tx_wakeup(hu);
+ if (mrvl_wait_for_hdr(hu, MRVL_HDR_REQ_FW) == -1) {
+ skb_push(skb, skb_len);
+ retry++;
+ continue;
+ } else {
+ break;
+ }
+ }
+ if (retry == MRVL_MAX_RETRY_SEND)
+ return -1;
+
+ return 0;
+}
+
+/* Download firmware to the device */
+static int mrvl_dnld_fw(struct hci_uart *hu, const char *file_name)
+{
+ struct hci_dev *hdev = hu->hdev;
+ const struct firmware *fw;
+ struct sk_buff *skb = NULL;
+ int offset = 0;
+ int ret, tx_len;
+ struct mrvl_data *mrvl = hu->priv;
+ struct fw_data *fw_data = mrvl->fwdata;
+
+ BT_INFO("enter dnld_fw\n");
+
+ ret = request_firmware(&fw, file_name, &hdev->dev);
+ if (ret < 0) {
+ BT_ERR("request_firmware() failed\n");
+ ret = -1;
+ goto done;
+ }
+ if (fw) {
+ BT_INFO("Downloading FW (%lu bytes)\n", fw->size);
+ } else {
+ BT_ERR("No FW image found\n");
+ ret = -1;
+ goto done;
+ }
+
+ skb = bt_skb_alloc(MRVL_MAX_FW_BLOCK_SIZE, GFP_ATOMIC);
+ if (!skb) {
+ BT_ERR("cannot allocate memory for skb\n");
+ ret = -1;
+ goto done;
+ }
+
+ skb->dev = (void *)hdev;
+ fw_data->last_ack = 0;
+
+ do {
+ if ((offset >= fw->size) || (fw_data->last_ack))
+ break;
+ tx_len = fw_data->next_len;
+ if ((fw->size - offset) < tx_len)
+ tx_len = fw->size - offset;
+
+ memcpy(skb->data, &fw->data[offset], tx_len);
+ skb_put(skb, tx_len);
+ if (mrvl_send_data(hu, skb) != 0) {
+ BT_ERR("fail to download firmware\n");
+ ret = -1;
+ goto done;
+ }
+ skb_push(skb, tx_len);
+ skb_trim(skb, 0);
+ offset += tx_len;
+ } while (1);
+
+ BT_INFO("downloaded %d byte firmware\n", offset);
+done:
+ if (fw)
+ release_firmware(fw);
+
+ kfree(skb);
+ BT_INFO("leave dnld_fw\n");
+
+ return ret;
+}
+
+/* Get standard baud rate, given the speed */
+static unsigned int get_baud_rate(unsigned int speed)
+{
+ switch (speed) {
+ case 9600:
+ return B9600;
+ case 19200:
+ return B19200;
+ case 38400:
+ return B38400;
+ case 57600:
+ return B57600;
+ case 115200:
+ return B115200;
+ case 230400:
+ return B230400;
+ case 460800:
+ return B460800;
+ case 921600:
+ return B921600;
+ case 2000000:
+ return B2000000;
+ case 3000000:
+ return B3000000;
+ default:
+ return -1;
+ }
+}
+
+/* Set terminal properties */
+static int mrvl_set_termios(struct tty_struct *tty, unsigned int speed,
+ unsigned char flow_ctl)
+{
+ struct ktermios old_termios = tty->termios;
+ int baud;
+
+ tty->termios.c_cflag &= ~CBAUD;
+ baud = get_baud_rate(speed);
+
+ if (baud == -1) {
+ BT_ERR("Baud rate not supported\n");
+ return -1;
+ }
+
+ tty->termios.c_cflag |= baud;
+
+ if (flow_ctl)
+ tty->termios.c_cflag |= CRTSCTS;
+ else
+ tty->termios.c_cflag &= ~CRTSCTS;
+
+ tty->ops->set_termios(tty, &old_termios);
+
+ return 0;
+}
+
+/* Check if firmware is already loaded */
+static bool mrvl_fw_loaded(struct hci_uart *hu)
+{
+ struct mrvl_data *mrvl = hu->priv;
+ struct fw_data *fw_data = mrvl->fwdata;
+
+ if ((get_cts(hu->tty)) || (fw_data->fw_loaded))
+ return 1;
+ else
+ return 0;
+}
+
+/* Set the baud rate */
+static int mrvl_set_baudrate(struct hci_uart *hu)
+{
+ struct hci_dev *hdev = hu->hdev;
+ struct sk_buff *skb;
+ static const u8 baud_param[] = { 0xc0, 0xc6, 0x2d, 0x00};
+ int err;
+
+ skb = __hci_cmd_sync(hdev, MRVL_HCI_OP_SET_BAUD, sizeof(baud_param),
+ baud_param, HCI_INIT_TIMEOUT);
+ if (IS_ERR(skb)) {
+ err = PTR_ERR(skb);
+ BT_ERR("%s: Set device baudrate failed (%d)", hdev->name, err);
+ return err;
+ }
+ kfree_skb(skb);
+
+ return 0;
+}
+
+/* Reset device */
+static int mrvl_reset(struct hci_uart *hu)
+{
+ struct hci_dev *hdev = hu->hdev;
+ struct sk_buff *skb;
+ int err;
+
+ skb = __hci_cmd_sync(hdev, HCI_OP_RESET, 0, NULL, HCI_INIT_TIMEOUT);
+ if (IS_ERR(skb)) {
+ err = PTR_ERR(skb);
+ BT_ERR("%s: Reset device failed (%d)", hdev->name, err);
+ return err;
+ }
+ kfree_skb(skb);
+
+ return 0;
+}
+
+/* Download helper and firmare to device */
+int hci_uart_dnld_fw(struct hci_uart *hu)
+{
+ struct mrvl_data *mrvl = hu->priv;
+ struct fw_data *fw_data = mrvl->fwdata;
+ struct tty_struct *tty = hu->tty;
+ struct ktermios new_termios;
+ struct ktermios old_termios;
+ int ret;
+
+ old_termios = tty->termios;
+
+ if (!tty) {
+ BT_ERR("tty is null\n");
+ clear_bit(HCI_UART_DNLD_FW, &hu->flags);
+ ret = -1;
+ goto fail;
+ }
+
+ if (mrvl_fw_loaded(hu)) {
+ BT_INFO("fw is running\n");
+ clear_bit(HCI_UART_DNLD_FW, &hu->flags);
+ goto set_term_baud;
+ }
+
+ ret = mrvl_set_termios(tty, 115200, 0);
+ if (ret)
+ goto fail;
+
+ ret = mrvl_wait_for_hdr(hu, MRVL_HDR_REQ_FW);
+ if (ret)
+ goto fail;
+
+ ret = mrvl_dnld_fw(hu, helper_name);
+ if (ret)
+ goto fail;
+
+ mdelay(MRVL_DNLD_DELAY);
+
+ ret = mrvl_set_termios(tty, 3000000, 1);
+ if (ret)
+ goto fail;
+
+ ret = mrvl_wait_for_hdr(hu, MRVL_HDR_CHIP_VER);
+ if (ret)
+ goto fail;
+
+ ret = mrvl_wait_for_hdr(hu, MRVL_HDR_REQ_FW);
+ if (ret)
+ goto fail;
+
+ ret = mrvl_dnld_fw(hu, fw_name);
+ if (ret)
+ goto fail;
+ else
+ fw_data->fw_loaded = 1;
+
+ mdelay(MRVL_DNLD_DELAY);
+ /* restore uart settings */
+ new_termios = tty->termios;
+ tty->termios.c_cflag = old_termios.c_cflag;
+ tty->ops->set_termios(tty, &new_termios);
+ clear_bit(HCI_UART_DNLD_FW, &hu->flags);
+
+ ret = mrvl_reset(hu);
+ if (ret)
+ goto fail;
+
+ ret = mrvl_set_baudrate(hu);
+ if (ret)
+ goto fail;
+
+set_term_baud:
+ ret = mrvl_set_termios(tty, 3000000, 1);
+ if (ret)
+ goto fail;
+
+ mdelay(MRVL_DNLD_DELAY);
+
+ return ret;
+fail:
+ /* restore uart settings */
+ new_termios = tty->termios;
+ tty->termios.c_cflag = old_termios.c_cflag;
+ tty->ops->set_termios(tty, &new_termios);
+ clear_bit(HCI_UART_DNLD_FW, &hu->flags);
+
+ return ret;
+}
+
+static void mrvl_print_fw_data(u8 *buf)
+{
+ int i;
+
+ BT_DBG("\nfive_bytes:");
+
+ for (i = 0; i < 5; i++)
+ BT_DBG(" 0x%x", buf[i]);
+
+ BT_DBG("\n");
+}
+
+/* Send ACK/NAK to the device */
+static void mrvl_send_ack(struct hci_uart *hu, unsigned char ack)
+{
+ struct tty_struct *tty = hu->tty;
+
+ tty->ops->write(tty, &ack, sizeof(ack));
+}
+
+/* Validate the feedback data from device */
+static void mrvl_validate_hdr_and_len(struct hci_uart *hu, u8 *buf)
+{
+ struct mrvl_data *mrvl = hu->priv;
+ struct fw_data *fw_data = mrvl->fwdata;
+ u16 lhs, rhs;
+
+ mrvl_print_fw_data(buf);
+ lhs = *((u16 *)(&buf[1]));
+ rhs = *((u16 *)(&buf[3]));
+ if ((lhs ^ rhs) == 0xffff) {
+ mrvl_send_ack(hu, MRVL_ACK);
+ fw_data->wait_fw = 1;
+ fw_data->next_len = lhs;
+ /*firmware download is done, send the last ack*/
+ if (!lhs)
+ fw_data->last_ack = 1;
+ wake_up_interruptible(&fw_data->init_wait_q);
+ } else {
+ mrvl_send_ack(hu, MRVL_NAK);
+ }
+}
+
+void hci_uart_recv_data(struct hci_uart *hu, u8 *buf, int len)
+{
+ struct mrvl_data *mrvl = hu->priv;
+ struct fw_data *fw_data = mrvl->fwdata;
+ int i = 0;
+
+ if (len < 5) {
+ if ((!fw_data->next_index) &&
+ (buf[0] != fw_data->expected_ack)) {
+ /*ex: XX XX XX*/
+ return;
+ }
+ } else if (len == 5) {
+ if (buf[0] != fw_data->expected_ack) {
+ /*ex: XX XX XX XX XX*/
+ return;
+ }
+ /*ex: 5A LL LL LL LL*/
+ fw_data->next_index = 0;
+ mrvl_validate_hdr_and_len(hu, buf);
+ return;
+ } else if (len > 5) {
+ i = 0;
+
+ while ((i < len) && (buf[i] != fw_data->expected_ack))
+ i++;
+
+ if (i == len) {
+ return;
+ } else if ((len - i) >= 5 &&
+ (buf[i] == fw_data->expected_ack)) {
+ /*ex: 00 00 00 00 a5 LL LL LL LL*/
+ /*ex: a5 LL LL LL LL 00 00 00 00*/
+ /*ex: 00 00 a5 LL LL LL LL 00 00*/
+ /*ex: a5 LL LL LL LL*/
+ fw_data->next_index = 0;
+ mrvl_validate_hdr_and_len(hu, buf + i);
+ return;
+ } else if (buf[i] == fw_data->expected_ack) {
+ /*ex: 00 00 00 00 a5 LL LL*/
+ hci_uart_recv_data(hu, buf + i, len - i);
+ }
+ }
+
+ for (i = 0; i < len; i++) {
+ fw_data->five_bytes[fw_data->next_index] = buf[i];
+ if (++fw_data->next_index == 5) {
+ mrvl_validate_hdr_and_len(hu, fw_data->five_bytes);
+ fw_data->next_index = 0;
+ return;
+ }
+ }
+}
+
+module_param_string(helper_name, helper_name, sizeof(helper_name), 0);
+MODULE_PARM_DESC(helper_name, "helper file name");
+
+module_param_string(fw_name, fw_name, sizeof(fw_name), 0);
+MODULE_PARM_DESC(fw_name, "firmware name");
diff --git a/drivers/bluetooth/hci_uart.h b/drivers/bluetooth/hci_uart.h
index 82c92f1..206677c 100644
--- a/drivers/bluetooth/hci_uart.h
+++ b/drivers/bluetooth/hci_uart.h
@@ -35,7 +35,7 @@
#define HCIUARTGETFLAGS _IOR('U', 204, int)
/* UART protocols */
-#define HCI_UART_MAX_PROTO 9
+#define HCI_UART_MAX_PROTO 10
#define HCI_UART_H4 0
#define HCI_UART_BCSP 1
@@ -46,6 +46,7 @@
#define HCI_UART_INTEL 6
#define HCI_UART_BCM 7
#define HCI_UART_QCA 8
+#define HCI_UART_MRVL 9
#define HCI_UART_RAW_DEVICE 0
#define HCI_UART_RESET_ON_INIT 1
@@ -94,11 +95,16 @@ struct hci_uart {
/* HCI_UART proto flag bits */
#define HCI_UART_PROTO_SET 0
#define HCI_UART_REGISTERED 1
+#define HCI_UART_DNLD_FW 3
/* TX states */
#define HCI_UART_SENDING 1
#define HCI_UART_TX_WAKEUP 2
+#ifdef CONFIG_BT_HCIUART_MRVL
+void hci_uart_recv_data(struct hci_uart *hu, u8 *buf, int len);
+int hci_uart_dnld_fw(struct hci_uart *hu);
+#endif
int hci_uart_register_proto(const struct hci_uart_proto *p);
int hci_uart_unregister_proto(const struct hci_uart_proto *p);
int hci_uart_tx_wakeup(struct hci_uart *hu);
@@ -182,3 +188,8 @@ int bcm_deinit(void);
int qca_init(void);
int qca_deinit(void);
#endif
+
+#ifdef CONFIG_BT_HCIUART_MRVL
+int mrvl_init(void);
+int mrvl_deinit(void);
+#endif
--
1.9.1
Hi Ganapathi,
[auto build test WARNING on bluetooth-next/master]
[also build test WARNING on v4.5-rc4 next-20160215]
[if your patch is applied to the wrong git tree, please drop us a note to help improving the system]
url: https://github.com/0day-ci/linux/commits/Amitkumar-Karwar/Bluetooth-hci_uart-Support-firmware-download-for-Marvell/20160215-234258
base: https://git.kernel.org/pub/scm/linux/kernel/git/bluetooth/bluetooth-next.git master
config: openrisc-allyesconfig (attached as .config)
reproduce:
wget https://git.kernel.org/cgit/linux/kernel/git/wfg/lkp-tests.git/plain/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# save the attached .config to linux build tree
make.cross ARCH=openrisc
All warnings (new ones prefixed by >>):
drivers/bluetooth/hci_mrvl.c: In function 'mrvl_dnld_fw':
>> drivers/bluetooth/hci_mrvl.c:301:3: warning: format '%lu' expects type 'long unsigned int', but argument 2 has type 'size_t'
vim +301 drivers/bluetooth/hci_mrvl.c
285 const struct firmware *fw;
286 struct sk_buff *skb = NULL;
287 int offset = 0;
288 int ret, tx_len;
289 struct mrvl_data *mrvl = hu->priv;
290 struct fw_data *fw_data = mrvl->fwdata;
291
292 BT_INFO("enter dnld_fw\n");
293
294 ret = request_firmware(&fw, file_name, &hdev->dev);
295 if (ret < 0) {
296 BT_ERR("request_firmware() failed\n");
297 ret = -1;
298 goto done;
299 }
300 if (fw) {
> 301 BT_INFO("Downloading FW (%lu bytes)\n", fw->size);
302 } else {
303 BT_ERR("No FW image found\n");
304 ret = -1;
305 goto done;
306 }
307
308 skb = bt_skb_alloc(MRVL_MAX_FW_BLOCK_SIZE, GFP_ATOMIC);
309 if (!skb) {
---
0-DAY kernel test infrastructure Open Source Technology Center
https://lists.01.org/pipermail/kbuild-all Intel Corporation
On Tue, 2016-02-16 at 00:25 +0800, kbuild test robot wrote:
> drivers/bluetooth/hci_mrvl.c:411:9-10: WARNING: return of 0/1 in
> function 'mrvl_fw_loaded' with return type bool
>
> ?Return statements in functions returning bool should use
> ?true/false instead of 1/0.
> Generated by: scripts/coccinelle/misc/boolreturn.cocci
>
> CC: Ganapathi Bhat <[email protected]>
> Signed-off-by: Fengguang Wu <[email protected]>
> ---
>
> ?hci_mrvl.c |????4 ++--
> ?1 file changed, 2 insertions(+), 2 deletions(-)
>
> --- a/drivers/bluetooth/hci_mrvl.c
> +++ b/drivers/bluetooth/hci_mrvl.c
> @@ -408,9 +408,9 @@ static bool mrvl_fw_loaded(struct hci_ua
> ? struct fw_data *fw_data = mrvl->fwdata;
> ?
> ? if ((get_cts(hu->tty)) || (fw_data->fw_loaded))
> - return 1;
> + return true;
> ? else
> - return 0;
> + return false;
> ?}
Nicer might be
return get_cts(hu->tty) || fw_data->fw_loaded;
?
> ?/* Set the baud rate */
Hi Ganapathi,
[auto build test WARNING on bluetooth-next/master]
[also build test WARNING on v4.5-rc4 next-20160215]
[if your patch is applied to the wrong git tree, please drop us a note to help improving the system]
url: https://github.com/0day-ci/linux/commits/Amitkumar-Karwar/Bluetooth-hci_uart-Support-firmware-download-for-Marvell/20160215-234258
base: https://git.kernel.org/pub/scm/linux/kernel/git/bluetooth/bluetooth-next.git master
config: mn10300-allmodconfig (attached as .config)
reproduce:
wget https://git.kernel.org/cgit/linux/kernel/git/wfg/lkp-tests.git/plain/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# save the attached .config to linux build tree
make.cross ARCH=mn10300
All warnings (new ones prefixed by >>):
drivers/bluetooth/hci_mrvl.c: In function 'mrvl_dnld_fw':
>> drivers/bluetooth/hci_mrvl.c:301:3: warning: format '%lu' expects argument of type 'long unsigned int', but argument 2 has type 'size_t' [-Wformat=]
BT_INFO("Downloading FW (%lu bytes)\n", fw->size);
^
vim +301 drivers/bluetooth/hci_mrvl.c
285 const struct firmware *fw;
286 struct sk_buff *skb = NULL;
287 int offset = 0;
288 int ret, tx_len;
289 struct mrvl_data *mrvl = hu->priv;
290 struct fw_data *fw_data = mrvl->fwdata;
291
292 BT_INFO("enter dnld_fw\n");
293
294 ret = request_firmware(&fw, file_name, &hdev->dev);
295 if (ret < 0) {
296 BT_ERR("request_firmware() failed\n");
297 ret = -1;
298 goto done;
299 }
300 if (fw) {
> 301 BT_INFO("Downloading FW (%lu bytes)\n", fw->size);
302 } else {
303 BT_ERR("No FW image found\n");
304 ret = -1;
305 goto done;
306 }
307
308 skb = bt_skb_alloc(MRVL_MAX_FW_BLOCK_SIZE, GFP_ATOMIC);
309 if (!skb) {
---
0-DAY kernel test infrastructure Open Source Technology Center
https://lists.01.org/pipermail/kbuild-all Intel Corporation
drivers/bluetooth/hci_mrvl.c:411:9-10: WARNING: return of 0/1 in function 'mrvl_fw_loaded' with return type bool
Return statements in functions returning bool should use
true/false instead of 1/0.
Generated by: scripts/coccinelle/misc/boolreturn.cocci
CC: Ganapathi Bhat <[email protected]>
Signed-off-by: Fengguang Wu <[email protected]>
---
hci_mrvl.c | 4 ++--
1 file changed, 2 insertions(+), 2 deletions(-)
--- a/drivers/bluetooth/hci_mrvl.c
+++ b/drivers/bluetooth/hci_mrvl.c
@@ -408,9 +408,9 @@ static bool mrvl_fw_loaded(struct hci_ua
struct fw_data *fw_data = mrvl->fwdata;
if ((get_cts(hu->tty)) || (fw_data->fw_loaded))
- return 1;
+ return true;
else
- return 0;
+ return false;
}
/* Set the baud rate */
Hi Ganapathi,
[auto build test WARNING on bluetooth-next/master]
[also build test WARNING on v4.5-rc4 next-20160215]
[if your patch is applied to the wrong git tree, please drop us a note to help improving the system]
url: https://github.com/0day-ci/linux/commits/Amitkumar-Karwar/Bluetooth-hci_uart-Support-firmware-download-for-Marvell/20160215-234258
base: https://git.kernel.org/pub/scm/linux/kernel/git/bluetooth/bluetooth-next.git master
config: i386-allmodconfig (attached as .config)
reproduce:
# save the attached .config to linux build tree
make ARCH=i386
All warnings (new ones prefixed by >>):
In file included from drivers/bluetooth/hci_mrvl.c:41:0:
drivers/bluetooth/hci_mrvl.c: In function 'mrvl_dnld_fw':
>> drivers/bluetooth/hci_mrvl.c:301:11: warning: format '%lu' expects argument of type 'long unsigned int', but argument 2 has type 'size_t {aka const unsigned int}' [-Wformat=]
BT_INFO("Downloading FW (%lu bytes)\n", fw->size);
^
include/net/bluetooth/bluetooth.h:133:35: note: in definition of macro 'BT_INFO'
#define BT_INFO(fmt, ...) bt_info(fmt "\n", ##__VA_ARGS__)
^
coccinelle warnings: (new ones prefixed by >>)
>> drivers/bluetooth/hci_mrvl.c:411:9-10: WARNING: return of 0/1 in function 'mrvl_fw_loaded' with return type bool
--
>> drivers/bluetooth/hci_mrvl.c:536:20-27: ERROR: tty is NULL but dereferenced.
Please review and possibly fold the followup patch.
vim +301 drivers/bluetooth/hci_mrvl.c
295 if (ret < 0) {
296 BT_ERR("request_firmware() failed\n");
297 ret = -1;
298 goto done;
299 }
300 if (fw) {
> 301 BT_INFO("Downloading FW (%lu bytes)\n", fw->size);
302 } else {
303 BT_ERR("No FW image found\n");
304 ret = -1;
305 goto done;
306 }
307
308 skb = bt_skb_alloc(MRVL_MAX_FW_BLOCK_SIZE, GFP_ATOMIC);
309 if (!skb) {
310 BT_ERR("cannot allocate memory for skb\n");
311 ret = -1;
312 goto done;
313 }
314
315 skb->dev = (void *)hdev;
316 fw_data->last_ack = 0;
317
318 do {
319 if ((offset >= fw->size) || (fw_data->last_ack))
320 break;
321 tx_len = fw_data->next_len;
322 if ((fw->size - offset) < tx_len)
323 tx_len = fw->size - offset;
324
325 memcpy(skb->data, &fw->data[offset], tx_len);
326 skb_put(skb, tx_len);
327 if (mrvl_send_data(hu, skb) != 0) {
328 BT_ERR("fail to download firmware\n");
329 ret = -1;
330 goto done;
331 }
332 skb_push(skb, tx_len);
333 skb_trim(skb, 0);
334 offset += tx_len;
335 } while (1);
336
337 BT_INFO("downloaded %d byte firmware\n", offset);
338 done:
339 if (fw)
340 release_firmware(fw);
341
342 kfree(skb);
343 BT_INFO("leave dnld_fw\n");
344
345 return ret;
346 }
347
348 /* Get standard baud rate, given the speed */
349 static unsigned int get_baud_rate(unsigned int speed)
350 {
351 switch (speed) {
352 case 9600:
353 return B9600;
354 case 19200:
355 return B19200;
356 case 38400:
357 return B38400;
358 case 57600:
359 return B57600;
360 case 115200:
361 return B115200;
362 case 230400:
363 return B230400;
364 case 460800:
365 return B460800;
366 case 921600:
367 return B921600;
368 case 2000000:
369 return B2000000;
370 case 3000000:
371 return B3000000;
372 default:
373 return -1;
374 }
375 }
376
377 /* Set terminal properties */
378 static int mrvl_set_termios(struct tty_struct *tty, unsigned int speed,
379 unsigned char flow_ctl)
380 {
381 struct ktermios old_termios = tty->termios;
382 int baud;
383
384 tty->termios.c_cflag &= ~CBAUD;
385 baud = get_baud_rate(speed);
386
387 if (baud == -1) {
388 BT_ERR("Baud rate not supported\n");
389 return -1;
390 }
391
392 tty->termios.c_cflag |= baud;
393
394 if (flow_ctl)
395 tty->termios.c_cflag |= CRTSCTS;
396 else
397 tty->termios.c_cflag &= ~CRTSCTS;
398
399 tty->ops->set_termios(tty, &old_termios);
400
401 return 0;
402 }
403
404 /* Check if firmware is already loaded */
405 static bool mrvl_fw_loaded(struct hci_uart *hu)
406 {
407 struct mrvl_data *mrvl = hu->priv;
408 struct fw_data *fw_data = mrvl->fwdata;
409
410 if ((get_cts(hu->tty)) || (fw_data->fw_loaded))
> 411 return 1;
412 else
413 return 0;
414 }
---
0-DAY kernel test infrastructure Open Source Technology Center
https://lists.01.org/pipermail/kbuild-all Intel Corporation
> From: Amitkumar Karwar [mailto:[email protected]]
> Sent: Thursday, March 31, 2016 5:25 PM
> To: [email protected]
> Cc: Cathy Luo; [email protected]; Nishant Sarmukadam;
> Ganapathi Bhat; Amitkumar Karwar
> Subject: [PATCH] Bluetooth: hci_uart: Support firmware download for
> Marvell
>
> From: Ganapathi Bhat <[email protected]>
>
> This patch implement firmware download feature for Marvell Bluetooth
> devices. If firmware is already downloaded, it will skip downloading.
>
> Signed-off-by: Ganapathi Bhat <[email protected]>
> Signed-off-by: Amitkumar Karwar <[email protected]>
> ---
> v2: Fixed compilation warning reported by kbuild test robot
> v3: Addressed review comments from Marcel Holtmann
> a) Removed vendor specific code from hci_ldisc.c
> b) Get rid of static forward declaration
> c) Removed unnecessary heavy nesting
> d) Git rid of module parameter and global variables
> e) Add logic to pick right firmware image
> v4: Addresses review comments from Alan
> a) Use existing kernel helper APIs instead of writing own.
> b) Replace mdelay() with msleep()
> v5: Addresses review comments from Loic Poulain
> a) Use bt_dev_err/warn/dbg helpers insted of BT_ERR/WARN/DBG
> b) Used static functions where required and removed forward
> delcarations
> c) Edited comments for the function hci_uart_recv_data
> d) Made HCI_UART_DNLD_FW flag a part of driver private data
> v6: Addresses review comments from Loic Poulain
> a) Used skb instead of array to store firmware data during download
> b) Used hci_uart_tx_wakeup and enqueued packets instead of tty write
> c) Used GFP_KERNEL instead of GFP_ATOMIC
>
> ---
> drivers/bluetooth/Kconfig | 10 +
> drivers/bluetooth/Makefile | 1 +
> drivers/bluetooth/btmrvl.h | 43 ++++
> drivers/bluetooth/hci_ldisc.c | 6 +
> drivers/bluetooth/hci_mrvl.c | 568
> ++++++++++++++++++++++++++++++++++++++++++
> drivers/bluetooth/hci_uart.h | 8 +-
> 6 files changed, 635 insertions(+), 1 deletion(-) create mode 100644
> drivers/bluetooth/btmrvl.h create mode 100644
> drivers/bluetooth/hci_mrvl.c
>
> diff --git a/drivers/bluetooth/Kconfig b/drivers/bluetooth/Kconfig index
> cf50fd2..cb825f1 100644
> --- a/drivers/bluetooth/Kconfig
> +++ b/drivers/bluetooth/Kconfig
> @@ -180,6 +180,16 @@ config BT_HCIUART_AG6XX
>
> Say Y here to compile support for Intel AG6XX protocol.
>
> +config BT_HCIUART_MRVL
> + bool "Marvell protocol support"
> + depends on BT_HCIUART
> + help
> + Marvell is serial protocol for communication between Bluetooth
> + device and host. This protocol is required for most Marvell
> Bluetooth
> + devices with UART interface.
> +
> + Say Y here to compile support for HCI MRVL protocol.
> +
> config BT_HCIBCM203X
> tristate "HCI BCM203x USB driver"
> depends on USB
> diff --git a/drivers/bluetooth/Makefile b/drivers/bluetooth/Makefile
> index 9c18939..364dbb6 100644
> --- a/drivers/bluetooth/Makefile
> +++ b/drivers/bluetooth/Makefile
> @@ -37,6 +37,7 @@ hci_uart-$(CONFIG_BT_HCIUART_INTEL) += hci_intel.o
> hci_uart-$(CONFIG_BT_HCIUART_BCM) += hci_bcm.o
> hci_uart-$(CONFIG_BT_HCIUART_QCA) += hci_qca.o
> hci_uart-$(CONFIG_BT_HCIUART_AG6XX) += hci_ag6xx.o
> +hci_uart-$(CONFIG_BT_HCIUART_MRVL) += hci_mrvl.o
> hci_uart-objs := $(hci_uart-y)
>
> ccflags-y += -D__CHECK_ENDIAN__
> diff --git a/drivers/bluetooth/btmrvl.h b/drivers/bluetooth/btmrvl.h new
> file mode 100644 index 0000000..66855de
> --- /dev/null
> +++ b/drivers/bluetooth/btmrvl.h
> @@ -0,0 +1,43 @@
> +/* Bluetooth support for Marvell devices
> + *
> + * Copyright (C) 2016, Marvell International Ltd.
> + *
> + * This software file (the "File") is distributed by Marvell
> +International
> + * Ltd. under the terms of the GNU General Public License Version 2,
> +June 1991
> + * (the "License"). You may use, redistribute and/or modify this File
> +in
> + * accordance with the terms and conditions of the License, a copy of
> +which
> + * is available on the worldwide web at
> + * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt.
> + *
> + * THE FILE IS DISTRIBUTED AS-IS, WITHOUT WARRANTY OF ANY KIND, AND THE
> + * IMPLIED WARRANTIES OF MERCHANTABILITY OR FITNESS FOR A PARTICULAR
> +PURPOSE
> + * ARE EXPRESSLY DISCLAIMED. The License provides additional details
> +about
> + * this warranty disclaimer.
> + */
> +
> +struct fw_data {
> + wait_queue_head_t init_wait_q __aligned(4);
> + u8 wait_fw;
> + int next_len;
> + u8 five_bytes[5];
> + u8 next_index;
> + u8 last_ack;
> + u8 expected_ack;
> + struct ktermios old_termios;
> + u8 chip_id;
> + u8 chip_rev;
> + struct sk_buff *skb;
> +};
> +
> +#define MRVL_HELPER_NAME "mrvl/helper_uart_3000000.bin"
> +#define MRVL_8997_FW_NAME "mrvl/uart8997_bt.bin"
> +#define MRVL_WAIT_TIMEOUT 12000
> +#define MRVL_MAX_FW_BLOCK_SIZE 1024
> +#define MRVL_MAX_RETRY_SEND 12
> +#define MRVL_DNLD_DELAY 100
> +#define MRVL_ACK 0x5A
> +#define MRVL_NAK 0xBF
> +#define MRVL_HDR_REQ_FW 0xA5
> +#define MRVL_HDR_CHIP_VER 0xAA
> +#define MRVL_HCI_OP_SET_BAUD 0xFC09
> +#define MRVL_FW_HDR_LEN 5
> diff --git a/drivers/bluetooth/hci_ldisc.c
> b/drivers/bluetooth/hci_ldisc.c index c00168a..b858758 100644
> --- a/drivers/bluetooth/hci_ldisc.c
> +++ b/drivers/bluetooth/hci_ldisc.c
> @@ -807,6 +807,9 @@ static int __init hci_uart_init(void) #ifdef
> CONFIG_BT_HCIUART_AG6XX
> ag6xx_init();
> #endif
> +#ifdef CONFIG_BT_HCIUART_MRVL
> + mrvl_init();
> +#endif
>
> return 0;
> }
> @@ -842,6 +845,9 @@ static void __exit hci_uart_exit(void) #ifdef
> CONFIG_BT_HCIUART_AG6XX
> ag6xx_deinit();
> #endif
> +#ifdef CONFIG_BT_HCIUART_MRVL
> + mrvl_deinit();
> +#endif
>
> /* Release tty registration of line discipline */
> err = tty_unregister_ldisc(N_HCI);
> diff --git a/drivers/bluetooth/hci_mrvl.c b/drivers/bluetooth/hci_mrvl.c
> new file mode 100644 index 0000000..bca47fd
> --- /dev/null
> +++ b/drivers/bluetooth/hci_mrvl.c
> @@ -0,0 +1,568 @@
> +/* Bluetooth HCI UART driver for Marvell devices
> + *
> + * Copyright (C) 2016, Marvell International Ltd.
> + *
> + * Acknowledgements:
> + * This file is based on hci_h4.c, which was written
> + * by Maxim Krasnyansky and Marcel Holtmann.
> + *
> + * This software file (the "File") is distributed by Marvell
> +International
> + * Ltd. under the terms of the GNU General Public License Version 2,
> +June 1991
> + * (the "License"). You may use, redistribute and/or modify this File
> +in
> + * accordance with the terms and conditions of the License, a copy of
> +which
> + * is available on the worldwide web at
> + * http://www.gnu.org/licenses/old-licenses/gpl-2.0.txt.
> + *
> + * THE FILE IS DISTRIBUTED AS-IS, WITHOUT WARRANTY OF ANY KIND, AND THE
> + * IMPLIED WARRANTIES OF MERCHANTABILITY OR FITNESS FOR A PARTICULAR
> +PURPOSE
> + * ARE EXPRESSLY DISCLAIMED. The License provides additional details
> +about
> + * this warranty disclaimer.
> + */
> +
> +#include <linux/module.h>
> +
> +#include <linux/kernel.h>
> +#include <linux/init.h>
> +#include <linux/types.h>
> +#include <linux/fcntl.h>
> +#include <linux/interrupt.h>
> +#include <linux/ptrace.h>
> +#include <linux/poll.h>
> +#include <linux/firmware.h>
> +#include <linux/version.h>
> +#include <linux/slab.h>
> +#include <linux/tty.h>
> +#include <linux/errno.h>
> +#include <linux/string.h>
> +#include <linux/signal.h>
> +#include <linux/ioctl.h>
> +#include <linux/skbuff.h>
> +#include <asm/unaligned.h>
> +
> +#include <net/bluetooth/bluetooth.h>
> +#include <net/bluetooth/hci_core.h>
> +
> +#include "hci_uart.h"
> +#include "btmrvl.h"
> +
> +#define HCI_UART_DNLD_FW 2
> +
> +struct mrvl_data {
> + struct sk_buff *rx_skb;
> + struct sk_buff_head txq;
> + struct fw_data *fwdata;
> + unsigned long flags;
> +};
> +
> +static int get_cts(struct hci_uart *hu) {
> + struct tty_struct *tty = hu->tty;
> + u32 state;
> +
> + if (tty->ops->tiocmget) {
> + state = tty->ops->tiocmget(tty);
> + if (state & TIOCM_CTS) {
> + bt_dev_dbg(hu->hdev, "CTS is low");
> + return 1;
> + }
> + bt_dev_dbg(hu->hdev, "CTS is high");
> + return 0;
> + }
> + return -1;
> +}
> +
> +/* Initialize protocol */
> +static int mrvl_open(struct hci_uart *hu) {
> + struct mrvl_data *mrvl;
> +
> + bt_dev_dbg(hu->hdev, "hu %p", hu);
> +
> + mrvl = kzalloc(sizeof(*mrvl), GFP_KERNEL);
> + if (!mrvl)
> + return -ENOMEM;
> +
> + skb_queue_head_init(&mrvl->txq);
> + hu->priv = mrvl;
> +
> + return 0;
> +}
> +
> +/* Flush protocol data */
> +static int mrvl_flush(struct hci_uart *hu) {
> + struct mrvl_data *mrvl = hu->priv;
> +
> + bt_dev_dbg(hu->hdev, "hu %p", hu);
> +
> + skb_queue_purge(&mrvl->txq);
> +
> + return 0;
> +}
> +
> +/* Close protocol */
> +static int mrvl_close(struct hci_uart *hu) {
> + struct mrvl_data *mrvl = hu->priv;
> +
> + bt_dev_dbg(hu->hdev, "hu %p", hu);
> +
> + skb_queue_purge(&mrvl->txq);
> + kfree_skb(mrvl->rx_skb);
> + kfree(mrvl->fwdata);
> + hu->priv = NULL;
> + kfree(mrvl);
> +
> + return 0;
> +}
> +
> +/* Enqueue frame for transmittion (padding, crc, etc) */ static int
> +mrvl_enqueue(struct hci_uart *hu, struct sk_buff *skb) {
> + struct mrvl_data *mrvl = hu->priv;
> +
> + if (test_bit(HCI_UART_DNLD_FW, &mrvl->flags))
> + return -EBUSY;
> +
> + bt_dev_dbg(hu->hdev, "hu %p skb %p", hu, skb);
> +
> + /* Prepend skb with frame type */
> + memcpy(skb_push(skb, 1), &hci_skb_pkt_type(skb), 1);
> + skb_queue_tail(&mrvl->txq, skb);
> +
> + return 0;
> +}
> +
> +static const struct h4_recv_pkt mrvl_recv_pkts[] = {
> + { H4_RECV_ACL, .recv = hci_recv_frame },
> + { H4_RECV_SCO, .recv = hci_recv_frame },
> + { H4_RECV_EVENT, .recv = hci_recv_frame }, };
> +
> +/* Send ACK/NAK to the device */
> +static void mrvl_send_ack(struct hci_uart *hu, unsigned char ack) {
> + struct tty_struct *tty = hu->tty;
> +
> + tty->ops->write(tty, &ack, sizeof(ack)); }
> +
> +/* Validate the feedback data from device */ static void
> +mrvl_pkt_complete(struct hci_uart *hu, struct sk_buff *skb) {
> + struct mrvl_data *mrvl = hu->priv;
> + struct fw_data *fw_data = mrvl->fwdata;
> + u8 buf[MRVL_FW_HDR_LEN];
> + u16 lhs, rhs;
> +
> + memcpy(buf, skb->data, skb->len);
> +
> + lhs = le16_to_cpu(*((__le16 *)(&buf[1])));
> + rhs = le16_to_cpu(*((__le16 *)(&buf[3])));
> + if ((lhs ^ rhs) == 0xffff) {
> + mrvl_send_ack(hu, MRVL_ACK);
> + fw_data->wait_fw = 1;
> + fw_data->next_len = lhs;
> + /*firmware download is done, send the last ack*/
> + if (!lhs)
> + fw_data->last_ack = 1;
> +
> + if (unlikely(fw_data->expected_ack == MRVL_HDR_CHIP_VER)) {
> + fw_data->chip_id = *((u8 *)(&buf[1]));
> + fw_data->chip_rev = *((u8 *)(&buf[2]));
> + }
> + wake_up_interruptible(&fw_data->init_wait_q);
> + } else {
> + mrvl_send_ack(hu, MRVL_NAK);
> + }
> +}
> +
> +/* This function receives data from the uart device during firmware
> download.
> + * Driver expects 5 bytes of data as per the protocal in the below
> format:
> + * <HEADER><BYTE_1><BYTE_2><BYTE_3><BYTE_4>
> + * BYTE_3 and BYTE_4 are compliment of BYTE_1 an BYTE_2. Data can come
> +in chunks
> + * of any length. If length received is < 5, accumulate the data in an
> +array,
> + * until we have a sequence of 5 bytes, starting with the expected
> +HEADER. If
> + * the length received is > 5 bytes, then get the first 5 bytes,
> +starting with
> + * the HEADER and process the same, ignoring the rest of the bytes as
> +per the
> + * protocal.
> + */
> +static struct sk_buff *mrvl_process_fw_data(struct hci_uart *hu,
> + struct sk_buff *skb,
> + u8 *buf, int count)
> +{
> + struct mrvl_data *mrvl = hu->priv;
> + struct fw_data *fw_data = mrvl->fwdata;
> + int i = 0, len;
> +
> + if (!skb) {
> + while (buf[i] != fw_data->expected_ack && i < count)
> + i++;
> + if (i == count)
> + return ERR_PTR(-EILSEQ);
> +
> + skb = bt_skb_alloc(MRVL_FW_HDR_LEN, GFP_KERNEL);
> + }
> +
> + if (!skb)
> + return ERR_PTR(-ENOMEM);
> +
> + len = count - i;
> + memcpy(skb_put(skb, len), &buf[i], len);
> +
> + if (skb->len == MRVL_FW_HDR_LEN) {
> + mrvl_pkt_complete(hu, skb);
> + kfree_skb(skb);
> + skb = NULL;
> + }
> +
> + return skb;
> +}
> +
> +/* Receive data */
> +static int mrvl_recv(struct hci_uart *hu, const void *data, int count)
> +{
> + struct mrvl_data *mrvl = hu->priv;
> +
> + if (test_bit(HCI_UART_DNLD_FW, &mrvl->flags)) {
> + mrvl->fwdata->skb = mrvl_process_fw_data(hu, mrvl->fwdata-
> >skb,
> + (u8 *)data, count);
> + if (IS_ERR(mrvl->fwdata->skb)) {
> + int err = PTR_ERR(mrvl->fwdata->skb);
> +
> + bt_dev_err(hu->hdev,
> + "Receive firmware data failed (%d)", err);
> + mrvl->fwdata->skb = NULL;
> + return err;
> + }
> + return 0;
> + }
> +
> + if (!test_bit(HCI_UART_REGISTERED, &hu->flags))
> + return -EUNATCH;
> +
> + mrvl->rx_skb = h4_recv_buf(hu->hdev, mrvl->rx_skb, data, count,
> + mrvl_recv_pkts, ARRAY_SIZE(mrvl_recv_pkts));
> + if (IS_ERR(mrvl->rx_skb)) {
> + int err = PTR_ERR(mrvl->rx_skb);
> +
> + bt_dev_err(hu->hdev, "Frame reassembly failed (%d)", err);
> + mrvl->rx_skb = NULL;
> + return err;
> + }
> +
> + return count;
> +}
> +
> +static struct sk_buff *mrvl_dequeue(struct hci_uart *hu) {
> + struct mrvl_data *mrvl = hu->priv;
> +
> + return skb_dequeue(&mrvl->txq);
> +}
> +
> +static int mrvl_init_fw_data(struct hci_uart *hu) {
> + struct fw_data *fwdata;
> + struct mrvl_data *mrvl = hu->priv;
> +
> + fwdata = kzalloc(sizeof(*fwdata), GFP_KERNEL);
> +
> + if (!fwdata)
> + return -ENOMEM;
> +
> + mrvl->fwdata = fwdata;
> + init_waitqueue_head(&fwdata->init_wait_q);
> +
> + return 0;
> +}
> +
> +/* Wait for the header from device */
> +static int mrvl_wait_for_hdr(struct hci_uart *hu, u8 header) {
> + struct mrvl_data *mrvl = hu->priv;
> + struct fw_data *fw_data = mrvl->fwdata;
> +
> + fw_data->expected_ack = header;
> + fw_data->wait_fw = 0;
> +
> + if (!wait_event_interruptible_timeout(fw_data->init_wait_q,
> + fw_data->wait_fw,
> + ((MRVL_WAIT_TIMEOUT) * HZ / 1000))) {
> + bt_dev_err(hu->hdev, "TIMEOUT, waiting for:0x%x",
> + fw_data->expected_ack);
> + return -1;
> + }
> +
> + return 0;
> +}
> +
> +/* Send bytes to device */
> +static int mrvl_send_data(struct hci_uart *hu, struct sk_buff *skb) {
> + struct mrvl_data *mrvl = hu->priv;
> +
> + skb_queue_head(&mrvl->txq, skb);
> + hci_uart_tx_wakeup(hu);
> +
> + if (mrvl_wait_for_hdr(hu, MRVL_HDR_REQ_FW) == -1)
> + return -1;
> +
> + return 0;
> +}
> +
> +static struct sk_buff *mrvl_alloc_skb(struct hci_dev *hdev) {
> + struct sk_buff *skb = NULL;
> +
> + skb = bt_skb_alloc(MRVL_MAX_FW_BLOCK_SIZE, GFP_KERNEL);
> + if (!skb)
> + bt_dev_err(hdev, "cannot allocate memory for skb");
> + else
> + skb->dev = (void *)hdev;
> +
> + return skb;
> +}
> +
> +/* Download firmware to the device */
> +static int mrvl_dnld_fw(struct hci_uart *hu, const char *file_name) {
> + struct hci_dev *hdev = hu->hdev;
> + const struct firmware *fw = NULL;
> + struct sk_buff *skb = NULL;
> + int offset = 0;
> + int ret, tx_len;
> + struct mrvl_data *mrvl = hu->priv;
> + struct fw_data *fw_data = mrvl->fwdata;
> +
> + ret = request_firmware(&fw, file_name, &hdev->dev);
> + if (ret < 0) {
> + bt_dev_err(hu->hdev, "request_firmware() failed");
> + return -1;
> + }
> +
> + bt_dev_info(hu->hdev, "Downloading FW (%d bytes)", (u16)fw->size);
> +
> + fw_data->last_ack = 0;
> +
> + do {
> + if ((offset >= fw->size) || (fw_data->last_ack))
> + break;
> + tx_len = fw_data->next_len;
> + if ((fw->size - offset) < tx_len)
> + tx_len = fw->size - offset;
> +
> + skb = mrvl_alloc_skb(hdev);
> + if (!skb) {
> + ret = -1;
> + goto done;
> + }
> +
> + memcpy(skb->data, &fw->data[offset], tx_len);
> + skb_put(skb, tx_len);
> + if (mrvl_send_data(hu, skb) != 0) {
> + bt_dev_err(hu->hdev, "fail to download firmware");
> + ret = -1;
> + goto done;
> + }
> + offset += tx_len;
> + } while (1);
> +
> + bt_dev_info(hu->hdev, "downloaded %d byte firmware", offset);
> +done:
> + release_firmware(fw);
> +
> + return ret;
> +}
> +
> +/* Set the baud rate */
> +static int mrvl_set_dev_baud(struct hci_uart *hu) {
> + struct hci_dev *hdev = hu->hdev;
> + struct sk_buff *skb;
> + static const u8 baud_param[] = { 0xc0, 0xc6, 0x2d, 0x00 };
> + int err;
> +
> + skb = __hci_cmd_sync(hdev, MRVL_HCI_OP_SET_BAUD,
> sizeof(baud_param),
> + baud_param, HCI_INIT_TIMEOUT);
> + if (IS_ERR(skb)) {
> + err = PTR_ERR(skb);
> + bt_dev_err(hu->hdev, "Set device baudrate failed (%d)",
> err);
> + return err;
> + }
> + kfree_skb(skb);
> +
> + return 0;
> +}
> +
> +/* Reset device */
> +static int mrvl_reset(struct hci_uart *hu) {
> + struct hci_dev *hdev = hu->hdev;
> + struct sk_buff *skb;
> + int err;
> +
> + skb = __hci_cmd_sync(hdev, HCI_OP_RESET, 0, NULL,
> HCI_CMD_TIMEOUT);
> + if (IS_ERR(skb)) {
> + err = PTR_ERR(skb);
> + bt_dev_err(hu->hdev, "Reset device failed (%d)", err);
> + return err;
> + }
> + kfree_skb(skb);
> +
> + return 0;
> +}
> +
> +static int mrvl_set_baud(struct hci_uart *hu) {
> + int err;
> +
> + hci_uart_set_baudrate(hu, 115200);
> + hci_uart_set_flow_control(hu, false);
> +
> + err = mrvl_reset(hu);
> + if (err)
> + goto set_term_baud;
> + else
> + goto set_dev_baud;
> +
> +set_dev_baud:
> + err = mrvl_set_dev_baud(hu);
> + if (err)
> + return -1;
> +
> +set_term_baud:
> + hci_uart_set_baudrate(hu, 3000000);
> + hci_uart_set_flow_control(hu, false);
> +
> + return 0;
> +}
> +
> +static int mrvl_get_fw_name(struct hci_uart *hu, char *fw_name) {
> + int ret;
> + struct mrvl_data *mrvl = hu->priv;
> + struct fw_data *fw_data = mrvl->fwdata;
> +
> + ret = mrvl_wait_for_hdr(hu, MRVL_HDR_CHIP_VER);
> + if (ret) {
> + ret = -1;
> + bt_dev_err(hu->hdev, "Could not read chip id and revision");
> + goto fail;
> + }
> +
> + bt_dev_dbg(hu->hdev, "chip_id=0x%x, chip_rev=0x%x",
> + fw_data->chip_id, fw_data->chip_rev);
> +
> + if (fw_data->chip_id == 0x50) {
> + memcpy(fw_name, MRVL_8997_FW_NAME,
> sizeof(MRVL_8997_FW_NAME));
> + } else {
> + ret = -1;
> + bt_dev_err(hu->hdev, "Invalid chip id");
> + }
> +fail:
> + return ret;
> +}
> +
> +/* Download helper and firmare to device */ static int
> +hci_uart_dnld_fw(struct hci_uart *hu) {
> + struct tty_struct *tty = hu->tty;
> + struct ktermios new_termios;
> + struct ktermios old_termios;
> + struct mrvl_data *mrvl = hu->priv;
> + char fw_name[128];
> + int ret;
> +
> + old_termios = tty->termios;
> +
> + if (get_cts(hu)) {
> + bt_dev_info(hu->hdev, "fw is running");
> + clear_bit(HCI_UART_DNLD_FW, &mrvl->flags);
> + goto set_baud;
> + }
> +
> + hci_uart_set_baudrate(hu, 115200);
> + hci_uart_set_flow_control(hu, true);
> +
> + ret = mrvl_wait_for_hdr(hu, MRVL_HDR_REQ_FW);
> + if (ret)
> + goto fail;
> +
> + ret = mrvl_dnld_fw(hu, MRVL_HELPER_NAME);
> + if (ret)
> + goto fail;
> +
> + msleep(MRVL_DNLD_DELAY);
> +
> + hci_uart_set_baudrate(hu, 3000000);
> + hci_uart_set_flow_control(hu, false);
> +
> + ret = mrvl_get_fw_name(hu, fw_name);
> + if (ret)
> + goto fail;
> +
> + ret = mrvl_wait_for_hdr(hu, MRVL_HDR_REQ_FW);
> + if (ret)
> + goto fail;
> +
> + ret = mrvl_dnld_fw(hu, fw_name);
> + if (ret)
> + goto fail;
> +
> + msleep(MRVL_DNLD_DELAY);
> + /* restore uart settings */
> + new_termios = tty->termios;
> + tty->termios.c_cflag = old_termios.c_cflag;
> + tty_set_termios(tty, &new_termios);
> + clear_bit(HCI_UART_DNLD_FW, &mrvl->flags);
> +
> +set_baud:
> + ret = mrvl_set_baud(hu);
> + if (ret)
> + goto fail;
> +
> + msleep(MRVL_DNLD_DELAY);
> +
> + return ret;
> +fail:
> + /* restore uart settings */
> + new_termios = tty->termios;
> + tty->termios.c_cflag = old_termios.c_cflag;
> + tty_set_termios(tty, &new_termios);
> + clear_bit(HCI_UART_DNLD_FW, &mrvl->flags);
> +
> + return ret;
> +}
> +
> +static int mrvl_setup(struct hci_uart *hu) {
> + struct mrvl_data *mrvl = hu->priv;
> +
> + mrvl_init_fw_data(hu);
> + set_bit(HCI_UART_DNLD_FW, &mrvl->flags);
> +
> + return hci_uart_dnld_fw(hu);
> +}
> +
> +static const struct hci_uart_proto mrvlp = {
> + .id = HCI_UART_MRVL,
> + .name = "MRVL",
> + .open = mrvl_open,
> + .close = mrvl_close,
> + .recv = mrvl_recv,
> + .enqueue = mrvl_enqueue,
> + .dequeue = mrvl_dequeue,
> + .flush = mrvl_flush,
> + .setup = mrvl_setup,
> +};
> +
> +int __init mrvl_init(void)
> +{
> + return hci_uart_register_proto(&mrvlp); }
> +
> +int __exit mrvl_deinit(void)
> +{
> + return hci_uart_unregister_proto(&mrvlp);
> +}
> diff --git a/drivers/bluetooth/hci_uart.h b/drivers/bluetooth/hci_uart.h
> index 4814ff0..8b1f744 100644
> --- a/drivers/bluetooth/hci_uart.h
> +++ b/drivers/bluetooth/hci_uart.h
> @@ -35,7 +35,7 @@
> #define HCIUARTGETFLAGS _IOR('U', 204, int)
>
> /* UART protocols */
> -#define HCI_UART_MAX_PROTO 10
> +#define HCI_UART_MAX_PROTO 11
>
> #define HCI_UART_H4 0
> #define HCI_UART_BCSP 1
> @@ -47,6 +47,7 @@
> #define HCI_UART_BCM 7
> #define HCI_UART_QCA 8
> #define HCI_UART_AG6XX 9
> +#define HCI_UART_MRVL 10
>
> #define HCI_UART_RAW_DEVICE 0
> #define HCI_UART_RESET_ON_INIT 1
> @@ -188,3 +189,8 @@ int qca_deinit(void); int ag6xx_init(void); int
> ag6xx_deinit(void); #endif
> +
> +#ifdef CONFIG_BT_HCIUART_MRVL
> +int mrvl_init(void);
> +int mrvl_deinit(void);
> +#endif
> --
> 1.9.1
Please ignore this patch. I missed to include v6 in patch title. I will resend it.
Regards,
Amitkumar