728x90

CYW920719B2Q40EVB-01 EVB의 모습니다.

CYW20719를 사용하고, 앞에 9로 시작하는 것은 EVB를 나타내는 것이다.

Bluetooth BR/EDR(Classic) 그리고 BLE가 같이 동작하는 dual mode chip이다.

자세한 설명은 아래 링크에서 확인 가능하다.

https://www.infineon.com/cms/en/product/wireless-connectivity/airoc-bluetooth-le-bluetooth-multiprotocol/airoc-bluetooth-le-bluetooth/cyw20719/

 

 

SDK는 ModusToolBox를 사용하는데 Infineon community에서 받을 수 있다.

https://community.infineon.com/

ModusToolBox를 설치하고 CYW20719를 USB(to serial)를 연결하면 UART 장치가 두개 생겨야 한다.(HCI/PUART)

만약 드라이버가 제대로 잡히지 않는다면 설치경로에 있는 driver를 이용하여 직접 설치해야 할 수 있다.

C:\Infineon\Tools\ModusToolbox\tools_3.1\driver_media

SDK는 Eclipse를 기반으로 만들어져 있다.

 

File -> New -> ModusToolBox Application을 선택하면 example을 받을 수 있다.

Project Creator가 github에서 받아오는 방식인데 먼저 AIROC Bluetooth BSPs를 선택하고 CYW920719B2Q40EVB-01를 선택한다.

Classic Bluetooth에서 가장 간단히 test하는 profile로는 SPP로 많이 시작한다.

SPP는 serial 통신을 Bluetooth 구현한 것이라 data 전송 외에는 특별한 기능이 없다.

ModusToolBox 에서는 "RFCOMM Serial Port" 예제를 선택하면 된다.

 

README.md : example에 대한 설명과 define을 어떻게 사용하는지 설명

makefile : build config들이 모여있다.

cycfg_bt.cybt : SDP정보를 바꿀 수 있다.

spp.c : example 내용이 들어있다. 간단히 c file하나로 사용하는 example이다.

 

spp.c code (더보기를 누르면 전체 코드를 확인 가능)

더보기
/*
 * Copyright 2016-2022, Cypress Semiconductor Corporation (an Infineon company) or
 * an affiliate of Cypress Semiconductor Corporation.  All rights reserved.
 *
 * This software, including source code, documentation and related
 * materials ("Software") is owned by Cypress Semiconductor Corporation
 * or one of its affiliates ("Cypress") and is protected by and subject to
 * worldwide patent protection (United States and foreign),
 * United States copyright laws and international treaty provisions.
 * Therefore, you may use this Software only as provided in the license
 * agreement accompanying the software package from which you
 * obtained this Software ("EULA").
 * If no EULA applies, Cypress hereby grants you a personal, non-exclusive,
 * non-transferable license to copy, modify, and compile the Software
 * source code solely for use in connection with Cypress's
 * integrated circuit products.  Any reproduction, modification, translation,
 * compilation, or representation of this Software except as specified
 * above is prohibited without the express written permission of Cypress.
 *
 * Disclaimer: THIS SOFTWARE IS PROVIDED AS-IS, WITH NO WARRANTY OF ANY KIND,
 * EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, NONINFRINGEMENT, IMPLIED
 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. Cypress
 * reserves the right to make changes to the Software without notice. Cypress
 * does not assume any liability arising out of the application or use of the
 * Software or any product or circuit described in the Software. Cypress does
 * not authorize its products for use in any products where a malfunction or
 * failure of the Cypress product may reasonably be expected to result in
 * significant property damage, injury or death ("High Risk Product"). By
 * including Cypress's product in a High Risk Product, the manufacturer
 * of such system or application assumes all risk of such use and in doing
 * so agrees to indemnify Cypress against all liability.
 */

/** @file
 *
 * SPP Application for 20XXX devices.
 *
 * SPP application uses SPP profile library to establish, terminate, send and receive SPP
 * data over BR/EDR. This sample supports single a single SPP connection.
 *
 * Following compilation flags are important for testing
 *  HCI_TRACE_OVER_TRANSPORT - configures HCI traces to be routed to the WICED HCI interface
 *  WICED_BT_TRACE_ENABLE    - enables WICED_BT_TRACEs.  You can also modify makefile.mk to build
 *                             with _debug version of the library
 *  SEND_DATA_ON_INTERRUPT   - if defined, the app will send 1Meg of data on application button push
 *  SEND_DATA_ON_TIMEOUT     - if defined, the app will send 4 bytes every second while session is up
 *  LOOPBACK_DATA            - if enabled, the app sends back received data
 *
 * To demonstrate the app, work through the following steps.
 * 1. Build and download the application to the WICED board.
 * 2. Open the Bluetooth Classic and LE Profile Client Control application and open the port for WICED HCI for the device.
 *    Default baud rate configured in the application is defined by the BSP HCI_UART_DEAULT_BAUD #define,
 *    usually either 3M or 115200 depending on board UART capabilities.
 * 3. Run the BTSpy program to view protocol and application traces.
 *    See "Bluetooth Classic and LE Profile Client Control" and "BTSpy" in chip-specifc readme.txt for more information about these apps.
 * 4. On Windows 10 PCs, right click on the Bluetooth icon in the system tray and
 *    select 'Add a Bluetooth Device'. Find and pair with the spp app. That should create an incoming and an outgoing
 *    COM port on your computer. Right click on the Bluetooth icon in the system tray and
 *    select 'Open Settings', scroll down and select "More Bluetooth options" and then
 *    select the 'COM Ports' tab.
 * 5. Use application such as Term Term to open the outgoing COM port. Opening the port
 *    will create the SPP connection.
 * 6. Type any key on the terminal of the outgoing COM port, the spp application will receive the key.
 * 7. By default, (SEND_DATA_ON_INTERRUPT=1) the application sends 1 MB data to the peer application on every
 *    App button press on the WICED board.
 * 8. If desired, edit the spp.c file to configure the application to send data on a timer to the peer application by
 *    setting SEND_DATA_ON_INTERRUPT=0 and SEND_DATA_ON_TIMEOUT=1*
 *
 * Features demonstrated
 *  - Use of SPP library
 *
 *  Note: This snippet app does not support WICED HCI Control and may use transport only for tracing.
 *  If you route traces to WICED HCI UART, use ClientControl app with baud rate equal to that
 *  set in the wiced_transport_cfg_t structure below (currently set at HCI_UART_DEFAULT_BAUD, either 3 Mbps or 115200
 *  depending on the capabilities of the board used).
 */

#include "sparcommon.h"
#include "bt_types.h"
#include "wiced.h"
#include "wiced_gki.h"
#include "wiced_bt_dev.h"
#include "wiced_bt_sdp.h"
#include "wiced_bt_ble.h"
#include "wiced_bt_uuid.h"
#include "wiced_hal_nvram.h"
#include "wiced_bt_trace.h"
#include "wiced_bt_cfg.h"
#include "wiced_bt_spp.h"
#include "wiced_hci.h"
#include "wiced_timer.h"
#include "wiced_transport.h"
#include "wiced_platform.h"
#include "wiced_memory.h"
#include "string.h"
#include "wiced_bt_stack.h"
#include "wiced_bt_rfcomm.h"
#include "cycfg_sdp_db.h"
#if defined(CYW20706A2) || defined(CYW43012C0)
#include "wiced_bt_app_hal_common.h"
#endif

#if BTSTACK_VER >= 0x03000001
#include "wiced_memory.h"
#include "clock_timer.h"
#define BT_STACK_HEAP_SIZE          1024 * 6
wiced_bt_heap_t *p_default_heap   = NULL;
#endif

#define HCI_TRACE_OVER_TRANSPORT            1   // If defined HCI traces are send over transport/WICED HCI interface
// configure either SEND_DATA_ON_INTERRUPT or SEND_DATA_ON_TIMEOUT, but not both
// CYW9M2BASE-43012BT does not support SEND_DATA_ON_INTERRUPT because the platform does not have button connected to Bluetooth board.
#if defined (NO_BUTTON_SUPPORT)
#if defined(SEND_DATA_ON_INTERRUPT) && (SEND_DATA_ON_INTERRUPT==1)
#undef SEND_DATA_ON_INTERRUPT                   // disable SEND_DATA_ON_INTERRUPT is no app button
#define SEND_DATA_ON_TIMEOUT                1
#endif
#endif

//#define LOOPBACK_DATA                     1   // If defined application loops back received data

#define WICED_EIR_BUF_MAX_SIZE              264
#define SPP_NVRAM_ID                        WICED_NVRAM_VSID_START

/* Max TX packet to be sent over SPP */
#define MAX_TX_BUFFER                       1017
#define TRANS_MAX_BUFFERS                   2
#define TRANS_UART_BUFFER_SIZE              1024
#define SPP_MAX_PAYLOAD                     1007

#if SEND_DATA_ON_INTERRUPT
#include "wiced_hal_gpio.h"
#include "wiced_platform.h"

#define APP_TOTAL_DATA_TO_SEND             1000000
#define BUTTON_GPIO                         WICED_P30

#if defined(CYW43012C0)
#define WICED_PLATFORM_BUTTON_1          WICED_P00
#ifndef WICED_GPIO_BUTTON
#define WICED_GPIO_BUTTON                WICED_PLATFORM_BUTTON_1
#endif
#ifndef WICED_GPIO_BUTTON_DEFAULT_STATE
#define WICED_GPIO_BUTTON_DEFAULT_STATE  GPIO_PIN_OUTPUT_HIGH
#endif
#endif

int     app_send_offset = 0;
uint8_t app_send_buffer[SPP_MAX_PAYLOAD];
uint32_t time_start = 0;
#endif

#ifdef SEND_DATA_ON_TIMEOUT
wiced_timer_t spp_app_timer;
void app_timeout(TIMER_PARAM_TYPE arg);
#endif

/*****************************************************************************
**  Structures
*****************************************************************************/
#define SPP_RFCOMM_SCN               2

#define MAX_TX_RETRY                 30
#define TX_RETRY_TIMEOUT             100 // msec

static void         spp_connection_up_callback(uint16_t handle, uint8_t* bda);
static void         spp_connection_down_callback(uint16_t handle);
static wiced_bool_t spp_rx_data_callback(uint16_t handle, uint8_t* p_data, uint32_t data_len);
static void         spp_bt_remote_name_callback(wiced_bt_dev_remote_name_result_t *p_remote_name_result);

wiced_bt_spp_reg_t spp_reg =
{
    SPP_RFCOMM_SCN,                     /* RFCOMM service channel number for SPP connection */
    MAX_TX_BUFFER,                      /* RFCOMM MTU for SPP connection */
    spp_connection_up_callback,         /* SPP connection established */
    NULL,                               /* SPP connection establishment failed, not used because this app never initiates connection */
    NULL,                               /* SPP service not found, not used because this app never initiates connection */
    spp_connection_down_callback,       /* SPP connection disconnected */
    spp_rx_data_callback,               /* Data packet received */
};
#if BTSTACK_VER < 0x03000001
wiced_transport_buffer_pool_t*  host_trans_pool;
#endif
uint16_t                        spp_handle = 0;
wiced_timer_t                   app_tx_timer;
uint32_t                        spp_rx_bytes = 0;
uint32_t                        spp_tx_retry_count = 0;

uint8_t pincode[4] = { 0x30, 0x30, 0x30, 0x30 };

extern const wiced_bt_cfg_settings_t wiced_bt_cfg_settings;
#if BTSTACK_VER < 0x03000001
extern const wiced_bt_cfg_buf_pool_t wiced_bt_cfg_buf_pools[WICED_BT_CFG_NUM_BUF_POOLS];
#endif

#if defined WICED_BT_TRACE_ENABLE || defined HCI_TRACE_OVER_TRANSPORT
const wiced_transport_cfg_t transport_cfg =
{
    .type = WICED_TRANSPORT_UART,
    .cfg =
    {
        .uart_cfg =
        {
            .mode = WICED_TRANSPORT_UART_HCI_MODE,
            .baud_rate =  HCI_UART_DEFAULT_BAUD
        },
    },
#if BTSTACK_VER >= 0x03000001
        .heap_config =
        {
            .data_heap_size = 1024 * 4 + 1500 * 2,
            .hci_trace_heap_size = 1024 * 2,
            .debug_trace_heap_size = 1024,
        },
#else
    .rx_buff_pool_cfg =
    {
        .buffer_size  = TRANS_UART_BUFFER_SIZE,
        .buffer_count = 1
    },
#endif
    .p_status_handler    = NULL,
    .p_data_handler      = NULL,
    .p_tx_complete_cback = NULL
};
#endif

/*******************************************************************
 * Function Prototypes
 ******************************************************************/
static wiced_bt_dev_status_t app_management_callback (wiced_bt_management_evt_t event, wiced_bt_management_evt_data_t *p_event_data);
static void                  app_write_eir(void);
static int                   app_write_nvram(int nvram_id, int data_len, void *p_data);
static int                   app_read_nvram(int nvram_id, void *p_data, int data_len);

#if SEND_DATA_ON_INTERRUPT
static void                  app_tx_ack_timeout(TIMER_PARAM_TYPE param);
static void                  app_interrupt_handler(void *data, uint8_t port_pin);
#endif
#ifdef HCI_TRACE_OVER_TRANSPORT
static void                  app_trace_callback(wiced_bt_hci_trace_type_t type, uint16_t length, uint8_t* p_data);
#endif

#if defined (CYW20706A2)
extern BOOL32 wiced_hal_puart_select_uart_pads(UINT8 rxdPin, UINT8 txdPin, UINT8 ctsPin, UINT8 rtsPin);
extern wiced_result_t wiced_bt_app_init( void );
#endif

#ifndef CYW20706A2
extern uint64_t clock_SystemTimeMicroseconds64();
#else
#include "rtc.h"
uint64_t clock_SystemTimeMicroseconds64(void)
{
    tRTC_REAL_TIME_CLOCK rtcClock;
    rtc_getRTCRawClock(&rtcClock);
    // To convert 128 kHz rtc timer to milliseconds divide it by 131: //128 kHz = 128 * 1024 = 131072; to microseconds: 1000000 / 131072 = 7.62939453125 (7.63)
    return rtcClock.rtc64 * 763 / 100;
}
#endif

