drivers/wireless/bluetooth/bt_uart_bcm4343x.c: BCM4343x HCIUART support.
This commit is contained in:
parent
bcb4409756
commit
de70e689cd
@ -16,6 +16,10 @@ config BLUETOOTH_UART_GENERIC
|
||||
bool
|
||||
default n
|
||||
|
||||
config BLUETOOTH_UART_SHIM
|
||||
bool
|
||||
default n
|
||||
|
||||
if BLUETOOTH_UART
|
||||
|
||||
choice
|
||||
@ -26,13 +30,18 @@ config BLUETOOTH_UART_BT860
|
||||
bool "Laird BT860"
|
||||
select BLUETOOTH_UART_GENERIC
|
||||
|
||||
config BLUETOOTH_UART_SHIM
|
||||
bool "Generic shim to serial port"
|
||||
|
||||
config BLUETOOTH_UART_CC2564
|
||||
bool "TI CC2564"
|
||||
depends on EXPERIMENTAL
|
||||
|
||||
config BLUETOOTH_BCM4343X
|
||||
bool "Broadcom (Cypress) BCM4343X device support"
|
||||
select BLUETOOTH_UART_SHIM
|
||||
---help---
|
||||
Enables download support for the bluetooth component of BCM4343X devices.
|
||||
Note that firmware needs to be provided for these devices to operate. In
|
||||
general this firmware is available in the Cypress WICED SDK.
|
||||
|
||||
config BLUETOOTH_UART_OTHER
|
||||
bool "Other generic HCI UART device"
|
||||
select BLUETOOTH_UART_GENERIC
|
||||
|
@ -45,11 +45,14 @@ ifeq ($(CONFIG_BLUETOOTH_UART_GENERIC),y)
|
||||
CSRCS += bt_uart_generic.c
|
||||
endif
|
||||
ifeq ($(CONFIG_BLUETOOTH_UART_SHIM),y)
|
||||
CSRCS += bt_uart_shim.c bt_uart_generic.c
|
||||
CSRCS += bt_uart_shim.c
|
||||
endif
|
||||
ifeq ($(CONFIG_BLUETOOTH_UART_CC2564),y)
|
||||
CSRCS += bt_uart_cc2564.c
|
||||
endif
|
||||
ifeq ($(CONFIG_BLUETOOTH_BCM4343X),y)
|
||||
CSRCS += bt_uart_bcm4343x.c
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_BLUETOOTH_NULL),y)
|
||||
|
475
drivers/wireless/bluetooth/bt_uart_bcm4343x.c
Normal file
475
drivers/wireless/bluetooth/bt_uart_bcm4343x.c
Normal file
@ -0,0 +1,475 @@
|
||||
/****************************************************************************
|
||||
* drivers/wireless/bluetooth/bt_uart_bcm4343x.c
|
||||
*
|
||||
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
|
||||
* Author: Dave Marples <dave@marples.net>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name NuttX nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
#include <fcntl.h>
|
||||
#include <poll.h>
|
||||
#include <semaphore.h>
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
#include <sys/stat.h>
|
||||
#include <sys/types.h>
|
||||
#include <unistd.h>
|
||||
|
||||
#include <nuttx/arch.h>
|
||||
#include <nuttx/fs/ioctl.h>
|
||||
#include <nuttx/irq.h>
|
||||
#include <nuttx/kmalloc.h>
|
||||
#include <nuttx/kthread.h>
|
||||
#include <nuttx/semaphore.h>
|
||||
#include <nuttx/serial/tioctl.h>
|
||||
#include <nuttx/wireless/bluetooth/bt_uart.h>
|
||||
#include <nuttx/wireless/bluetooth/bt_uart_shim.h>
|
||||
#include <termios.h>
|
||||
|
||||
#include "bt_uart.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define HCIUART_DEFAULT_SPEED 2000000
|
||||
#define HCIUART_LOW_SPEED 115200
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
static const uint8_t g_hcd_patchram_command = 0x2e;
|
||||
static const uint8_t g_hcd_launch_command = 0x4e;
|
||||
static const uint8_t g_hcd_write_command = 0x4c;
|
||||
static const uint8_t g_hcd_command_byte2 = 0xfc;
|
||||
|
||||
/****************************************************************************
|
||||
* Public Data
|
||||
****************************************************************************/
|
||||
|
||||
extern const long int g_bt_firmware_len;
|
||||
extern const uint8_t g_bt_firmware_hcd[];
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: hciuartCB
|
||||
*
|
||||
* Callback from hcirx indicating that there are data to read.
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - an instance of the lower half driver interface
|
||||
* param - pointer to the semaphore to indicate data readiness
|
||||
*
|
||||
* Returned Value:
|
||||
* None
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void hciuart_cb(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR void *param)
|
||||
|
||||
{
|
||||
FAR sem_t *rxsem = (FAR sem_t *)param;
|
||||
|
||||
/* Data has arrived - post to release the semaphore */
|
||||
|
||||
nxsem_post(rxsem);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: uartwriteconf
|
||||
*
|
||||
* Write to HCI UART and get confirmation back
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - an instance of the lower half driver interface
|
||||
* rxsem - pointer to the semaphore to indicate data readiness
|
||||
* dout - pointer to data to send
|
||||
* doutl - length of out data
|
||||
* cmp - pointer to comparison data on inbound side
|
||||
* maxl - length of data to receive on inbound side
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 or error code.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int uartwriteconf(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR sem_t *rxsem,
|
||||
FAR const uint8_t *dout, uint32_t doutl,
|
||||
FAR const uint8_t *cmp, uint32_t maxl)
|
||||
|
||||
{
|
||||
int ret;
|
||||
int gotlen = 0;
|
||||
FAR uint8_t *din;
|
||||
struct timespec abstime;
|
||||
|
||||
DEBUGASSERT(lower != NULL);
|
||||
|
||||
lower->rxdrain(lower);
|
||||
|
||||
ret = lower->write(lower, dout, doutl);
|
||||
if (ret < 0)
|
||||
{
|
||||
wlerr("Failed to write\n");
|
||||
goto exit_uartwriteconf_nofree;
|
||||
}
|
||||
|
||||
if ((cmp == NULL) || (maxl == 0))
|
||||
{
|
||||
ret = OK;
|
||||
goto exit_uartwriteconf_nofree;
|
||||
}
|
||||
|
||||
/* We've been asked to check the response too ... */
|
||||
|
||||
din = kmm_malloc(maxl);
|
||||
while (gotlen < maxl)
|
||||
{
|
||||
do
|
||||
{
|
||||
ret = clock_gettime(CLOCK_REALTIME, &abstime);
|
||||
if (ret < 0)
|
||||
{
|
||||
goto exit_uartwriteconf;
|
||||
}
|
||||
|
||||
/* Add the offset to the time in the future */
|
||||
|
||||
abstime.tv_nsec += NSEC_PER_SEC / 10;
|
||||
if (abstime.tv_nsec >= NSEC_PER_SEC)
|
||||
{
|
||||
abstime.tv_nsec -= NSEC_PER_SEC;
|
||||
abstime.tv_sec++;
|
||||
}
|
||||
|
||||
ret = nxsem_timedwait(rxsem, &abstime);
|
||||
if (ret == -ETIMEDOUT)
|
||||
{
|
||||
/* We didn't receive enough message, so fall out */
|
||||
|
||||
wlerr("Response timed out\n");
|
||||
goto exit_uartwriteconf;
|
||||
}
|
||||
}
|
||||
while (ret == -EINTR);
|
||||
|
||||
ret = lower->read(lower, &din[gotlen], maxl - gotlen);
|
||||
if (ret < 0)
|
||||
{
|
||||
wlerr("Couldn't read\n");
|
||||
ret = -ECOMM;
|
||||
goto exit_uartwriteconf;
|
||||
}
|
||||
gotlen += ret;
|
||||
}
|
||||
|
||||
ret = ((memcmp(din, cmp, maxl) == 0) ? 0 : -ECOMM);
|
||||
|
||||
exit_uartwriteconf:
|
||||
free(din);
|
||||
exit_uartwriteconf_nofree:
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: set_baudrate
|
||||
*
|
||||
* Set baudrate to be used in future for UART comms. In case of error the
|
||||
* current baudrate is not changed.
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - an instance of the lower half driver interface
|
||||
* rxsem - pointer to the semaphore to indicate data readiness
|
||||
* targetspeed - new baudrate to be used
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 or error code.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int set_baudrate(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR sem_t *rxsem, int targetspeed)
|
||||
|
||||
{
|
||||
int ret;
|
||||
uint8_t baudrate_cmd[] =
|
||||
{
|
||||
0x01, 0x18, g_hcd_command_byte2, 0x06, 0x00, 0x00,
|
||||
targetspeed & 0xff, (targetspeed >> 8) & 0xff,
|
||||
(targetspeed >> 16) & 0xff, (targetspeed >> 24) & 0xff
|
||||
};
|
||||
|
||||
const uint8_t baudrate_conf[] =
|
||||
{
|
||||
0x04, 0x0e, 0x04, 0x01, 0x18, g_hcd_command_byte2, 0x00
|
||||
};
|
||||
|
||||
ret = uartwriteconf(lower, rxsem, baudrate_cmd, sizeof(baudrate_cmd),
|
||||
baudrate_conf, sizeof(baudrate_conf));
|
||||
|
||||
if (ret == OK)
|
||||
{
|
||||
ret = lower->setbaud(lower, targetspeed);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: load_bcm4343x_firmware
|
||||
*
|
||||
* Attempt to load firmware into target device.
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - an instance of the lower half driver interface
|
||||
*
|
||||
* Returned Value:
|
||||
* 0 or error code.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static int load_bcm4343x_firmware(FAR const struct btuart_lowerhalf_s *lower)
|
||||
|
||||
{
|
||||
FAR uint8_t *rp = (FAR uint8_t *)g_bt_firmware_hcd;
|
||||
int ret = OK;
|
||||
sem_t rxsem;
|
||||
uint8_t command;
|
||||
uint8_t txlen;
|
||||
uint8_t istx = 1;
|
||||
uint32_t blockattempts;
|
||||
|
||||
/* Various responses to upload commands */
|
||||
|
||||
const uint8_t command_resp[] =
|
||||
{
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_write_command, g_hcd_command_byte2, 0x00
|
||||
};
|
||||
const uint8_t launch_resp[] =
|
||||
{
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_launch_command, g_hcd_command_byte2, 0x00
|
||||
};
|
||||
const uint8_t download_resp[] =
|
||||
{
|
||||
0x04, 0x0e, 0x04, 0x01, g_hcd_patchram_command, g_hcd_command_byte2, 0x00
|
||||
};
|
||||
|
||||
/* Command to switch the chip into download mode */
|
||||
|
||||
const uint8_t enter_download_mode[] =
|
||||
{
|
||||
0x01, g_hcd_patchram_command, g_hcd_command_byte2, 0x00
|
||||
};
|
||||
|
||||
/* Let's temporarily connect to the hci uart rx callback so we can get data */
|
||||
|
||||
lower->rxattach(lower, hciuart_cb, &rxsem);
|
||||
lower->rxenable(lower, true);
|
||||
|
||||
nxsem_init(&rxsem, 0, 0);
|
||||
nxsem_setprotocol(&rxsem, SEM_PRIO_NONE);
|
||||
|
||||
/* It is possible this could fail if modem is already at high speed, so we
|
||||
* can safely ignore error return value.
|
||||
*/
|
||||
|
||||
lower->setbaud(lower, HCIUART_LOW_SPEED);
|
||||
set_baudrate(lower, &rxsem, HCIUART_DEFAULT_SPEED);
|
||||
|
||||
/* New baudrate is established, prepare to receive firmware */
|
||||
|
||||
ret = uartwriteconf(lower, &rxsem,
|
||||
enter_download_mode, sizeof(enter_download_mode),
|
||||
download_resp, sizeof(download_resp));
|
||||
if (ret != OK)
|
||||
{
|
||||
wlerr("Failed to enter download mode\n");
|
||||
ret = -ECOMM;
|
||||
goto load_bcm4343x_firmware_finished;
|
||||
}
|
||||
|
||||
/* ...so now we can spin, pushing firmware into the chip */
|
||||
|
||||
while (rp < (g_bt_firmware_hcd + g_bt_firmware_len))
|
||||
{
|
||||
command = rp[0];
|
||||
txlen = rp[2];
|
||||
|
||||
if (command == g_hcd_launch_command)
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
/* Try a few times for each block, just in case */
|
||||
|
||||
blockattempts = 0;
|
||||
do
|
||||
{
|
||||
lower->write(lower, &istx, 1);
|
||||
ret = uartwriteconf(lower, &rxsem, rp, 3 + txlen,
|
||||
command_resp, sizeof(command_resp));
|
||||
if (ret)
|
||||
{
|
||||
wlwarn("block offset %x upload failed, retrying\n",
|
||||
rp - g_bt_firmware_hcd);
|
||||
}
|
||||
}
|
||||
while ((ret != 0) && (++blockattempts < 3));
|
||||
|
||||
if (ret != 0)
|
||||
{
|
||||
wlerr("block upload repeatedly failed, aborting\n");
|
||||
goto load_bcm4343x_firmware_finished;
|
||||
}
|
||||
|
||||
/* The +3 in here is the header bytes from the source file */
|
||||
|
||||
rp += 3 + txlen;
|
||||
}
|
||||
|
||||
/* To have gotten here we must've uploaded correctly, or barfed out */
|
||||
|
||||
if (command == g_hcd_launch_command)
|
||||
{
|
||||
lower->write(lower, &istx, 1);
|
||||
ret = uartwriteconf(lower, &rxsem, rp, 3 + txlen,
|
||||
launch_resp, sizeof(launch_resp));
|
||||
if (ret != 0)
|
||||
{
|
||||
wlerr("failed to launch firmware\n");
|
||||
goto load_bcm4343x_firmware_finished;
|
||||
}
|
||||
|
||||
/* Give everything time to start up */
|
||||
|
||||
nxsig_usleep(1000000);
|
||||
|
||||
/* Once the firmware has booted it goes back to low speed,
|
||||
* so kick it up again
|
||||
*/
|
||||
|
||||
lower->setbaud(lower, HCIUART_LOW_SPEED);
|
||||
|
||||
ret = set_baudrate(lower, &rxsem, HCIUART_DEFAULT_SPEED);
|
||||
}
|
||||
else
|
||||
{
|
||||
ret = -ECOMM;
|
||||
}
|
||||
|
||||
load_bcm4343x_firmware_finished:
|
||||
lower->rxattach(lower, NULL, NULL);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: btuart_register
|
||||
*
|
||||
* Create the UART-based Bluetooth device and register it with the
|
||||
* Bluetooth stack.
|
||||
*
|
||||
* Input Parameters:
|
||||
* lower - an instance of the lower half driver interface
|
||||
*
|
||||
* Returned Value:
|
||||
* Zero is returned on success; a negated errno value is returned on any
|
||||
* failure.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
int btuart_register(FAR const struct btuart_lowerhalf_s *lower)
|
||||
{
|
||||
FAR struct btuart_upperhalf_s *upper;
|
||||
int ret;
|
||||
|
||||
wlinfo("lower %p\n", lower);
|
||||
|
||||
DEBUGASSERT(lower != NULL);
|
||||
|
||||
/* Allocate a new instance of the upper half driver state structure */
|
||||
|
||||
upper = (FAR struct btuart_upperhalf_s *)
|
||||
kmm_zalloc(sizeof(struct btuart_upperhalf_s));
|
||||
|
||||
if (upper == NULL)
|
||||
{
|
||||
wlerr("ERROR: Failed to allocate upper-half state\n");
|
||||
return -ENOMEM;
|
||||
}
|
||||
|
||||
/* Initialize the upper half driver state */
|
||||
|
||||
upper->dev.head_reserve = H4_HEADER_SIZE;
|
||||
upper->dev.open = btuart_open;
|
||||
upper->dev.send = btuart_send;
|
||||
upper->lower = lower;
|
||||
|
||||
/* Load firmware */
|
||||
|
||||
ret = load_bcm4343x_firmware(lower);
|
||||
if (ret < 0)
|
||||
{
|
||||
wlerr("ERROR: Firmware error\n");
|
||||
kmm_free(upper);
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* And register the driver with the network and the Bluetooth stack. */
|
||||
|
||||
ret = bt_netdev_register(&upper->dev);
|
||||
if (ret < 0)
|
||||
{
|
||||
wlerr("ERROR: bt_driver_register failed: %d\n", ret);
|
||||
kmm_free(upper);
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
@ -60,14 +60,9 @@
|
||||
#include <nuttx/semaphore.h>
|
||||
#include <nuttx/serial/tioctl.h>
|
||||
#include <nuttx/wireless/bluetooth/bt_uart.h>
|
||||
#include <nuttx/wireless/bluetooth/bt_uart_shim.h>
|
||||
#include <termios.h>
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define HCIUART_DEFAULT_SPEED 115200
|
||||
|
||||
/****************************************************************************
|
||||
* Private Types
|
||||
****************************************************************************/
|
||||
@ -75,29 +70,29 @@
|
||||
/* This structure is the variable state of the binding to the UART */
|
||||
|
||||
struct hciuart_state_s
|
||||
{
|
||||
/* Registered Rx callback */
|
||||
{
|
||||
/* Registered Rx callback */
|
||||
|
||||
btuart_rxcallback_t callback; /* Rx callback function */
|
||||
void *arg; /* Rx callback argument */
|
||||
btuart_rxcallback_t callback; /* Rx callback function */
|
||||
FAR void *arg; /* Rx callback argument */
|
||||
|
||||
int h; /* File handle to serial device */
|
||||
struct file f; /* File structure, detached */
|
||||
int h; /* File handle to serial device */
|
||||
struct file f; /* File structure, detached */
|
||||
|
||||
sem_t dready; /* Semaphore used by the poll operation */
|
||||
bool enabled; /* Flag indicating that reception is enabled */
|
||||
sem_t dready; /* Semaphore used by the poll operation */
|
||||
bool enabled; /* Flag indicating that reception is enabled */
|
||||
|
||||
int serialmontask; /* The receive serial octets task handle */
|
||||
volatile struct pollfd p; /* Polling structure for serial monitor task */
|
||||
};
|
||||
int serialmontask; /* The receive serial octets task handle */
|
||||
volatile struct pollfd p; /* Polling structure for serial monitor task */
|
||||
};
|
||||
|
||||
struct hciuart_config_s
|
||||
{
|
||||
/* Setup the interface from the upper to the lower */
|
||||
{
|
||||
/* Setup the interface from the upper to the lower */
|
||||
|
||||
struct btuart_lowerhalf_s lower; /* Generic UART lower half */
|
||||
struct hciuart_state_s state; /* Variable state */
|
||||
};
|
||||
struct btuart_lowerhalf_s lower; /* Generic UART lower half */
|
||||
struct hciuart_state_s state; /* Variable state */
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Function Prototypes
|
||||
@ -105,21 +100,25 @@ struct hciuart_config_s
|
||||
|
||||
/* UART Lower-Half Methods */
|
||||
|
||||
static void hciuart_rxattach(const struct btuart_lowerhalf_s *lower,
|
||||
btuart_rxcallback_t callback, void *arg);
|
||||
static void hciuart_rxenable(const struct btuart_lowerhalf_s *lower,
|
||||
static void hciuart_rxattach(FAR const struct btuart_lowerhalf_s *lower,
|
||||
btuart_rxcallback_t callback, FAR void *arg);
|
||||
static void hciuart_rxenable(FAR const struct btuart_lowerhalf_s *lower,
|
||||
bool enable);
|
||||
static int hciuart_setbaud(const struct btuart_lowerhalf_s *lower,
|
||||
static int hciuart_setbaud(FAR const struct btuart_lowerhalf_s *lower,
|
||||
uint32_t baud);
|
||||
static ssize_t hciuart_read(const struct btuart_lowerhalf_s *lower,
|
||||
void *buffer, size_t buflen);
|
||||
static ssize_t hciuart_write(const struct btuart_lowerhalf_s *lower,
|
||||
const void *buffer, size_t buflen);
|
||||
static ssize_t hciuart_rxdrain(const struct btuart_lowerhalf_s *lower);
|
||||
static ssize_t hciuart_read(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR void *buffer, size_t buflen);
|
||||
static ssize_t hciuart_write(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR const void *buffer, size_t buflen);
|
||||
static ssize_t hciuart_rxdrain(FAR const struct btuart_lowerhalf_s *lower);
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
|
||||
/* This structure is the configuration of the HCI UART shim */
|
||||
|
||||
static struct btuart_lowerhalf_s lowerstatic =
|
||||
static struct btuart_lowerhalf_s g_lowerstatic =
|
||||
{
|
||||
.rxattach = hciuart_rxattach,
|
||||
.rxenable = hciuart_rxenable,
|
||||
@ -129,12 +128,9 @@ static struct btuart_lowerhalf_s lowerstatic =
|
||||
.rxdrain = hciuart_rxdrain
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
/* This is held global because its inconvenient to pass to the task */
|
||||
|
||||
static struct hciuart_config_s *g_n; /* This is held global because its
|
||||
* inconvenient to pass to the task */
|
||||
static FAR struct hciuart_config_s *g_n;
|
||||
|
||||
/****************************************************************************
|
||||
* Private Functions
|
||||
@ -155,8 +151,8 @@ static struct hciuart_config_s *g_n; /* This is held global because its
|
||||
****************************************************************************/
|
||||
|
||||
static void
|
||||
hciuart_rxattach(const struct btuart_lowerhalf_s *lower,
|
||||
btuart_rxcallback_t callback, void *arg)
|
||||
hciuart_rxattach(FAR const struct btuart_lowerhalf_s *lower,
|
||||
btuart_rxcallback_t callback, FAR void *arg)
|
||||
{
|
||||
struct hciuart_config_s *config = (struct hciuart_config_s *)lower;
|
||||
struct hciuart_state_s *state;
|
||||
@ -184,7 +180,6 @@ hciuart_rxattach(const struct btuart_lowerhalf_s *lower,
|
||||
state->callback = callback;
|
||||
}
|
||||
|
||||
hciuart_setbaud(lower, HCIUART_DEFAULT_SPEED);
|
||||
spin_unlock_irqrestore(flags);
|
||||
}
|
||||
|
||||
@ -201,24 +196,20 @@ hciuart_rxattach(const struct btuart_lowerhalf_s *lower,
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static void hciuart_rxenable(const struct btuart_lowerhalf_s *lower,
|
||||
static void hciuart_rxenable(FAR const struct btuart_lowerhalf_s *lower,
|
||||
bool enable)
|
||||
{
|
||||
struct hciuart_config_s *config = (struct hciuart_config_s *)lower;
|
||||
struct hciuart_state_s *s = &config->state;
|
||||
FAR struct hciuart_config_s *config = (FAR struct hciuart_config_s *)lower;
|
||||
FAR struct hciuart_state_s *s = &config->state;
|
||||
|
||||
irqstate_t flags = spin_lock_irqsave();
|
||||
if ((enable) && (!s->enabled))
|
||||
if (enable != s->enabled)
|
||||
{
|
||||
wlinfo("Enable\n");
|
||||
s->enabled = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
s->enabled = false;
|
||||
wlinfo("Disable\n");
|
||||
wlinfo(enable?"Enable\n":"Disable\n");
|
||||
}
|
||||
|
||||
s->enabled = enable;
|
||||
|
||||
spin_unlock_irqrestore(flags);
|
||||
}
|
||||
|
||||
@ -237,10 +228,10 @@ static void hciuart_rxenable(const struct btuart_lowerhalf_s *lower,
|
||||
****************************************************************************/
|
||||
|
||||
static int
|
||||
hciuart_setbaud(const struct btuart_lowerhalf_s *lower, uint32_t baud)
|
||||
hciuart_setbaud(FAR const struct btuart_lowerhalf_s *lower, uint32_t baud)
|
||||
{
|
||||
struct hciuart_config_s *config = (struct hciuart_config_s *)lower;
|
||||
struct hciuart_state_s *state = &config->state;
|
||||
FAR struct hciuart_config_s *config = (FAR struct hciuart_config_s *)lower;
|
||||
FAR struct hciuart_state_s *state = &config->state;
|
||||
int ret;
|
||||
|
||||
struct termios tio;
|
||||
@ -289,11 +280,11 @@ hciuart_setbaud(const struct btuart_lowerhalf_s *lower, uint32_t baud)
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t
|
||||
hciuart_read(const struct btuart_lowerhalf_s *lower,
|
||||
void *buffer, size_t buflen)
|
||||
hciuart_read(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR void *buffer, size_t buflen)
|
||||
{
|
||||
struct hciuart_config_s *config = (struct hciuart_config_s *)lower;
|
||||
struct hciuart_state_s *state = &config->state;
|
||||
FAR struct hciuart_config_s *config = (FAR struct hciuart_config_s *)lower;
|
||||
FAR struct hciuart_state_s *state = &config->state;
|
||||
size_t ntotal;
|
||||
|
||||
wlinfo("config %p buffer %p buflen %lu\n", config, buffer, (size_t) buflen);
|
||||
@ -321,16 +312,16 @@ hciuart_read(const struct btuart_lowerhalf_s *lower,
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t
|
||||
hciuart_write(const struct btuart_lowerhalf_s *lower,
|
||||
const void *buffer, size_t buflen)
|
||||
hciuart_write(FAR const struct btuart_lowerhalf_s *lower,
|
||||
FAR const void *buffer, size_t buflen)
|
||||
{
|
||||
const struct hciuart_config_s *config
|
||||
= (const struct hciuart_config_s *)lower;
|
||||
struct hciuart_state_s *state = &config->state;
|
||||
FAR const struct hciuart_config_s *config
|
||||
= (FAR const struct hciuart_config_s *)lower;
|
||||
FAR const struct hciuart_state_s *state = &config->state;
|
||||
|
||||
wlinfo("config %p buffer %p buflen %lu\n", config, buffer, (size_t) buflen);
|
||||
|
||||
buflen = file_write(&state->f, buffer, buflen);
|
||||
buflen = file_write((struct file *)&state->f, buffer, buflen);
|
||||
|
||||
return buflen;
|
||||
}
|
||||
@ -343,10 +334,10 @@ hciuart_write(const struct btuart_lowerhalf_s *lower,
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
static ssize_t hciuart_rxdrain(const struct btuart_lowerhalf_s *lower)
|
||||
static ssize_t hciuart_rxdrain(FAR const struct btuart_lowerhalf_s *lower)
|
||||
{
|
||||
struct hciuart_config_s *config = (struct hciuart_config_s *)lower;
|
||||
struct hciuart_state_s *s = &config->state;
|
||||
FAR struct hciuart_config_s *config = (FAR struct hciuart_config_s *)lower;
|
||||
FAR struct hciuart_state_s *s = &config->state;
|
||||
|
||||
file_ioctl(&s->f, TCDRN, 0);
|
||||
return 0;
|
||||
@ -362,9 +353,9 @@ static ssize_t hciuart_rxdrain(const struct btuart_lowerhalf_s *lower)
|
||||
|
||||
static int hcicollecttask(int argc, FAR char **argv)
|
||||
{
|
||||
struct hciuart_state_s *s = &g_n->state;
|
||||
FAR struct hciuart_state_s *s = &g_n->state;
|
||||
|
||||
file_poll(&s->f, &s->p, true);
|
||||
file_poll(&s->f, (struct pollfd *)&s->p, true);
|
||||
|
||||
for (; ; )
|
||||
{
|
||||
@ -423,23 +414,23 @@ static int hcicollecttask(int argc, FAR char **argv)
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: hci_uart_getdevice
|
||||
* Name: bt_uart_shim_getdevice
|
||||
*
|
||||
* Description:
|
||||
* Get a pointer to the device that will be used to communicate with the
|
||||
* regular serial port on the HCI.
|
||||
*
|
||||
* Input Paramters:
|
||||
* Entry in filesystem hirearchy for device
|
||||
* Input Parameters:
|
||||
* Entry in filesystem hierarchy for device
|
||||
*
|
||||
* Returned Value:
|
||||
* Pointer to device interface
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void *hci_uart_getdevice(char *path)
|
||||
FAR void *bt_uart_shim_getdevice(FAR char *path)
|
||||
{
|
||||
struct hciuart_state_s *s;
|
||||
FAR struct hciuart_state_s *s;
|
||||
int f2;
|
||||
|
||||
/* Get the memory for this shim instance */
|
||||
@ -468,11 +459,10 @@ void *hci_uart_getdevice(char *path)
|
||||
|
||||
/* Hook the routines in */
|
||||
|
||||
memcpy(&g_n->lower, &lowerstatic, sizeof(struct btuart_lowerhalf_s));
|
||||
memcpy(&g_n->lower, &g_lowerstatic, sizeof(struct btuart_lowerhalf_s));
|
||||
|
||||
/* Put materials into poll structure */
|
||||
|
||||
nxsem_init(&s->dready, 0, 0);
|
||||
nxsem_setprotocol(&s->dready, SEM_PRIO_NONE);
|
||||
|
||||
s->p.fd = s->h;
|
||||
|
55
include/nuttx/wireless/bluetooth/bt_uart_shim.h
Normal file
55
include/nuttx/wireless/bluetooth/bt_uart_shim.h
Normal file
@ -0,0 +1,55 @@
|
||||
/****************************************************************************
|
||||
* drivers/wireless/bluetooth/bt_uart_shim.h
|
||||
* Shim for connecting generic UART ports to bluetooth H4 interfaces
|
||||
*
|
||||
* Copyright (C) 2019 Gregory Nutt. All rights reserved.
|
||||
* Author: Dave Marples <dave@marples.net>
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright notice,
|
||||
* this list of conditions and the following disclaimer.
|
||||
*
|
||||
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||
* this list of conditions and the following disclaimer in the documentation
|
||||
* and/or other materials provided with the distribution.
|
||||
*
|
||||
* 3. Neither the name of the copyright holder nor the names of its
|
||||
* contributors may be used to endorse or promote products derived from this
|
||||
* software without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
|
||||
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
|
||||
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
|
||||
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
|
||||
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
|
||||
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
|
||||
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __INCLUDE_NUTTX_WIRELESS_BT_UART_SHIM_H
|
||||
#define __INCLUDE_NUTTX_WIRELESS_BT_UART_SHIM_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <nuttx/compiler.h>
|
||||
|
||||
#ifdef CONFIG_BLUETOOTH_UART_SHIM
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
FAR void *bt_uart_shim_getdevice(FAR char *path);
|
||||
|
||||
#endif
|
||||
#endif
|
Loading…
Reference in New Issue
Block a user