Skip to content
Commits on Source (3)
  • Gregory Nutt's avatar
    This commit brings in the Bluetooth stack from the Intel/Zephyr... · accef0ca
    Gregory Nutt authored
    This commit brings in the Bluetooth stack from the Intel/Zephyr arduino101_firmware_source-v1.tar package.
    
    NOTE: This selection is marked EXPERIMENTAL.  It is incomplete and, hence, untested.  It still lacks any low-level Bluetooth drivers and is missing the network interface driver.
    
    Squashed commit of the following:
    
        wireless/bluetooth:  Fixe last of compile issues.  Now compiles without errors or warnings.
        wireless/blutooth:  Add macros BT_GETUINT16() and BT_PUTUINT16().  Fix more compile errors.  Only one file now generates compile errors.
        wireless/bluetooth:  Add macros BT_LE162HOST() and BT_HOST2LE16().
        wireless/bluetooth:  Add bt_queue.c; begin fixing comple errors.  Many more compile problems yet to resolve.
        Kconfig edited online with Bitbucket
        wireless/bluetooth:  Struggling to remove nano_fifo logic:  Replace buffer management with IOB allocate... this changes some logic and might have some side effects.  Use messages queues instead of nano-fifos to inter-task communications.  nano-fifos still used in 'frag' logic... whatever that is.
        wireless/bluetooth:  Fix numerous typos introduced by an ill conceived search-and-replace.
        wireless/bluetooth:  Add message queue support to manage interthread buffer transfers.
        wireless/bluetooth:  Replace fibers with kernel threads.
        wireless/bluetooth:  Fix a few initial compile errors.  Just the tip of the iceberg.
        wireless/bluetooth:  Complete leveage of the bluetooth stack including public header files.
        wireless/bluetooth:  Complete leverage of all Bluetooth source files.  Still missing header files that defines the driver interface.  Also missing the network driver implementation.
        wireless/bluetooth:  Fix some naming of static global variables.
        wireless/bluetooth:  Adds three more files ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package (plus two original files).
        wireless/bluetooth:  Adds five more files ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package.
        wireless/bluetooth:  Adds three more files ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package.
        wireless/bluetooth:  First few files ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package.
    accef0ca
  • Gregory Nutt's avatar
    wireless/bluetooth: Add driver object in all driver methods so that the driver... · aaf5fee1
    Gregory Nutt authored
    wireless/bluetooth: Add driver object in all driver methods so that the driver has a way of maintaingin context.
    aaf5fee1
  • Gregory Nutt's avatar
    Adds re-architected Bluetooth UART driver from the Intel/Zephyr... · 380d5587
    Gregory Nutt authored
    Adds re-architected Bluetooth UART driver from the Intel/Zephyr arduino101_firmware_source-v1.tar package.
    
    Squashed commit of the following:
    
        drivers/bluetooth:  Re-architect Bluetooth UART driver to follow upper/lower half model.  Completely untested.
        drivers/bluetooth:  Grr..  Another band-aid commit to stay in sync with master.  Why is this so difficult
        drivers/bluetooth:  Band-aid commit to stay in sync with master.  Lost it somehow.
        drivers/wireless/bluetooth:  A few changes, mostly thought experiments.
        drivers/wireless/bluetooth:  UART-based Bluetooth driver ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package.  This initial commit is the original files in the NuttX build environment with changes to conform with the coding standard.  It should not even build.
    380d5587