/*******************************************************************
 * Function Definitions
 ******************************************************************/

void buffer_report(char *msg)
{
#if BTSTACK_VER >= 0x03000001
    /*
     * Get statistics of default heap.
     * TODO: get statistics of stack heap (btu_cb.p_heap)
     */
    wiced_bt_heap_statistics_t heap_stat;

    if (wiced_bt_get_heap_statistics(p_default_heap, &heap_stat))
    {
        WICED_BT_TRACE("--- heap_size:%d ---\n", heap_stat.heap_size);
        WICED_BT_TRACE("max_single_allocation:%d max_heap_size_used:%d\n",
                        heap_stat.max_single_allocation,
                        heap_stat.max_heap_size_used);
        WICED_BT_TRACE("allocation_failure_count:%d current_largest_free_size:%d\n",
                        heap_stat.allocation_failure_count,
                        heap_stat.current_largest_free_size);
        WICED_BT_TRACE("current_num_allocations:%d current_size_allocated:%d\n",
                        heap_stat.current_num_allocations,
                        heap_stat.current_size_allocated);
        WICED_BT_TRACE("current_num_free_fragments:%d current_free_size\n",
                        heap_stat.current_num_free_fragments,
                        heap_stat.current_free_size);
    }
    else
    {
        WICED_BT_TRACE("buffer_report: wiced_bt_get_heap_statistics failed\n");
    }
#else /* !BTSTACK_VER */

    wiced_bt_buffer_statistics_t buffer_stats[5];
    wiced_result_t result;

    result = wiced_bt_get_buffer_usage (buffer_stats, sizeof(buffer_stats));

    if (result == WICED_BT_SUCCESS)
    {
        WICED_BT_TRACE("%s: pool %x %d %d/%d/%d\n", msg,
                buffer_stats[1].pool_id,
                buffer_stats[1].pool_size,
                buffer_stats[1].current_allocated_count,
                buffer_stats[1].max_allocated_count,
                buffer_stats[1].total_count);
        WICED_BT_TRACE("%s: pool %x %d %d/%d/%d\n", msg,
                buffer_stats[2].pool_id,
                buffer_stats[2].pool_size,
                buffer_stats[2].current_allocated_count,
                buffer_stats[2].max_allocated_count,
                buffer_stats[2].total_count);
    }
    else
        WICED_BT_TRACE("buffer_report: wiced_bt_get_buffer_usage failed, returned %d\n", result);
#endif
}

/*
 * Entry point to the application. Set device configuration and start Bluetooth
 * stack initialization.  The actual application initialization will happen
 * when stack reports that Bluetooth device is ready
 */
APPLICATION_START()
{
    wiced_result_t result;
    int interupt = 0, timeout = 0, loopback = 0;

#if defined WICED_BT_TRACE_ENABLE || defined HCI_TRACE_OVER_TRANSPORT
    wiced_transport_init(&transport_cfg);

#if BTSTACK_VER < 0x03000001
    // create special pool for sending data to the MCU
    host_trans_pool = wiced_transport_create_buffer_pool(TRANS_UART_BUFFER_SIZE, TRANS_MAX_BUFFERS);
#endif

    // Set the debug uart as WICED_ROUTE_DEBUG_NONE to get rid of prints
    // wiced_set_debug_uart(WICED_ROUTE_DEBUG_NONE);

    // Set to PUART to see traces on peripheral uart(puart) if platform has PUART
#ifdef NO_PUART_SUPPORT
    // wiced_set_debug_uart( WICED_ROUTE_DEBUG_TO_WICED_UART );
#else
    // wiced_set_debug_uart( WICED_ROUTE_DEBUG_TO_PUART );
#if defined (CYW20706A2)
    // wiced_hal_puart_select_uart_pads( WICED_PUART_RXD, WICED_PUART_TXD, 0, 0);
#endif
#endif

    // Set to HCI to see traces on HCI uart - default if no call to wiced_set_debug_uart()
    // wiced_set_debug_uart( WICED_ROUTE_DEBUG_TO_HCI_UART );

    // Use WICED_ROUTE_DEBUG_TO_WICED_UART to send formatted debug strings over the WICED
    // HCI debug interface to be parsed by ClientControl/BtSpy.
    wiced_set_debug_uart(WICED_ROUTE_DEBUG_TO_WICED_UART);
#endif

#if SEND_DATA_ON_INTERRUPT
    interupt = 1;
#endif
#if SEND_DATA_ON_TIMEOUT
    timeout = 1;
#endif
#if LOOPBACK_DATA
    loopback = 1;
#endif
    WICED_BT_TRACE("APP Start, interupt=%d, timeout=%d, loopback=%d\n", interupt, timeout, loopback);

#if BTSTACK_VER >= 0x03000001
    /* Create default heap */
    p_default_heap = wiced_bt_create_heap("default_heap", NULL, BT_STACK_HEAP_SIZE, NULL, WICED_TRUE);
    if (p_default_heap == NULL)
    {
        WICED_BT_TRACE("create default heap error: size %d\n", BT_STACK_HEAP_SIZE);
        return;
    }
    /* Initialize Stack and Register Management Callback */
    // Register call back and configuration with stack
    wiced_bt_stack_init(app_management_callback, &wiced_bt_cfg_settings);
#else
    /* Initialize Stack and Register Management Callback */
    // Register call back and configuration with stack
    wiced_bt_stack_init(app_management_callback, &wiced_bt_cfg_settings, wiced_bt_cfg_buf_pools);
#endif
}

/*
 * SPP application initialization is executed after Bluetooth stack initialization is completed.
 */
void application_init(void)
{
    wiced_result_t         result;

#if defined (CYW20706A2)
    /* Initialize wiced app */
    wiced_bt_app_init();

    /* Initialize the RTC block */
    rtc_init();
#endif

#if SEND_DATA_ON_INTERRUPT
#if !defined (CYW20706A2) && !defined (CYW43012C0)
    /* Configure the button available on the platform */
    wiced_platform_register_button_callback( WICED_PLATFORM_BUTTON_1, app_interrupt_handler, NULL, WICED_PLATFORM_BUTTON_RISING_EDGE);
#elif defined(CYW20706A2) || defined(CYW43012C0)
/* Initializes the GPIO driver */
    wiced_bt_app_hal_init();
	wiced_hal_gpio_configure_pin(WICED_GPIO_BUTTON, WICED_GPIO_BUTTON_SETTINGS( GPIO_EN_INT_RISING_EDGE ), WICED_GPIO_BUTTON_DEFAULT_STATE );
	wiced_hal_gpio_register_pin_for_interrupt(WICED_GPIO_BUTTON, app_interrupt_handler, NULL);
#endif // CYW20706A2 && CYW43012C0
    // init timer that we will use for the rx data flow control.
    wiced_init_timer(&app_tx_timer, app_tx_ack_timeout, 0, WICED_MILLI_SECONDS_TIMER);
#endif // SEND_DATA_ON_INTERRUPT

    app_write_eir();

#if defined (CYW20706A2)
    // Initialize RFCOMM.  We will not be using application buffer pool and will rely on the
    // stack pools configured in the wiced_bt_cfg.c
    wiced_bt_rfcomm_init(MAX_TX_BUFFER, 1);
#endif

    // Initialize SPP library
    wiced_bt_spp_startup(&spp_reg);

#ifdef HCI_TRACE_OVER_TRANSPORT
    // There is a virtual HCI interface between upper layers of the stack and
    // the controller portion of the chip with lower layers of the Bluetooth stack.
    // Register with the stack to receive all HCI commands, events and data.
    wiced_bt_dev_register_hci_trace(app_trace_callback);
#endif
    /* create SDP records */
    wiced_bt_sdp_db_init((uint8_t *)sdp_database, sdp_database_len);

    /* Allow peer to pair */
    wiced_bt_set_pairable_mode(WICED_TRUE, 0);

#if BTSTACK_VER >= 0x03000001
        // This application will always configure device connectable and discoverable
    wiced_bt_dev_set_discoverability(BTM_GENERAL_DISCOVERABLE,
                                     WICED_BT_CFG_DEFAULT_INQUIRY_SCAN_INTERVAL,
                                     WICED_BT_CFG_DEFAULT_INQUIRY_SCAN_WINDOW);

    wiced_bt_dev_set_connectability(BTM_CONNECTABLE,
                                    WICED_BT_CFG_DEFAULT_PAGE_SCAN_INTERVAL,
                                    WICED_BT_CFG_DEFAULT_PAGE_SCAN_WINDOW);
#else
    // This application will always configure device connectable and discoverable
    wiced_bt_dev_set_discoverability(BTM_GENERAL_DISCOVERABLE,
        wiced_bt_cfg_settings.br_edr_scan_cfg.inquiry_scan_interval,
        wiced_bt_cfg_settings.br_edr_scan_cfg.inquiry_scan_window);

    wiced_bt_dev_set_connectability(BTM_CONNECTABLE,
        wiced_bt_cfg_settings.br_edr_scan_cfg.page_scan_interval,
        wiced_bt_cfg_settings.br_edr_scan_cfg.page_scan_window);
#endif

#if SEND_DATA_ON_TIMEOUT
    /* Starting the app timers, seconds timer and the ms timer  */
    wiced_init_timer(&spp_app_timer, app_timeout, 0, WICED_SECONDS_PERIODIC_TIMER);
    wiced_start_timer(&spp_app_timer, 1);
#endif
}

/*
 *  Management callback receives various notifications from the stack
 */
wiced_result_t app_management_callback(wiced_bt_management_evt_t event, wiced_bt_management_evt_data_t *p_event_data)
{
    wiced_result_t                      result = WICED_BT_SUCCESS;
    wiced_bt_dev_status_t               dev_status;
    wiced_bt_dev_pairing_info_t*        p_pairing_info;
    wiced_bt_dev_encryption_status_t*   p_encryption_status;
    int                                 bytes_written, bytes_read;
    wiced_bt_power_mgmt_notification_t* p_power_mgmt_notification;

    WICED_BT_TRACE("app_management_callback %d\n", event);

    switch(event)
    {
    /* Bluetooth  stack enabled */
    case BTM_ENABLED_EVT:
        application_init();
        //WICED_BT_TRACE("Free mem:%d", cfa_mm_MemFreeBytes());
        break;

    case BTM_DISABLED_EVT:
        break;

    case BTM_PIN_REQUEST_EVT:
        WICED_BT_TRACE("remote address= %B\n", p_event_data->pin_request.bd_addr);
        wiced_bt_dev_pin_code_reply(*p_event_data->pin_request.bd_addr,result/*WICED_BT_SUCCESS*/,4, &pincode[0]);
        break;

    case BTM_USER_CONFIRMATION_REQUEST_EVT:
        /* This application always confirms peer's attempt to pair */
        wiced_bt_dev_confirm_req_reply (WICED_BT_SUCCESS, p_event_data->user_confirmation_request.bd_addr);
        /* get the remote name to show in the log */
        result = wiced_bt_dev_get_remote_name(p_event_data->user_confirmation_request.bd_addr, spp_bt_remote_name_callback);
        break;

    case BTM_PAIRING_IO_CAPABILITIES_BR_EDR_REQUEST_EVT:
        /* This application supports only Just Works pairing */
        WICED_BT_TRACE("BTM_PAIRING_IO_CAPABILITIES_REQUEST_EVT bda %B\n", p_event_data->pairing_io_capabilities_br_edr_request.bd_addr);
        p_event_data->pairing_io_capabilities_br_edr_request.local_io_cap   = BTM_IO_CAPABILITIES_NONE;
        p_event_data->pairing_io_capabilities_br_edr_request.auth_req       = BTM_AUTH_SINGLE_PROFILE_GENERAL_BONDING_NO;
        break;

    case BTM_PAIRING_COMPLETE_EVT:
        p_pairing_info = &p_event_data->pairing_complete.pairing_complete_info;
        WICED_BT_TRACE("Pairing Complete: %d\n", p_pairing_info->br_edr.status);
        result = WICED_BT_USE_DEFAULT_SECURITY;
        break;

    case BTM_ENCRYPTION_STATUS_EVT:
        p_encryption_status = &p_event_data->encryption_status;
        WICED_BT_TRACE("Encryption Status Event: bd (%B) res %d\n", p_encryption_status->bd_addr, p_encryption_status->result);
        break;

    case BTM_PAIRED_DEVICE_LINK_KEYS_UPDATE_EVT:
        /* This application supports a single paired host, we can save keys under the same NVRAM ID overwriting previous pairing if any */
        app_write_nvram(SPP_NVRAM_ID, sizeof(wiced_bt_device_link_keys_t), &p_event_data->paired_device_link_keys_update);
        break;

    case  BTM_PAIRED_DEVICE_LINK_KEYS_REQUEST_EVT:
        /* read existing key from the NVRAM  */
        if (app_read_nvram(SPP_NVRAM_ID, &p_event_data->paired_device_link_keys_request, sizeof(wiced_bt_device_link_keys_t)) != 0)
        {
            result = WICED_BT_SUCCESS;
        }
        else
        {
            result = WICED_BT_ERROR;
            WICED_BT_TRACE("Key retrieval failure\n");
        }
        break;

    case BTM_POWER_MANAGEMENT_STATUS_EVT:
        p_power_mgmt_notification = &p_event_data->power_mgmt_notification;
        WICED_BT_TRACE("Power mgmt status event: bd (%B) status:%d hci_status:%d\n", p_power_mgmt_notification->bd_addr, \
                p_power_mgmt_notification->status, p_power_mgmt_notification->hci_status);
        break;

    default:
        result = WICED_BT_USE_DEFAULT_SECURITY;
        break;
    }
    return result;
}


/*
 *  Prepare extended inquiry response data.  Current version publishes device name and 16bit
 *  SPP service.
 */
