Return-Path: Date: Sat, 20 Dec 2014 21:23:14 +0100 From: Pavel Machek To: pali.rohar@gmail.com, sre@debian.org, sre@ring0.de, kernel list , linux-arm-kernel , linux-omap@vger.kernel.org, tony@atomide.com, khilman@kernel.org, aaro.koskinen@iki.fi, ivo.g.dimitrov.75@gmail.com, linux-bluetooth@vger.kernel.org, marcel@holtmann.org Subject: [PATCH] bluetooth: Add hci_h4p driver Message-ID: <20141220202314.GA8484@amd> References: <20141213223727.GA13894@amd> MIME-Version: 1.0 Content-Type: text/plain; charset=us-ascii In-Reply-To: <20141213223727.GA13894@amd> List-ID: Add hci_h4p bluetooth driver. This device is used for example on Nokia N900 cell phone. Signed-off-by: Pavel Machek Thanks-to: Sebastian Reichel Thanks-to: Joe Perches --- 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 + * + * 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 +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#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 + * + * 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 +#include +#include +#include + +#include + +#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 +#include +#include + +#include + +#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 + * + * 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 +#include + +#include + +#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