......@@ -35,7 +35,7 @@ menuconfig DRIVERS_IEEE802154
bool "IEEE 802.15.4 Device Support"
default n
---help---
This directory holds implementations of IEEE802.15.4 device drivers.
Select to enable building of IEEE802.15.4 device drivers.
source drivers/wireless/ieee802154/Kconfig
......@@ -43,10 +43,19 @@ menuconfig DRIVERS_IEEE80211
bool "IEEE 802.11 Device Support"
default n
---help---
This directory holds implementations of IEEE802.11 device drivers.
Select to enable building of IEEE802.11 device drivers.
source drivers/wireless/ieee80211/Kconfig
menuconfig DRIVERS_BLUETOOTH
bool "Bluetooth Device Support"
default n
depends on WIRELESS_BLUETOOTH
---help---
Select to enable building of Bluetooth device drivers.
source drivers/wireless/bluetooth/Kconfig
config WL_NRF24L01
bool "nRF24l01+ transceiver support"
default n
......
......@@ -47,6 +47,12 @@ ifeq ($(CONFIG_DRIVERS_IEEE80211),y)
include wireless$(DELIM)ieee80211$(DELIM)Make.defs
endif
# Include Bluetooth support
ifeq ($(CONFIG_DRIVERS_BLUETOOTH),y)
include wireless$(DELIM)bluetooth$(DELIM)Make.defs
endif
# Include wireless drivers
ifeq ($(CONFIG_WL_CC1101),y)
......
#############################################################################
# wireless/bluetooth/Kconfig
# Bluetooth LE driver configuration options
#
# Copyright (C) 2018 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
# where the code was released with a compatible 3-clause BSD license:
#
# Copyright (c) 2016, Intel Corporation
# All rights reserved.
#
# 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.
#
#############################################################################
if DRIVERS_BLUETOOTH
config BLUETOOTH_UART
bool "Bluetooth UART driver"
default n
---help---
Enable Bluetooth UART driver.
endif # DRIVERS_BLUETOOTH
############################################################################
# drivers/bluetooth/Make.defs
#
# Copyright (C) 2018 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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.
#
############################################################################
# Include nothing if Bluetooth is disabled
ifeq ($(CONFIG_DRIVERS_BLUETOOTH),y)
# Include Bluetooth drivers into the build
ifeq ($(CONFIG_BLUETOOTH_UART),y)
CSRCS += bt_uart.c
endif
# Include common Bluetooth drvier build support
DEPPATH += --dep-path wireless$(DELIM)bluetooth
VPATH += :wireless$(DELIM)bluetooth
CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)drivers$(DELIM)wireless$(DELIM)bluetooth}
endif # CONFIG_DRIVERS_BLUETOOTH
/****************************************************************************
* drivers/wireless/bluetooth/btuart.c
* UART based Bluetooth driver
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stddef.h>
#include <assert.h>
#include <errno.h>
#include <nuttx/kmalloc.h>
#include <nuttx/wireless/bt_core.h>
#include <nuttx/wireless/bt_hci.h>
#include <nuttx/wireless/bt_driver.h>
#include <nuttx/wireless/bt_uart.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define H4_HEADER_SIZE 1
#define H4_CMD 0x01
#define H4_ACL 0x02
#define H4_SCO 0x03
#define H4_EVT 0x04
/****************************************************************************
* Private Types
****************************************************************************/
struct btuart_upperhalf_s
{
/* This structure must appear first in the structure so that this structure
* is cast compatible with struct bt_driver_s.
*/
struct bt_driver_s dev;
/* The cached lower half interface */
FAR const struct btuart_lowerhalf_s *lower;
};
/****************************************************************************
* Private Functions
****************************************************************************/
static ssize_t btuart_read(FAR struct btuart_upperhalf_s *upper,
FAR uint8_t *buffer, size_t buflen,
size_t minread)
{
FAR const struct btuart_lowerhalf_s *lower;
ssize_t nread;
ssize_t ntotal = 0;
DEBUGASSERT(upper != NULL && upper->lower != NULL);
lower = upper->lower;
DEBUGASSERT(lower->read != NULL);
while (buflen > 0)
{
nread = lower->read(lower, buffer, buflen);
if (nread == 0)
{
wlinfo("Got zero bytes from UART\n");
if (ntotal < minread)
{
continue;
}
break;
}
else if (nread < 0)
{
return nread;
}
wlinfo("read %ld remaining %lu\n",
(long)nread, (unsigned long)(buflen - nread));
buflen -= nread;
ntotal += nread;
buffer += nread;
}
return ntotal;
}
static FAR struct bt_buf_s *btuart_evt_recv(FAR struct btuart_upperhalf_s *upper,
FAR int *remaining)
{
FAR struct bt_buf_s *buf;
struct bt_hci_evt_hdr_s hdr;
ssize_t nread;
/* We can ignore the return value since we pass buflen == minread */
nread = btuart_read(upper, (FAR uint8_t *)&hdr,
sizeof(struct bt_hci_evt_hdr_s),
sizeof(struct bt_hci_evt_hdr_s));
if (nread < 0)
{
return NULL;
}
*remaining = hdr.len;
buf = bt_buf_get(BT_EVT, 0);
if (buf != NULL)
{
memcpy(bt_buf_add(buf, sizeof(struct bt_hci_evt_hdr_s)), &hdr,
sizeof(struct bt_hci_evt_hdr_s));
}
else
{
wlerr("ERROR: No available event buffers!\n");
}
wlinfo("len %u\n", hdr.len);
return buf;
}
static FAR struct bt_buf_s *btuart_acl_recv(FAR struct btuart_upperhalf_s *upper,
FAR int *remaining)
{
FAR struct bt_buf_s *buf;
struct bt_hci_acl_hdr_s hdr;
ssize_t nread;
/* We can ignore the return value since we pass buflen == minread */
nread = btuart_read(upper, (FAR uint8_t *)&hdr,
sizeof(struct bt_hci_acl_hdr_s),
sizeof(struct bt_hci_acl_hdr_s));
if (nread < 0)
{
return NULL;
}
buf = bt_buf_get(BT_ACL_IN, 0);
if (buf)
{
memcpy(bt_buf_add(buf, sizeof(struct bt_hci_acl_hdr_s)), &hdr,
sizeof(struct bt_hci_acl_hdr_s));
}
else
{
wlerr("ERROR: No available ACL buffers!\n");
}
*remaining = BT_LE162HOST(hdr.len);
wlinfo("len %u\n", *remaining);
return buf;
}
static void btuart_interrupt(FAR const struct btuart_lowerhalf_s *lower,
FAR void *arg)
{
FAR struct btuart_upperhalf_s *upper;
static FAR struct bt_buf_s *buf;
static int remaining;
ssize_t nread;
DEBUGASSERT(lower != NULL && lower->rxdrain != NULL && arg != NULL);
upper = (FAR struct btuart_upperhalf_s *)arg;
/* Beginning of a new packet */
while (remaining > 0)
{
uint8_t type;
/* Get packet type */
nread = btuart_read(upper, &type, 1, 0);
if (nread != sizeof(type))
{
wlwarn("WARNING: Unable to read H4 packet type\n");
continue;
}
switch (type)
{
case H4_EVT:
buf = btuart_evt_recv(upper, &remaining);
break;
case H4_ACL:
buf = btuart_acl_recv(upper, &remaining);
break;
default:
wlerr("ERROR: Unknown H4 type %u\n", type);
return;
}
if (buf != NULL && remaining > bt_buf_tailroom(buf))
{
wlerr("ERROR: Not enough space in buffer\n");
goto failed;
}
wlinfo("Need to get %u bytes\n", remaining);
}
if (buf == NULL)
{
nread = lower->rxdrain(lower);
wlwarn("WARNING: Discarded %ld bytes\n", (long)nread);
remaining -= nread;
}
nread = btuart_read(upper, bt_buf_tail(buf), remaining, 0);
buf->len += nread;
remaining -= nread;
wlinfo("Received %ld bytes\n", (long)nread);
if (remaining == 0)
{
wlinfo("Full packet received\n");
/* Pass buffer to the stack */
bt_recv(buf);
buf = NULL;
}
return;
failed:
bt_buf_put(buf);
remaining = 0;
buf = NULL;
return;
}
static int btuart_send(FAR const struct bt_driver_s *dev,
FAR struct bt_buf_s *buf)
{
FAR struct btuart_upperhalf_s *upper;
FAR const struct btuart_lowerhalf_s *lower;
FAR uint8_t *type;
ssize_t nwritten;
upper = (FAR struct btuart_upperhalf_s *)dev;
DEBUGASSERT(upper != NULL && upper->lower != NULL);
lower = upper->lower;
if (bt_buf_headroom(buf) < H4_HEADER_SIZE)
{
wlerr("Not enough headroom in buffer\n");
return -EINVAL;
}
type = bt_buf_push(buf, 1);
switch (buf->type)
{
case BT_CMD:
*type = H4_CMD;
break;
case BT_ACL_OUT:
*type = H4_ACL;
break;
case BT_EVT:
*type = H4_EVT;
break;
default:
wlerr("Unknown buf type %u\n", buf->type);
return -EINVAL;
}
nwritten = lower->write(lower, buf->data, buf->len);
if (nwritten == buf->len)
{
return OK;
}
if (nwritten < 0)
{
return (int)nwritten;
}
return -EIO;
}
static int btuart_open(FAR const struct bt_driver_s *dev)
{
FAR struct btuart_upperhalf_s *upper;
FAR const struct btuart_lowerhalf_s *lower;
upper = (FAR struct btuart_upperhalf_s *)dev;
DEBUGASSERT(upper != NULL && upper->lower != NULL);
lower = upper->lower;
/* Disable Tx and Rx interrupts */
lower->txenable(lower, false);
lower->rxenable(lower, false);
/* Drain any cached Rx data */
(void)lower->rxdrain(lower);
/* Enable Rx interrupts */
lower->rxenable(lower, true);
return OK;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: btuart_register
*
* Description:
* 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;
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;
/* Attach the interrupt handler */
lower->attach(lower, btuart_interrupt, upper);
/* And register the driver with the Bluetooth stack */
ret = bt_driver_register(&upper->dev);
if (ret < 0)
{
kmm_free(upper);
}
return ret;
}
/****************************************************************************
* wireless/bluetooth/bt_att.h
* Bluetooth buffer management.
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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_BUF_H
#define __INCLUDE_NUTTX_WIRELESS_BT_BUF_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <stddef.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* BT_BUF_MAX_DATA
* Maximum amount of data that can fit in a buffer.
*
* The biggest foreseeable buffer size requirement right now comes from
* the Bluetooth 4.2 SMP MTU which is 65. This then become 65 + 4 (L2CAP
* header) + 4 (ACL header) + 1 (H4 header) = 74. This also covers the
* biggest HCI commands and events which are a bit under the 70 byte
* mark.
*/
#define BT_BUF_MAX_DATA 74
/****************************************************************************
* Public Types
****************************************************************************/
/* Type of data contained in a buffer */
enum bt_buf_type_e
{
BT_CMD, /* HCI command */
BT_EVT, /* HCI event */
BT_ACL_OUT, /* Outgoing ACL data */
BT_ACL_IN, /* Incoming ACL data */
BT_DUMMY = BT_CMD /* Only used for waking up kernel threads */
};
/* HCI command specific information */
struct bt_buf_hci_data_s
{
/* Used by bt_hci_cmd_send_sync. Initially contains the waiting
* semaphore, as the semaphore is given back contains the bt_buf
* for the return parameters.
*/
FAR void *sync;
/* The command opcode that the buffer contains */
uint16_t opcode;
};
/* ACL data buffer specific information */
struct bt_buf_acl_data_s
{
uint16_t handle;
};
struct bt_buf_s
{
FAR struct iob_s *iob; /* IOB container of the buffer */
union
{
struct bt_buf_hci_data_s hci;
struct bt_buf_acl_data_s acl;
} u;
FAR uint8_t *data; /* Start of data in the buffer */
uint8_t len; /* Length of data in the buffer */
uint8_t ref : 5; /* Reference count */
uint8_t type : 3; /* Type of data contained in the buffer */
/* The full available buffer. */
uint8_t buf[BT_BUF_MAX_DATA];
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: bt_buf_get
*
* Description:
* Get buffer from the available buffers pool with specified type and
* reserved headroom.
*
* Input Parameters:
* type - Buffer type.
* reserve_head - How much headroom to reserve.
*
* Returned Value:
* New buffer or NULL if out of buffers.
*
* WARNING: If there are no available buffers and the function is
* called from a task or thread the call will block until a buffer
* becomes available in the pool.
*
****************************************************************************/
FAR struct bt_buf_s *bt_buf_get(enum bt_buf_type_e type, size_t reserve_head);
/****************************************************************************
* Name: bt_buf_put
*
* Description:
* Decrements the reference count of a buffer and puts it back into the
* pool if the count reaches zero.
*
* Input Parameters:
* buf - Buffer.
*
****************************************************************************/
void bt_buf_put(FAR struct bt_buf_s *buf);
/****************************************************************************
* Name: bt_buf_hold
*
* Description:
* Increment the reference count of a buffer.
*
* Input Parameters:
* buf - Buffer.
*
****************************************************************************/
FAR struct bt_buf_s *bt_buf_hold(FAR struct bt_buf_s *buf);
/****************************************************************************
* Name: bt_buf_add
*
* Description:
* Increments the data length of a buffer to account for more data
* at the end.
*
* Input Parameters:
* buf - Buffer to update.
* len - Number of bytes to increment the length with.
*
* Returned Value:
* The original tail of the buffer.
*
****************************************************************************/
FAR void *bt_buf_add(FAR struct bt_buf_s *buf, size_t len);
/****************************************************************************
* Name: bt_buf_add_le16
*
* Description:
* Adds 16-bit value in little endian format at the end of buffer.
* Increments the data length of a buffer to account for more data
* at the end.
*
* Input Parameters:
* buf - Buffer to update.
* value - 16-bit value to be added.
*
* Returned Value:
* None
*
****************************************************************************/
void bt_buf_add_le16(FAR struct bt_buf_s *buf, uint16_t value);
/****************************************************************************
* Name: bt_buf_push
*
* Description:
* Modifies the data pointer and buffer length to account for more data
* in the beginning of the buffer.
*
* Input Parameters:
* buf - Buffer to update.
* len - Number of bytes to add to the beginning.
*
* Returned Value:
* The new beginning of the buffer data.
*
****************************************************************************/
FAR void *bt_buf_push(FAR struct bt_buf_s *buf, size_t len);
/****************************************************************************
* Name: bt_buf_pull
*
* Description:
* Removes data from the beginning of the buffer by modifying the data
* pointer and buffer length.
*
* Input Parameters:
* len - Number of bytes to remove.
*
* Returned Value:
* New beginning of the buffer data.
*
****************************************************************************/
FAR void *bt_buf_pull(FAR struct bt_buf_s *buf, size_t len);
/****************************************************************************
* Name: bt_buf_pull_le16
*
* Description:
* Same idea as with bt_buf_pull(), but a helper for operating on
* 16-bit little endian data.
*
* Input Parameters:
* buf - Buffer.
*
* Returned Value:
* 16-bit value converted from little endian to host endian.
*
****************************************************************************/
uint16_t bt_buf_pull_le16(FAR struct bt_buf_s *buf);
/****************************************************************************
* Name: bt_buf_tailroom
*
* Description:
* Check how much free space there is at the end of the buffer.
*
* Returned Value:
* Number of bytes available at the end of the buffer.
*
****************************************************************************/
size_t bt_buf_tailroom(FAR struct bt_buf_s *buf);
/****************************************************************************
* Name: bt_buf_headroom
*
* Description:
* Check how much free space there is in the beginning of the buffer.
*
* Returned Value:
* Number of bytes available in the beginning of the buffer.
*
****************************************************************************/
size_t bt_buf_headroom(FAR struct bt_buf_s *buf);
/****************************************************************************
* Name: bt_buf_tail
*
* Description:
* Get a pointer to the end of the data in a buffer.
*
* Input Parameters:
* buf - Buffer.
*
* Returned Value:
* Tail pointer for the buffer.
*
****************************************************************************/
#define bt_buf_tail(buf) ((buf)->data + (buf)->len)
/****************************************************************************
* Name: bt_buf_init
*
* Description:
* Initialize the buffers with specified amount of incoming and outgoing
* ACL buffers. The HCI command and event buffers will be allocated from
* whatever is left over.
*
* Input Parameters:
* None.
*
* Returned Value:
* Zero on success or (negative) error code on failure.
*
****************************************************************************/
int bt_buf_init(void);
#endif /* __INCLUDE_NUTTX_WIRELESS_BT_BUF_H */
/****************************************************************************
* wireless/bluetooth/bt_conn.h
* Bluetooth connection handling.
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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_CONN_H
#define __INCLUDE_NUTTX_WIRELESS_BT_CONN_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdbool.h>
#include <nuttx/wireless/bt_core.h>
#include <nuttx/wireless/bt_hci.h>
/****************************************************************************
* Public Types
****************************************************************************/
/* Connection callback structure */
struct bt_conn_s; /* Forward Reference */
struct bt_conn_cb_s
{
CODE void (*connected)(FAR struct bt_conn_s *conn);
CODE void (*disconnected)(FAR struct bt_conn_s *conn);
FAR struct bt_conn_cb_s *next;
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: bt_conn_get
*
* Description:
* Increment the reference count of a connection object.
*
* Input Parameters:
* conn - Connection object.
*
* Returned Value:
* Connection object with incremented reference count.
*
****************************************************************************/
FAR struct bt_conn_s *bt_conn_get(FAR struct bt_conn_s *conn);
/****************************************************************************
* Name: bt_conn_put
*
* Description:
* Decrement the reference count of a connection object.
*
* Input Parameters:
* conn - Connection object.
*
****************************************************************************/
void bt_conn_put(FAR struct bt_conn_s *conn);
/****************************************************************************
* Name: bt_conn_lookup_addr_le
*
* Description:
* Look up an existing connection based on the remote address.
*
* Input Parameters:
* peer - Remote address.
*
* Returned Value:
* Connection object or NULL if not found. The caller gets a new reference
* to the connection object which must be released with bt_conn_put() once
* done using the object.
*
****************************************************************************/
FAR struct bt_conn_s *bt_conn_lookup_addr_le(const bt_addr_le_t *peer);
/****************************************************************************
* Name: bt_conn_get_dst
*
* Description:
* Get destination (peer) address of a connection.
*
* Input Parameters:
* conn - Connection object.
*
* Returned Value:
* Destination address.
*
****************************************************************************/
FAR const bt_addr_le_t *bt_conn_get_dst(FAR const struct bt_conn_s *conn);
/****************************************************************************
* Name: bt_conn_disconnect
*
* Description:
* Disconnect an active connection with the specified reason code or cancel
* pending outgoing connection.
*
* Input Parameters:
* conn - Connection to disconnect.
* reason - Reason code for the disconnection.
*
* Returned Value:
* Zero on success or (negative) error code on failure.
*
****************************************************************************/
int bt_conn_disconnect(FAR struct bt_conn_s *conn, uint8_t reason);
/****************************************************************************
* Name: bt_conn_create_le
*
* Description:
* Allows initiate new LE link to remote peer using its address.
* Returns a new reference that the the caller is responsible for managing.
*
* Input Parameters:
* peer - Remote address.
*
* Returned Value:
* Valid connection object on success or NULL otherwise.
*
****************************************************************************/
FAR struct bt_conn_s *bt_conn_create_le(const bt_addr_le_t *peer);
/****************************************************************************
* Name: bt_conn_security
*
* Description:
* This function enable security (encryption) for a connection. If device is
* already paired with sufficiently strong key encryption will be enabled. If
* link is already encrypted with sufficiently strong key this function does
* nothing.
*
* If device is not paired pairing will be initiated. If device is paired and
* keys are too weak but input output capabilities allow for strong enough keys
* pairing will be initiated.
*
* This function may return error if required level of security is not possible
* to achieve due to local or remote device limitation (eg input output
* capabilities).
*
* Input Parameters:
* conn - Connection object.
* sec - Requested security level.
*
* Returned Value:
* 0 on success or negative error
*
****************************************************************************/
int bt_conn_security(FAR struct bt_conn_s *conn, enum bt_security_e sec);
/****************************************************************************
* Name: bt_conn_cb_register
*
* Description:
* Register callbacks to monitor the state of connections.
*
* Input Parameters:
* cb - Callback struct.
*
****************************************************************************/
void bt_conn_cb_register(struct bt_conn_cb_s *cb);
/****************************************************************************
* Name:
*
* Description:
* This function enables/disables automatic connection initiation.
* Every time the device looses the connection with peer, this connection
* will be re-established if connectible advertisement from peer is
* received.
*
* Input Parameters:
* conn - Existing connection object.
* auto_conn - boolean value. If true, auto connect is enabled, if false,
* auto connect is disabled.
*
* Returned Value:
* None
*
****************************************************************************/
void bt_conn_set_auto_conn(FAR struct bt_conn_s *conn, bool auto_conn);
#endif /* __INCLUDE_NUTTX_WIRELESS_BT_CONN_H */
/****************************************************************************
* wireless/bluetooth/bt_core.h
* Bluetooth subsystem core APIs.
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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_CORE_H
#define __INCLUDE_NUTTX_WIRELESS_BT_CORE_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdio.h>
#include <string.h>
#include <nuttx/wireless/bt_buf.h>
#include <nuttx/wireless/bt_hci.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/* BT_ADDR_STR_LEN
* Recommended length of user string buffer for Bluetooth address
*
* The recommended length guarantee the output of address conversion will not
* lose valuable information about address being processed.
*/
#define BT_ADDR_STR_LEN 18
/* BT_ADDR_LE_STR_LEN
* Recommended length of user string buffer for Bluetooth LE address
*
* The recommended length guarantee the output of address conversion will not
* lose valuable information about address being processed.
*/
#define BT_ADDR_LE_STR_LEN 27
/* BT_LE162HOST
* Convert 16-bit integer from little-endian to host endianness.
*/
#ifdef CONFIG_ENDIAN_BIG
# define BT_LE162HOST(le) \
((((uint16_t)(le) >> 8) & 0xff) | (((uint16_t)(le) & 0xff) << 8))
#else
# define BT_LE162HOST(le) (le)
#endif
/* BT_HOST2LE16
* Convert 16-bit integer from host endianness to little-endian.
*/
#ifdef CONFIG_ENDIAN_BIG
# define BT_HOST2LE16(h) \
((((uint16_t)(h) >> 8) & 0xff) | (((uint16_t)(h) & 0xff) << 8))
#else
# define BT_HOST2LE16(h) (h)
#endif
/* Unaligned access */
#ifdef CONFIG_ENDIAN_BIG
# define BT_GETUINT16(p) \
((((uint16_t)(((FAR uint8_t *)(p))[1]) >> 8) & 0xff) | \
(((uint16_t)(((FAR uint8_t *)(p))[0]) & 0xff) << 8))
# define BT_PUTUINT16(p,v) \
do \
{ \
((FAR uint8_t *)(p))[0] = ((uint16_t)(v) >> 8) & 0xff; \
((FAR uint8_t *)(p))[1] = ((uint16_t)(v) & 0xff) >> 8; \
} \
while (0)
#else
# define BT_GETUINT16(p) \
((((uint16_t)(((FAR uint8_t *)(p))[0]) >> 8) & 0xff) | \
(((uint16_t)(((FAR uint8_t *)(p))[1]) & 0xff) << 8))
# define BT_PUTUINT16(p,v) \
do \
{ \
((FAR uint8_t *)(p))[0] = ((uint16_t)(v) & 0xff) >> 8; \
((FAR uint8_t *)(p))[1] = ((uint16_t)(v) >> 8) & 0xff; \
} \
while (0)
#endif
/****************************************************************************
* Public Types
****************************************************************************/
/* Advertising API */
begin_packed_struct struct bt_eir_s
{
uint8_t len;
uint8_t type;
uint8_t data[29];
} end_packed_struct;
/* Security level */
enum bt_security_e
{
BT_SECURITY_LOW, /* No encryption and no authentication. */
BT_SECURITY_MEDIUM, /* encryption and no authentication (no MITM). */
BT_SECURITY_HIGH, /* encryption and authentication (MITM). */
BT_SECURITY_FIPS, /* Authenticated LE Secure Connections and
* encryption. */
};
/****************************************************************************
* Name: bt_le_scan_cb_t
*
* Description:
* A function of this type will be called back when user application
* triggers active LE scan. The caller will populate all needed
* parameters based on data coming from scan result.
* Such function can be set by user when LE active scan API is used.
*
* Input Parameters:
* addr - Advertiser LE address and type.
* rssi - Strength of advertiser signal.
* adv_type - Type of advertising response from advertiser.
* adv_data - Address of buffer containing advertiser data.
* len - Length of advertiser data contained in buffer.
*
****************************************************************************/
typedef CODE void bt_le_scan_cb_t(FAR const bt_addr_le_t *addr, int8_t rssi,
uint8_t adv_type,
FAR const uint8_t *adv_data, uint8_t len);
/****************************************************************************
* Inline Functions
****************************************************************************/
/****************************************************************************
* Name: bt_addr_to_str
*
* Description:
* Converts binary Bluetooth address to string.
*
* Input Parameters:
* addr - Address of buffer containing binary Bluetooth address.
* str - Address of user buffer with enough room to store formatted
* string containing binary address.
* len - Length of data to be copied to user string buffer. Refer to
* BT_ADDR_STR_LEN about recommended value.
*
* Returned Value:
* Number of successfully formatted bytes from binary address.
*
****************************************************************************/
static inline int bt_addr_to_str(FAR const bt_addr_t *addr, FAR char *str,
size_t len)
{
return snprintf(str, len, "%2.2X:%2.2X:%2.2X:%2.2X:%2.2X:%2.2X",
addr->val[5], addr->val[4], addr->val[3],
addr->val[2], addr->val[1], addr->val[0]);
}
/****************************************************************************
* Name: bt_addr_le_to_str
*
* Description:
* Converts binary LE Bluetooth address to string.
*
* Input Parameters:
* addr - Address of buffer containing binary LE Bluetooth address.
* user_buf - Address of user buffer with enough room to store
* formatted string containing binary LE address.
* len - Length of data to be copied to user string buffer. Refer to
* BT_ADDR_LE_STR_LEN about recommended value.
*
* Returned Value:
* Number of successfully formatted bytes from binary address.
*
****************************************************************************/
static inline int bt_addr_le_to_str(const bt_addr_le_t *addr, char *str,
size_t len)
{
char type[7];
switch (addr->type)
{
case BT_ADDR_LE_PUBLIC:
strcpy(type, "public");
break;
case BT_ADDR_LE_RANDOM:
strcpy(type, "random");
break;
default:
sprintf(type, "0x%02x", addr->type);
break;
}
return snprintf(str, len, "%2.2X:%2.2X:%2.2X:%2.2X:%2.2X:%2.2X (%s)",
addr->val[5], addr->val[4], addr->val[3],
addr->val[2], addr->val[1], addr->val[0], type);
}
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: bt_init
*
* Description:
* Initialize Bluetooth. Must be the called before anything else.
*
* Returned Value:
* Zero on success or (negative) error code otherwise.
*
****************************************************************************/
int bt_init(void);
/****************************************************************************
* Name: bt_start_advertising
*
* Description:
* Set advertisement data, scan response data, advertisement parameters
* and start advertising.
*
* Input Parameters:
* type - Advertising type.
* ad - Data to be used in advertisement packets.
* sd - Data to be used in scan response packets.
*
* Returned Value:
* Zero on success or (negative) error code otherwise.
*
****************************************************************************/
int bt_start_advertising(uint8_t type, FAR const struct bt_eir_s *ad,
FAR const struct bt_eir_s *sd);
/****************************************************************************
* Name: bt_stop_advertising
*
* Description:
* Stops ongoing advertising.
*
* Returned Value:
* Zero on success or (negative) error code otherwise.
*
****************************************************************************/
int bt_stop_advertising(void);
/****************************************************************************
* Name: bt_start_scanning
*
* Description:
* Start LE scanning with and provide results through the specified
* callback.
*
* Input Parameters:
* filter_dups - Enable duplicate filtering (or not).
* cb - Callback to notify scan results.
*
* Returned Value:
* Zero on success or error code otherwise, positive in case
* of protocol error or negative (POSIX) in case of stack internal error
*
****************************************************************************/
int bt_start_scanning(uint8_t filter_dups, bt_le_scan_cb_t cb);
/****************************************************************************
* Name: bt_stop_scanning
*
* Description:
* Stops ongoing LE scanning.
*
* Returned Value:
* Zero on success or error code otherwise, positive in case
* of protocol error or negative (POSIX) in case of stack internal error
*
****************************************************************************/
int bt_stop_scanning(void);
#endif /* __INCLUDE_NUTTX_WIRELESS_BT_CORE_H */
/****************************************************************************
* wireless/bluetooth/bt_driver.h
* Bluetooth HCI driver API.
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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_DRIVER_H
#define __INCLUDE_NUTTX_WIRELESS_BT_DRIVER_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/wireless/bt_buf.h>
/****************************************************************************
* Public Types
****************************************************************************/
struct bt_driver_s
{
/* How much headroom is needed for HCI transport headers */
size_t head_reserve;
/* Open the HCI transport */
CODE int (*open)(FAR const struct bt_driver_s *dev);
/* Send data to HCI */
CODE int (*send)(FAR const struct bt_driver_s *dev,
FAR struct bt_buf_s *buf);
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/* Register a new HCI driver to the Bluetooth stack */
int bt_driver_register(FAR const struct bt_driver_s *dev);
/* Unregister a previously registered HCI driver */
void bt_driver_unregister(FAR const struct bt_driver_s *dev);
/* Receive data from the controller/HCI driver */
void bt_recv(FAR struct bt_buf_s *buf);
#endif /* __INCLUDE_NUTTX_WIRELESS_BT_DRIVER_H */
This diff is collapsed.
/****************************************************************************
* wireless/bluetooth/bt_hci.h
* Bluetooth Host Control Interface definitions.
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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_HCI_H
#define __INCLUDE_NUTTX_WIRELESS_BT_HCI_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define BT_ADDR_LE_PUBLIC 0x00
#define BT_ADDR_LE_RANDOM 0x01
#define BT_ADDR_ANY (&(bt_addr_t) {{0, 0, 0, 0, 0, 0}})
#define BT_ADDR_LE_ANY (&(bt_addr_le_t) { 0, {0, 0, 0, 0, 0, 0}})
/* HCI Error Codes */
#define BT_HCI_ERR_AUTHENTICATION_FAIL 0x05
#define BT_HCI_ERR_REMOTE_USER_TERM_CONN 0x13
#define BT_HCI_ERR_UNSUPP_REMOTE_FEATURE 0x1a
#define BT_HCI_ERR_PAIRING_NOT_SUPPORTED 0x29
#define BT_HCI_ERR_UNACCEPT_CONN_PARAMS 0x3b
/* EIR/AD definitions */
#define BT_EIR_FLAGS 0x01 /* AD flags */
#define BT_EIR_UUID16_SOME 0x02 /* 16-bit UUID, more available */
#define BT_EIR_UUID16_ALL 0x03 /* 16-bit UUID, all listed */
#define BT_EIR_UUID32_SOME 0x04 /* 32-bit UUID, more available */
#define BT_EIR_UUID32_ALL 0x05 /* 32-bit UUID, all listed */
#define BT_EIR_UUID128_SOME 0x06 /* 128-bit UUID, more available */
#define BT_EIR_UUID128_ALL 0x07 /* 128-bit UUID, all listed */
#define BT_EIR_NAME_COMPLETE 0x09 /* Complete name */
#define BT_EIR_TX_POWER 0x0a /* Tx Power */
#define BT_EIR_SOLICIT16 0x14 /* Solicit UUIDs, 16-bit */
#define BT_EIR_SOLICIT128 0x15 /* Solicit UUIDs, 128-bit */
#define BT_EIR_SVC_DATA16 0x16 /* Service data, 16-bit UUID */
#define BT_EIR_GAP_APPEARANCE 0x19 /* GAP appearance */
#define BT_EIR_SOLICIT32 0x1f /* Solicit UUIDs, 32-bit */
#define BT_EIR_SVC_DATA32 0x20 /* Service data, 32-bit UUID */
#define BT_EIR_SVC_DATA128 0x21 /* Service data, 128-bit UUID */
#define BT_EIR_MANUFACTURER_DATA 0xff /* Manufacturer Specific Data */
#define BT_LE_AD_GENERAL 0x02 /* General Discoverable */
#define BT_LE_AD_NO_BREDR 0x04 /* BR/EDR not supported */
#define bt_acl_handle(h) ((h) & 0x0fff)
/* LMP features */
#define BT_LMP_NO_BREDR 0x20
#define BT_LMP_LE 0x40
/* LE features */
#define BT_HCI_LE_ENCRYPTION 0x01
/* OpCode Group Fields */
#define BT_OGF_LINK_CTRL 0x01
#define BT_OGF_BASEBAND 0x03
#define BT_OGF_INFO 0x04
#define BT_OGF_LE 0x08
/* Construct OpCode from OGF and OCF */
#define BT_OP(ogf, ocf) ((ocf) | ((ogf) << 10))
#define BT_HCI_OP_DISCONNECT BT_OP(BT_OGF_LINK_CTRL, 0x0006)
#define BT_HCI_OP_SET_EVENT_MASK BT_OP(BT_OGF_BASEBAND, 0x0001)
#define BT_HCI_OP_RESET BT_OP(BT_OGF_BASEBAND, 0x0003)
#define BT_HCI_OP_SET_CTL_TO_HOST_FLOW BT_OP(BT_OGF_BASEBAND, 0x0031)
#define BT_HCI_OP_HOST_BUFFER_SIZE BT_OP(BT_OGF_BASEBAND, 0x0033)
#define BT_HCI_OP_HOST_NUM_COMPLETED_PACKETS BT_OP(BT_OGF_BASEBAND, 0x0035)
#define BT_HCI_OP_LE_WRITE_LE_HOST_SUPP BT_OP(BT_OGF_BASEBAND, 0x006d)
#define BT_HCI_OP_READ_LOCAL_VERSION_INFO BT_OP(BT_OGF_INFO, 0x0001)
#define BT_HCI_OP_READ_LOCAL_FEATURES BT_OP(BT_OGF_INFO, 0x0003)
#define BT_HCI_OP_READ_BUFFER_SIZE BT_OP(BT_OGF_INFO, 0x0005)
#define BT_HCI_OP_READ_BD_ADDR BT_OP(BT_OGF_INFO, 0x0009)
#define BT_HCI_OP_LE_READ_BUFFER_SIZE BT_OP(BT_OGF_LE, 0x0002)
#define BT_HCI_OP_LE_READ_LOCAL_FEATURES BT_OP(BT_OGF_LE, 0x0003)
/* Advertising types */
#define BT_LE_ADV_IND 0x00
#define BT_LE_ADV_DIRECT_IND 0x01
#define BT_LE_ADV_SCAN_IND 0x02
#define BT_LE_ADV_NONCONN_IND 0x03
#define BT_LE_ADV_SCAN_RSP 0x04
#define BT_HCI_OP_LE_SET_ADV_PARAMETERS BT_OP(BT_OGF_LE, 0x0006)
#define BT_HCI_OP_LE_SET_ADV_DATA BT_OP(BT_OGF_LE, 0x0008)
#define BT_HCI_OP_LE_SET_SCAN_RSP_DATA BT_OP(BT_OGF_LE, 0x0009)
#define BT_HCI_OP_LE_SET_ADV_ENABLE BT_OP(BT_OGF_LE, 0x000a)
/* Scan types */
#define BT_HCI_OP_LE_SET_SCAN_PARAMS BT_OP(BT_OGF_LE, 0x000b)
# define BT_LE_SCAN_PASSIVE 0x00
# define BT_LE_SCAN_ACTIVE 0x01
#define BT_HCI_OP_LE_SET_SCAN_ENABLE BT_OP(BT_OGF_LE, 0x000c)
# define BT_LE_SCAN_DISABLE 0x00
# define BT_LE_SCAN_ENABLE 0x01
# define BT_LE_SCAN_FILTER_DUP_DISABLE 0x00
# define BT_LE_SCAN_FILTER_DUP_ENABLE 0x01
#define BT_HCI_OP_LE_CREATE_CONN BT_OP(BT_OGF_LE, 0x000d)
#define BT_HCI_OP_LE_CREATE_CONN_CANCEL BT_OP(BT_OGF_LE, 0x000e)
#define BT_HCI_OP_LE_CONN_UPDATE BT_OP(BT_OGF_LE, 0x0013)
#define BT_HCI_OP_LE_ENCRYPT BT_OP(BT_OGF_LE, 0x0017)
#define BT_HCI_OP_LE_RAND BT_OP(BT_OGF_LE, 0x0018)
#define BT_HCI_OP_LE_START_ENCRYPTION BT_OP(BT_OGF_LE, 0x0019)
#define BT_HCI_OP_LE_LTK_REQ_REPLY BT_OP(BT_OGF_LE, 0x001a)
#define BT_HCI_OP_LE_LTK_REQ_NEG_REPLY BT_OP(BT_OGF_LE, 0x001b)
/* Event definitions */
#define BT_HCI_EVT_DISCONN_COMPLETE 0x05
#define BT_HCI_EVT_ENCRYPT_CHANGE 0x08
#define BT_HCI_EVT_CMD_COMPLETE 0x0e
#define BT_HCI_EVT_CMD_STATUS 0x0f
#define BT_HCI_EVT_NUM_COMPLETED_PACKETS 0x13
#define BT_HCI_EVT_ENCRYPT_KEY_REFRESH_COMPLETE 0x30
#define BT_HCI_EVT_LE_META_EVENT 0x3e
#define BT_HCI_EVT_LE_CONN_COMPLETE 0x01
# define BT_HCI_ROLE_MASTER 0x00
# define BT_HCI_ROLE_SLAVE 0x01
#define BT_HCI_EVT_LE_ADVERTISING_REPORT 0x02
#define BT_HCI_EVT_LE_LTK_REQUEST 0x05
/****************************************************************************
* Public Types
****************************************************************************/
typedef struct bt_addr_s
{
uint8_t val[6];
} bt_addr_t;
typedef struct bt_addr_le_s
{
uint8_t type;
uint8_t val[6];
} bt_addr_le_t;
begin_packed_struct struct bt_hci_evt_hdr_s
{
uint8_t evt;
uint8_t len;
} end_packed_struct;
begin_packed_struct struct bt_hci_acl_hdr_s
{
uint16_t handle;
uint16_t len;
} end_packed_struct;
begin_packed_struct struct bt_hci_cmd_hdr_s
{
uint16_t opcode;
uint8_t param_len;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_disconnect_s
{
uint16_t handle;
uint8_t reason;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_set_event_mask_s
{
uint8_t events[8];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_host_buffer_size_s
{
uint16_t acl_mtu;
uint8_t sco_mtu;
uint16_t acl_pkts;
uint16_t sco_pkts;
} end_packed_struct;
begin_packed_struct struct bt_hci_handle_count_s
{
uint16_t handle;
uint16_t count;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_host_num_completed_packets_s
{
uint8_t num_handles;
struct bt_hci_handle_count_s h[0];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_write_le_host_supp_s
{
uint8_t le;
uint8_t simul;
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_read_local_version_info_s
{
uint8_t status;
uint8_t hci_version;
uint16_t hci_revision;
uint8_t lmp_version;
uint16_t manufacturer;
uint16_t lmp_subversion;
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_read_local_features_s
{
uint8_t status;
uint8_t features[8];
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_read_buffer_size_s
{
uint8_t status;
uint16_t acl_max_len;
uint8_t sco_max_len;
uint16_t acl_max_num;
uint16_t sco_max_num;
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_read_bd_addr_s
{
uint8_t status;
bt_addr_t bdaddr;
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_le_read_buffer_size_s
{
uint8_t status;
uint16_t le_max_len;
uint8_t le_max_num;
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_le_read_local_features_s
{
uint8_t status;
uint8_t features[8];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_set_adv_parameters_s
{
uint16_t min_interval;
uint16_t max_interval;
uint8_t type;
uint8_t own_addr_type;
bt_addr_le_t direct_addr;
uint8_t channel_map;
uint8_t filter_policy;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_set_adv_data_s
{
uint8_t len;
uint8_t data[31];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_set_scan_rsp_data_s
{
uint8_t len;
uint8_t data[31];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_set_adv_enable_s
{
uint8_t enable;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_set_scan_params_s
{
uint8_t scan_type;
uint16_t interval;
uint16_t window;
uint8_t addr_type;
uint8_t filter_policy;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_set_scan_enable_s
{
uint8_t enable;
uint8_t filter_dup;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_create_conn_s
{
uint16_t scan_interval;
uint16_t scan_window;
uint8_t filter_policy;
bt_addr_le_t peer_addr;
uint8_t own_addr_type;
uint16_t conn_interval_min;
uint16_t conn_interval_max;
uint16_t conn_latency;
uint16_t supervision_timeout;
uint16_t min_ce_len;
uint16_t max_ce_len;
} end_packed_struct;
begin_packed_struct struct hci_cp_le_conn_update_s
{
uint16_t handle;
uint16_t conn_interval_min;
uint16_t conn_interval_max;
uint16_t conn_latency;
uint16_t supervision_timeout;
uint16_t min_ce_len;
uint16_t max_ce_len;
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_encrypt_s
{
uint8_t key[16];
uint8_t plaintext[16];
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_le_encrypt_s
{
uint8_t status;
uint8_t enc_data[16];
} end_packed_struct;
begin_packed_struct struct bt_hci_rp_le_rand_s
{
uint8_t status;
uint8_t rand[8];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_start_encryption_s
{
uint16_t handle;
uint64_t rand;
uint16_t ediv;
uint8_t ltk[16];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_ltk_req_reply_s
{
uint16_t handle;
uint8_t ltk[16];
} end_packed_struct;
begin_packed_struct struct bt_hci_cp_le_ltk_req_neg_reply_s
{
uint16_t handle;
} end_packed_struct;
/* Event definitions */
begin_packed_struct struct bt_hci_evt_disconn_complete_s
{
uint8_t status;
uint16_t handle;
uint8_t reason;
} end_packed_struct;
begin_packed_struct struct bt_hci_evt_encrypt_change_s
{
uint8_t status;
uint16_t handle;
uint8_t encrypt;
} end_packed_struct;
begin_packed_struct struct hci_evt_cmd_complete_s
{
uint8_t ncmd;
uint16_t opcode;
} end_packed_struct;
begin_packed_struct struct bt_hci_evt_cmd_status_s
{
uint8_t status;
uint8_t ncmd;
uint16_t opcode;
} end_packed_struct;
begin_packed_struct struct bt_hci_evt_num_completed_packets_s
{
uint8_t num_handles;
struct bt_hci_handle_count_s h[0];
} end_packed_struct;
begin_packed_struct struct bt_hci_evt_encrypt_key_refresh_complete_s
{
uint8_t status;
uint16_t handle;
} end_packed_struct;
begin_packed_struct struct bt_hci_evt_le_meta_event_s
{
uint8_t subevent;
} end_packed_struct;
begin_packed_struct struct bt_hci_evt_le_conn_complete_s
{
uint8_t status;
uint16_t handle;
uint8_t role;
bt_addr_le_t peer_addr;
uint16_t interval;
uint16_t latency;
uint16_t supv_timeout;
uint8_t clock_accuracy;
} end_packed_struct;
begin_packed_struct struct bt_hci_ev_le_advertising_info_s
{
uint8_t evt_type;
bt_addr_le_t addr;
uint8_t length;
uint8_t data[0];
} end_packed_struct;
begin_packed_struct struct bt_hci_evt_le_ltk_request_s
{
uint16_t handle;
uint64_t rand;
uint16_t ediv;
} end_packed_struct;
#endif /* __INCLUDE_NUTTX_WIRELESS_BT_HCI_H */
/****************************************************************************
* drivers/wireless/bluetooth/bt_uart.h
* UART based Bluetooth driver
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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_H
#define __INCLUDE_NUTTX_WIRELESS_BT_UART_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <stdbool.h>
/****************************************************************************
* Public Types
****************************************************************************/
/* This is the type of the Bluetooth UART upper-half driver interrupt
* handler used with the struct btuart_lowerhalf_s attach() method.
*/
struct btuart_lowerhalf_s;
typedef CODE void (*btuart_handler_t)
(FAR const struct btuart_lowerhalf_s *lower, FAR void *arg);
/* The Bluetooth UART driver is a two-part driver:
*
* 1) A common upper half driver that provides the common Bluetooth stack
* interface to UART.
* 2) Platform-specific lower half drivers that provide the interface
* between the common upper half and the platform-specific UARTs.
*
* This structure defines the interface between an instance of the lower
* half driver and the common upper half driver. Such an instance is
* passed to the upper half driver when the driver is initialized, binding
* the upper and lower halves into one driver.
*/
struct btuart_lowerhalf_s
{
/* Attach the upper half interrupt handler */
CODE void (*attach)(FAR const struct btuart_lowerhalf_s *lower,
btuart_handler_t handler, FAR void *arg);
/* Enable/disable RX/TX interrupts from the UART. */
CODE void (*rxenable)(FAR const struct btuart_lowerhalf_s *lower,
bool enable);
CODE void (*txenable)(FAR const struct btuart_lowerhalf_s *lower,
bool enable);
/* Read/write UART data */
CODE ssize_t (*read)(FAR const struct btuart_lowerhalf_s *lower,
FAR void *buffer, size_t buflen);
CODE ssize_t (*write)(FAR const struct btuart_lowerhalf_s *lower,
FAR const void *buffer, size_t buflen);
/* Flush/drain all buffered RX data */
CODE ssize_t (*rxdrain)(FAR const struct btuart_lowerhalf_s *lower);
};
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: btuart_register
*
* Description:
* 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);
#endif /* __INCLUDE_NUTTX_WIRELESS_BT_UART_H */
/****************************************************************************
* wireless/bluetooth/bt_uuid.h
* B Bluetooth UUID handling.
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
* where the code was released with a compatible 3-clause BSD license:
*
* Copyright (c) 2016, Intel Corporation
* All rights reserved.
*
* 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_UUID_H
#define __INCLUDE_NUTTX_WIRELESS_BT_UUID_H 1
/****************************************************************************
* Included Files
****************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/** @def BBT_UUID_GAP
* @brief Generic Access
*/
#define BT_UUID_GAP 0x1800
/** @def BBT_UUID_GATT
* @brief Generic Attribute
*/
#define BT_UUID_GATT 0x1801
/** @def BBT_UUID_CTS
* @brief Current Time Service
*/
#define BT_UUID_CTS 0x1805
/** @def BBT_UUID_DIS
* @brief Device Information Service
*/
#define BT_UUID_DIS 0x180a
/** @def BBT_UUID_HRS
* @brief Heart Rate Service
*/
#define BT_UUID_HRS 0x180d
/** @def BBT_UUID_BAS
* @brief Battery Service
*/
#define BT_UUID_BAS 0x180f
/** @def BT_UUID_GATT_PRIMARY
* @brief GATT Primary Service
*/
#define BT_UUID_GATT_PRIMARY 0x2800
/** @def BT_UUID_GATT_SECONDARY
* @brief GATT Secondary Service
*/
#define BT_UUID_GATT_SECONDARY 0x2801
/** @def BT_UUID_GATT_INCLUDE
* @brief GATT Include Service
*/
#define BT_UUID_GATT_INCLUDE 0x2802
/** @def BT_UUID_GATT_CHRC
* @brief GATT Characteristic
*/
#define BT_UUID_GATT_CHRC 0x2803
/** @def BT_UUID_GATT_CEP
* @brief GATT Characteristic Extended Properties
*/
#define BT_UUID_GATT_CEP 0x2900
/** @def BT_UUID_GATT_CUD
* @brief GATT Characteristic User Description
*/
#define BT_UUID_GATT_CUD 0x2901
/** @def BT_UUID_GATT_CCC
* @brief GATT Client Characteristic Configuration
*/
#define BT_UUID_GATT_CCC 0x2902
/** @def BT_UUID_GAP_DEVICE_NAME
* @brief GAP Characteristic Device Name
*/
#define BT_UUID_GAP_DEVICE_NAME 0x2a00
/** @def BT_UUID_GAP_APPEARANCE
* @brief GAP Characteristic Appearance
*/
#define BT_UUID_GAP_APPEARANCE 0x2a01
/** @def BT_UUID_BAS_BATTERY_LEVEL
* @brief BAS Characteristic Battery Level
*/
#define BT_UUID_BAS_BATTERY_LEVEL 0x2a19
/** @def BT_UUID_DIS_SYSTEM_ID
* @brief DIS Characteristic System ID
*/
#define BT_UUID_DIS_SYSTEM_ID 0x2a23
/** @def BT_UUID_DIS_MODEL_NUMBER_STRING
* @brief DIS Characteristic Model Number String
*/
#define BT_UUID_DIS_MODEL_NUMBER_STRING 0x2a24
/** @def BT_UUID_DIS_SERIAL_NUMBER_STRING
* @brief DIS Characteristic Serial Number String
*/
#define BT_UUID_DIS_SERIAL_NUMBER_STRING 0x2a25
/** @def BT_UUID_DIS_FIRMWARE_REVISION_STRING
* @brief DIS Characteristic Firmware Revision String
*/
#define BT_UUID_DIS_FIRMWARE_REVISION_STRING 0x2a26
/** @def BT_UUID_DIS_HARDWARE_REVISION_STRING
* @brief DIS Characteristic Hardware Revision String
*/
#define BT_UUID_DIS_HARDWARE_REVISION_STRING 0x2a27
/** @def BT_UUID_DIS_SOFTWARE_REVISION_STRING
* @brief DIS Characteristic Software Revision String
*/
#define BT_UUID_DIS_SOFTWARE_REVISION_STRING 0x2a28
/** @def BT_UUID_DIS_MANUFACTURER_NAME_STRING
* @brief DIS Characteristic Manufacturer Name String
*/
#define BT_UUID_DIS_MANUFACTURER_NAME_STRING 0x2a29
/** @def BT_UUID_DIS_PNP_ID
* @brief DIS Characteristic PnP ID
*/
#define BT_UUID_DIS_PNP_ID 0x2a50
/** @def BT_UUID_CTS_CURRENT_TIME
* @brief CTS Characteristic Current Time
*/
#define BT_UUID_CTS_CURRENT_TIME 0x2a2b
/** @def BT_UUID_HR_MEASUREMENT
* @brief HRS Characteristic Measurement Interval
*/
#define BT_UUID_HRS_MEASUREMENT 0x2a37
/** @def BT_UUID_HRS_BODY_SENSOR
* @brief HRS Characteristic Body Sensor Location
*/
#define BT_UUID_HRS_BODY_SENSOR 0x2a38
/** @def BT_UUID_HR_CONTROL_POINT
* @brief HRS Characteristic Control Point
*/
#define BT_UUID_HRS_CONTROL_POINT 0x2a39
/****************************************************************************
* Public Types
****************************************************************************/
/* Bluetooth UUID types */
enum bt_uuid_type_e
{
BT_UUID_16,
BT_UUID_128,
};
/* Bluetooth UUID structure */
struct bt_uuid_s
{
/* UUID type */
uint8_t type;
union
{
/* UUID 16 bits value */
uint16_t u16;
/* UUID 128 bits value */
uint8_t u128[16];
} u;
};
/****************************************************************************
* Public Functin Prototypes
****************************************************************************/
/****************************************************************************
* Name: bt_uuid_cmp
*
* Description:
* Compares 2 Bluetooth UUIDs, if the types are different both UUIDs are
* first converted to 128 bits format before comparing.
*
* Input Paramters:
* u1 - First Bluetooth UUID to compare
* u2 - Second Bluetooth UUID to compare
*
* Returned Value:
* negative value if <u1> < <u2>, 0 if <u1> == <u2>, else positive
*
****************************************************************************/
int bt_uuid_cmp(FAR const struct bt_uuid_s *u1,
FAR const struct bt_uuid_s *u2);
#endif /* __INCLUDE_NUTTX_WIRELESS_BT_UUID_H */
......@@ -11,6 +11,7 @@ config WIRELESS
if WIRELESS
source wireless/bluetooth/Kconfig
source wireless/ieee802154/Kconfig
source wireless/pktradio/Kconfig
......
......@@ -50,6 +50,7 @@ VPATH = .
# Add IEEE 802.15.4 files to the build
include bluetooth$(DELIM)Make.defs
include ieee802154$(DELIM)Make.defs
include pktradio$(DELIM)Make.defs
......
#############################################################################
# wireless/bluetooth/Kconfig
# Bluetooth LE stack configuration options
#
# Copyright (C) 2018 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# Ported from the Intel/Zephyr arduino101_firmware_source-v1.tar package
# where the code was released with a compatible 3-clause BSD license:
#
# Copyright (c) 2016, Intel Corporation
# All rights reserved.
#
# 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.
#
#############################################################################
menuconfig WIRELESS_BLUETOOTH
bool
prompt "Bluetooth LE support"
default n
select MM_IOB
depends on EXPERIMENTAL
---help---
This option enables Bluetooth Low Energy support.
NOTE: This selection is marked EXPERIMENTAL. It is incomplete and,
hence, untested. It still lacks any low-level Bluetooth drivers and
is missing the network interface driver.
if WIRELESS_BLUETOOTH
config BLUETOOTH_MAX_CONN
int
prompt "Maximum number of simultaneous connections"
default 1
range 1 16
---help---
Maximum number of simultaneous Bluetooth connections
supported. The minimum (and default) number is 1.
config BLUETOOTH_MAX_PAIRED
int
prompt "Maximum number of paired devices"
default 1
range 1 32
---help---
Maximum number of paired Bluetooth devices. The minimum (and
default) number is 1.
menu "Kernel Thread Configuration"
config BLUETOOTH_RXTHREAD_STACKSIZE
int "Rx thread stack size"
default 1024
config BLUETOOTH_RXTHREAD_PRIORITY
int "Rx thread priority"
default 100
range 1 255
config BLUETOOTH_RXTHREAD_NMSGS
int "Rx thread mqueue size"
default 16
config BLUETOOTH_TXCMD_STACKSIZE
int "Tx command thread stack size"
default 1024
config BLUETOOTH_TXCMD_PRIORITY
int "Tx command thread priority"
default 100
range 1 255
config BLUETOOTH_TXCMD_NMSGS
int "Tx command thread mqueue size"
default 16
config BLUETOOTH_TXCONN_STACKSIZE
int "Tx connection thread stack size"
default 1024
config BLUETOOTH_TXCONN_PRIORITY
int "Tx connection thread priority"
default 100
range 1 255
config BLUETOOTH_TXCONN_NMSGS
int "Tx connection thread mqueue size"
default 16
endmenu # Kernel Thread Configuration
config BLUETOOTH_SMP_SELFTEST
bool
prompt "Bluetooth SMP self tests executed on init"
default n
---help---
This option enables SMP self-tests executed on startup
to verify security and crypto functions.
endif # WIRELESS_BLUETOOTH
############################################################################
# wireless/bluetooth/Make.defs
#
# Copyright (C) 2018 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
#
# 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.
#
############################################################################
ifeq ($(CONFIG_WIRELESS_BLUETOOTH),y)
# Include Bluetooth support
CSRCS += bt_atomic.c bt_att.c bt_buf.c bt_conn.c bt_gatt.c bt_hcicore.c
CSRCS += bt_keys.c bt_l2cap.c bt_queue.c bt_smp.c bt_uuid.c
DEPPATH += --dep-path bluetooth
VPATH += :bluetooth
CFLAGS += ${shell $(INCDIR) $(INCDIROPT) "$(CC)" $(TOPDIR)$(DELIM)wireless$(DELIM)bluetooth}
endif # CONFIG_WIRELESS_BLUETOOTH
/****************************************************************************
* wireless/bluetooth/bt_atomic.c
* Linux like atomic operations
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 <nuttx/irq.h>
#include "bt_atomic.h"
/****************************************************************************
* Public Function
****************************************************************************/
#ifndef CONFIG_HAVE_INLINE
void bt_atomic_set(FAR bt_atomic_t *ptr, bt_atomic_t value)
{
*ptr = value;
}
#endif
bt_atomic_t bt_atomic_incr(FAR bt_atomic_t *ptr)
{
irqstate_t flags;
bt_atomic_t value;
flags = spin_lock_irqsave();
value = *ptr;
*ptr = value + 1;
spin_unlock_irqrestore(flags);
return value;
}
bt_atomic_t bt_atomic_decr(FAR bt_atomic_t *ptr)
{
irqstate_t flags;
bt_atomic_t value;
flags = spin_lock_irqsave();
value = *ptr;
*ptr = value - 1;
spin_unlock_irqrestore(flags);
return value;
}
bt_atomic_t bt_atomic_setbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno)
{
irqstate_t flags;
bt_atomic_t value;
flags = spin_lock_irqsave();
value = *ptr;
*ptr = value | (1 << bitno);
spin_unlock_irqrestore(flags);
return value;
}
bt_atomic_t bt_atomic_clrbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno)
{
irqstate_t flags;
bt_atomic_t value;
flags = spin_lock_irqsave();
value = *ptr;
*ptr = value & ~(1 << bitno);
spin_unlock_irqrestore(flags);
return value;
}
#ifndef CONFIG_HAVE_INLINE
bt_atomic_t bt_atomic_get(FAR bt_atomic_t *ptr)
{
return *ptr;
}
#endif
#ifndef CONFIG_HAVE_INLINE
bool bt_atomic_testbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno)
{
return (*ptr & (1 << bitno)) != 0;
}
#endif
bool bt_atomic_testsetbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno)
{
irqstate_t flags;
bt_atomic_t value;
flags = spin_lock_irqsave();
value = *ptr;
*ptr = value | (1 << bitno);
spin_unlock_irqrestore(flags);
return (value & (1 << bitno)) != 0;
}
bool bt_atomic_testclrbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno)
{
irqstate_t flags;
bt_atomic_t value;
flags = spin_lock_irqsave();
value = *ptr;
*ptr = value & ~(1 << bitno);
spin_unlock_irqrestore(flags);
return (value & (1 << bitno)) != 0;
}
/****************************************************************************
* wireless/bluetooth/bt_atomic.h
* Linux like atomic operations
*
* Copyright (C) 2018 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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.
*
****************************************************************************/
#ifndef __WIRELESS_BLUETOOTH_BT_ATOMIC_H
#define __WIRELESS_BLUETOOTH_BT_ATOMIC_H 1
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stdbool.h>
/****************************************************************************
* Public Types
****************************************************************************/
typedef uint8_t bt_atomic_t;
/****************************************************************************
* Inline Prototypes
****************************************************************************/
#ifdef CONFIG_HAVE_INLINE
/* These operations are inherently atomic */
static inline void bt_atomic_set(FAR bt_atomic_t *ptr, bt_atomic_t value)
{
*ptr = value;
}
static inline bt_atomic_t bt_atomic_get(FAR bt_atomic_t *ptr)
{
return *ptr;
}
static inline bool bt_atomic_testbit(FAR bt_atomic_t *ptr,
bt_atomic_t bitno)
{
return (*ptr & (1 << bitno)) != 0;
}
#endif
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
#ifndef CONFIG_HAVE_INLINE
void bt_atomic_set(FAR bt_atomic_t *ptr, bt_atomic_t value);
bt_atomic_t bt_atomic_get(FAR bt_atomic_t *ptr);
#endif
bt_atomic_t bt_atomic_incr(FAR bt_atomic_t *ptr);
bt_atomic_t bt_atomic_decr(FAR bt_atomic_t *ptr);
bt_atomic_t bt_atomic_setbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno);
bt_atomic_t bt_atomic_clrbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno);
#ifndef CONFIG_HAVE_INLINE
bool bt_atomic_testbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno);
#endif
bool bt_atomic_testsetbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno);
bool bt_atomic_testclrbit(FAR bt_atomic_t *ptr, bt_atomic_t bitno);
#endif /* __WIRELESS_BLUETOOTH_BT_ATOMIC_H */
\ No newline at end of file
This diff is collapsed.