void app_write_eir(void)
{
    uint8_t *pBuf;
    uint8_t *p;
    uint8_t length;
    uint16_t eir_length;

    pBuf = (uint8_t *)wiced_bt_get_buffer(WICED_EIR_BUF_MAX_SIZE);
    WICED_BT_TRACE("hci_control_write_eir %x\n", pBuf);

    if (!pBuf)
    {
        WICED_BT_TRACE("app_write_eir %x\n", pBuf);
        return;
    }

    p = pBuf;

    length = strlen((char *)wiced_bt_cfg_settings.device_name);

    *p++ = length + 1;
    *p++ = BT_EIR_COMPLETE_LOCAL_NAME_TYPE;        // EIR type full name
    memcpy(p, wiced_bt_cfg_settings.device_name, length);
    p += length;

    *p++ = 2 + 1;                                   // Length of 16 bit services
    *p++ = BT_EIR_COMPLETE_16BITS_UUID_TYPE;        // 0x03 EIR type full list of 16 bit service UUIDs
    *p++ = UUID_SERVCLASS_SERIAL_PORT & 0xff;
    *p++ = (UUID_SERVCLASS_SERIAL_PORT >> 8) & 0xff;

    *p++ = 0;                                       // end of EIR Data is 0

    eir_length = (uint16_t) (p - pBuf);

    // print EIR data
    WICED_BT_TRACE_ARRAY(pBuf, MIN(p-pBuf, 100), "EIR :");
    wiced_bt_dev_write_eir(pBuf, eir_length);

    return;
}

/*
 * The function invoked on timeout of app seconds timer.
 */
#if SEND_DATA_ON_TIMEOUT
void app_timeout(TIMER_PARAM_TYPE arg)
{
    static uint32_t timer_count = 0;
    timer_count++;
    wiced_bool_t ret;
    WICED_BT_TRACE("app_timeout: %d, handle %d \n", timer_count, spp_handle);
    if (spp_handle != 0)
    {
        ret = wiced_bt_spp_send_session_data(spp_handle, (uint8_t *)&timer_count, sizeof(uint32_t));
        if (ret != WICED_TRUE)
            WICED_BT_TRACE("wiced_bt_spp_send_session_data failed, ret = %d\n", ret);
    }
}
#endif

/*
 * SPP connection up callback
 */
void spp_connection_up_callback(uint16_t handle, uint8_t* bda)
{
    WICED_BT_TRACE("%s handle:%d address:%B\n", __FUNCTION__, handle, bda);
    spp_handle = handle;
    spp_rx_bytes = 0;
}

/*
 * SPP connection down callback
 */
void spp_connection_down_callback(uint16_t handle)
{
    WICED_BT_TRACE("%s handle:%d rx_bytes:%d\n", __FUNCTION__, handle, spp_rx_bytes);
    spp_handle = 0;
#if defined(SEND_DATA_ON_INTERRUPT) && (SEND_DATA_ON_INTERRUPT==1)
    app_send_offset = 0;
    spp_tx_retry_count = 0;

    if(wiced_is_timer_in_use(&app_tx_timer))
    wiced_stop_timer(&app_tx_timer);
#endif
}

/*
 * Process data received over EA session.  Return TRUE if we were able to allocate buffer to
 * deliver to the host.
 */
wiced_bool_t spp_rx_data_callback(uint16_t handle, uint8_t* p_data, uint32_t data_len)
{
//    int i;
//    wiced_bt_buffer_statistics_t buffer_stats[4];

//    wiced_bt_get_buffer_usage (buffer_stats, sizeof(buffer_stats));

//    WICED_BT_TRACE("0:%d/%d 1:%d/%d 2:%d/%d 3:%d/%d\n", buffer_stats[0].current_allocated_count, buffer_stats[0].max_allocated_count,
//                   buffer_stats[1].current_allocated_count, buffer_stats[1].max_allocated_count,
//                   buffer_stats[2].current_allocated_count, buffer_stats[2].max_allocated_count,
//                   buffer_stats[3].current_allocated_count, buffer_stats[3].max_allocated_count);
//    buffer_report("spp_rx_data_callback");

//    wiced_result_t wiced_bt_get_buffer_usage (&buffer_stats, sizeof(buffer_stats));

    spp_rx_bytes += data_len;

    WICED_BT_TRACE("%s handle:%d len:%d %02x-%02x, total rx %d\n", __FUNCTION__, handle, data_len, p_data[0], p_data[data_len - 1], spp_rx_bytes);

#if LOOPBACK_DATA
    return wiced_bt_spp_send_session_data(handle, p_data, data_len);
#else
    return WICED_TRUE;
#endif
}

/*
 * spp_bt_remote_name_callback
 */
static void spp_bt_remote_name_callback(wiced_bt_dev_remote_name_result_t *p_remote_name_result)
{
    WICED_BT_TRACE("Pairing with: BdAddr:%B Status:%d Len:%d Name:%s\n",
            p_remote_name_result->bd_addr, p_remote_name_result->status,
            p_remote_name_result->length, p_remote_name_result->remote_bd_name);
}

/*
 * Write NVRAM function is called to store information in the NVRAM.
 */
int app_write_nvram(int nvram_id, int data_len, void *p_data)
{
    wiced_result_t  result;
    int             bytes_written = wiced_hal_write_nvram(nvram_id, data_len, (uint8_t*)p_data, &result);

    WICED_BT_TRACE("NVRAM ID:%d written :%d bytes result:%d\n", nvram_id, bytes_written, result);
    return (bytes_written);
}

/*
 * Read data from the NVRAM and return in the passed buffer
 */
int app_read_nvram(int nvram_id, void *p_data, int data_len)
{
    uint16_t        read_bytes = 0;
    wiced_result_t  result;

    if (data_len >= sizeof(wiced_bt_device_link_keys_t))
    {
        read_bytes = wiced_hal_read_nvram(nvram_id, sizeof(wiced_bt_device_link_keys_t), p_data, &result);
        WICED_BT_TRACE("NVRAM ID:%d read out of %d bytes:%d result:%d\n", nvram_id, sizeof(wiced_bt_device_link_keys_t), read_bytes, result);
    }
    return (read_bytes);
}

#if SEND_DATA_ON_INTERRUPT
/*
 * Test function which sends as much data as possible.
 */
void app_send_data(void)
{
    int i;
    wiced_bool_t ret;

    while ((spp_handle != 0) && (app_send_offset != APP_TOTAL_DATA_TO_SEND))
    {
        int bytes_to_send = app_send_offset + SPP_MAX_PAYLOAD < APP_TOTAL_DATA_TO_SEND ? SPP_MAX_PAYLOAD : APP_TOTAL_DATA_TO_SEND - app_send_offset;
        ret = wiced_bt_spp_can_send_more_data(spp_handle);
        if(!ret)
        {
            // buffer_report(" app_send_data can't send");
            // WICED_BT_TRACE(" ! return from wiced_bt_spp_can_send_more_data\n");
            break;
        }
        for (i = 0; i < bytes_to_send; i++)
        {
            app_send_buffer[i] = app_send_offset + i;
        }
        ret = wiced_bt_spp_send_session_data(spp_handle, app_send_buffer, bytes_to_send);
        if(ret != WICED_TRUE)
        {
            // WICED_BT_TRACE(" ! return from wiced_bt_spp_send_session_data\n");
            break;
        }
        app_send_offset += bytes_to_send;
        spp_tx_retry_count = 0;
    }
    // Check if we were able to send everything
    if (app_send_offset < APP_TOTAL_DATA_TO_SEND)
    {
        if(spp_tx_retry_count >= MAX_TX_RETRY)
        {
		WICED_BT_TRACE("Reached max tx retries! Terminating transfer!\n");
		WICED_BT_TRACE("Make sure peer device is providing us credits\n");
		app_send_offset = 0;
        }
        else
        {
            WICED_BT_TRACE("wiced_start_timer app_tx_timer %d\n", app_send_offset);
		wiced_start_timer(&app_tx_timer, TX_RETRY_TIMEOUT);
		spp_tx_retry_count++;
        }
    }
    else
    {
        uint32_t time_tx = clock_SystemTimeMicroseconds64() / 1000 - time_start;
        WICED_BT_TRACE("sent %d in %dmsec (%dKbps)\n", APP_TOTAL_DATA_TO_SEND, time_tx, APP_TOTAL_DATA_TO_SEND * 8 / time_tx);
        app_send_offset = 0;
    }
}

/*
 * Test function which start sending data.
 */
void app_interrupt_handler(void *data, uint8_t port_pin)
{
    WICED_BT_TRACE("gpio_interrupt_handler pin:%d send_offset:%d\n", port_pin, app_send_offset);
    time_start = clock_SystemTimeMicroseconds64() / 1000;

     /* Get the status of interrupt on P# */
    if (wiced_hal_gpio_get_pin_interrupt_status(BUTTON_GPIO))
    {
        /* Clear the GPIO interrupt */
        wiced_hal_gpio_clear_pin_interrupt_status(BUTTON_GPIO);
    }
    // If we are already sending data, do nothing
    if (app_send_offset != 0)
        return;

    app_send_data();
}

/*
 * The timeout function is periodically called while we are sending big amount of data
 */
void app_tx_ack_timeout(TIMER_PARAM_TYPE param)
{
    app_send_data();
}
#endif


#ifdef HCI_TRACE_OVER_TRANSPORT
/*
 *  Pass protocol traces up over the transport
 */
void app_trace_callback(wiced_bt_hci_trace_type_t type, uint16_t length, uint8_t* p_data)
{
#if BTSTACK_VER >= 0x03000001
    wiced_transport_send_hci_trace( type, p_data, length );
#else
    wiced_transport_send_hci_trace(host_trans_pool, type, length, p_data);
#endif
}
#endif

 

우선은 debug print를 UART로 보고 싶으니 debug를 PUART로 바꿔 놓는다.

    APPLICATION_START()
    {
    ...
        //wiced_set_debug_uart(WICED_ROUTE_DEBUG_TO_WICED_UART);
        wiced_hal_puart_configuration(921600, PARITY_NONE, STOP_BIT_1);
        wiced_set_debug_uart(WICED_ROUTE_DEBUG_TO_PUART);
    ...
    }

 

spp를 연결하면 button push를 인식하여 Tx throughput을 측정하는 것은 지원한다.

app_management_callback 2
Power mgmt status event: bd (be ef be ef 7e f6 ) status:2 hci_status:0
wiced_start_timer app_tx_timer 961685
wiced_start_timer app_tx_timer 961685
wiced_start_timer app_tx_timer 961685
wiced_start_timer app_tx_timer 961685
app_management_callback 2
Power mgmt status event: bd (be ef be ef 7e f6 ) status:0 hci_status:0
wiced_start_timer app_tx_timer 961685
wiced_start_timer app_tx_timer 964706
wiced_start_timer app_tx_timer 970748
wiced_start_timer app_tx_timer 976790
wiced_start_timer app_tx_timer 982832
wiced_start_timer app_tx_timer 988874
wiced_start_timer app_tx_timer 994916
sent 1000000 in 23744msec (336Kbps)
app_management_callback 2
Power mgmt status event: bd (be ef be ef 7e f6 ) status:2 hci_status:0

1M 보내는데 23초가 걸린다. 이건 사용할 수 없는 수준이다. 

 

반복되는 Power mgmt status event가 수상하다.

p_power_mgmt_notification->status가 0 -> 2 -> 0 으로 계속 변경되는데 확인해보면 0은 active mode, 2는 sniff mode로 들어갔다는 이야기다.

sniff상태로 data를 보내면 상당히 느리기 때문에 우선 sniff에 들어가지 않도록 해야 한다.

 

API document를 살펴보자.

https://infineon.github.io/btsdk-docs/BT-SDK/20719-B2_Bluetooth/API/index.html

 

AIROC™ CYW20719: Main Page

This page collects software and hardware documentation related to the CYW20719 family of devices and evaluation kits. Links to AIROC™ BTSDK software API reference material, user guides, and hardware documentation can be found below. AIROC™ API Referenc

infineon.github.io

wiced_bt_dev_cancel_sniff_mode()를 지원한다. 그런데 이건 sniff에서 빠져나오는 것이다. 우리가 필요한 것은 sniff에 들어가지 않는 것인다.

wiced_bt_dev_set_link_policy()는 연결되어 있는 device마다 link와 관련된 setting을 정할 수 있다.

API가 모두 wiced로 시작하는 것은 AIROC이 이전에는 WICED라는 이름으로 출발했기 때문이다.

parameter로 bd address와 link settings가 필요하다. bd address는 연결할 때 저장했다가 사용하면 되고, settings는 hcidefs.h를 참고하면 된다.

/* Policy settings status */
#define HCI_DISABLE_ALL_LM_MODES        0x0000
#define HCI_ENABLE_ROLE_SWITCH          0x0001
#define HCI_ENABLE_HOLD_MODE            0x0002
#define HCI_ENABLE_SNIFF_MODE           0x0004
#define HCI_ENABLE_PARK_MODE            0x0008
/*
 * SPP connection up callback
 */
 wiced_bt_device_address_t       peer_addr;
void spp_connection_up_callback(uint16_t handle, uint8_t* bda)
{
	uint16_t link_settings;
    WICED_BT_TRACE("%s handle:%d address:%B\n", __FUNCTION__, handle, bda);
    spp_handle = handle;
    spp_rx_bytes = 0;
    memcpy(peer_addr, bda, 6);
    link_settings = HCI_ENABLE_ROLE_SWITCH;
    wiced_bt_dev_set_link_policy(peer_addr, &link_settings);
}

연결하고나면 link policy를 변경하여 sniff에 빠지 않게 한다.

크게 필요해 보이진 않지만 app_send_data()에도 wiced_bt_dev_cancel_sniff_mode(peer_addr);를 추가하여 혹시라도 sniff에 들어갔다가면 나올 수 있게 해준다.

wiced_start_timer app_tx_timer 958664
wiced_start_timer app_tx_timer 964706
wiced_start_timer app_tx_timer 970748
wiced_start_timer app_tx_timer 976790
wiced_start_timer app_tx_timer 982832
wiced_start_timer app_tx_timer 988874
wiced_start_timer app_tx_timer 994916
sent 1000000 in 17277msec (463Kbps)

