driver/bluetooth: Added initial version of hci cyw208xx driver

Added initial version of hci cyw208xx driver

Signed-off-by: Nazar Palamar <nazar.palamar@infineon.com>
This commit is contained in:
Nazar Palamar 2024-04-03 11:25:44 +03:00 committed by Anas Nashif
commit 17889d23b9
15 changed files with 643 additions and 12 deletions

View file

@ -0,0 +1,13 @@
# The Infineon AIROC™ CYW20829 Bluetooth® LE evaluation kit (CYW92089M2EVK-02)
# Copyright (c) 2024 Cypress Semiconductor Corporation.
# SPDX-License-Identifier: Apache-2.0
choice AIROC_PART
default CYW20829 if BT
endchoice
# Heap Pool Size
config HEAP_MEM_POOL_ADD_SIZE_BOARD
int
default 10096

View file

@ -22,6 +22,7 @@
zephyr,flash = &app_region;
zephyr,console = &uart2;
zephyr,shell-uart = &uart2;
zephyr,bt-hci = &bluetooth;
};
};
@ -79,6 +80,10 @@ uart2: &scb2 {
status = "okay";
};
&bluetooth {
status = "okay";
};
/ {
flash0: flash@60000000 {
compatible = "soc-nv-flash";

View file

@ -72,6 +72,17 @@ The AIROC™ CYW20829 Bluetooth® MCU SoC is configured to use the internal IMO
the system clock. Other sources for the system clock are provided in the SOC, depending on your
system requirements.
Fetch Binary Blobs
******************
cyw920829m2evk_02 board requires fetch binary files (e.g Bluetooth controller firmware).
To fetch Binary Blobs:
.. code-block:: console
west blobs fetch hal_infineon
Build blinking led sample
*************************

View file

@ -13,7 +13,6 @@ if(CONFIG_BT_HCI_IPC)
endif()
endif()
zephyr_library_sources_ifdef(CONFIG_BT_AIROC cyw43xxx.c)
zephyr_library_sources_ifdef(CONFIG_BT_ESP32 hci_esp32.c)
zephyr_library_sources_ifdef(CONFIG_BT_H4 h4.c)
zephyr_library_sources_ifdef(CONFIG_BT_H5 h5.c)
@ -25,11 +24,14 @@ if(CONFIG_BT_SPI)
zephyr_library_sources(spi.c)
endif()
endif()
zephyr_library_sources_ifdef(CONFIG_BT_CYW43XX h4_ifx_cyw43xxx.c)
zephyr_library_sources_ifdef(CONFIG_BT_CYW208XX hci_ifx_cyw208xx.c)
zephyr_library_sources_ifdef(CONFIG_BT_STM32_IPM ipm_stm32wb.c)
zephyr_library_sources_ifdef(CONFIG_BT_STM32WBA hci_stm32wba.c)
zephyr_library_sources_ifdef(CONFIG_BT_USERCHAN userchan.c)
zephyr_library_sources_ifdef(CONFIG_BT_SILABS_HCI slz_hci.c)
zephyr_library_sources_ifdef(CONFIG_BT_PSOC6_BLESS hci_psoc6_bless.c)
zephyr_library_sources_ifdef(CONFIG_BT_PSOC6_BLESS hci_ifx_psoc6_bless.c)
zephyr_library_sources_ifdef(CONFIG_SOC_NRF5340_CPUAPP nrf53_support.c)
zephyr_library_sources_ifdef(CONFIG_BT_AMBIQ_HCI hci_ambiq.c apollox_blue.c)
zephyr_library_sources_ifdef(CONFIG_BT_DA1469X hci_da1469x.c)

View file

@ -133,6 +133,13 @@ config BT_NXP
help
NXP HCI bluetooth interface
config BT_CYW208XX
bool "CYW208XX BLE driver"
default y
depends on DT_HAS_INFINEON_CYW208XX_HCI_ENABLED
help
Infineon CYW208XX HCI bluetooth interface
config BT_AMBIQ_HCI
bool "AMBIQ BT HCI driver"
default y
@ -145,6 +152,7 @@ config BT_AMBIQ_HCI
Supports Ambiq Bluetooth SoC using SPI as the communication protocol.
HCI packets are sent and received as single Byte transfers.
if BT_SPI
config BT_SPI_INIT_PRIORITY
@ -175,11 +183,13 @@ config BT_STM32_IPM_RX_STACK_SIZE
menuconfig BT_AIROC
bool "AIROC BT connectivity"
default y
select GPIO if BT_H4
select UART if BT_H4
select UART_USE_RUNTIME_CONFIGURE if BT_H4
select BT_HCI_SETUP
select UART_USE_RUNTIME_CONFIGURE
depends on GPIO
depends on DT_HAS_INFINEON_CYW43XXX_BT_HCI_ENABLED
depends on BT_H4
select USE_INFINEON_ABSTRACTION_RTOS if BT_CYW208XX
select EVENTS if BT_CYW208XX
depends on DT_HAS_INFINEON_CYW43XXX_BT_HCI_ENABLED || DT_HAS_INFINEON_CYW208XX_HCI_ENABLED
help
Infineon's AIROC™ Wi-Fi & combos portfolio integrates
IEEE 802.11a/b/g/n/ac/ax Wi-Fi and Bluetooth® 5.2 in a single-chip

View file

@ -4,11 +4,16 @@
if BT_AIROC
config BT_CYW43XX
bool
default y if BT_AIROC && BT_H4
choice AIROC_PART
prompt "Select AIROC part"
config CYW4343W
bool "CYW4343W"
depends on BT_H4
help
Enable Infineon CYW4343W BLE connectivity,
More information about CYW4343W device you can find on
@ -16,6 +21,7 @@ config CYW4343W
config CYW4373
bool "CYW4373"
depends on BT_H4
help
Enable Infineon CYW4373 BLE connectivity,
More information about CYW4373 device you can find on
@ -23,6 +29,7 @@ config CYW4373
config CYW43012
bool "CYW43012"
depends on BT_H4
help
Enable Infineon CYW43012 BLE connectivity,
More information about CYW43012 device you can find on
@ -30,6 +37,7 @@ config CYW43012
config CYW43438
bool "CYW43438"
depends on BT_H4
help
Enable Infineon CYW43438 BLE connectivity,
More information about CYW43438 device you can find on
@ -37,11 +45,20 @@ config CYW43438
config CYW43439
bool "CYW43439"
depends on BT_H4
help
Enable Infineon CYW43439 BLE connectivity,
More information about CYW43439 device you can find on
https://www.infineon.com/cms/en/product/wireless-connectivity/airoc-wi-fi-plus-bluetooth-combos/cyw43439/
config CYW20829
bool "CYW20829"
depends on BT_CYW208XX
help
Enable Infineon CYW20829 BLE connectivity,
More information about CYW20829 device you can find on
https://www.infineon.com/cms/en/product/wireless-connectivity/airoc-bluetooth-le-bluetooth-multiprotocol/airoc-bluetooth-le/cyw20829/
config BT_AIROC_CUSTOM
bool "Custom AIROC device/module"
help
@ -117,6 +134,61 @@ config CYW43439_MURATA_1YN
endchoice
if CYW20829
config CYW20829_BT_FW_TX10DBM_POWER
bool "CYW20829_BT_FW_TX10DBM_POWER"
help
Enable 10dBm TX Power variant of CYW20829 FW patch.
choice CYW20829_BT_FW
prompt "Select variant of default CYW20829 BT FW"
default CYW20829_BT_FW_ISOC_TX10 if BT_ISO && CYW20829_BT_FW_TX10DBM_POWER
default CYW20829_BT_FW_ISOC_TX0 if BT_ISO && !CYW20829_BT_FW_TX10DBM_POWER
default CYW20829_BT_FW_PAWR_TX10 if BT_PER_ADV_RSP && CYW20829_BT_FW_TX10DBM_POWER
default CYW20829_BT_FW_PAWR_TX0 if BT_PER_ADV_RSP && !CYW20829_BT_FW_TX10DBM_POWER
default CYW20829_BT_FW_TX10 if CYW20829_BT_FW_TX10DBM_POWER
default CYW20829_BT_FW_TX0
config CYW20829_BT_FW_TX0
bool "CYW20829_BT_FW_TX0"
help
Enable CYW20829 FW patch for 0dBm TX Power.
This configuration should be used with non-PAWR and non-ISOC applications.
config CYW20829_BT_FW_TX10
bool "CYW20829_BT_FW_TX10"
help
Enable CYW20829 FW patch for 10dBm TX Power.
This configuration should be used with non-PAwR and non-ISOC applications.
config CYW20829_BT_FW_PAWR_TX0
bool "CYW20829_BT_FW_PAWR_TX0"
help
Enable CYW20829 FW patch with PAwR support for 0dBm TX Power.
This configuration should be used with PAwR applications.
config CYW20829_BT_FW_PAWR_TX10
bool "CYW20829_BT_FW_PAWR_TX10"
help
Enable CYW20829 FW patch for 10dBm TX Power.
This configuration should be used with PAwR applications.
config CYW20829_BT_FW_ISOC_TX0
bool "CYW20829_BT_FW_ISOC_TX0"
help
Enable CYW20829 FW patch for 0dBm TX Power.
This configuration should be used with ISOC applications.
config CYW20829_BT_FW_ISOC_TX10
bool "CYW20829_BT_FW_ISOC_TX10"
help
Enable CYW20829 FW patch for 10dBm TX Power.
This configuration should be used with ISOC applications.
endchoice
endif # CYW20829
config AIROC_CUSTOM_FIRMWARE_HCD_BLOB
depends on BT_AIROC_CUSTOM
string "Path to user BT firmware HCD file"

View file

@ -0,0 +1,422 @@
/*
* Copyright (c) 2024 Cypress Semiconductor Corporation (an Infineon company) or
* an affiliate of Cypress Semiconductor Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @brief Zephyr CYW20829 driver.
*
* This driver uses btstack-integration asset as hosts platform adaptation layer
* (porting layer) for CYW20829. btstack-integration layer implements/
* invokes the interfaces defined by BTSTACK to to enable communication
* with the BT controller by using IPC_BTSS (IPC Bluetooth sub-system interface).
* Zephyr CYW20829 driver implements wiced_bt_**** functions requreds for
* btstack-integration asset and Zephyr Bluetooth driver interface
* (defined in struct bt_hci_driver).
*
* CM33 (application core)
* |=========================================|
* | |-------------------------| |
* | | Zephyr application | |
* | |-------------------------| |
* | | |
* | |------------| |
* | | Zephyr | |
* | | Bluetooth | |
* CM33 (BTSS core) | | Host | |
* |=====================| | |------------| |
* | | | | |
* | |---------------| | | |--------------| | -----------| |
* | | Bluetooth | | IPC_BTSS | | btstack- | | Zephyr | |
* | | Controller FW | | <--------|-> | integration | ---- | CYW20829 | |
* | |---------------| | | | asset | | driver | |
* | | | |--------------| |------------| |
* |=====================| | |
* | |=========================================|
* |====================|
* | CYW20829 |
* | Bluetooth |
* |====================|
*
* NOTE:
* cyw920829 requires fetch binary files of Bluetooth controller firmware.
* To fetch Binary Blobs: west blobs fetch hal_infineon
*
*/
#include <errno.h>
#include <stddef.h>
#include <string.h>
#include <zephyr/arch/cpu.h>
#include <zephyr/bluetooth/bluetooth.h>
#include <zephyr/bluetooth/hci.h>
#include <zephyr/drivers/bluetooth.h>
#include <zephyr/drivers/uart.h>
#include <zephyr/init.h>
#include <zephyr/sys/byteorder.h>
#include <zephyr/sys/util.h>
#include <zephyr/logging/log.h>
#include <wiced_bt_stack_platform.h>
#include <cybt_platform_config.h>
#include <cybt_platform_trace.h>
#include <cybt_platform_hci.h>
#include <cybt_platform_task.h>
#include <cyabs_rtos.h>
#include <cybt_result.h>
#define LOG_LEVEL CONFIG_BT_HCI_DRIVER_LOG_LEVEL
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(cyw208xx);
#define DT_DRV_COMPAT infineon_cyw208xx_hci
struct cyw208xx_data {
bt_hci_recv_t recv;
};
enum {
BT_HCI_VND_OP_DOWNLOAD_MINIDRIVER = 0xFC2E,
BT_HCI_VND_OP_WRITE_RAM = 0xFC4C,
BT_HCI_VND_OP_LAUNCH_RAM = 0xFC4E,
BT_HCI_VND_OP_UPDATE_BAUDRATE = 0xFC18,
};
/* Externs for CY43xxx controller FW */
extern const uint8_t brcm_patchram_buf[];
extern const int brcm_patch_ram_length;
#define CYBSP_BT_PLATFORM_CFG_SLEEP_MODE_LP_ENABLED (1)
static K_SEM_DEFINE(hci_sem, 1, 1);
static K_SEM_DEFINE(cybt_platform_task_init_sem, 0, 1);
/******************************************************************************
* Function Declarations
******************************************************************************/
extern void host_stack_platform_interface_init(void);
extern void cybt_platform_hci_wait_for_boot_fully_up(bool is_from_isr);
extern uint8_t *host_stack_get_acl_to_lower_buffer(wiced_bt_transport_t transport, uint32_t size);
extern wiced_result_t host_stack_send_acl_to_lower(wiced_bt_transport_t transport,
uint8_t *data, uint16_t len);
extern wiced_result_t host_stack_send_cmd_to_lower(uint8_t *cmd, uint16_t cmd_len);
extern wiced_result_t host_stack_send_iso_to_lower(uint8_t *data, uint16_t len);
extern cybt_result_t cybt_platform_msg_to_bt_task(const uint16_t msg, bool is_from_isr);
extern void cybt_bttask_deinit(void);
static int cyw208xx_bt_firmware_download(const uint8_t *firmware_image, uint32_t size)
{
uint8_t *data = (uint8_t *)firmware_image;
volatile uint32_t remaining_length = size;
struct net_buf *buf;
int err;
LOG_DBG("Executing Fw downloading for CYW208xx device");
/* The firmware image (.hcd format) contains a collection of hci_write_ram
* command + a block of the image, followed by a hci_write_ram image at the end.
* Parse and send each individual command and wait for the response. This is to
* ensure the integrity of the firmware image sent to the bluetooth chip.
*/
while (remaining_length) {
size_t data_length = data[2]; /* data length from firmware image block */
uint16_t op_code = *(uint16_t *)data;
/* Allocate buffer for hci_write_ram/hci_launch_ram command. */
buf = bt_hci_cmd_create(op_code, data_length);
if (buf == NULL) {
LOG_ERR("Unable to allocate command buffer");
return err;
}
/* Add data part of packet */
net_buf_add_mem(buf, &data[3], data_length);
/* Send hci_write_ram command. */
err = bt_hci_cmd_send_sync(op_code, buf, NULL);
if (err) {
return err;
}
switch (op_code) {
case BT_HCI_VND_OP_WRITE_RAM:
/* Update remaining length and data pointer:
* content of data length + 2 bytes of opcode and 1 byte of data length.
*/
data += data_length + 3;
remaining_length -= data_length + 3;
break;
case BT_HCI_VND_OP_LAUNCH_RAM:
remaining_length = 0;
break;
default:
return -ENOMEM;
}
}
LOG_DBG("Fw downloading complete");
return 0;
}
static int cyw208xx_setup(const struct device *dev, const struct bt_hci_setup_params *params)
{
ARG_UNUSED(dev);
ARG_UNUSED(params);
int err;
/* Send HCI_RESET */
err = bt_hci_cmd_send_sync(BT_HCI_OP_RESET, NULL, NULL);
if (err) {
return err;
}
/* BT firmware download */
err = cyw208xx_bt_firmware_download(brcm_patchram_buf, (uint32_t)brcm_patch_ram_length);
if (err) {
return err;
}
/* Waiting when BLE up after firmware launch */
cybt_platform_hci_wait_for_boot_fully_up(false);
return 0;
}
static int cyw208xx_open(const struct device *dev, bt_hci_recv_t recv)
{
int err;
struct cyw208xx_data *hci = dev->data;
hci->recv = recv;
/* Initialize Bluetooth platform related OS tasks. */
err = cybt_platform_task_init((void *)NULL);
if (err) {
return err;
}
/* Wait until cybt platform task starts */
k_sem_take(&cybt_platform_task_init_sem, K_FOREVER);
return 0;
}
static int cyw208xx_close(const struct device *dev)
{
struct cyw208xx_data *hci = dev->data;
/* Send SHUTDOWN event, BT task will release resources and tervinate task */
cybt_platform_msg_to_bt_task(BT_EVT_TASK_SHUTDOWN, false);
cybt_bttask_deinit();
k_sem_reset(&cybt_platform_task_init_sem);
hci->recv = NULL;
return 0;
}
static int cyw208xx_send(const struct device *dev, struct net_buf *buf)
{
ARG_UNUSED(dev);
int ret = 0;
k_sem_take(&hci_sem, K_FOREVER);
LOG_DBG("buf %p type %u len %u", buf, bt_buf_get_type(buf), buf->len);
switch (bt_buf_get_type(buf)) {
case BT_BUF_ACL_OUT:
uint8_t *bt_msg = host_stack_get_acl_to_lower_buffer(BT_TRANSPORT_LE, buf->len);
memcpy(bt_msg, buf->data, buf->len);
ret = host_stack_send_acl_to_lower(BT_TRANSPORT_LE, bt_msg, buf->len);
break;
case BT_BUF_CMD:
ret = host_stack_send_cmd_to_lower(buf->data, buf->len);
break;
case BT_BUF_ISO_OUT:
ret = host_stack_send_iso_to_lower(buf->data, buf->len);
break;
default:
LOG_ERR("Unknown type %u", bt_buf_get_type(buf));
ret = EIO;
goto done;
}
LOG_HEXDUMP_DBG(buf->data, buf->len, "Final HCI buffer:");
if (ret) {
LOG_ERR("SPI write error %d", ret);
}
done:
k_sem_give(&hci_sem);
net_buf_unref(buf);
return ret ? -EIO : 0;
}
static const struct bt_hci_driver_api drv = {
.open = cyw208xx_open,
.close = cyw208xx_close,
.send = cyw208xx_send,
.setup = cyw208xx_setup
};
static int cyw208xx_hci_init(const struct device *dev)
{
ARG_UNUSED(dev);
const cybt_platform_config_t cybsp_bt_platform_cfg = {
.hci_config = {
.hci_transport = CYBT_HCI_IPC,
},
.controller_config = {
.sleep_mode = {
.sleep_mode_enabled = CYBSP_BT_PLATFORM_CFG_SLEEP_MODE_LP_ENABLED,
},
}
};
/* Configure platform specific settings for the BT device */
cybt_platform_config_init(&cybsp_bt_platform_cfg);
return 0;
}
/* Implements wiced_bt_**** functions requreds for the btstack-integration asset */
wiced_result_t wiced_bt_dev_vendor_specific_command(uint16_t opcode, uint8_t param_len,
uint8_t *param_buf, wiced_bt_dev_vendor_specific_command_complete_cback_t cback)
{
/*
* This function is using only by btstack-integration asset
* for enable LPM.
*/
struct net_buf *buf = NULL;
/* Allocate a HCI command buffer */
buf = bt_hci_cmd_create(opcode, param_len);
if (!buf) {
LOG_ERR("Unable to allocate buffer");
return WICED_NO_MEMORY;
}
/* Add data part of packet */
net_buf_add_mem(buf, param_buf, param_len);
bt_hci_cmd_send(opcode, buf);
return WICED_BT_SUCCESS;
}
void wiced_bt_process_hci(hci_packet_type_t pti, uint8_t *data, uint32_t length)
{
const struct device *dev = DEVICE_DT_GET(DT_DRV_INST(0));
struct cyw208xx_data *hci = dev->data;
struct net_buf *buf = NULL;
size_t buf_tailroom = 0;
switch (pti) {
case HCI_PACKET_TYPE_EVENT:
buf = bt_buf_get_evt(data[0], 0, K_NO_WAIT);
if (!buf) {
LOG_ERR("Failed to allocate the buffer for RX: EVENT ");
return;
}
break;
case HCI_PACKET_TYPE_ACL:
buf = bt_buf_get_rx(BT_BUF_ACL_IN, K_NO_WAIT);
if (!buf) {
LOG_ERR("Failed to allocate the buffer for RX: ACL ");
return;
}
bt_buf_set_type(buf, BT_BUF_ACL_IN);
break;
case HCI_PACKET_TYPE_SCO:
/* NA */
break;
case HCI_PACKET_TYPE_ISO:
buf = bt_buf_get_rx(BT_BUF_ISO_IN, K_NO_WAIT);
if (!buf) {
LOG_ERR("Failed to allocate the buffer for RX: ISO ");
return;
}
break;
default:
return;
}
buf_tailroom = net_buf_tailroom(buf);
if (buf_tailroom < length) {
LOG_WRN("Not enough space for rx data");
return;
}
net_buf_add_mem(buf, data, length);
/* Provide the buffer to the host */
hci->recv(dev, buf);
}
void wiced_bt_process_hci_events(uint8_t *data, uint32_t length)
{
wiced_bt_process_hci(HCI_PACKET_TYPE_EVENT, data, length);
}
void wiced_bt_process_acl_data(uint8_t *data, uint32_t length)
{
wiced_bt_process_hci(HCI_PACKET_TYPE_ACL, data, length);
}
void wiced_bt_process_isoc_data(uint8_t *data, uint32_t length)
{
wiced_bt_process_hci(HCI_PACKET_TYPE_ISO, data, length);
}
void wiced_bt_stack_init_internal(wiced_bt_management_cback_t mgmt_cback,
wiced_bt_internal_post_stack_init_cb post_stack_cb,
wiced_bt_internal_stack_evt_handler_cb evt_handler_cb)
{
k_sem_give(&cybt_platform_task_init_sem);
}
/* Keep below empty functions, used in the btstack_integration assets for Wiced BT stack. */
void wiced_bt_stack_indicate_lower_tx_complete(void)
{
/* NA for Zephyr */
}
void wiced_bt_stack_shutdown(void)
{
/* NA for Zephyr */
}
void wiced_bt_process_timer(void)
{
/* NA for Zephyr */
}
#define CYW208XX_DEVICE_INIT(inst) \
static struct cyw208xx_data cyw208xx_data_##inst = { \
}; \
DEVICE_DT_INST_DEFINE(inst, cyw208xx_hci_init, NULL, &cyw208xx_data_##inst, NULL, \
POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEVICE, &drv)
/* Only one instance supported */
CYW208XX_DEVICE_INIT(0)

View file

@ -289,6 +289,12 @@
<34 6>; /* CH15 */
status = "disabled";
};
bluetooth: btss@42000000 {
compatible = "infineon,cyw208xx-hci";
reg = <0x42000000 0x6186A0>;
interrupts = <16 6>;
status = "disabled";
};
};
};

