diff --git a/examples/platform/silabs/SiWx917/SiWx917/wfx_rsi_host.c b/examples/platform/silabs/SiWx917/SiWx917/wfx_rsi_host.c index eef6cdb8a7db61..8f1f895f9683f9 100644 --- a/examples/platform/silabs/SiWx917/SiWx917/wfx_rsi_host.c +++ b/examples/platform/silabs/SiWx917/SiWx917/wfx_rsi_host.c @@ -25,7 +25,6 @@ #include "silabs_utils.h" #include "sl_status.h" #include "task.h" - #include "wfx_host_events.h" #include "wfx_rsi.h" diff --git a/examples/platform/silabs/efr32/BUILD.gn b/examples/platform/silabs/efr32/BUILD.gn index a4fb8f1ac684dc..effbe038389f06 100644 --- a/examples/platform/silabs/efr32/BUILD.gn +++ b/examples/platform/silabs/efr32/BUILD.gn @@ -281,7 +281,7 @@ source_set("efr32-common") { } if (chip_enable_wifi) { - if (use_rs9116 || use_SiWx917) { + if (use_rs9116) { sources += rs911x_src_plat # All the stuff from wiseconnect @@ -290,6 +290,14 @@ source_set("efr32-common") { #add compilation flags for rs991x build. This will be addressed directly in wiseconnect sdk in the next version release of that sdk cflags = rs911x_cflags + } else if (use_SiWx917) { + sources += rs911x_src_plat + + # All the stuff from wiseconnect + sources += rs9117_src_sapi + include_dirs += rs9117_inc_plat + + #add compilation flags for rs991x build. This will be addressed directly in wiseconnect sdk in the next version release of that sdk } else if (use_wf200) { sources += wf200_plat_src include_dirs += wf200_plat_incs diff --git a/examples/platform/silabs/efr32/rs911x/hal/efx32_ncp_host.c b/examples/platform/silabs/efr32/rs911x/hal/efx32_ncp_host.c new file mode 100644 index 00000000000000..414153ecd0164c --- /dev/null +++ b/examples/platform/silabs/efr32/rs911x/hal/efx32_ncp_host.c @@ -0,0 +1,302 @@ +/******************************************************************************* + * @file efx32_ncp_host.c + * @brief + ******************************************************************************* + * # License + * Copyright 2023 Silicon Laboratories Inc. www.silabs.com + ******************************************************************************* + * + * The licensor of this software is Silicon Laboratories Inc. Your use of this + * software is governed by the terms of Silicon Labs Master Software License + * Agreement (MSLA) available at + * www.silabs.com/about-us/legal/master-software-license-agreement. This + * software is distributed to you in Source Code format and is governed by the + * sections of the MSLA applicable to Source Code. + * + ******************************************************************************/ + +#include "FreeRTOS.h" +#include "cmsis_os2.h" +#include "dmadrv.h" +#include "em_cmu.h" +#include "em_core.h" +#include "em_gpio.h" +#include "em_usart.h" +#include "gpiointerrupt.h" +#include "sl_board_configuration_SiWx917.h" +#include "sl_constants.h" +#include "sl_rsi_utility.h" +#include "sl_si91x_host_interface.h" +#include "sl_si91x_status.h" +#include "sl_status.h" +#include "sl_wifi_constants.h" +#include +#include + +#if defined(SL_CATLOG_POWER_MANAGER_PRESENT) +#include "sl_power_manager.h" +#endif + +static bool dma_callback(unsigned int channel, unsigned int sequenceNo, void * userParam); + +unsigned int rx_ldma_channel; +unsigned int tx_ldma_channel; +osMutexId_t spi_transfer_mutex = 0; + +static uint32_t dummy_buffer; + +// LDMA descriptor and transfer configuration structures for USART TX channel +LDMA_Descriptor_t ldmaTXDescriptor; +LDMA_TransferCfg_t ldmaTXConfig; + +// LDMA descriptor and transfer configuration structures for USART RX channel +LDMA_Descriptor_t ldmaRXDescriptor; +LDMA_TransferCfg_t ldmaRXConfig; + +static osSemaphoreId_t transfer_done_semaphore = NULL; + +static bool dma_callback(unsigned int channel, unsigned int sequenceNo, void * userParam) +{ + UNUSED_PARAMETER(channel); + UNUSED_PARAMETER(sequenceNo); + UNUSED_PARAMETER(userParam); +#if defined(SL_CATLOG_POWER_MANAGER_PRESENT) + sl_power_manager_remove_em_requirement(SL_POWER_MANAGER_EM1); +#endif + osSemaphoreRelease(transfer_done_semaphore); + return false; +} + +static void gpio_interrupt(uint8_t interrupt_number) +{ + UNUSED_PARAMETER(interrupt_number); + sl_si91x_host_set_bus_event(NCP_HOST_BUS_RX_EVENT); + // GPIO_IntClear(0xAAAA); +} + +void sl_si91x_host_set_sleep_indicator(void) +{ + GPIO_PinOutSet(SLEEP_CONFIRM_PIN.port, SLEEP_CONFIRM_PIN.pin); +} + +void sl_si91x_host_clear_sleep_indicator(void) +{ + GPIO_PinOutClear(SLEEP_CONFIRM_PIN.port, SLEEP_CONFIRM_PIN.pin); +} + +uint32_t sl_si91x_host_get_wake_indicator(void) +{ + return GPIO_PinInGet(WAKE_INDICATOR_PIN.port, WAKE_INDICATOR_PIN.pin); +} + +sl_status_t sl_si91x_host_init(void) +{ + // Enable clock (not needed on xG21) + CMU_ClockEnable(cmuClock_GPIO, true); + +#if SL_SPICTRL_MUX + spi_board_init(); +#endif + // Configure SPI bus pins + GPIO_PinModeSet(SPI_MISO_PIN.port, SPI_MISO_PIN.pin, gpioModeInput, 0); + GPIO_PinModeSet(SPI_MOSI_PIN.port, SPI_MOSI_PIN.pin, gpioModePushPull, 0); + GPIO_PinModeSet(SPI_CLOCK_PIN.port, SPI_CLOCK_PIN.pin, gpioModePushPullAlternate, 0); + GPIO_PinModeSet(SPI_CS_PIN.port, SPI_CS_PIN.pin, gpioModePushPull, 1); + // Enable clock (not needed on xG21) + CMU_ClockEnable(SPI_USART_CMU_CLOCK, true); + + // Default asynchronous initializer (master mode, 1 Mbps, 8-bit data) + USART_InitSync_TypeDef init = USART_INITSYNC_DEFAULT; + + init.msbf = true; // MSB first transmission for SPI compatibility + init.autoCsEnable = true; // Allow the USART to assert CS + init.baudrate = 12500000; + /* + * Route USART RX, TX, and CLK to the specified pins. Note that CS is + * not controlled by USART so there is no write to the corresponding + * USARTROUTE register to do this. + */ + GPIO->USARTROUTE[SPI_USART_ROUTE_INDEX].RXROUTE = + (SPI_MISO_PIN.port << _GPIO_USART_RXROUTE_PORT_SHIFT) | (SPI_MISO_PIN.pin << _GPIO_USART_RXROUTE_PIN_SHIFT); + GPIO->USARTROUTE[SPI_USART_ROUTE_INDEX].TXROUTE = + (SPI_MOSI_PIN.port << _GPIO_USART_TXROUTE_PORT_SHIFT) | (SPI_MOSI_PIN.pin << _GPIO_USART_TXROUTE_PIN_SHIFT); + GPIO->USARTROUTE[SPI_USART_ROUTE_INDEX].CLKROUTE = + (SPI_CLOCK_PIN.port << _GPIO_USART_CLKROUTE_PORT_SHIFT) | (SPI_CLOCK_PIN.pin << _GPIO_USART_CLKROUTE_PIN_SHIFT); + GPIO->USARTROUTE[SPI_USART_ROUTE_INDEX].CSROUTE = + (SPI_CS_PIN.port << _GPIO_USART_CSROUTE_PORT_SHIFT) | (SPI_CS_PIN.pin << _GPIO_USART_CSROUTE_PIN_SHIFT); + + // Enable USART interface pins + GPIO->USARTROUTE[SPI_USART_ROUTE_INDEX].ROUTEEN = GPIO_USART_ROUTEEN_RXPEN | // MISO + GPIO_USART_ROUTEEN_TXPEN | // MOSI + GPIO_USART_ROUTEEN_CLKPEN | GPIO_USART_ROUTEEN_CSPEN; + + // Set slew rate for alternate usage pins + GPIO_SlewrateSet(SPI_CLOCK_PIN.port, 7, 7); + + // Configure and enable USART + USART_InitSync(SPI_USART, &init); + + SPI_USART->TIMING |= /*USART_TIMING_TXDELAY_ONE | USART_TIMING_CSSETUP_ONE |*/ USART_TIMING_CSHOLD_ONE; + + // SPI_USART->CTRL_SET |= USART_CTRL_SMSDELAY; + if (transfer_done_semaphore == NULL) + { + transfer_done_semaphore = osSemaphoreNew(1, 0, NULL); + } + + if (spi_transfer_mutex == 0) + { + spi_transfer_mutex = osMutexNew(NULL); + } + + DMADRV_Init(); + DMADRV_AllocateChannel(&rx_ldma_channel, NULL); + DMADRV_AllocateChannel(&tx_ldma_channel, NULL); + + // Start reset line low + GPIO_PinModeSet(RESET_PIN.port, RESET_PIN.pin, gpioModePushPull, 0); + + // configure packet pending interrupt priority + NVIC_SetPriority(GPIO_ODD_IRQn, PACKET_PENDING_INT_PRI); + + // Configure interrupt, sleep and wake confirmation pins + GPIOINT_CallbackRegister(INTERRUPT_PIN.pin, gpio_interrupt); + GPIO_PinModeSet(INTERRUPT_PIN.port, INTERRUPT_PIN.pin, gpioModeInputPullFilter, 0); + GPIO_ExtIntConfig(INTERRUPT_PIN.port, INTERRUPT_PIN.pin, INTERRUPT_PIN.pin, true, false, true); + GPIO_PinModeSet(SLEEP_CONFIRM_PIN.port, SLEEP_CONFIRM_PIN.pin, gpioModeWiredOrPullDown, 1); + GPIO_PinModeSet(WAKE_INDICATOR_PIN.port, WAKE_INDICATOR_PIN.pin, gpioModeWiredOrPullDown, 0); + + return SL_STATUS_OK; +} + +sl_status_t sl_si91x_host_deinit(void) +{ + return SL_STATUS_OK; +} + +void sl_si91x_host_enable_high_speed_bus() +{ + // SPI_USART->CTRL_SET |= USART_CTRL_SMSDELAY | USART_CTRL_SSSEARLY; + // USART_BaudrateSyncSet(SPI_USART, 0, 20000000); +} + +/*==================================================================*/ +/** + * @fn sl_status_t sl_si91x_host_spi_transfer(const void *tx_buffer, void *rx_buffer, uint16_t buffer_length) + * @param[in] uint8_t *tx_buff, pointer to the buffer with the data to be transferred + * @param[in] uint8_t *rx_buff, pointer to the buffer to store the data received + * @param[in] uint16_t transfer_length, Number of bytes to send and receive + * @param[in] uint8_t mode, To indicate mode 8 BIT/32 BIT mode transfers. + * @param[out] None + * @return 0, 0=success + * @section description + * This API is used to transfer/receive data to the Wi-Fi module through the SPI interface. + */ +sl_status_t sl_si91x_host_spi_transfer(const void * tx_buffer, void * rx_buffer, uint16_t buffer_length) +{ + osMutexAcquire(spi_transfer_mutex, 0xFFFFFFFFUL); + +#if SL_SPICTRL_MUX + sl_wfx_host_spi_cs_assert(); +#endif // SL_SPICTRL_MUX + + if (buffer_length < 16) + { + uint8_t * tx = (tx_buffer != NULL) ? (uint8_t *) tx_buffer : (uint8_t *) &dummy_buffer; + uint8_t * rx = (rx_buffer != NULL) ? (uint8_t *) rx_buffer : (uint8_t *) &dummy_buffer; + while (buffer_length > 0) + { + while (!(SPI_USART->STATUS & USART_STATUS_TXBL)) + { + } + SPI_USART->TXDATA = (uint32_t) *tx; + while (!(SPI_USART->STATUS & USART_STATUS_TXC)) + { + } + *rx = (uint8_t) SPI_USART->RXDATA; + if (tx_buffer != NULL) + { + tx++; + } + if (rx_buffer != NULL) + { + rx++; + } + buffer_length--; + } + } + else + { + if (tx_buffer == NULL) + { + dummy_buffer = 0; + ldmaTXDescriptor = + (LDMA_Descriptor_t) LDMA_DESCRIPTOR_SINGLE_P2P_BYTE(&dummy_buffer, &(SPI_USART->TXDATA), buffer_length); + } + else + { + ldmaTXDescriptor = (LDMA_Descriptor_t) LDMA_DESCRIPTOR_SINGLE_M2P_BYTE(tx_buffer, &(SPI_USART->TXDATA), buffer_length); + } + + if (rx_buffer == NULL) + { + ldmaRXDescriptor = + (LDMA_Descriptor_t) LDMA_DESCRIPTOR_SINGLE_P2P_BYTE(&(SPI_USART->RXDATA), &dummy_buffer, buffer_length); + } + else + { + ldmaRXDescriptor = (LDMA_Descriptor_t) LDMA_DESCRIPTOR_SINGLE_P2M_BYTE(&(SPI_USART->RXDATA), rx_buffer, buffer_length); + } + + // Transfer a byte on free space in the USART buffer + ldmaTXConfig = (LDMA_TransferCfg_t) LDMA_TRANSFER_CFG_PERIPHERAL(SPI_USART_LDMA_TX); + + // Transfer a byte on receive data valid + ldmaRXConfig = (LDMA_TransferCfg_t) LDMA_TRANSFER_CFG_PERIPHERAL(SPI_USART_LDMA_RX); + +#if defined(SL_CATLOG_POWER_MANAGER_PRESENT) + sl_power_manager_remove_em_requirement(SL_POWER_MANAGER_EM1); +#endif + + // Start both channels + DMADRV_LdmaStartTransfer(rx_ldma_channel, &ldmaRXConfig, &ldmaRXDescriptor, dma_callback, NULL); + DMADRV_LdmaStartTransfer(tx_ldma_channel, &ldmaTXConfig, &ldmaTXDescriptor, NULL, NULL); + + if (osSemaphoreAcquire(transfer_done_semaphore, 1000) != osOK) + { + BREAKPOINT(); + } + } + + osMutexRelease(spi_transfer_mutex); +#if SL_SPICTRL_MUX + sl_wfx_host_spi_cs_deassert(); +#endif // SL_SPICTRL_MUX + return SL_STATUS_OK; +} + +void sl_si91x_host_hold_in_reset(void) +{ + GPIO_PinModeSet(RESET_PIN.port, RESET_PIN.pin, gpioModePushPull, 1); + GPIO_PinOutClear(RESET_PIN.port, RESET_PIN.pin); +} + +void sl_si91x_host_release_from_reset(void) +{ + GPIO_PinModeSet(RESET_PIN.port, RESET_PIN.pin, gpioModeWiredOrPullDown, 1); +} + +void sl_si91x_host_enable_bus_interrupt(void) +{ + NVIC_EnableIRQ(GPIO_ODD_IRQn); +} + +void sl_si91x_host_disable_bus_interrupt(void) +{ + NVIC_DisableIRQ(GPIO_ODD_IRQn); +} + +bool sl_si91x_host_is_in_irq_context(void) +{ + return (SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) != 0U; +} \ No newline at end of file diff --git a/examples/platform/silabs/efr32/rs911x/hal/efx_spi.c b/examples/platform/silabs/efr32/rs911x/hal/efx_spi.c index 1e30b8bdf2f9c6..ad6b5ed5e3418d 100644 --- a/examples/platform/silabs/efr32/rs911x/hal/efx_spi.c +++ b/examples/platform/silabs/efr32/rs911x/hal/efx_spi.c @@ -38,7 +38,6 @@ #include "spidrv.h" #include "sl_device_init_clocks.h" -#include "sl_device_init_dpll.h" #include "sl_device_init_hfxo.h" #include "sl_spidrv_instances.h" #include "sl_status.h" @@ -48,27 +47,15 @@ #include "wfx_host_events.h" #include "wfx_rsi.h" +#define DEFAULT_SPI_TRASFER_MODE 0 +// Macro to drive semaphore block minimun timer in milli seconds +#define RSI_SEM_BLOCK_MIN_TIMER_VALUE_MS (50) #if defined(SL_CATALOG_POWER_MANAGER_PRESENT) #include "sl_power_manager.h" #endif -#ifdef CHIP_9117 -#include "cmsis_os2.h" -#include "sl_board_configuration.h" -#include "sl_net.h" -#include "sl_si91x_driver.h" -#include "sl_si91x_types.h" -#include "sl_wifi_callback_framework.h" -#include "sl_wifi_constants.h" -#include "sl_wifi_types.h" - -// macro to drive semaphore block minimum timer in milli seconds -// ported from rsi_hal.h (rs911x) -#define RSI_SEM_BLOCK_MIN_TIMER_VALUE_MS (50) -#else #include "rsi_board_configuration.h" #include "rsi_driver.h" -#endif // CHIP_9117 #if SL_BTLCTRL_MUX #include "btl_interface.h" @@ -110,6 +97,16 @@ static TaskHandle_t spiInitiatorTaskHandle = NULL; static uint32_t dummy_buffer; /* Used for DMA - when results don't matter */ +#if defined(EFR32MG12) +#include "sl_spidrv_exp_config.h" +extern SPIDRV_Handle_t sl_spidrv_exp_handle; +#define SL_SPIDRV_HANDLE sl_spidrv_exp_handle +#elif defined(EFR32MG24) +#include "spi_multiplex.h" +#else +#error "Unknown platform" +#endif + // variable to identify spi configured for expansion header // EUSART configuration available on the SPIDRV static bool spi_enabled = false; @@ -174,6 +171,11 @@ void sl_wfx_host_reset_chip(void) vTaskDelay(pdMS_TO_TICKS(3)); } +void gpio_interrupt(uint8_t interrupt_number) +{ + UNUSED_PARAMETER(interrupt_number); +} + /***************************************************************** * @fn void rsi_hal_board_init(void) * @brief @@ -202,13 +204,6 @@ void rsi_hal_board_init(void) sl_wfx_host_reset_chip(); } -// wifi-sdk -sl_status_t sl_si91x_host_bus_init(void) -{ - rsi_hal_board_init(); - return SL_STATUS_OK; -} - void sl_si91x_host_enable_high_speed_bus() { // dummy function for wifi-sdk @@ -461,20 +456,3 @@ int16_t rsi_spi_transfer(uint8_t * tx_buf, uint8_t * rx_buf, uint16_t xlen, uint #endif // SL_SPICTRL_MUX return rsiError; } - -#ifdef CHIP_9117 -/********************************************************************* - * @fn int16_t sl_si91x_host_spi_transfer(uint8_t *tx_buf, uint8_t *rx_buf, uint16_t xlen) - * @param[in] uint8_t *tx_buff, pointer to the buffer with the data to be transferred - * @param[in] uint8_t *rx_buff, pointer to the buffer to store the data received - * @param[in] uint16_t transfer_length, Number of bytes to send and receive - * @param[out] None - * @return 0, 0=success - * @section description - * This API is used to transfer/receive data to the Wi-Fi module through the SPI interface. - **************************************************************************/ -sl_status_t sl_si91x_host_spi_transfer(const void * tx_buf, void * rx_buf, uint16_t xlen) -{ - return (rsi_spi_transfer((uint8_t *) tx_buf, rx_buf, xlen, RSI_MODE_8BIT)); -} -#endif // CHIP_9117 diff --git a/examples/platform/silabs/efr32/rs911x/hal/rsi_hal_mcu_interrupt.c b/examples/platform/silabs/efr32/rs911x/hal/rsi_hal_mcu_interrupt.c index b57bd9cf988f4f..f7a40551fdc5b5 100644 --- a/examples/platform/silabs/efr32/rs911x/hal/rsi_hal_mcu_interrupt.c +++ b/examples/platform/silabs/efr32/rs911x/hal/rsi_hal_mcu_interrupt.c @@ -41,6 +41,7 @@ #if (SIWX_917 | EXP_BOARD) #include "sl_board_configuration.h" +#include "sl_rsi_utility.h" #include "sl_si91x_host_interface.h" void gpio_interrupt(uint8_t interrupt_number); diff --git a/examples/platform/silabs/efr32/rs911x/hal/sl_board_configuration_SiWx917.h b/examples/platform/silabs/efr32/rs911x/hal/sl_board_configuration_SiWx917.h new file mode 100644 index 00000000000000..7145e318b33d30 --- /dev/null +++ b/examples/platform/silabs/efr32/rs911x/hal/sl_board_configuration_SiWx917.h @@ -0,0 +1,62 @@ +#pragma once + +#ifdef SL_UART +#include "sl_device_registers.h" +#include "sl_uart.h" + +#define DEFAULT_UART USART0 + +#define SL_UART_VCOM_PORT SL_GPIO_PORT_D +#define SL_UART_VCOM_PIN 4 +static const sl_gpio_t vcom_enable_pin = { SL_UART_VCOM_PORT, SL_UART_VCOM_PIN }; + +#define DEFAULT_UART_PIN_CONFIG &default_uart_pin_configuration + +// XXX: HACK to get things working +#define UART_CLOCK cmuClock_USART0 +#define UART_RX_IRQ USART0_RX_IRQn + +/* Note: This creates a static instance for each C file that includes this header and references the variable */ +static const sl_uart_pin_configuration_t default_uart_pin_configuration = { + .tx_port = SL_GPIO_PORT_A, + .tx_pin = 5, + .rx_port = SL_GPIO_PORT_A, + .rx_pin = 6, + .cts_port = SL_GPIO_PORT_A, + .cts_pin = 4, + .rts_port = SL_GPIO_PORT_C, + .rts_pin = 1, + .uart_number = 0, + //.route_loc = USART_ROUTELOC0_RXLOC_LOC4 | USART_ROUTELOC0_TXLOC_LOC4, +}; +#endif + +typedef struct +{ + unsigned char port; + unsigned char pin; +} sl_pin_t; + +#define PIN(port_id, pin_id) \ + (sl_pin_t) \ + { \ + .port = gpioPort##port_id, .pin = pin_id \ + } + +#define SLEEP_CONFIRM_PIN PIN(D, 2) +#define WAKE_INDICATOR_PIN PIN(A, 5) +#define RESET_PIN PIN(A, 6) +#define INTERRUPT_PIN PIN(A, 7) + +#define SPI_CLOCK_PIN PIN(C, 3) +#define SPI_MOSI_PIN PIN(C, 1) +#define SPI_MISO_PIN PIN(C, 2) +#define SPI_CS_PIN PIN(C, 0) + +#define SPI_USART USART0 +#define SPI_USART_CMU_CLOCK cmuClock_USART0 +#define SPI_USART_LDMA_TX ldmaPeripheralSignal_USART0_TXBL +#define SPI_USART_LDMA_RX ldmaPeripheralSignal_USART0_RXDATAV +#define SPI_USART_ROUTE_INDEX 0 + +#define PACKET_PENDING_INT_PRI 3 diff --git a/examples/platform/silabs/efr32/rs911x/hal/sl_si91x_ncp_utility.c b/examples/platform/silabs/efr32/rs911x/hal/sl_si91x_ncp_utility.c new file mode 100644 index 00000000000000..6a9d02f47dd027 --- /dev/null +++ b/examples/platform/silabs/efr32/rs911x/hal/sl_si91x_ncp_utility.c @@ -0,0 +1,280 @@ +/* + * + * Copyright (c) 2023 Project CHIP Authors + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * Includes + */ +#include +#include +#include + +#include "FreeRTOS.h" +#include "dmadrv.h" +#include "em_chip.h" +#include "em_cmu.h" +#include "em_core.h" +#include "em_device.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "event_groups.h" +#include "gpiointerrupt.h" +#include "semphr.h" +#include "spidrv.h" +#include "task.h" + +#include "sl_device_init_clocks.h" +#include "sl_device_init_hfxo.h" +#include "sl_status.h" + +#include "silabs_utils.h" +#include "sl_si91x_ncp_utility.h" +#include "wfx_host_events.h" +#include "wfx_rsi.h" + +#if SL_MX25CTRL_MUX +sl_status_t sl_wfx_host_spiflash_cs_assert(void); +sl_status_t sl_wfx_host_spiflash_cs_deassert(void); +#endif + +#if SL_BTLCTRL_MUX +#include "btl_interface.h" +#endif // SL_BTLCTRL_MUX +#if SL_LCDCTRL_MUX +#include "sl_memlcd.h" +#endif // SL_LCDCTRL_MUX +#if SL_MX25CTRL_MUX +#include "sl_mx25_flash_shutdown_usart_config.h" +#endif // SL_MX25CTRL_MUX + +#define CONCAT(A, B) (A##B) +#define SPI_CLOCK(N) CONCAT(cmuClock_USART, N) + +#if SL_SPICTRL_MUX +StaticSemaphore_t spi_sem_peripheral; +SemaphoreHandle_t spi_sem_sync_hdl; +#endif // SL_SPICTRL_MUX + +#if SL_LCDCTRL_MUX + +/******************************************************** + * @fn sl_wfx_host_pre_lcd_spi_transfer(void) + * @brief + * Deal with the SPI PINS MUX that are associated with LCD. for setup before data transfer PINS. + * @return + * None + **********************************************************/ +sl_status_t sl_wfx_host_pre_lcd_spi_transfer(void) +{ +#if SL_SPICTRL_MUX + if (sl_wfx_host_spi_cs_deassert() != SL_STATUS_OK) + { + return SL_STATUS_FAIL; + } + xSemaphoreTake(spi_sem_sync_hdl, portMAX_DELAY); +#endif // SL_SPICTRL_MUX + // sl_memlcd_refresh takes care of SPIDRV_Init() + if (SL_STATUS_OK != sl_memlcd_refresh(sl_memlcd_get())) + { +#if SL_SPICTRL_MUX + xSemaphoreGive(spi_sem_sync_hdl); +#endif // SL_SPICTRL_MUX + SILABS_LOG("%s error.", __func__); + return SL_STATUS_FAIL; + } + return SL_STATUS_OK; +} + +/******************************************************** + * @fn sl_wfx_host_post_lcd_spi_transfer(void) + * @brief + * Deal with the SPI PINS MUX that are associated with LCD. for setup after data transfer PINS. + * @return + * None + **********************************************************/ +sl_status_t sl_wfx_host_post_lcd_spi_transfer(void) +{ + USART_Enable(SL_MEMLCD_SPI_PERIPHERAL, usartDisable); + CMU_ClockEnable(SPI_CLOCK(SL_MEMLCD_SPI_PERIPHERAL_NO), false); + GPIO->USARTROUTE[SL_MEMLCD_SPI_PERIPHERAL_NO].ROUTEEN = PINOUT_CLEAR; +#if SL_SPICTRL_MUX + xSemaphoreGive(spi_sem_sync_hdl); +#endif // SL_SPICTRL_MUX + return SL_STATUS_OK; +} +#endif // SL_LCDCTRL_MUX + +#if SL_SPICTRL_MUX + +void SPIDRV_SetBaudrate(uint32_t baudrate) +{ +#if !defined(CHIP_9117) + if (EUSART_BaudrateGet(MY_USART) == baudrate) + { + // EUSART synced to baudrate already + return; + } + EUSART_BaudrateSet(MY_USART, 0, baudrate); +#endif +} + +/******************************************************** + * @fn spi_board_init(void) + * @brief + * Deal with the SPI PINS multiplexing related changes for the initialization. + * @return + * None + **********************************************************/ +sl_status_t spi_board_init() +{ +#if SL_SPICTRL_MUX + if (spi_sem_sync_hdl == NULL) + { + spi_sem_sync_hdl = xSemaphoreCreateBinaryStatic(&spi_sem_peripheral); + } + configASSERT(spi_sem_sync_hdl); + xSemaphoreGive(spi_sem_sync_hdl); +#endif /* SL_SPICTRL_MUX */ + return SL_STATUS_OK; +} + +/******************************************************** + * @fn sl_wfx_host_spi_cs_assert(void) + * @brief + * Deal with the SPI PINS multiplexing related changes for the initialization. + * @return + * None + **********************************************************/ +sl_status_t sl_wfx_host_spi_cs_assert(void) +{ + xSemaphoreTake(spi_sem_sync_hdl, portMAX_DELAY); + + if (!spi_enabled) // Reduce sl_spidrv_init_instances + { + +#if defined(EFR32MG24) +#if defined(CHIP_9117) + GPIO_PinOutClear(SPI_CS_PIN.port, SPI_CS_PIN.pin); +#else + sl_spidrv_init_instances(); + GPIO_PinOutClear(SL_SPIDRV_EUSART_EXP_CS_PORT, SL_SPIDRV_EUSART_EXP_CS_PIN); +#endif // CHIP_9117 +#endif // EFR32MG24 + spi_enabled = true; + } + return SL_STATUS_OK; +} + +sl_status_t sl_wfx_host_spi_cs_deassert(void) +{ + if (spi_enabled) + { +#if defined(CHIP_9117) + LDMA_DeInit(); + xSemaphoreGive(spi_sem_sync_hdl); + SILABS_LOG("%s error.", __func__); +#else + if (ECODE_EMDRV_SPIDRV_OK != SPIDRV_DeInit(SL_SPIDRV_HANDLE)) + { + xSemaphoreGive(spi_sem_sync_hdl); + SILABS_LOG("%s error.", __func__); + return SL_STATUS_FAIL; + } +#endif +#if defined(EFR32MG24) +#if defined(CHIP_9117) + GPIO_PinModeSet(SPI_CS_PIN.port, SPI_CS_PIN.pin, gpioModePushPull, 1); + GPIO->USARTROUTE[SPI_USART_ROUTE_INDEX].ROUTEEN = PINOUT_CLEAR; +#else + GPIO_PinOutSet(SL_SPIDRV_EUSART_EXP_CS_PORT, SL_SPIDRV_EUSART_EXP_CS_PIN); + GPIO->EUSARTROUTE[SL_SPIDRV_EUSART_EXP_PERIPHERAL_NO].ROUTEEN = PINOUT_CLEAR; +#endif // CHIP_9117 +#endif // EFR32MG24 + spi_enabled = false; + } + xSemaphoreGive(spi_sem_sync_hdl); + return SL_STATUS_OK; +} +#endif // SL_SPICTRL_MUX + +#if SL_BTLCTRL_MUX +sl_status_t sl_wfx_host_pre_bootloader_spi_transfer(void) +{ +#if SL_SPICTRL_MUX + if (sl_wfx_host_spi_cs_deassert() != SL_STATUS_OK) + { + return SL_STATUS_FAIL; + } + xSemaphoreTake(spi_sem_sync_hdl, portMAX_DELAY); +#endif // SL_SPICTRL_MUX + int32_t status = BOOTLOADER_OK; +#if defined(CHIP_9117) + LDMA_Init_t ldma_init = LDMA_INIT_DEFAULT; + LDMA_Init(&ldma_init); +#else + // bootloader_init takes care of SPIDRV_Init() + status = bootloader_init(); +#endif + if (status != BOOTLOADER_OK) + { + SILABS_LOG("bootloader_init error: %x", status); +#if SL_SPICTRL_MUX + xSemaphoreGive(spi_sem_sync_hdl); +#endif // SL_SPICTRL_MUX + return SL_STATUS_FAIL; + } +#if SL_MX25CTRL_MUX + sl_wfx_host_spiflash_cs_assert(); +#endif // SL_MX25CTRL_MUX + return SL_STATUS_OK; +} + +sl_status_t sl_wfx_host_post_bootloader_spi_transfer(void) +{ + // bootloader_deinit will do USART disable + int32_t status = bootloader_deinit(); + if (status != BOOTLOADER_OK) + { + SILABS_LOG("bootloader_deinit error: %x", status); +#if SL_SPICTRL_MUX + xSemaphoreGive(spi_sem_sync_hdl); +#endif // SL_SPICTRL_MUX + return SL_STATUS_FAIL; + } + GPIO->USARTROUTE[SL_MX25_FLASH_SHUTDOWN_PERIPHERAL_NO].ROUTEEN = PINOUT_CLEAR; +#if SL_MX25CTRL_MUX + sl_wfx_host_spiflash_cs_deassert(); +#endif // SL_MX25CTRL_MUX +#if SL_SPICTRL_MUX + xSemaphoreGive(spi_sem_sync_hdl); +#endif // SL_SPICTRL_MUX + return SL_STATUS_OK; +} +#endif // SL_BTLCTRL_MUX + +#if SL_MX25CTRL_MUX +sl_status_t sl_wfx_host_spiflash_cs_assert(void) +{ + GPIO_PinOutClear(SL_MX25_FLASH_SHUTDOWN_CS_PORT, SL_MX25_FLASH_SHUTDOWN_CS_PIN); + return SL_STATUS_OK; +} + +sl_status_t sl_wfx_host_spiflash_cs_deassert(void) +{ + GPIO_PinOutSet(SL_MX25_FLASH_SHUTDOWN_CS_PORT, SL_MX25_FLASH_SHUTDOWN_CS_PIN); + return SL_STATUS_OK; +} +#endif // SL_MX25CTRL_MUX \ No newline at end of file diff --git a/examples/platform/silabs/efr32/rs911x/hal/sl_si91x_ncp_utility.h b/examples/platform/silabs/efr32/rs911x/hal/sl_si91x_ncp_utility.h new file mode 100644 index 00000000000000..a1e6f4525e5bb2 --- /dev/null +++ b/examples/platform/silabs/efr32/rs911x/hal/sl_si91x_ncp_utility.h @@ -0,0 +1,55 @@ +/* + * + * Copyright (c) 2023 Project CHIP Authors + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * This file contains all the functions specific to the MG24 family for + * multiplexing the SPI port with WiFi NCP and other WSTK + * devices such as External Flash and LCD. + * That can be extended to other families as well. + */ + +#include "silabs_utils.h" +#include "sl_status.h" +#include "spi_multiplex.h" + +#if defined(CHIP_9117) +#include "sl_board_configuration_SiWx917.h" +#else +#include "sl_board_configuration.h" +#if defined(EFR32MG12) +#include "em_usart.h" +#include "sl_spidrv_exp_config.h" +extern SPIDRV_Handle_t sl_spidrv_exp_handle; +#define SL_SPIDRV_HANDLE sl_spidrv_exp_handle +#elif defined(EFR32MG24) +#include "em_eusart.h" +#include "sl_spidrv_eusart_exp_config.h" +#include "sl_spidrv_instances.h" + +#define SL_SPIDRV_HANDLE sl_spidrv_eusart_exp_handle +#else // EFR32MG12 || EFR32MG24 +#error "Unknown platform" +#endif +#endif // CHIP_9117 + +// variable to identify spi configured for expansion header +// EUSART configuration available on the SPIDRV + +#if SL_SPICTRL_MUX +sl_status_t spi_board_init(void); +static bool spi_enabled = false; +#endif // SL_SPICTRL_MUX diff --git a/examples/platform/silabs/efr32/rs911x/rs9117.gni b/examples/platform/silabs/efr32/rs911x/rs9117.gni index a753a66153bec4..251de0be213fe6 100644 --- a/examples/platform/silabs/efr32/rs911x/rs9117.gni +++ b/examples/platform/silabs/efr32/rs911x/rs9117.gni @@ -6,47 +6,28 @@ rs911x_src_plat = [ "${examples_plat_dir}/rs911x/sl_wifi_if.c", "${examples_plat_dir}/rs911x/wfx_rsi_host.c", "${examples_plat_dir}/rs911x/hal/rsi_hal_mcu_interrupt.c", - "${examples_plat_dir}/rs911x/hal/efx_spi.c", + "${examples_plat_dir}/rs911x/hal/sl_si91x_ncp_utility.c", + "${examples_plat_dir}/rs911x/hal/efx32_ncp_host.c", "${silabs_plat_efr32_wifi_dir}/wfx_notify.cpp", ] -rs911x_inc_plat = [ +rs9117_inc_plat = [ "${examples_plat_dir}/rs911x", "${examples_plat_dir}/rs911x/hal", "${wifi_sdk_root}/components/si91x/ble/inc", - - # si91x component - "${wifi_sdk_root}/components/si91x/inc", - "${wifi_sdk_root}/components/si91x/memory", - "${wifi_sdk_root}/components/si91x/sl_net/inc", - - # wifi component - "${wifi_sdk_root}/components/protocol/wifi/inc", - - # si91x_support component - "${wifi_sdk_root}/components/si91x_support/inc", - - # wifi_resources component - "${wifi_sdk_root}/resources/certificates", - "${wifi_sdk_root}/resources/defaults", - "${wifi_sdk_root}/resources/other", - - # network_manager component - "${wifi_sdk_root}/components/service/network_manager/inc", - - "${wifi_sdk_root}/components/protocol/wifi/si91x", ] rs911x_cflags = [ "-Wno-empty-body" ] -rs911x_src_sapi = [ - "${wifi_sdk_root}/components/si91x/src/sl_si91x_driver.c", - "${wifi_sdk_root}/components/si91x/spi_interface/sl_si91x_spi_driver.c", - "${wifi_sdk_root}/components/si91x/src/sl_rsi_utility.c", - "${wifi_sdk_root}/components/si91x/src/sl_si91x_callback_framework.c", - "${wifi_sdk_root}/components/si91x/threading/sli_si91x_multithreaded.c", - "${wifi_sdk_root}/components/si91x/sl_net/src/sl_net_si91x.c", - "${wifi_sdk_root}/components/si91x/sl_net/src/sl_net_rsi_utility.c", - "${wifi_sdk_root}/components/si91x/sl_net/src/sl_net_si91x_integration_handler.c", +rs9117_src_sapi = [ + # sl_si91x_wireless component + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/src/sl_si91x_driver.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/src/sl_rsi_utility.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/src/sl_si91x_callback_framework.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/threading/sli_si91x_multithreaded.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/sl_net/src/sl_net_rsi_utility.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/sl_net/src/sl_net_si91x_integration_handler.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/sl_net/src/sl_si91x_net_credentials.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/spi_interface/sl_si91x_spi_driver.c", # wifi component "${wifi_sdk_root}/components/protocol/wifi/src/sl_wifi_callback_framework.c", @@ -57,13 +38,12 @@ rs911x_src_sapi = [ "${wifi_sdk_root}/components/service/network_manager/src/sl_net_basic_profiles.c", # si91x_basic_buffers component - "${wifi_sdk_root}/components/si91x/memory/malloc_buffers.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/memory/malloc_buffers.c", # si91x_support component - "${wifi_sdk_root}/components/si91x_support/src/sl_utility.c", + "${wifi_sdk_root}/components/common/src/sl_utility.c", # network_manager component "${wifi_sdk_root}/components/service/network_manager/src/sl_net_basic_certificate_store.c", "${wifi_sdk_root}/components/service/network_manager/src/sl_net.c", - "${wifi_sdk_root}/components/si91x/platforms/efx32/efx32_ncp_host.c", ] diff --git a/examples/platform/silabs/efr32/rs911x/sl_wlan_config.h b/examples/platform/silabs/efr32/rs911x/sl_wlan_config.h index 91acde1ecbcb2a..c8eef5c60e830e 100644 --- a/examples/platform/silabs/efr32/rs911x/sl_wlan_config.h +++ b/examples/platform/silabs/efr32/rs911x/sl_wlan_config.h @@ -34,7 +34,7 @@ static const sl_wifi_device_configuration_t config = { .boot_config = { .oper_mode = SL_SI91X_CLIENT_MODE, .coex_mode = SL_SI91X_WLAN_BLE_MODE, .feature_bit_map = -#ifdef RSI_M4_INTERFACE +#ifdef SLI_SI91X_MCU_INTERFACE (SL_SI91X_FEAT_SECURITY_OPEN | SL_SI91X_FEAT_WPS_DISABLE), #else (SL_SI91X_FEAT_SECURITY_OPEN | SL_SI91X_FEAT_AGGREGATION), @@ -45,12 +45,12 @@ static const sl_wifi_device_configuration_t config = { | SL_SI91X_TCP_IP_FEAT_DHCPV6_CLIENT | SL_SI91X_TCP_IP_FEAT_IPV6 #endif | SL_SI91X_TCP_IP_FEAT_ICMP | SL_SI91X_TCP_IP_FEAT_EXTENSION_VALID), - .custom_feature_bit_map = (SL_SI91X_FEAT_CUSTOM_FEAT_EXTENTION_VALID | RSI_CUSTOM_FEATURE_BIT_MAP), + .custom_feature_bit_map = (SL_SI91X_CUSTOM_FEAT_EXTENTION_VALID | RSI_CUSTOM_FEATURE_BIT_MAP), .ext_custom_feature_bit_map = ( -#ifdef CHIP_917 +#ifdef SLI_SI917 (RSI_EXT_CUSTOM_FEATURE_BIT_MAP) #else // defaults -#ifdef RSI_M4_INTERFACE +#ifdef SLI_SI91X_MCU_INTERFACE (SL_SI91X_EXT_FEAT_256K_MODE | RSI_EXT_CUSTOM_FEATURE_BIT_MAP) #else (SL_SI91X_EXT_FEAT_384K_MODE | RSI_EXT_CUSTOM_FEATURE_BIT_MAP) diff --git a/examples/platform/silabs/efr32/rs911x/wfx_rsi.h b/examples/platform/silabs/efr32/rs911x/wfx_rsi.h index 2275549ef7af41..4d692064a5768f 100644 --- a/examples/platform/silabs/efr32/rs911x/wfx_rsi.h +++ b/examples/platform/silabs/efr32/rs911x/wfx_rsi.h @@ -51,6 +51,7 @@ #define WFX_RSI_ST_STA_READY (WFX_RSI_ST_STA_CONNECTED | WFX_RSI_ST_STA_DHCP_DONE) #define WFX_RSI_ST_STARTED (0x200) /* RSI task started */ #define WFX_RSI_ST_SCANSTARTED (0x400) /* Scan Started */ +#define WFX_RSI_ST_SLEEP_READY (0x800) /* Notify the M4 to go to sleep*/ struct wfx_rsi { diff --git a/examples/platform/silabs/efr32/rs911x/wfx_rsi_host.c b/examples/platform/silabs/efr32/rs911x/wfx_rsi_host.c index 3482f222b3bc35..331895bd3e524e 100644 --- a/examples/platform/silabs/efr32/rs911x/wfx_rsi_host.c +++ b/examples/platform/silabs/efr32/rs911x/wfx_rsi_host.c @@ -31,7 +31,6 @@ #include "FreeRTOS.h" #include "event_groups.h" #include "task.h" - #include "wfx_host_events.h" #include "wfx_rsi.h" diff --git a/scripts/examples/gn_silabs_example.sh b/scripts/examples/gn_silabs_example.sh index b3f9906e0dae38..fc8fcfd387f8fa 100755 --- a/scripts/examples/gn_silabs_example.sh +++ b/scripts/examples/gn_silabs_example.sh @@ -292,7 +292,7 @@ else if [ "$SILABS_BOARD" == "BRD4338A" ]; then echo "Compiling for 917 WiFi SOC" USE_WIFI=true - optArgs+="chip_device_platform =\"SiWx917\" " + optArgs+="chip_device_platform =\"SiWx917\" is_debug=false " fi if [ "$USE_GIT_SHA_FOR_VERSION" == true ]; then diff --git a/src/platform/silabs/efr32/wifi/ethernetif.cpp b/src/platform/silabs/efr32/wifi/ethernetif.cpp index 2aeaf00fc14b95..3dbd1b85b3ef9a 100644 --- a/src/platform/silabs/efr32/wifi/ethernetif.cpp +++ b/src/platform/silabs/efr32/wifi/ethernetif.cpp @@ -36,7 +36,6 @@ extern "C" { #endif #include "cmsis_os2.h" -#include "sl_board_configuration.h" #include "sl_net.h" #include "sl_si91x_driver.h" #include "sl_si91x_host_interface.h" diff --git a/src/platform/silabs/rs911x/BLEManagerImpl.cpp b/src/platform/silabs/rs911x/BLEManagerImpl.cpp index 749ff8614220ee..bc79b1429ff94a 100644 --- a/src/platform/silabs/rs911x/BLEManagerImpl.cpp +++ b/src/platform/silabs/rs911x/BLEManagerImpl.cpp @@ -107,16 +107,15 @@ void sl_ble_init() NULL, NULL, NULL); // registering the GATT call back functions - rsi_ble_gatt_register_callbacks(NULL, NULL, NULL, NULL, NULL, NULL, NULL, rsi_ble_on_gatt_write_event, NULL, NULL, NULL, - rsi_ble_on_mtu_event, NULL, NULL, NULL, NULL, NULL, NULL, NULL, NULL, NULL, - rsi_ble_on_event_indication_confirmation, NULL); + rsi_ble_gatt_register_callbacks(NULL, NULL, NULL, NULL, NULL, NULL, NULL, rsi_ble_on_gatt_write_event, NULL, NULL, + rsi_ble_on_read_req_event, rsi_ble_on_mtu_event, NULL, NULL, NULL, NULL, NULL, NULL, NULL, NULL, + NULL, rsi_ble_on_event_indication_confirmation, NULL); // Exchange of GATT info with BLE stack rsi_ble_add_matter_service(); // initializing the application events map rsi_ble_app_init_events(); - rsi_ble_set_random_address_with_value(randomAddrBLE); chip::DeviceLayer::Internal::BLEMgrImpl().HandleBootEvent(); } @@ -167,6 +166,17 @@ void sl_ble_event_handling_task(void) rsi_ble_app_clear_event(RSI_BLE_MTU_EVENT); } break; + case RSI_BLE_EVENT_GATT_RD: { +#if CHIP_ENABLE_ADDITIONAL_DATA_ADVERTISING + if (event_msg.rsi_ble_read_req->type == 0) + { + BLEMgrImpl().HandleC3ReadRequest(event_msg.rsi_ble_read_req); + } +#endif // CHIP_ENABLE_ADDITIONAL_DATA_ADVERTISING + // clear the served event + rsi_ble_app_clear_event(RSI_BLE_EVENT_GATT_RD); + } + break; case RSI_BLE_GATT_WRITE_EVENT: { // event invokes when write/notification events received BLEMgrImpl().HandleWriteEvent(event_msg.rsi_ble_write); @@ -1011,8 +1021,16 @@ CHIP_ERROR BLEManagerImpl::EncodeAdditionalDataTlv() return err; } -// TODO:: Need to do the correct implementation -void BLEManagerImpl::HandleC3ReadRequest(void) {} +void BLEManagerImpl::HandleC3ReadRequest(rsi_ble_read_req_t * rsi_ble_read_req) +{ + sl_status_t ret = rsi_ble_gatt_read_response(rsi_ble_read_req->dev_addr, GATT_READ_RESP, rsi_ble_read_req->handle, + GATT_READ_ZERO_OFFSET, sInstance.c3AdditionalDataBufferHandle->DataLength(), + sInstance.c3AdditionalDataBufferHandle->Start()); + if (ret != SL_STATUS_OK) + { + ChipLogDetail(DeviceLayer, "Failed to send read response, err:%ld", ret); + } +} #endif // CHIP_ENABLE_ADDITIONAL_DATA_ADVERTISING diff --git a/src/platform/silabs/rs911x/rsi_ble_config.h b/src/platform/silabs/rs911x/rsi_ble_config.h index e58cadcc77dd4c..bf40cad514dada 100644 --- a/src/platform/silabs/rs911x/rsi_ble_config.h +++ b/src/platform/silabs/rs911x/rsi_ble_config.h @@ -25,6 +25,7 @@ #else #include #endif + /****************************************************** * * Macros * ******************************************************/ @@ -40,7 +41,10 @@ #define RSI_BLE_GATT_WRITE_EVENT (0x03) #define RSI_BLE_MTU_EVENT (0x04) #define RSI_BLE_GATT_INDICATION_CONFIRMATION (0x05) +#define RSI_BLE_RESP_ATT_VALUE (0x06) #define RSI_BLE_EVENT_GATT_RD (0x08) +#define RSI_BLE_ADDR_LENGTH 6 + #define RSI_SSID (0x0D) #define RSI_SECTYPE (0x0E) #define RSI_BLE_WLAN_DISCONN_NOTIFY (0x0F) @@ -71,6 +75,8 @@ #define RSI_BLE_TX_TIME 2120 // microseconds #define RSI_BLE_MATTER_CUSTOM_SERVICE_DATA_LENGTH 240 +#define GATT_READ_ZERO_OFFSET 0x00 +#define GATT_READ_RESP 0x00 #define ALL_PHYS (0x00) #define RSI_BLE_DEV_ADDR_RESOLUTION_ENABLE (0) @@ -133,7 +139,7 @@ #define RSI_BLE_ADV_TYPE UNDIR_CONN #define RSI_BLE_ADV_FILTER_TYPE ALLOW_SCAN_REQ_ANY_CONN_REQ_ANY -#define RSI_BLE_ADV_DIR_ADDR_TYPE LE_PUBLIC_ADDRESS +#define RSI_BLE_ADV_DIR_ADDR_TYPE LE_RANDOM_ADDRESS #define RSI_BLE_ADV_DIR_ADDR "00:15:83:6A:64:17" //! Reduced the BLE adv interval time to match with EFR BLE diff --git a/src/platform/silabs/rs911x/wfx_sl_ble_init.c b/src/platform/silabs/rs911x/wfx_sl_ble_init.c index ef44d380d90740..7e7c165043a71a 100644 --- a/src/platform/silabs/rs911x/wfx_sl_ble_init.c +++ b/src/platform/silabs/rs911x/wfx_sl_ble_init.c @@ -150,6 +150,24 @@ void rsi_ble_on_event_indication_confirmation(uint16_t resp_status, rsi_ble_set_ /*==============================================*/ /** + * @fn rsi_ble_on_read_req_event + * @brief its invoked when read events are received. + * @param[in] event_id, it indicates write/notification event id. + * @param[in] rsi_ble_read, read event parameters. + * @return none. + * @section description + * This callback function is invoked when read events are received + */ +void rsi_ble_on_read_req_event(uint16_t event_id, rsi_ble_read_req_t * rsi_ble_read_req) +{ + SILABS_LOG("%s: starting", __func__); + event_msg.event_id = event_id; + memcpy(&event_msg.rsi_ble_read_req, rsi_ble_read_req, sizeof(rsi_ble_read_req_t)); + rsi_ble_app_set_event(RSI_BLE_EVENT_GATT_RD); +} + +/*==============================================*/ +/**s * @fn rsi_ble_app_get_event * @brief returns the first set event based on priority * @param[in] none. diff --git a/src/platform/silabs/rs911x/wfx_sl_ble_init.h b/src/platform/silabs/rs911x/wfx_sl_ble_init.h index 2c124f4549caa1..26ee258300c5de 100644 --- a/src/platform/silabs/rs911x/wfx_sl_ble_init.h +++ b/src/platform/silabs/rs911x/wfx_sl_ble_init.h @@ -67,6 +67,7 @@ typedef struct sl_wfx_msg_s rsi_ble_event_write_t rsi_ble_write; rsi_ble_event_enhance_conn_status_t resp_enh_conn; rsi_ble_event_disconnect_t * resp_disconnect; + rsi_ble_read_req_t * rsi_ble_read_req; rsi_ble_set_att_resp_t rsi_ble_event_set_att_rsp; uint32_t ble_app_event_map; uint32_t ble_app_event_mask; @@ -116,6 +117,7 @@ void rsi_ble_on_enhance_conn_status_event(rsi_ble_event_enhance_conn_status_t * void rsi_ble_on_gatt_write_event(uint16_t event_id, rsi_ble_event_write_t * rsi_ble_write); void rsi_ble_on_mtu_event(rsi_ble_event_mtu_t * rsi_ble_mtu); void rsi_ble_on_event_indication_confirmation(uint16_t resp_status, rsi_ble_set_att_resp_t * rsi_ble_event_set_att_rsp); +void rsi_ble_on_read_req_event(uint16_t event_id, rsi_ble_read_req_t * rsi_ble_read_req); void rsi_gatt_add_attribute_to_list(rsi_ble_t * p_val, uint16_t handle, uint16_t data_len, uint8_t * data, uuid_t uuid, uint8_t char_prop); void rsi_ble_add_char_serv_att(void * serv_handler, uint16_t handle, uint8_t val_prop, uint16_t att_val_handle, diff --git a/third_party/silabs/efr32_sdk.gni b/third_party/silabs/efr32_sdk.gni index 0741a06f9d3507..3a80deb7f99e33 100644 --- a/third_party/silabs/efr32_sdk.gni +++ b/third_party/silabs/efr32_sdk.gni @@ -130,6 +130,9 @@ template("efr32_sdk") { # Treat these includes as system includes, so warnings in them are not fatal. _include_dirs = [ "${efr32_sdk_root}", + + #TODO: Added this as include files because of spi_multiplexing.h file. we will remove it after the cleanup. + "${examples_plat_dir}", "${efr32_sdk_root}/util/plugin/security_manager/", "${efr32_sdk_root}/hardware/kit/common/bsp", "${efr32_sdk_root}/hardware/board/inc", @@ -204,11 +207,22 @@ template("efr32_sdk") { "${sl_ot_efr32_root}", ] + if (silabs_family == "efr32mg24") { + _include_dirs += + [ "${efr32_sdk_root}/platform/Device/SiliconLabs/EFR32MG24/Include" ] + } + if (use_SiWx917) { _include_dirs += [ - "${wifi_sdk_root}/components/si91x/inc", + # si91x component "${wifi_sdk_root}/components/si91x/memory", - "${wifi_sdk_root}/components/si91x/sl_net/inc", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/sl_net/inc", + "${wifi_sdk_root}/components/device/silabs/si91x/mcu/drivers/rom_driver/inc", + "${wifi_sdk_root}/components/device/silabs/si91x/mcu/core/chip/inc", + "${wifi_sdk_root}/components/common/inc", + "${wifi_sdk_root}/components/device/silabs/si91x/mcu/core/config", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/inc", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/inc", # wifi component "${wifi_sdk_root}/components/protocol/wifi/inc", @@ -223,9 +237,13 @@ template("efr32_sdk") { # network_manager component "${wifi_sdk_root}/components/service/network_manager/inc", + + "${wifi_sdk_root}/components/protocol/wifi/si91x", ] } - + if (use_rs9116 || use_SiWx917) { + _include_dirs += [ "${chip_root}/src/platform/silabs/rs911x" ] + } if (silabs_family != "mgm24") { _include_dirs += [ "${efr32_sdk_root}/platform/radio/rail_lib/hal", @@ -237,9 +255,10 @@ template("efr32_sdk") { if (use_rs9116) { _include_dirs += [ "${wiseconnect_sdk_root}/sapi/include" ] } else { - _include_dirs += [ "${wifi_sdk_root}/components/si91x/ble/inc" ] + _include_dirs += [ + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/inc", + ] } - _include_dirs += [ "${chip_root}/src/platform/silabs/rs911x" ] } # Note that we're setting the mbedTLS and PSA configuration files through a @@ -301,6 +320,8 @@ template("efr32_sdk") { "RSI_BLE_ENABLE=1", "BLE_ENABLE=1", "RSI_LITTLE_ENDIAN=1", + "SLI_SI91X_ENABLE_BLE=1", + "SL_SI91X_ENABLE_LITTLE_ENDIAN=1", ] } @@ -331,6 +352,8 @@ template("efr32_sdk") { defines += [ "EXP_BOARD=1", "CHIP_917", + "SLI_SI917=1", + "SL_WFX_CONFIG_SCAN=1", "CHIP_9117", "SL_WIFI_COMPONENT_INCLUDED", ] @@ -494,7 +517,6 @@ template("efr32_sdk") { defines += [ "EFR32MG12" ] } else if (silabs_family == "efr32mg24") { _include_dirs += [ - "${efr32_sdk_root}/platform/Device/SiliconLabs/EFR32MG24/Include", "${efr32_sdk_root}/platform/radio/rail_lib/chip/efr32/efr32xg2x", "${efr32_sdk_root}/util/third_party/freertos/kernel/portable/GCC/ARM_CM33_NTZ/non_secure", "${efr32_sdk_root}/platform/radio/rail_lib/plugin/pa-conversions/efr32xg24", @@ -776,13 +798,13 @@ template("efr32_sdk") { ] } else { sources += [ - "${wifi_sdk_root}/components/si91x/ble/src/rsi_ble_gap_apis.c", - "${wifi_sdk_root}/components/si91x/ble/src/rsi_ble_gatt_apis.c", - "${wifi_sdk_root}/components/si91x/ble/src/rsi_bt_ble.c", - "${wifi_sdk_root}/components/si91x/ble/src/rsi_bt_common_apis.c", - "${wifi_sdk_root}/components/si91x/ble/src/rsi_common_apis.c", - "${wifi_sdk_root}/components/si91x/ble/src/rsi_utils.c", - "${wifi_sdk_root}/components/si91x/ble/src/sl_si91x_ble.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/src/rsi_ble_gap_apis.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/src/rsi_ble_gatt_apis.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/src/rsi_bt_ble.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/src/rsi_bt_common_apis.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/src/rsi_common_apis.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/src/rsi_utils.c", + "${wifi_sdk_root}/components/device/silabs/si91x/wireless/ble/src/sl_si91x_ble.c", ] } } else { diff --git a/third_party/silabs/matter_support b/third_party/silabs/matter_support index 73fcd8b084355b..70800e2f6d5fbc 160000 --- a/third_party/silabs/matter_support +++ b/third_party/silabs/matter_support @@ -1 +1 @@ -Subproject commit 73fcd8b084355babbab333ebeaaa36323fdb4d8a +Subproject commit 70800e2f6d5fbc972d22387fd4969a92568b455b