대략 17초로 줄어들긴 했지만 이걸로 만족할 수는 없다.

 

code를 보면 app_tx_timer를 TX_RETRY_TIMEOUT 주기로 호출하여 app_tx_ack_timeout callback을 부른다.

app_tx_ack_timeout에서 app_send_data();를 이용하여 Tx를 하고 있다.

즉, 100ms마다 data를 보내게 된다.

#define MAX_TX_RETRY                 100
#define TX_RETRY_TIMEOUT             10 // msec
wiced_start_timer app_tx_timer 982832
wiced_start_timer app_tx_timer 982832
wiced_start_timer app_tx_timer 985853
wiced_start_timer app_tx_timer 988874
wiced_start_timer app_tx_timer 991895
wiced_start_timer app_tx_timer 994916
wiced_start_timer app_tx_timer 997937
sent 1000000 in 4602msec (1738Kbps)

약 5초가량이 되었다.

 

수정된 spp.c code (더보기를 누르면 전체 코드를 확인 가능)

더보기
/*
 * Copyright 2016-2022, Cypress Semiconductor Corporation (an Infineon company) or
 * an affiliate of Cypress Semiconductor Corporation.  All rights reserved.
 *
 * This software, including source code, documentation and related
 * materials ("Software") is owned by Cypress Semiconductor Corporation
 * or one of its affiliates ("Cypress") and is protected by and subject to
 * worldwide patent protection (United States and foreign),
 * United States copyright laws and international treaty provisions.
 * Therefore, you may use this Software only as provided in the license
 * agreement accompanying the software package from which you
 * obtained this Software ("EULA").
 * If no EULA applies, Cypress hereby grants you a personal, non-exclusive,
 * non-transferable license to copy, modify, and compile the Software
 * source code solely for use in connection with Cypress's
 * integrated circuit products.  Any reproduction, modification, translation,
 * compilation, or representation of this Software except as specified
 * above is prohibited without the express written permission of Cypress.
 *
 * Disclaimer: THIS SOFTWARE IS PROVIDED AS-IS, WITH NO WARRANTY OF ANY KIND,
 * EXPRESS OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, NONINFRINGEMENT, IMPLIED
 * WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. Cypress
 * reserves the right to make changes to the Software without notice. Cypress
 * does not assume any liability arising out of the application or use of the
 * Software or any product or circuit described in the Software. Cypress does
 * not authorize its products for use in any products where a malfunction or
 * failure of the Cypress product may reasonably be expected to result in
 * significant property damage, injury or death ("High Risk Product"). By
 * including Cypress's product in a High Risk Product, the manufacturer
 * of such system or application assumes all risk of such use and in doing
 * so agrees to indemnify Cypress against all liability.
 */

/** @file
 *
 * SPP Application for 20XXX devices.
 *
 * SPP application uses SPP profile library to establish, terminate, send and receive SPP
 * data over BR/EDR. This sample supports single a single SPP connection.
 *
 * Following compilation flags are important for testing
 *  HCI_TRACE_OVER_TRANSPORT - configures HCI traces to be routed to the WICED HCI interface
 *  WICED_BT_TRACE_ENABLE    - enables WICED_BT_TRACEs.  You can also modify makefile.mk to build
 *                             with _debug version of the library
 *  SEND_DATA_ON_INTERRUPT   - if defined, the app will send 1Meg of data on application button push
 *  SEND_DATA_ON_TIMEOUT     - if defined, the app will send 4 bytes every second while session is up
 *  LOOPBACK_DATA            - if enabled, the app sends back received data
 *
 * To demonstrate the app, work through the following steps.
 * 1. Build and download the application to the WICED board.
 * 2. Open the Bluetooth Classic and LE Profile Client Control application and open the port for WICED HCI for the device.
 *    Default baud rate configured in the application is defined by the BSP HCI_UART_DEAULT_BAUD #define,
 *    usually either 3M or 115200 depending on board UART capabilities.
 * 3. Run the BTSpy program to view protocol and application traces.
 *    See "Bluetooth Classic and LE Profile Client Control" and "BTSpy" in chip-specifc readme.txt for more information about these apps.
 * 4. On Windows 10 PCs, right click on the Bluetooth icon in the system tray and
 *    select 'Add a Bluetooth Device'. Find and pair with the spp app. That should create an incoming and an outgoing
 *    COM port on your computer. Right click on the Bluetooth icon in the system tray and
 *    select 'Open Settings', scroll down and select "More Bluetooth options" and then
 *    select the 'COM Ports' tab.
 * 5. Use application such as Term Term to open the outgoing COM port. Opening the port
 *    will create the SPP connection.
 * 6. Type any key on the terminal of the outgoing COM port, the spp application will receive the key.
 * 7. By default, (SEND_DATA_ON_INTERRUPT=1) the application sends 1 MB data to the peer application on every
 *    App button press on the WICED board.
 * 8. If desired, edit the spp.c file to configure the application to send data on a timer to the peer application by
 *    setting SEND_DATA_ON_INTERRUPT=0 and SEND_DATA_ON_TIMEOUT=1*
 *
 * Features demonstrated
 *  - Use of SPP library
 *
 *  Note: This snippet app does not support WICED HCI Control and may use transport only for tracing.
 *  If you route traces to WICED HCI UART, use ClientControl app with baud rate equal to that
 *  set in the wiced_transport_cfg_t structure below (currently set at HCI_UART_DEFAULT_BAUD, either 3 Mbps or 115200
 *  depending on the capabilities of the board used).
 */

#include "sparcommon.h"
#include "bt_types.h"
#include "wiced.h"
#include "wiced_gki.h"
#include "wiced_bt_dev.h"
#include "wiced_bt_sdp.h"
#include "wiced_bt_ble.h"
#include "wiced_bt_uuid.h"
#include "wiced_hal_nvram.h"
#include "wiced_bt_trace.h"
#include "wiced_bt_cfg.h"
#include "wiced_bt_spp.h"
#include "wiced_hci.h"
#include "wiced_timer.h"
#include "wiced_transport.h"
#include "wiced_platform.h"
#include "wiced_memory.h"
#include "string.h"
#include "wiced_bt_stack.h"
#include "wiced_bt_rfcomm.h"
#include "cycfg_sdp_db.h"
#include "wiced_hal_puart.h"
#if defined(CYW20706A2) || defined(CYW43012C0)
#include "wiced_bt_app_hal_common.h"
#endif

#if BTSTACK_VER >= 0x03000001
#include "wiced_memory.h"
#include "clock_timer.h"
#define BT_STACK_HEAP_SIZE          1024 * 6
wiced_bt_heap_t *p_default_heap   = NULL;
#endif

#define HCI_TRACE_OVER_TRANSPORT            1   // If defined HCI traces are send over transport/WICED HCI interface
// configure either SEND_DATA_ON_INTERRUPT or SEND_DATA_ON_TIMEOUT, but not both
// CYW9M2BASE-43012BT does not support SEND_DATA_ON_INTERRUPT because the platform does not have button connected to Bluetooth board.
#if defined (NO_BUTTON_SUPPORT)
#if defined(SEND_DATA_ON_INTERRUPT) && (SEND_DATA_ON_INTERRUPT==1)
#undef SEND_DATA_ON_INTERRUPT                   // disable SEND_DATA_ON_INTERRUPT is no app button
#define SEND_DATA_ON_TIMEOUT                1
#endif
#endif

//#define LOOPBACK_DATA                     1   // If defined application loops back received data

#define WICED_EIR_BUF_MAX_SIZE              264
#define SPP_NVRAM_ID                        WICED_NVRAM_VSID_START

/* Max TX packet to be sent over SPP */
#define MAX_TX_BUFFER                       1017
#define TRANS_MAX_BUFFERS                   2
#define TRANS_UART_BUFFER_SIZE              1024
#define SPP_MAX_PAYLOAD                     1007

#if SEND_DATA_ON_INTERRUPT
#include "wiced_hal_gpio.h"
#include "wiced_platform.h"

#define APP_TOTAL_DATA_TO_SEND             1000000
#define BUTTON_GPIO                         WICED_P30

#if defined(CYW43012C0)
#define WICED_PLATFORM_BUTTON_1          WICED_P00
#ifndef WICED_GPIO_BUTTON
#define WICED_GPIO_BUTTON                WICED_PLATFORM_BUTTON_1
#endif
#ifndef WICED_GPIO_BUTTON_DEFAULT_STATE
#define WICED_GPIO_BUTTON_DEFAULT_STATE  GPIO_PIN_OUTPUT_HIGH
#endif
#endif

int     app_send_offset = 0;
uint8_t app_send_buffer[SPP_MAX_PAYLOAD];
uint32_t time_start = 0;
#endif

#ifdef SEND_DATA_ON_TIMEOUT
wiced_timer_t spp_app_timer;
void app_timeout(TIMER_PARAM_TYPE arg);
#endif

/*****************************************************************************
**  Structures
*****************************************************************************/
#define SPP_RFCOMM_SCN               2

#define MAX_TX_RETRY                 100
#define TX_RETRY_TIMEOUT             10 // msec

static void         spp_connection_up_callback(uint16_t handle, uint8_t* bda);
static void         spp_connection_down_callback(uint16_t handle);
static wiced_bool_t spp_rx_data_callback(uint16_t handle, uint8_t* p_data, uint32_t data_len);
static void         spp_bt_remote_name_callback(wiced_bt_dev_remote_name_result_t *p_remote_name_result);

wiced_bt_spp_reg_t spp_reg =
{
    SPP_RFCOMM_SCN,                     /* RFCOMM service channel number for SPP connection */
    MAX_TX_BUFFER,                      /* RFCOMM MTU for SPP connection */
    spp_connection_up_callback,         /* SPP connection established */
    NULL,                               /* SPP connection establishment failed, not used because this app never initiates connection */
    NULL,                               /* SPP service not found, not used because this app never initiates connection */
    spp_connection_down_callback,       /* SPP connection disconnected */
    spp_rx_data_callback,               /* Data packet received */
};
#if BTSTACK_VER < 0x03000001
wiced_transport_buffer_pool_t*  host_trans_pool;
#endif
uint16_t                        spp_handle = 0;
wiced_timer_t                   app_tx_timer;
uint32_t                        spp_rx_bytes = 0;
uint32_t                        spp_tx_retry_count = 0;
wiced_bt_device_address_t       peer_addr;
uint8_t pincode[4] = { 0x30, 0x30, 0x30, 0x30 };

extern const wiced_bt_cfg_settings_t wiced_bt_cfg_settings;
#if BTSTACK_VER < 0x03000001
extern const wiced_bt_cfg_buf_pool_t wiced_bt_cfg_buf_pools[WICED_BT_CFG_NUM_BUF_POOLS];
#endif

#if defined WICED_BT_TRACE_ENABLE || defined HCI_TRACE_OVER_TRANSPORT
const wiced_transport_cfg_t transport_cfg =
{
    .type = WICED_TRANSPORT_UART,
    .cfg =
    {
        .uart_cfg =
        {
            .mode = WICED_TRANSPORT_UART_HCI_MODE,
            .baud_rate =  HCI_UART_DEFAULT_BAUD
        },
    },
#if BTSTACK_VER >= 0x03000001
        .heap_config =
        {
            .data_heap_size = 1024 * 4 + 1500 * 2,
            .hci_trace_heap_size = 1024 * 2,
            .debug_trace_heap_size = 1024,
        },
#else
    .rx_buff_pool_cfg =
    {
        .buffer_size  = TRANS_UART_BUFFER_SIZE,
        .buffer_count = 1
    },
#endif
    .p_status_handler    = NULL,
    .p_data_handler      = NULL,
    .p_tx_complete_cback = NULL
};
#endif

/*******************************************************************
 * Function Prototypes
 ******************************************************************/
static wiced_bt_dev_status_t app_management_callback (wiced_bt_management_evt_t event, wiced_bt_management_evt_data_t *p_event_data);
static void                  app_write_eir(void);
static int                   app_write_nvram(int nvram_id, int data_len, void *p_data);
static int                   app_read_nvram(int nvram_id, void *p_data, int data_len);

#if SEND_DATA_ON_INTERRUPT
static void                  app_tx_ack_timeout(TIMER_PARAM_TYPE param);
static void                  app_interrupt_handler(void *data, uint8_t port_pin);
#endif
#ifdef HCI_TRACE_OVER_TRANSPORT
static void                  app_trace_callback(wiced_bt_hci_trace_type_t type, uint16_t length, uint8_t* p_data);
#endif

#if defined (CYW20706A2)
extern BOOL32 wiced_hal_puart_select_uart_pads(UINT8 rxdPin, UINT8 txdPin, UINT8 ctsPin, UINT8 rtsPin);
extern wiced_result_t wiced_bt_app_init( void );
#endif

#ifndef CYW20706A2
extern uint64_t clock_SystemTimeMicroseconds64();
#else
#include "rtc.h"
uint64_t clock_SystemTimeMicroseconds64(void)
{
    tRTC_REAL_TIME_CLOCK rtcClock;
    rtc_getRTCRawClock(&rtcClock);
    // To convert 128 kHz rtc timer to milliseconds divide it by 131: //128 kHz = 128 * 1024 = 131072; to microseconds: 1000000 / 131072 = 7.62939453125 (7.63)
    return rtcClock.rtc64 * 763 / 100;
}
#endif

/*******************************************************************
 * Function Definitions
 ******************************************************************/