View file

@ -0,0 +1,21 @@
# Copyright (c) 2024 Cypress Semiconductor Corporation (an Infineon company) or
# an affiliate of Cypress Semiconductor Corporation
#
# SPDX-License-Identifier: Apache-2.0
description: |
Bluetooth module that uses Infineon CYW208XX HCI bluetooth interface
NOTE:
cyw920829 requires fetch binary files of Bluetooth controller firmware.
To fetch Binary Blobs: west blobs fetch hal_infineon
compatible: "infineon,cyw208xx-hci"
include: bt-hci.yaml
properties:
bt-hci-name:
default: "CYW208XX"
bt-hci-bus:
default: "BT_HCI_BUS_VIRTUAL"

View file

@ -2,14 +2,39 @@
#
# SPDX-License-Identifier: Apache-2.0
set(hal_dir ${ZEPHYR_HAL_INFINEON_MODULE_DIR})
set(hal_ble_dir ${hal_dir}/bluetooth-freertos)
set(hal_blobs_dir ${hal_dir}/zephyr/blobs/img/bluetooth/firmware)
set(blob_gen_inc_file ${ZEPHYR_BINARY_DIR}/include/generated/bt_firmware.hcd.inc)
set(hal_dir ${ZEPHYR_HAL_INFINEON_MODULE_DIR})
set(btstack_integration ${hal_dir}/btstack-integration)
set(hal_blobs_dir ${hal_dir}/zephyr/blobs/img/bluetooth/firmware)
set(blob_gen_inc_file ${ZEPHYR_BINARY_DIR}/include/generated/bt_firmware.hcd.inc)
#########################################################################################
# btstack integration assets sources for cyw208xx
#########################################################################################
if(CONFIG_BT_CYW208XX)
zephyr_include_directories(${btstack_integration}/../btstack/wiced_include)
zephyr_include_directories(${btstack_integration}/COMPONENT_BTSS-IPC/platform/include)
zephyr_include_directories(${btstack_integration}/COMPONENT_BTSS-IPC/platform/ipc/include)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/ipc/cybt_platform_freertos.c)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/ipc/cybt_platform_hci.c)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/ipc/cybt_bt_task.c)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/ipc/cybt_host_stack_platform_interface.c)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/ipc/cybt_platform_task.c)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/common/cybt_platform_main.c)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/common/cybt_platform_trace.c)
zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/common/cybt_prm.c)
#zephyr_library_sources(${btstack_integration}/COMPONENT_BTSS-IPC/platform/common/cybt_patchram_download.c)
endif()
#########################################################################################
# BT firmware
#########################################################################################
# HCD files for CYW43xx devices
# CYW43012 modules
if(CONFIG_CYW43012_MURATA_1LV)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_43012/COMPONENT_MURATA-1LV/bt_firmware.hcd)
@ -30,6 +55,38 @@ if(CONFIG_CYW4373_STERLING_LWB5PLUS)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_4373/COMPONENT_STERLING-LWB5plus/bt_firmware.hcd)
endif()
# HCD files for CYW208xx
# CYW20829 device (FW patch for 0dBm TX Power)
if(CONFIG_CYW20829_BT_FW_TX0)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_CYW20829B0/COMPONENT_BTFW-TX0/bt_firmware.hcd)
endif()
# CYW20829 device (FW patch for 10dBm TX Power)
if(CONFIG_CYW20829_BT_FW_TX10)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_CYW20829B0/COMPONENT_BTFW-TX10/bt_firmware.hcd)
endif()
# CYW20829 device (FW patch with PAwR support for 0dBm TX Power)
if(CONFIG_CYW20829_BT_FW_PAWR_TX0)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_CYW20829B0/COMPONENT_BTFW-PAWR-TX0/bt_firmware.hcd)
endif()
# CYW20829 device (FW patch with PAwR support for 10dBm TX Power)
if(CONFIG_CYW20829_BT_FW_PAWR_TX10)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_CYW20829B0/COMPONENT_BTFW-PAWR-TX10/bt_firmware.hcd)
endif()
# CYW20829 device (FW patch with ISOC support for 0dBm TX Power)
if(CONFIG_CYW20829_BT_FW_ISOC_TX0)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_CYW20829B0/COMPONENT_BTFW-ISOC-TX0/bt_firmware.hcd)
endif()
# CYW20829 device (FW patch with ISOC support for 10dBm TX Power)
if(CONFIG_CYW20829_BT_FW_ISOC_TX10)
set(blob_hcd_file ${hal_blobs_dir}/COMPONENT_CYW20829B0/COMPONENT_BTFW-ISOC-TX10/bt_firmware.hcd)
endif()
# use user provided FIRMWARE HCD file (path must be defined in CONFIG_AIROC_CUSTOM_FIRMWARE_HCD_BLOB)
if(CONFIG_AIROC_CUSTOM_FIRMWARE_HCD_BLOB)
# Allowed to pass absolute path to HCD blob file, or relative path from Application folder.