void buffer_report(char *msg)
{
#if BTSTACK_VER >= 0x03000001
    /*
     * Get statistics of default heap.
     * TODO: get statistics of stack heap (btu_cb.p_heap)
     */
    wiced_bt_heap_statistics_t heap_stat;

    if (wiced_bt_get_heap_statistics(p_default_heap, &heap_stat))
    {
        WICED_BT_TRACE("--- heap_size:%d ---\n", heap_stat.heap_size);
        WICED_BT_TRACE("max_single_allocation:%d max_heap_size_used:%d\n",
                        heap_stat.max_single_allocation,
                        heap_stat.max_heap_size_used);
        WICED_BT_TRACE("allocation_failure_count:%d current_largest_free_size:%d\n",
                        heap_stat.allocation_failure_count,
                        heap_stat.current_largest_free_size);
        WICED_BT_TRACE("current_num_allocations:%d current_size_allocated:%d\n",
                        heap_stat.current_num_allocations,
                        heap_stat.current_size_allocated);
        WICED_BT_TRACE("current_num_free_fragments:%d current_free_size\n",
                        heap_stat.current_num_free_fragments,
                        heap_stat.current_free_size);
    }
    else
    {
        WICED_BT_TRACE("buffer_report: wiced_bt_get_heap_statistics failed\n");
    }
#else /* !BTSTACK_VER */

    wiced_bt_buffer_statistics_t buffer_stats[5];
    wiced_result_t result;

    result = wiced_bt_get_buffer_usage (buffer_stats, sizeof(buffer_stats));

    if (result == WICED_BT_SUCCESS)
    {
        WICED_BT_TRACE("%s: pool %x %d %d/%d/%d\n", msg,
                buffer_stats[1].pool_id,
                buffer_stats[1].pool_size,
                buffer_stats[1].current_allocated_count,
                buffer_stats[1].max_allocated_count,
                buffer_stats[1].total_count);
        WICED_BT_TRACE("%s: pool %x %d %d/%d/%d\n", msg,
                buffer_stats[2].pool_id,
                buffer_stats[2].pool_size,
                buffer_stats[2].current_allocated_count,
                buffer_stats[2].max_allocated_count,
                buffer_stats[2].total_count);
    }
    else
        WICED_BT_TRACE("buffer_report: wiced_bt_get_buffer_usage failed, returned %d\n", result);
#endif
}

/*
 * Entry point to the application. Set device configuration and start Bluetooth
 * stack initialization.  The actual application initialization will happen
 * when stack reports that Bluetooth device is ready
 */
APPLICATION_START()
{
    wiced_result_t result;
    int interupt = 0, timeout = 0, loopback = 0;

#if defined WICED_BT_TRACE_ENABLE || defined HCI_TRACE_OVER_TRANSPORT
    wiced_transport_init(&transport_cfg);

#if BTSTACK_VER < 0x03000001
    // create special pool for sending data to the MCU
    host_trans_pool = wiced_transport_create_buffer_pool(TRANS_UART_BUFFER_SIZE, TRANS_MAX_BUFFERS);
#endif

    // Set the debug uart as WICED_ROUTE_DEBUG_NONE to get rid of prints
    // wiced_set_debug_uart(WICED_ROUTE_DEBUG_NONE);

    // Set to PUART to see traces on peripheral uart(puart) if platform has PUART
#ifdef NO_PUART_SUPPORT
    // wiced_set_debug_uart( WICED_ROUTE_DEBUG_TO_WICED_UART );
#else
    // wiced_set_debug_uart( WICED_ROUTE_DEBUG_TO_PUART );
#if defined (CYW20706A2)
    // wiced_hal_puart_select_uart_pads( WICED_PUART_RXD, WICED_PUART_TXD, 0, 0);
#endif
#endif

    // Set to HCI to see traces on HCI uart - default if no call to wiced_set_debug_uart()
    // wiced_set_debug_uart( WICED_ROUTE_DEBUG_TO_HCI_UART );

    // Use WICED_ROUTE_DEBUG_TO_WICED_UART to send formatted debug strings over the WICED
    // HCI debug interface to be parsed by ClientControl/BtSpy.
    //wiced_set_debug_uart(WICED_ROUTE_DEBUG_TO_WICED_UART);
    wiced_hal_puart_configuration(921600, PARITY_NONE, STOP_BIT_1);
    wiced_set_debug_uart(WICED_ROUTE_DEBUG_TO_PUART);
#endif

#if SEND_DATA_ON_INTERRUPT
    interupt = 1;
#endif
#if SEND_DATA_ON_TIMEOUT
    timeout = 1;
#endif
#if LOOPBACK_DATA
    loopback = 1;
#endif
    WICED_BT_TRACE("APP Start, interupt=%d, timeout=%d, loopback=%d\n", interupt, timeout, loopback);

#if BTSTACK_VER >= 0x03000001
    /* Create default heap */
    p_default_heap = wiced_bt_create_heap("default_heap", NULL, BT_STACK_HEAP_SIZE, NULL, WICED_TRUE);
    if (p_default_heap == NULL)
    {
        WICED_BT_TRACE("create default heap error: size %d\n", BT_STACK_HEAP_SIZE);
        return;
    }
    /* Initialize Stack and Register Management Callback */
    // Register call back and configuration with stack
    wiced_bt_stack_init(app_management_callback, &wiced_bt_cfg_settings);
#else
    /* Initialize Stack and Register Management Callback */
    // Register call back and configuration with stack
    wiced_bt_stack_init(app_management_callback, &wiced_bt_cfg_settings, wiced_bt_cfg_buf_pools);
#endif
}

/*
 * SPP application initialization is executed after Bluetooth stack initialization is completed.
 */
void application_init(void)
{
    wiced_result_t         result;

#if defined (CYW20706A2)
    /* Initialize wiced app */
    wiced_bt_app_init();

    /* Initialize the RTC block */
    rtc_init();
#endif

#if SEND_DATA_ON_INTERRUPT
#if !defined (CYW20706A2) && !defined (CYW43012C0)
    /* Configure the button available on the platform */
    wiced_platform_register_button_callback( WICED_PLATFORM_BUTTON_1, app_interrupt_handler, NULL, WICED_PLATFORM_BUTTON_RISING_EDGE);
#elif defined(CYW20706A2) || defined(CYW43012C0)
/* Initializes the GPIO driver */
    wiced_bt_app_hal_init();
	wiced_hal_gpio_configure_pin(WICED_GPIO_BUTTON, WICED_GPIO_BUTTON_SETTINGS( GPIO_EN_INT_RISING_EDGE ), WICED_GPIO_BUTTON_DEFAULT_STATE );
	wiced_hal_gpio_register_pin_for_interrupt(WICED_GPIO_BUTTON, app_interrupt_handler, NULL);
#endif // CYW20706A2 && CYW43012C0
    // init timer that we will use for the rx data flow control.
    wiced_init_timer(&app_tx_timer, app_tx_ack_timeout, 0, WICED_MILLI_SECONDS_TIMER);
#endif // SEND_DATA_ON_INTERRUPT

    app_write_eir();

#if defined (CYW20706A2)
    // Initialize RFCOMM.  We will not be using application buffer pool and will rely on the
    // stack pools configured in the wiced_bt_cfg.c
    wiced_bt_rfcomm_init(MAX_TX_BUFFER, 1);
#endif

    // Initialize SPP library
    wiced_bt_spp_startup(&spp_reg);

#ifdef HCI_TRACE_OVER_TRANSPORT
    // There is a virtual HCI interface between upper layers of the stack and
    // the controller portion of the chip with lower layers of the Bluetooth stack.
    // Register with the stack to receive all HCI commands, events and data.
    wiced_bt_dev_register_hci_trace(app_trace_callback);
#endif
    /* create SDP records */
    wiced_bt_sdp_db_init((uint8_t *)sdp_database, sdp_database_len);

    /* Allow peer to pair */
    wiced_bt_set_pairable_mode(WICED_TRUE, 0);

#if BTSTACK_VER >= 0x03000001
        // This application will always configure device connectable and discoverable
    wiced_bt_dev_set_discoverability(BTM_GENERAL_DISCOVERABLE,
                                     WICED_BT_CFG_DEFAULT_INQUIRY_SCAN_INTERVAL,
                                     WICED_BT_CFG_DEFAULT_INQUIRY_SCAN_WINDOW);

    wiced_bt_dev_set_connectability(BTM_CONNECTABLE,
                                    WICED_BT_CFG_DEFAULT_PAGE_SCAN_INTERVAL,
                                    WICED_BT_CFG_DEFAULT_PAGE_SCAN_WINDOW);
#else
    // This application will always configure device connectable and discoverable
    wiced_bt_dev_set_discoverability(BTM_GENERAL_DISCOVERABLE,
        wiced_bt_cfg_settings.br_edr_scan_cfg.inquiry_scan_interval,
        wiced_bt_cfg_settings.br_edr_scan_cfg.inquiry_scan_window);

    wiced_bt_dev_set_connectability(BTM_CONNECTABLE,
        wiced_bt_cfg_settings.br_edr_scan_cfg.page_scan_interval,
        wiced_bt_cfg_settings.br_edr_scan_cfg.page_scan_window);
#endif

#if SEND_DATA_ON_TIMEOUT
    /* Starting the app timers, seconds timer and the ms timer  */
    wiced_init_timer(&spp_app_timer, app_timeout, 0, WICED_SECONDS_PERIODIC_TIMER);
    wiced_start_timer(&spp_app_timer, 1);
#endif
}

/*
 *  Management callback receives various notifications from the stack
 */
wiced_result_t app_management_callback(wiced_bt_management_evt_t event, wiced_bt_management_evt_data_t *p_event_data)
{
    wiced_result_t                      result = WICED_BT_SUCCESS;
    wiced_bt_dev_status_t               dev_status;
    wiced_bt_dev_pairing_info_t*        p_pairing_info;
    wiced_bt_dev_encryption_status_t*   p_encryption_status;
    int                                 bytes_written, bytes_read;
    wiced_bt_power_mgmt_notification_t* p_power_mgmt_notification;

    WICED_BT_TRACE("app_management_callback %d\n", event);

    switch(event)
    {
    /* Bluetooth  stack enabled */
    case BTM_ENABLED_EVT:
        application_init();
        //WICED_BT_TRACE("Free mem:%d", cfa_mm_MemFreeBytes());
        break;

    case BTM_DISABLED_EVT:
        break;

    case BTM_PIN_REQUEST_EVT:
        WICED_BT_TRACE("remote address= %B\n", p_event_data->pin_request.bd_addr);
        wiced_bt_dev_pin_code_reply(*p_event_data->pin_request.bd_addr,result/*WICED_BT_SUCCESS*/,4, &pincode[0]);
        break;

    case BTM_USER_CONFIRMATION_REQUEST_EVT:
        /* This application always confirms peer's attempt to pair */
        wiced_bt_dev_confirm_req_reply (WICED_BT_SUCCESS, p_event_data->user_confirmation_request.bd_addr);
        /* get the remote name to show in the log */
        result = wiced_bt_dev_get_remote_name(p_event_data->user_confirmation_request.bd_addr, spp_bt_remote_name_callback);
        break;

    case BTM_PAIRING_IO_CAPABILITIES_BR_EDR_REQUEST_EVT:
        /* This application supports only Just Works pairing */
        WICED_BT_TRACE("BTM_PAIRING_IO_CAPABILITIES_REQUEST_EVT bda %B\n", p_event_data->pairing_io_capabilities_br_edr_request.bd_addr);
        p_event_data->pairing_io_capabilities_br_edr_request.local_io_cap   = BTM_IO_CAPABILITIES_NONE;
        p_event_data->pairing_io_capabilities_br_edr_request.auth_req       = BTM_AUTH_SINGLE_PROFILE_GENERAL_BONDING_NO;
        break;

    case BTM_PAIRING_COMPLETE_EVT:
        p_pairing_info = &p_event_data->pairing_complete.pairing_complete_info;
        WICED_BT_TRACE("Pairing Complete: %d\n", p_pairing_info->br_edr.status);
        result = WICED_BT_USE_DEFAULT_SECURITY;
        break;

    case BTM_ENCRYPTION_STATUS_EVT:
        p_encryption_status = &p_event_data->encryption_status;
        WICED_BT_TRACE("Encryption Status Event: bd (%B) res %d\n", p_encryption_status->bd_addr, p_encryption_status->result);
        break;

    case BTM_PAIRED_DEVICE_LINK_KEYS_UPDATE_EVT:
        /* This application supports a single paired host, we can save keys under the same NVRAM ID overwriting previous pairing if any */
        app_write_nvram(SPP_NVRAM_ID, sizeof(wiced_bt_device_link_keys_t), &p_event_data->paired_device_link_keys_update);
        break;

    case  BTM_PAIRED_DEVICE_LINK_KEYS_REQUEST_EVT:
        /* read existing key from the NVRAM  */
        if (app_read_nvram(SPP_NVRAM_ID, &p_event_data->paired_device_link_keys_request, sizeof(wiced_bt_device_link_keys_t)) != 0)
        {
            result = WICED_BT_SUCCESS;
        }
        else
        {
            result = WICED_BT_ERROR;
            WICED_BT_TRACE("Key retrieval failure\n");
        }
        break;

    case BTM_POWER_MANAGEMENT_STATUS_EVT:
        p_power_mgmt_notification = &p_event_data->power_mgmt_notification;
        WICED_BT_TRACE("Power mgmt status event: bd (%B) status:%d hci_status:%d\n", p_power_mgmt_notification->bd_addr, \
                p_power_mgmt_notification->status, p_power_mgmt_notification->hci_status);
        break;

    default:
        result = WICED_BT_USE_DEFAULT_SECURITY;
        break;
    }
    return result;
}


/*
 *  Prepare extended inquiry response data.  Current version publishes device name and 16bit
 *  SPP service.
 */
void app_write_eir(void)
{
    uint8_t *pBuf;
    uint8_t *p;
    uint8_t length;
    uint16_t eir_length;

    pBuf = (uint8_t *)wiced_bt_get_buffer(WICED_EIR_BUF_MAX_SIZE);
    WICED_BT_TRACE("hci_control_write_eir %x\n", pBuf);

    if (!pBuf)
    {
        WICED_BT_TRACE("app_write_eir %x\n", pBuf);
        return;
    }

    p = pBuf;

    length = strlen((char *)wiced_bt_cfg_settings.device_name);

    *p++ = length + 1;
    *p++ = BT_EIR_COMPLETE_LOCAL_NAME_TYPE;        // EIR type full name
    memcpy(p, wiced_bt_cfg_settings.device_name, length);
    p += length;

    *p++ = 2 + 1;                                   // Length of 16 bit services
    *p++ = BT_EIR_COMPLETE_16BITS_UUID_TYPE;        // 0x03 EIR type full list of 16 bit service UUIDs
    *p++ = UUID_SERVCLASS_SERIAL_PORT & 0xff;
    *p++ = (UUID_SERVCLASS_SERIAL_PORT >> 8) & 0xff;

    *p++ = 0;                                       // end of EIR Data is 0

    eir_length = (uint16_t) (p - pBuf);

    // print EIR data
    WICED_BT_TRACE_ARRAY(pBuf, MIN(p-pBuf, 100), "EIR :");
    wiced_bt_dev_write_eir(pBuf, eir_length);

    return;
}

/*
 * The function invoked on timeout of app seconds timer.
 */
#if SEND_DATA_ON_TIMEOUT
void app_timeout(TIMER_PARAM_TYPE arg)
{
    static uint32_t timer_count = 0;
    timer_count++;
    wiced_bool_t ret;
    WICED_BT_TRACE("app_timeout: %d, handle %d \n", timer_count, spp_handle);
    if (spp_handle != 0)
    {
        ret = wiced_bt_spp_send_session_data(spp_handle, (uint8_t *)&timer_count, sizeof(uint32_t));
        if (ret != WICED_TRUE)
            WICED_BT_TRACE("wiced_bt_spp_send_session_data failed, ret = %d\n", ret);
    }
}
#endif

/*
 * SPP connection up callback
 */
void spp_connection_up_callback(uint16_t handle, uint8_t* bda)
{
	uint16_t link_settings;
    WICED_BT_TRACE("%s handle:%d address:%B\n", __FUNCTION__, handle, bda);
    spp_handle = handle;
    spp_rx_bytes = 0;
    memcpy(peer_addr, bda, 6);
    link_settings = HCI_ENABLE_ROLE_SWITCH;
    wiced_bt_dev_set_link_policy(peer_addr, &link_settings);
}

/*
 * SPP connection down callback
 */
void spp_connection_down_callback(uint16_t handle)
{
    WICED_BT_TRACE("%s handle:%d rx_bytes:%d\n", __FUNCTION__, handle, spp_rx_bytes);
    spp_handle = 0;
#if defined(SEND_DATA_ON_INTERRUPT) && (SEND_DATA_ON_INTERRUPT==1)
    app_send_offset = 0;
    spp_tx_retry_count = 0;

    if(wiced_is_timer_in_use(&app_tx_timer))
    wiced_stop_timer(&app_tx_timer);
#endif
}

/*
 * Process data received over EA session.  Return TRUE if we were able to allocate buffer to
 * deliver to the host.
 */
wiced_bool_t spp_rx_data_callback(uint16_t handle, uint8_t* p_data, uint32_t data_len)
{
//    int i;
//    wiced_bt_buffer_statistics_t buffer_stats[4];

//    wiced_bt_get_buffer_usage (buffer_stats, sizeof(buffer_stats));

//    WICED_BT_TRACE("0:%d/%d 1:%d/%d 2:%d/%d 3:%d/%d\n", buffer_stats[0].current_allocated_count, buffer_stats[0].max_allocated_count,
//                   buffer_stats[1].current_allocated_count, buffer_stats[1].max_allocated_count,
//                   buffer_stats[2].current_allocated_count, buffer_stats[2].max_allocated_count,
//                   buffer_stats[3].current_allocated_count, buffer_stats[3].max_allocated_count);
//    buffer_report("spp_rx_data_callback");

//    wiced_result_t wiced_bt_get_buffer_usage (&buffer_stats, sizeof(buffer_stats));

    spp_rx_bytes += data_len;

    WICED_BT_TRACE("%s handle:%d len:%d %02x-%02x, total rx %d\n", __FUNCTION__, handle, data_len, p_data[0], p_data[data_len - 1], spp_rx_bytes);

#if LOOPBACK_DATA
    return wiced_bt_spp_send_session_data(handle, p_data, data_len);
#else
    return WICED_TRUE;
#endif
}

/*
 * spp_bt_remote_name_callback
 */
static void spp_bt_remote_name_callback(wiced_bt_dev_remote_name_result_t *p_remote_name_result)
{
    WICED_BT_TRACE("Pairing with: BdAddr:%B Status:%d Len:%d Name:%s\n",
            p_remote_name_result->bd_addr, p_remote_name_result->status,
            p_remote_name_result->length, p_remote_name_result->remote_bd_name);
}

/*
 * Write NVRAM function is called to store information in the NVRAM.
 */
int app_write_nvram(int nvram_id, int data_len, void *p_data)
{
    wiced_result_t  result;
    int             bytes_written = wiced_hal_write_nvram(nvram_id, data_len, (uint8_t*)p_data, &result);

    WICED_BT_TRACE("NVRAM ID:%d written :%d bytes result:%d\n", nvram_id, bytes_written, result);
    return (bytes_written);
}

/*
 * Read data from the NVRAM and return in the passed buffer
 */
int app_read_nvram(int nvram_id, void *p_data, int data_len)
{
    uint16_t        read_bytes = 0;
    wiced_result_t  result;

    if (data_len >= sizeof(wiced_bt_device_link_keys_t))
    {
        read_bytes = wiced_hal_read_nvram(nvram_id, sizeof(wiced_bt_device_link_keys_t), p_data, &result);
        WICED_BT_TRACE("NVRAM ID:%d read out of %d bytes:%d result:%d\n", nvram_id, sizeof(wiced_bt_device_link_keys_t), read_bytes, result);
    }
    return (read_bytes);
}

#if SEND_DATA_ON_INTERRUPT
/*
 * Test function which sends as much data as possible.
 */
void app_send_data(void)
{
    int i;
    wiced_bool_t ret;
    wiced_bt_dev_cancel_sniff_mode(peer_addr);
    while ((spp_handle != 0) && (app_send_offset != APP_TOTAL_DATA_TO_SEND))
    {
        int bytes_to_send = app_send_offset + SPP_MAX_PAYLOAD < APP_TOTAL_DATA_TO_SEND ? SPP_MAX_PAYLOAD : APP_TOTAL_DATA_TO_SEND - app_send_offset;
        ret = wiced_bt_spp_can_send_more_data(spp_handle);
        if(!ret)
        {
            // buffer_report(" app_send_data can't send");
            // WICED_BT_TRACE(" ! return from wiced_bt_spp_can_send_more_data\n");
            break;
        }
        for (i = 0; i < bytes_to_send; i++)
        {
            app_send_buffer[i] = app_send_offset + i;
        }
        ret = wiced_bt_spp_send_session_data(spp_handle, app_send_buffer, bytes_to_send);
        if(ret != WICED_TRUE)
        {
            // WICED_BT_TRACE(" ! return from wiced_bt_spp_send_session_data\n");
            break;
        }
        app_send_offset += bytes_to_send;
        spp_tx_retry_count = 0;
    }
    // Check if we were able to send everything
    if (app_send_offset < APP_TOTAL_DATA_TO_SEND)
    {
        if(spp_tx_retry_count >= MAX_TX_RETRY)
        {
		WICED_BT_TRACE("Reached max tx retries! Terminating transfer!\n");
		WICED_BT_TRACE("Make sure peer device is providing us credits\n");
		app_send_offset = 0;
        }
        else
        {
            WICED_BT_TRACE("wiced_start_timer app_tx_timer %d\n", app_send_offset);
		wiced_start_timer(&app_tx_timer, TX_RETRY_TIMEOUT);
		spp_tx_retry_count++;
        }
    }
    else
    {
        uint32_t time_tx = clock_SystemTimeMicroseconds64() / 1000 - time_start;
        WICED_BT_TRACE("sent %d in %dmsec (%dKbps)\n", APP_TOTAL_DATA_TO_SEND, time_tx, APP_TOTAL_DATA_TO_SEND * 8 / time_tx);
        app_send_offset = 0;
        spp_tx_retry_count = 0;
    }
}

/*
 * Test function which start sending data.
 */
void app_interrupt_handler(void *data, uint8_t port_pin)
{
    WICED_BT_TRACE("gpio_interrupt_handler pin:%d send_offset:%d\n", port_pin, app_send_offset);
    time_start = clock_SystemTimeMicroseconds64() / 1000;

     /* Get the status of interrupt on P# */
    if (wiced_hal_gpio_get_pin_interrupt_status(BUTTON_GPIO))
    {
        /* Clear the GPIO interrupt */
        wiced_hal_gpio_clear_pin_interrupt_status(BUTTON_GPIO);
    }
    // If we are already sending data, do nothing
    if (app_send_offset != 0)
        return;

    app_send_data();
}

/*
 * The timeout function is periodically called while we are sending big amount of data
 */
void app_tx_ack_timeout(TIMER_PARAM_TYPE param)
{
    app_send_data();
}
#endif


#ifdef HCI_TRACE_OVER_TRANSPORT
/*
 *  Pass protocol traces up over the transport
 */
void app_trace_callback(wiced_bt_hci_trace_type_t type, uint16_t length, uint8_t* p_data)
{
#if BTSTACK_VER >= 0x03000001
    wiced_transport_send_hci_trace( type, p_data, length );
#else
    wiced_transport_send_hci_trace(host_trans_pool, type, length, p_data);
#endif
}
#endif

 

 

728x90
728x90

REF. 

https://interrupt.memfault.com/blog/ble-throughput-primer#:~:text=For%20Bluetooth%204.0%2C%20the%20BLE,be%20encoded%20in%20each%20symbol

 

A Practical Guide to BLE Throughput

A community and blog for embedded software makers

interrupt.memfault.com

https://novelbits.io/bluetooth-5-speed-maximum-throughput/

 

Bluetooth 5 speed: How to achieve maximum throughput for your BLE application

In this second post in the series on Bluetooth 5, we cover the new feature of 2x speed and how to achieve maximum data throughput for your BLE application.

novelbits.io

 

Why is it impossible to achieve the theoretical speeds of BLE?

The data rates of 1 Mbps (LE 1M PHY), 2 Mbps (LE 2M PHY), 125 kbps and 500 kbps (both using the LE Coded PHY with S=8 and S=2, respectively) are the rates at which the radio transmits data, but this is not achievable for the application throughput due to the following reasons:

  • Limit on the number of packets per connection interval
  • Inter Frame Space (IFS) delay between packets (150 us)
  • Empty packets required to be sent from a device even if no data is available for transmission
  • Packet overhead – not all bytes in a packet are used for payload

In order to better understand these factors and understand what impacts application throughput, we have to take a deeper look at the packet format. The following figure shows what LE 1M PHY and 2M PHY data packets look like:

The part we’re interested in (and the one that really defines the application data) is the ATT Payload. As you can see from the figure, there are a number of overhead bytes that are used by each layer in Bluetooth Low Energy.

  • In 4.0 and 4.1, the maximum ATT Payload is 20 bytes.
  • In 4.2 and 5.0, a new feature called Data Length Extensions (DLE) allows the ATT Payload to hold up to 244 bytes of data.

 

Factors that impact/determine the data throughput

There are a few factors that impact the data throughput of a BLE application. The most common are:

  • PHY being used (LE 1M vs. LE 2M vs. LE Coded (S=2 or S=8))
  • Connection interval
  • Maximum number of packets per connection interval
  • ATT Maximum Transmission Unit (ATT MTU)
  • Data Length Extension (DLE)
  • Operation type: Write with response vs. write without response, Indications vs. Notifications
  • Inter Frame Space (IFS): time gap between consequent packets (150 us)
  • Transmission of empty packets
  • Packet overhead – not all bytes, in a packet, are used for the application payload

Calculating your application data throughput

The big question is: how do we calculate our application throughput?

As we mentioned before, there are a few variables that impact the data throughput:

  • Bluetooth version & PHY used
  • DLE: Data Length Extensions – enabled or not
  • ATT MTU value
  • Connection interval
  • Maximum number of packets per connection event
  • Operation (writes with responses vs. writes without responses, and notification vs. indication)
  • Inter Frame Space (IFS): 150 microseconds

The Link Layer (LL) Packet

All data during a BLE connection is sent via Link Layer (LL) packets. All higher level messages are packed within Data Payloads of LL Packets. Below is what a LL Packet sending data looks like (each tick mark represents 1 byte):

 

NOTE: The astute reader may note that Data Payload can be up to 251 bytes. This however is an optional feature known as “LE Data Packet Length Extension” which we will explore in more detail below

Maximum Link Layer Data Payload Throughput

With the three rules we mentioned about transmissions on the Bluetooth Radio in mind, let’s take a look at the procedure to transmit a maximally sized LL packet.

  • Side A sends a maximum size LL data packet (27 bytes of data in a 41 byte payload) which takes 328μs (41 bytes * 8 bits / byte * 1Mbps) to transmit
  • Side B receives the packet and waits T_IFS (150μs)
  • Side B ACKs the LL packet it received in 80μs (0 bytes of data)
  • Side A waits T_IFS before sending any more data

Here’s an example exchange of two packets of data in one Connection Event:

The time it takes to transmit one packet can be computed as:

328μs data packet + 150μs T_IFS + 80μs ACK + 150μs T_IFS = 708μs

During this time period, 27 bytes of actual data can be transmitted which takes 216μs.

This yields a raw data throughput of:

(216μs / 708μs) * 1Mbps = 305,084 bits/second = ~0.381 Mbps

The Link Layer (LL) Packet

All data during a BLE connection is sent via Link Layer (LL) packets. All higher level messages are packed within Data Payloads of LL Packets. Below is what a LL Packet sending data looks like (each tick mark represents 1 byte):

NOTE: The astute reader may note that Data Payload can be up to 251 bytes. This however is an optional feature known as “LE Data Packet Length Extension” which we will explore in more detail below

Maximum Link Layer Data Payload Throughput

With the three rules we mentioned about transmissions on the Bluetooth Radio in mind, let’s take a look at the procedure to transmit a maximally sized LL packet.

  • Side A sends a maximum size LL data packet (27 bytes of data in a 41 byte payload) which takes 328μs (41 bytes * 8 bits / byte * 1Mbps) to transmit
  • Side B receives the packet and waits T_IFS (150μs)
  • Side B ACKs the LL packet it received in 80μs (0 bytes of data)
  • Side A waits T_IFS before sending any more data