View file

@ -23,6 +23,8 @@ zephyr_include_directories_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1A ${pdl_dev_cat1
zephyr_include_directories_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1A ${pdl_dev_cat1a_dir}/include/ip)
zephyr_library_sources_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1A ${pdl_dev_cat1a_dir}/source/cy_device.c)
zephyr_include_directories(${pdl_drv_dir}/include)
zephyr_include_directories_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1B ${pdl_dev_cat1b_dir}/include)
zephyr_include_directories_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1B ${pdl_dev_cat1b_dir}/include/ip)
zephyr_library_sources_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1B ${pdl_dev_cat1b_dir}/source/cy_device.c)
@ -70,6 +72,7 @@ zephyr_library_sources(${pdl_drv_dir}/source/cy_sysclk.c)
if(CONFIG_SOC_FAMILY_INFINEON_CAT1B)
zephyr_library_sources(${pdl_drv_dir}/source/cy_sysclk_v2.c)
zephyr_library_sources(${pdl_drv_dir}/source/cy_systick_v2.c)
zephyr_library_sources(${pdl_drv_dir}/source/cy_syspm_v2.c)
zephyr_library_sources(${pdl_drv_dir}/source/cy_syspm_btss.c)
endif()
zephyr_library_sources(${pdl_drv_dir}/source/cy_syslib.c)
@ -77,3 +80,7 @@ zephyr_library_sources(${pdl_drv_dir}/source/cy_syspm.c)
zephyr_library_sources(${pdl_drv_dir}/source/cy_systick.c)
zephyr_library_sources(${pdl_drv_dir}/source/cy_trigmux.c)
zephyr_library_sources(${pdl_drv_dir}/source/cy_wdt.c)
# add IPC_BT driver for CYW208XX devices
zephyr_library_sources_ifdef(CONFIG_BT_CYW208XX ${pdl_drv_dir}/source/cy_ipc_bt.c)
zephyr_library_sources_ifdef(CONFIG_BT_CYW208XX ${pdl_drv_dir}/source/cy_syspm_pdcm.c)

View file

@ -5,9 +5,14 @@ zephyr_sources(soc.c)
zephyr_sources(app_header.c)
zephyr_include_directories(.)
# CAT1B family defines
zephyr_compile_definitions_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1 CY_USING_HAL)
zephyr_compile_definitions_ifdef(CONFIG_SOC_FAMILY_INFINEON_CAT1B COMPONENT_CAT1B)
zephyr_compile_definitions(COMPONENT_CM33)
# Use custom linker script
# In MTB for APPTYPE == flash: -DFLASH_BOOT -DCY_PDL_FLASH_BOOT
zephyr_compile_definitions(FLASH_BOOT)
zephyr_compile_definitions(CY_PDL_FLASH_BOOT)
# Use custome linker script
set(SOC_LINKER_SCRIPT ${ZEPHYR_BASE}/soc/infineon/cat1b/cyw20829/linker.ld CACHE INTERNAL "")

View file

@ -173,7 +173,7 @@ manifest:
groups:
- hal
- name: hal_infineon
revision: b1a47231e8671c882c5f055f9f10c32b18133d08
revision: f25734a72c585f6675e8254a382e80e78a3cd03a
path: modules/hal/infineon
groups:
- hal