Here’s an example exchange of two packets of data in one Connection Event:

The time it takes to transmit one packet can be computed as:

328μs data packet + 150μs T_IFS + 80μs ACK + 150μs T_IFS = 708μs

During this time period, 27 bytes of actual data can be transmitted which takes 216μs.

This yields a raw data throughput of:

(216μs / 708μs) * 1Mbps = 305,084 bits/second = ~0.381 Mbps

 

Maximum throughput over GATT

The Attribute Protocol Handle Value Notification is the best way for a server to stream data to a client when using GATT. The Opcode Overhead for this operation is 2 bytes. That means there are 3 bytes of ATT packet overhead and 4 bytes of L2CAP overhead for each ATT payload. We can determine the max ATT throughput by taking the maximum raw Link Layer throughput and multiplying it by the efficiency of the ATT packet:

ATT Throughput = LL throughput * ((MTU Size - ATT Overhead) / (L2CAP overhead + MTU Size))

Tabulating this information for a couple common MTU sizes we get:

MTU size (bytes) Throughput (Mbps)
23 (default) 0.226
185 (iOS 10 max) 0.294
512 0.301

LE Data Packet Length Extension (BT v4.2)

As part of the 4.2 Bluetooth Core Specification revision, a new feature known as LE Data Packet Length Extension was added 4. This optional feature allows for a device to extend the length of the Data Payload in a Link Layer packet from 27 up to 251 bytes! This means that instead of sending 27 bytes of data in a 41 byte payload, 251 bytes of data can now be sent in a 265 byte payload. Furthermore, we can send a lot more data with fewer T_IFS gaps. Let’s take a look at what exchanging a maximally sized packet looks like:

We can calculate the raw data throughput and see that this modification yields greater than a 2x improvement on the maximum raw data throughput which can be achieved!

251 bytes / 2500μs = 100.4 kBytes/sec = ~0.803 Mbps

 

LE 2M PHY (BT v5.0)

As part of the 5.0 Bluetooth Core Specification revision, a new feature known as “LE 2M PHY”5 was added. As you may recall in the section above, we discussed how the BLE Radio is capable of transmitting 1 symbol per μs for a bitrate of 1Mbps. This revision to the Bluetooth Low Energy Physical Layer (PHY), allows for a symbol rate of 2Mbps. This means we can transmit each individual bit in half the time. However, the 150μs IFS is still needed between transmissions. Let’s take a look on how this impacts the throughput when sending packets that are using the data packet length extension feature:

We can calculate this throughput and see the modification yields almost a 4x improvement over the original maximal raw data speed that could be achived with BLE 4.0:

251 bytes / 1400μs = 179.3 kBytes/sec = ~1.434 Mbps

 

LE Coded PHY (BT v5.0)

The “LE Coded PHY” feature, also introduced in the 5.0 Spec 5 provides a way to extend the range of BLE at the cost of speed. The feature works by encoding a bit across multiple symbols on the radio. This makes the bits being transmitted more resilient to noise. There are two operation modes where either two symbols or eight symbols can be used to encode a single bit. This effectively reduces the radio bitrate to 500 kbps or 125kbps, respectively.

 

 

Determine the time it takes to send one data packet and the empty packet from the receiver.

The time during which one data packet can be sent will include the following:
Data_Packet_Time = Time to transmit empty packet + IFS + Time to transmit the actual data packet + IFS.

An empty packet transmission time can be calculated as follows:
Time to transmit empty packet = empty packet size / raw data rate

An empty packet will contain the following fields:
Preamble + Access Address + LL Header + CRC.
For 1M PHY, Preamble will be 1 byte, and so the total size of the empty packet = 1 + 4 + 2 + 3 bytes = 10 bytes = 
80 bits.

(for 2M PHY, the size of an empty packet will be 88 bits since the Premable is 2 bytes instead of 1 byte).
Based on this, the time to transmit an empty 1M PHY packet will be:
Time to transmit empty packet = empty packet size / raw data rate = 80 bits/ 1 Megabits per second =
80 micro seconds

A data packet will contain all fields listed in the packet format diagram with the exception of the MIC field (encryption disabled).
Time to transmit data packet = data packet size / raw data rate

If we have DLE enabled and the ATT MTU is equal to the maximum bytes allowed in one packet: 247 bytes, then we can calculate the data packet size as:
Data packet size = 1 + 4 + 2 + 4 + 247 + 3 bytes = 265 bytes = 265*8 bits = 2088 bits
Time to transmit data  packet = 2088 bits / 1 Mbps = 
2,088 micro seconds

Data_Packet_Time = Time to transmit empty packet + IFS + Time to transmit the actual data packet + IFS = 80 + 2*150 + 2088 = 2,468 microsecs

For comparison, in the case of 2M PHY, it would be:
Data_Packet_Time = Time to transmit empty packet + IFS + Time to transmit the actual data packet + IFS = 88/2 + 2*150 + (2 + 4 + 2 + 4 + 247 + 3)*8/2 = 
1,392 microsecs

When DLE is enabled and the ATT MTU is set to less than 247, we end up with more overhead (since now data larger than the ATT MTU gets split up into more packets). For example, say we have the ATT MTU set to 158, then in order to transfer 244 bytes of application data, we will need two packets instead of one, causing the throughput to go down due to the increased byte overhead as well as the increased IFS between the packets. In another scenario, we could have DLE disabled (Payload size up to 27 bytes) and the ATT MTU greater than 27 bytes. Here, this will also result in more packets needed to be sent for the same amount of data, causing the throughput to go down.
Note: The same method for calculating the data and empty packet sizes that we used above can be used for the LE Coded PHY.

 

728x90
728x90

 http://www.ledsmagazine.com/articles/print/volume-13/issue-3/features/smart-lighting/bluetooth-mesh-what-s-that-noise-about.html

Bluetooth Mesh - What's that noise about? (MAGAZINE)

    

Coming Bluetooth extensions will make the wireless technology a better fit for smart lighting, explains MAREK WIERZBICKI, while mesh extensions will retain the low power, ease of use, and reliability of the proven radio technology.

 

Smart lighting might be the biggest revolution the lighting industry has seen in decades, but the multitude of available wireless communication technologies can cause a real headache for manufacturers willing to delve into this new, exciting market. Bluetooth is the latest talk of the town with its mesh networking support to be adopted later this year. We at Silvair have been deeply involved in the Bluetooth Smart Mesh Working Group's efforts aimed at standardizing a Bluetooth-based mesh architecture, and this examination of the basic concepts behind one approach to a Bluetooth Mesh implementation will give you an idea as to what Bluetooth Smart mesh networking is all about.

Interested in more articles & announcements on smart lighting?

Lighting standards we've all known for years are now being challenged by the next generation of lighting systems that promise to deliver so much more than just a well-lit space. The transition toward digital lighting is happening right in front of our eyes, and while a couple of months ago many had doubts as to whether smart lighting could be a real deal, it now seems that there is no turning back. Over the last 12 months, we've seen multiple heavyweight lighting manufacturers spinning off big chunks of their traditional businesses to put more focus on connected technologies (See LEDs Magazinecoverage of Osram). Smart lighting promises new business models with a steady stream of revenue from value-added features and services, which is exactly what lighting companies need to overcome the challenges resulting from the impressive longevity of LEDs and razor-thin margins in the LED market.

SPONSORED CONTENT BY Bluetooth®‎ ?

Bluetooth Mesh Shows Wireless Connectivity in a Whole New Light

Many of today’s wireless platforms—especially those supported by a Bluetooth® mesh network—ensure greater flexibility and extensibility at a much lower cost than a wired system can provide.

FIG. 1. There were a number of Bluetooth-based, mesh-enabled lighting products at the Consumer Electronics Show (CES) in 2016 including a lamp from Girard Sudron and a switch from NodOn.

FIG. 1. There were a number of Bluetooth-based, mesh-enabled lighting products at the Consumer Electronics Show (CES) in 2016 including a lamp from Girard Sudron and a switch from NodOn.

Moving to networks

It is therefore not surprising that virtually every week we are hearing news about lighting manufacturers entering into agreements with companies that can relatively swiftly implement smart technologies into their products, or even straightforwardly acquiring providers of wireless connectivity, cloud services, or advanced data analytics. Things have gone so far that we've already seen Goldman Sachs downgrading its rating on one of the leading lighting manufacturers, citing concerns over the company's deteriorating earnings and emphasizing its low exposure to connected technologies. The trend is clear: Lighting systems are becoming digital, and a wide variety of smart lighting products (Fig. 1) presented at CES (Consumer Electronics Show) 2016 only confirms this.

That said, there is still no consensus regarding the wireless communication protocol that could be the go-to technology for lighting applications, let alone the entire Internet of Things (IoT). Countless times has it been said that the lack of interoperability is a major obstacle to mass adoption of connected solutions, but instead of some sort of standardization, we're only seeing things getting more and more fragmented. New technologies keep emerging, each claiming to have exactly what it takes to enable seamless, robust, and secure connectivity in the Internet of Things (IoT).

In the meantime, the more mature communication standards keep evolving to address the dynamically changing customer needs, as many of them were introduced to the market when expectations and hype surrounding the IoT and connected spaces were nowhere near as big as they are today. What's more, certain product categories did not even exist back then, with smart lighting being a perfect example of a segment that has come a long way from nonexistence to being one of the hottest smart building automation segments over just a couple of years.

One of those mature standards is Bluetooth, a wireless communication protocol that seems to have been around forever and thus enjoys unmatched brand recognition. However, for certain very specific reasons, it is currently not being considered a viable option for advanced building automation solutions. The Bluetooth Special Interest Group (SIG), a 28,000-member strong body that oversees the development of Bluetooth standards, claims this is about to change once the mesh networking support is introduced into the protocol's core specification. We are only a couple of months away from this release, so let's see what's coming.

Bluetooth Classic versus Bluetooth Smart

All that noise surrounding Bluetooth might be somewhat confusing for those not too familiar with the recent developments in the wireless communication landscape. After all, the protocol was first developed before the term "Internet of Things" was even coined. But what many are still not aware of is that the Bluetooth of today is something completely different than Bluetooth of the past.

FIG. 2. Legacy Bluetooth has relied on a hub-and-spoke topology while commercial smart lighting will require a mesh network for communications.

FIG. 2. Legacy Bluetooth has relied on a hub-and-spoke topology while commercial smart lighting will require a mesh network for communications.

The original Bluetooth, known as Bluetooth Classic, was designed as a short-range, cable-replacement technology for point-topoint communications. Initially, the main goal was to synchronize data between mobile phones, but the standard quickly became the default technology for wireless data exchange between personal computing equipment (mobile phones, PCs, PDAs) and peripherals (headsets, cordless keyboards and mice, printers, and such). Devices could form a tiny personal area network (PAN) called a piconet, whereby a single central device would coordinate the activity of up to seven active peripherals.

Fast-forward to 2010, the Bluetooth Core Specification version 4.0 is released, introducing Bluetooth Low Energy (BLE), more commonly known as Bluetooth Smart. This is where the story of Bluetooth in the IoT really begins. Bluetooth Smart was designed specifically to address the needs of a new generation of smart devices, many of which are battery-powered and therefore require fast connection times and efficient power management to reduce unnecessary energy consumption.

The new specification extended Bluetooth's usefulness to a whole new range of products, ultimately making it a default technology for all kinds of wearable devices. But despite some really outstanding features of the Bluetooth Smart radio, the protocol didn't make any significant impact in the building automation segment. Smart homes were dominated by other low-power technologies, mainly ZigBee and Z-Wave, and wireless communication never really took off in commercial spaces. Due to certain important drawbacks of the available low-power communication standards, building managers preferred to stick to wired solutions, considering them way more reliable.

The reason why Bluetooth Smart was never considered a serious contender for building automation purposes is because it was designed to support relatively simple hub-and-spoke networks (Fig. 2). Applications like smart lighting require much more than that. Peer-to-peer communication and extended range are among the must-have features enabling a robust network consisting of multiple smart bulbs, and the core specification of Bluetooth Smart simply didn't provide such capability. Its hub-and-spoke model couldn't match with the mesh topology of ZigBee or Z-Wave networks, and for this reason Bluetooth could never really compete with the two in the applications they were intended for.

Is this meshable?

Even though the support for mesh networking wasn't included in the core specification of Bluetooth Smart, several companies noticed that building a mesh network based on this particular communication standard might not be such a bad idea. In 2014, Silvair (operating as Seed Labs back then) started building a mesh architecture based on Bluetooth Smart. Transforming the protocol's single-hop topology into a robust multi-hop, peer-to-peer network was quite a challenge, but the potential reward was enormous.

A mesh network based on Bluetooth Smart also turned out to offer outstanding performance and the core features of the Bluetooth radio allowed us to overcome many of the challenges that other communication protocols have a hard time dealing with. Obviously, the technology developed by Silvair was proprietary, although we did manage to maintain compliance with Bluetooth Smart's core specification.

Having received a fair amount of input from Silvair and other companies working on their proprietary mesh solutions, the Bluetooth Special Interest Group realized that such an opportunity cannot be wasted. In February 2015, it announced the formation of the Bluetooth Smart Mesh Working Group. Its goal was to standardize mesh networking support and incorporate it into the protocol's core specification. Competing companies sat down to share their experiences and find the best way to implement the mesh architecture into Bluetooth Smart. Near the end of 2015, the SIG officially confirmed that it's on track with the development of the Bluetooth Mesh, and that the standard would be adopted at some point in 2016. Moreover, some major improvements with regard to both the data rate and range of Bluetooth Smart will be included in the new standard.

The standardized mesh architecture based on Bluetooth Smart is shaping up to be a powerful framework enabling robust and scalable implementations in some of the most challenging applications. Being part of that development process and seeing many of our concepts being incorporated into the global standard is a great feeling. We are currently among the leading contributors to the Bluetooth Smart Mesh Working Group. The details about the upcoming mesh standard remain strictly confidential until some official announcements are made by the SIG itself, but we can provide you with a sneak peek into the basic concepts behind our Silvair Mesh technology, which might give you a good idea of what Bluetooth-based mesh networking is all about.

Meet a mesh

Silvair Mesh has been developed to allow users to build their smart mesh networks in which one or more mobile devices (smartphones/tablets) can control one or more mesh-enabled peripheral devices (e.g., lamps, sensors, dimmers, switches, etc.). When equipped with the mesh software stack, essentially an enhanced Bluetooth Smart stack, these devices can communicate with each other and the central controller via the Bluetooth Smart radio using the protocol's standard mechanisms called GATT (Generic Attribute Profile). This means that all mesh-enabled peripherals can create their own autonomous mesh network that does not require any central device to operate.

FIG. 3. Smart mesh capabilities are added to Bluetooth devices in the network, transport, and application layers in software and don't impact the physical and link layers that are captured in radio ICs and modules.

FIG. 3. Smart mesh capabilities are added to Bluetooth devices in the network, transport, and application layers in software and don't impact the physical and link layers that are captured in radio ICs and modules.

The decision to base Silvair Mesh on Bluetooth Smart was intentional, as it meant that the ecosystem would be compatible with all existing Bluetooth Smart devices and chipsets. However, a mesh stack also requires numerous additional features to standard Bluetooth Smart. For instance, the Silvair Mesh includes a high-performance Bluetooth controller and a new Network Security Manager, as well as the secure OverThe-Air Update functionality, which means that a device can be upgraded to the newest version of the firmware at any time.

Such a carefully crafted mesh software stack can be installed on any compatible Bluetooth chip. Silvair also developed a reference design for modules to provide the best possible solution for large installations such as those found in commercial buildings. These modules consist of standard Texas Instruments CC254x Bluetooth modules with upgraded firmware, an amplifier, and an antenna. Operating at +10-dBm Tx (transmit) power and with -98-dBm Rx (receive) sensitivity, the modules provide a 108-dB link budget that translates to a range of 1500 ft (about 500m) in the open air. Inside buildings, this value will obviously be much lower and dependent on numerous factors, yet it still remains impressive.

An important thing to realize is that mesh is a purely software solution. This means that Bluetooth Smart chipsets found in today's smartphones can control devices employing proprietary technologies such as Silvair Mesh, and will remain perfectly suitable for controlling and managing mesh networks once the standard is adopted by the SIG. The aforementioned software stack is applied to the networking and application layers of the standard Bluetooth Smart protocol stack as shown in Fig. 3.

How the mesh works

Now let's consider how the mesh extension works. There are two types of communication within a Silvair Mesh network: central to peripheral and peripheral to peripheral. Once the mesh network is commissioned, there is no need for further central-peripheral communication.

Central devices are usually smartphones and tablets. Such devices would typically run some type of control software. In the Silvair case, we developed an app for iOS and Android devices. The central devices are used to configure and manage the network but can also perform a software update of peripheral devices. Central devices connect to peripherals using Bluetooth Smart's standard GATT services. While this type of connection is fully compatible with Bluetooth 4.0, it employs certain proprietary techniques to allow many smartphones to be used simultaneously to control more than eight peripheral devices with eight being the limit in standard Bluetooth 4.0.

Peripheral devices are the nodes of a mesh network. A robust mesh implementation must allow peripherals to talk to each other and act as relays that pass messages through the mesh. This is a radical departure from the original architecture of Bluetooth Smart, and it allows for controlling entire groups of devices using multicast (one to many) communications - e.g., dimming a group of ceiling lights in a hallway. The Silvair Mesh implementation allows a maximum of 63 hops, which enables it to cover very extensive areas out of the box, in contrast to other technologies that require setting up more complicated or more expensive networks.

One of the most significant concepts introduced in the Silvair implementation is connectionless communication, which means that every peripheral can advertise its status in the network. As a result, lights, fans, shades, and any other mesh-enabled device are displayed automatically in the app on the central device, not only as a simple list of available devices, but with very specific parameters that can be controlled by the user - e.g., on/off, color, temperature, fan speed, or shade position. Every status change made by the user is immediately advertised to the network, and every controlling device in the mesh is updated instantly with the new status.

Network setup

As will be required in commercial applications, the Silvair Mesh software allows networks of any size to be set up, but the way in which large and small networks are commissioned, is different. Small networks of up to about 30 devices can be commissioned and managed using just the app on a smartphone or a tablet. The plug-and-play nature of Bluetooth, and the fact that the protocol is natively supported by virtually all smartphones and tablets on the market, makes the entire process extremely simple and intuitive. The app detects and displays mesh devices in its vicinity. The user creates a mesh network by selecting which devices should be added, and by giving the network a name. Once added to the network, associations and relationships can be set up between the devices as desired. The smartphone can then be switched off and these connections will remain in place (Fig. 4).

FIG. 4. Silvair Mesh supports both smaller mesh networks controlled by a single smartphone and complex networks with dedicated cloud-connected servers.

FIG. 4. Silvair Mesh supports both smaller mesh networks controlled by a single smartphone and complex networks with dedicated cloud-connected servers.

Networks of over about 30 devices, or the ones requiring more sophisticated associations, scenarios, and network monitoring services, are best set up using some type of server or management appliance. In the case of Silvair, an embedded server called Silvair Logic hosts all the logic that controls the entire network, checks the status of all peripherals, and reports any issues and unusual events via a browser-based interface.

Other mesh needs

There are a few other key elements of a Bluetooth Mesh implementation that we will mention briefly here. There needs to be a concept of permissions for control devices that ensures proper management of devices in the network. The Silvair software stack implements four levels of permissions: 1) Administrator - can operate all devices within the network, as well as configure them and manage other users' permissions; 2) Family - can operate all devices within the network, but cannot configure or manage them; 3) Guest - has limited permission to operate selected devices within the network; 4) and AdHoc - can operate public devices only on a one-to-one basis (no access to the mesh network).

Likewise, the network nodes or peripherals require the ability to provide information on their operational status and programmability. The Silvair software stack defines three Peripheral Device States: 1) Factory Default - the device leaves the factory in this state and is ready for commissioning; 2) Private - all communication is encrypted, so only users with matching keys can decrypt the state information and control the device; and 3) Public - state information, as well as selected control functions, are not encrypted and can be accessed by anyone.

The Bluetooth difference

The question one might ask at this point is why the Bluetooth Smart mesh would be any better than other mesh protocols available on the market? Simply put, it's all about the radio. Out of all low-power, low-bandwidth communication standards, none is even close to having such impressive qualities as Bluetooth Smart. This allows the protocol to address some of the most difficult issues in such challenging applications as smart lighting, where multicast, synchronous operation and responsiveness are among the must-have features.

We've tested many other technologies inside out, and we know exactly why the existing mesh protocols have failed to deliver the smart lighting experience to environments where reliability and scalability are top priorities. And we firmly believe that this year's adoption of the Bluetooth Smart mesh standard might finally open the door for smart lighting networks to become widely deployed in professional applications.


728x90
728x90

https://en.wikipedia.org/wiki/Bluetooth_mesh_networking


Bluetooth mesh networking, conceived in 2015,[1] adopted on July 13, 2017[2] is a protocol based upon Bluetooth Low Energy that allows for many-to-many communication over Bluetooth radio.

It has been defined in Mesh Profile Specification[3] and Mesh Model Specification.[4]

Overview[edit]

Communication is carried in the messages that may be up to 384 bytes long, when using Segmentation and Reassembly (SAR) mechanism, but most of the messages fit in one segment, that is 11 bytes. Each message starts with an opcode, which may be a single byte (for special messages), 2 bytes (for standard messages), or 3 bytes (for vendor-specific messages).

Every message has a source and a destination address, determining which devices process messages. Devices publish messages to destinations which can be single things / groups of things / everything.

Each message has a sequence number that protects the network against replay attacks.

Each message is encrypted and authenticated. Two keys are used to secure messages: (1) network keys – allocated to a single mesh network, (2) application keys – specific for a given application functionality, e.g. turning the light on vs reconfiguring the light.

Messages have a time to live (TTL). Each time message is received and retransmitted, TTL is decremented which limits the number of "hops", eliminating endless loops.

Bluetooth Mesh is a flood network. It's based on the nodes relaying the messages: every relay node that receives a network packet that authenticates against a known network key that is not in message cache, that has a TTL ≥ 2 can be retransmitted with TTL = TTL - 1. Message cache used to prevent relaying messages recently seen.

Bluetooth Mesh has a layered architecture, with multiple layers as below.

LayerFunctionality
Model LayerIt defines a standard way to exchange application specific messages. For example, a Light Lightness Model defines an interoperable way to control lightness. There are mandatory models, called Foundation Models, defining states and messages needed to manage a mesh network.
Access LayerIt defines mechanism to ensure that data is transmitted and received in the right context of a model and its associated application keys.
Upper Transport LayerIt defines authenticated encryption of access layer packets using an application (or device specific key). It also defines some control messages to manage Friendship or to notify the behavior of node using Heartbeat messages.
Lower Transport LayerThis layer defines a reliable (through a Block Acknowledgement) Segmented transmission upper layer packets, when a complete upper layer packet can't be carried in a single network layer packet. It also defines a mechanism to reassemble segments on the receiver.
Network LayerThis layer defines how transport packets are addressed over network to one or more nodes. It defines relay functionality for forwarding messages by a relay node to extended the range. It handles the network layer authenticated encryption using network key.
Bearer LayerIt defines how the network packets are exchanged between nodes. Mesh Profile Specification defines BLE advert bearer and BLE GATT bearer. Mesh Profile defines Proxy Protocol, through which mesh packets can be exchanged via other bearers like TCP/IP.

Theoretical limits[edit]

It's yet to be determined what are the practical limits of Bluetooth Mesh technology. There are some limits that are built into the specification, though:

Limit for a networkValueRemarks
Maximum number of nodes32 767The limit is 32768 addresses and while a node may occupy more than one address, practical limit is most likely lower
Maximum number of groups16 384

Number of virtual groups is 2128.

Maximum number of scenes65 535
Maximum number of subnets4 096
Maximum TTL127

Mesh models[edit]

As of version 1.0 of Bluetooth Mesh specification, the following standard models and model groups have been defined:

Foundation models[edit]

Foundation models have been defined in the core specification. Two of them are mandatory for all mesh nodes.

  • Configuration Server (mandatory)
  • Configuration Client
  • Health Server (mandatory)
  • Health Client

Generic models[edit]

  • Generic OnOff Server, used to represent devices that do not fit any of the model descriptions defined but support the generic properties of On/Off
  • Generic Level Server, keeping the state of an element in a 16-bit signed integer
  • Generic Default Transition Time Server, used to represent a default transition time for a variety of devices
  • Generic Power OnOff Server & Generic Power OnOff Setup Server, used to represent devices that do not fit any of the model descriptions but support the generic properties of On/Off
  • Generic Power Level Server & Generic Power Level Setup Server, including a Generic Power Actual state, a Generic Power Last state, a Generic Power Default state and a Generic Power Range state
  • Generic Battery Server, representing a set of four values representing the state of a battery
  • Generic Location Server & Generic Location Setup Server, representing location information of an element, either global (Lat/Lon) or local
  • Generic User/Admin/Manufacturer/Client Property Server, representing any value to be stored by an element
  • Generic OnOff Client & Generic Level Client
  • Generic Default Transition Time Client
  • Generic Power OnOff Client & Generic Power Level Client
  • Generic Battery Client
  • Generic Location Client
  • Generic Property Client

Sensors[edit]

  • Sensor Server & Sensor Setup Server, representing a sensor device. Sensor device may be configured to return a measured value periodically or on request; measurement period (cadence) may be configured to be fixed or to change, so that more important value range is being reported faster.
  • Sensor Client

Time and scenes[edit]

  • Time Server & Time Setup Server, allowing for time synchronization in mesh network
  • Scene Server & Scene Setup Server, allowing for up to 65535 scenes to be configured and recalled when needed.
  • Scheduler Server & Scheduler Setup Server
  • Time Client, Scene Client & Scheduler Client

Lighting[edit]

  • Light Lightness Server & Light Lightness Setup Server, representing a dimmable light source
  • Light CTL Server, Light CTL Temperature Server & Light CTL Setup Server, representing a CCT or "tunable white" light source
  • Light HSL Server, Light HSL Hue Server, Light HSL Saturation Server & Light HSL Setup Server, representing a light source based on Hue, Saturation, Lightness color representation
  • Light xyL Server & Light xyL Setup Server, representing a light source based on modified CIE xyY color space.
  • Light LC (Lightness Control) Server & Light LC Setup Server, representing a light control device, able to control Light Lightness model using an occupancy sensor and ambient light sensor. It may be used for light control scenarios like Auto-On, Auto-Off and/or Daylight Harvesting.
  • Light Lightness Client, Light CTL Client, Light HSL Client, Light xyL Client & Light LC Client

Provisioning[edit]

Provisioning is a process of installing the device into a network. It is a mandatory step to build a Bluetooth Mesh network.

In the provisioning process, a provisioner securely distributes a network key and a unique address space for a device. Provisioning protocol uses P256 Elliptic Curve Diffie-HellmanKey Exchange to create a temporary key to encrypt network key and other information. This provides security from a passive eavesdropper. It also provides various authentication mechanisms to protect network information, from an active eavesdropper who uses Man-In-The-Middle attack, during provisioning process.

A key unique to a device known as "Device Key" is derived from elliptic curve shared secret on provisioner and device during the provisioning process. This device key is used by the provisioner to encrypt messages for that specific device.

Terminology used in Bluetooth mesh networking specification[edit]

  • Destination: The address to which a message is sent.
  • Element: An addressable entity within a device.
  • Model: Standardized operation of typical user scenarios.
  • Node: A provisioned device.
  • Provisioner: A node that can add a device to a mesh network.
  • Relay: A node able to retransmit messages.
  • Source: The address from which a message is sent.


728x90

+ Recent posts