diff --git a/examples/light-switch-app/efr32/BUILD.gn b/examples/light-switch-app/efr32/BUILD.gn index f9a87873a5b36d..ee863acd48cfac 100644 --- a/examples/light-switch-app/efr32/BUILD.gn +++ b/examples/light-switch-app/efr32/BUILD.gn @@ -94,7 +94,7 @@ if (silabs_board == "BRD4166A" || silabs_board == "BRD2601B" || # WiFi settings if (chip_enable_wifi) { - wifi_sdk_dir = "${chip_root}/third_party/silabs/matter_support/matter/wifi" + wifi_sdk_dir = "${chip_root}/src/platform/EFR32/wifi" efr32_lwip_defs = [ "LWIP_NETIF_API=1" ] efr32_lwip_defs += [ "LWIP_IPV4=1", @@ -108,9 +108,9 @@ if (chip_enable_wifi) { if (use_rs911x) { wiseconnect_sdk_root = "${chip_root}/third_party/silabs/wiseconnect-wifi-bt-sdk" - import("${wifi_sdk_dir}/rs911x/rs911x.gni") + import("${examples_plat_dir}/rs911x/rs911x.gni") } else { - import("${wifi_sdk_dir}/wf200/wf200.gni") + import("${examples_plat_dir}/wf200/wf200.gni") } } diff --git a/examples/lighting-app/efr32/BUILD.gn b/examples/lighting-app/efr32/BUILD.gn index 4a9ffa08a3a298..531012d061803f 100644 --- a/examples/lighting-app/efr32/BUILD.gn +++ b/examples/lighting-app/efr32/BUILD.gn @@ -99,7 +99,7 @@ if (chip_enable_wifi) { show_qr_code = false disable_lcd = true } - wifi_sdk_dir = "${chip_root}/third_party/silabs/matter_support/matter/wifi" + wifi_sdk_dir = "${chip_root}/src/platform/EFR32/wifi" efr32_lwip_defs = [ "LWIP_NETIF_API=1" ] efr32_lwip_defs += [ "LWIP_IPV4=1", @@ -113,9 +113,9 @@ if (chip_enable_wifi) { if (use_rs911x) { wiseconnect_sdk_root = "${chip_root}/third_party/silabs/wiseconnect-wifi-bt-sdk" - import("${wifi_sdk_dir}/rs911x/rs911x.gni") + import("${examples_plat_dir}/rs911x/rs911x.gni") } else { - import("${wifi_sdk_dir}/wf200/wf200.gni") + import("${examples_plat_dir}/wf200/wf200.gni") } } diff --git a/examples/lock-app/efr32/BUILD.gn b/examples/lock-app/efr32/BUILD.gn index 77df63b61c1868..1d1297e4b9708b 100644 --- a/examples/lock-app/efr32/BUILD.gn +++ b/examples/lock-app/efr32/BUILD.gn @@ -94,7 +94,7 @@ if (silabs_board == "BRD4166A" || silabs_board == "BRD2601B" || # WiFi settings if (chip_enable_wifi) { - wifi_sdk_dir = "${chip_root}/third_party/silabs/matter_support/matter/wifi" + wifi_sdk_dir = "${chip_root}/src/platform/EFR32/wifi" efr32_lwip_defs = [ "LWIP_NETIF_API=1" ] efr32_lwip_defs += [ "LWIP_IPV4=1", @@ -108,9 +108,9 @@ if (chip_enable_wifi) { if (use_rs911x) { wiseconnect_sdk_root = "${chip_root}/third_party/silabs/wiseconnect-wifi-bt-sdk" - import("${wifi_sdk_dir}/rs911x/rs911x.gni") + import("${examples_plat_dir}/rs911x/rs911x.gni") } else { - import("${wifi_sdk_dir}/wf200/wf200.gni") + import("${examples_plat_dir}/wf200/wf200.gni") } } diff --git a/examples/platform/efr32/rs911x/hal/efx_spi.c b/examples/platform/efr32/rs911x/hal/efx_spi.c new file mode 100644 index 00000000000000..87a9fbaa9abfe5 --- /dev/null +++ b/examples/platform/efr32/rs911x/hal/efx_spi.c @@ -0,0 +1,297 @@ +/* + * + * Copyright (c) 2022 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 "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" +#if defined(EFR32MG12) +#include "em_usart.h" +#elif defined(EFR32MG24) +#include "em_eusart.h" +#endif +#include "spidrv.h" + +#include "gpiointerrupt.h" +#include "sl_device_init_clocks.h" +#include "sl_status.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "wfx_host_events.h" +#include "wfx_rsi.h" + +#include "rsi_board_configuration.h" +#include "rsi_driver.h" +#include "sl_device_init_dpll.h" +#include "sl_device_init_hfxo.h" + +StaticSemaphore_t xEfxSpiIntfSemaBuffer; +static SemaphoreHandle_t spi_sem; + +#if defined(EFR32MG12) +#include "sl_spidrv_exp_config.h" +extern SPIDRV_Handle_t sl_spidrv_exp_handle; +#endif + +#if defined(EFR32MG24) +#include "sl_spidrv_eusart_exp_config.h" +extern SPIDRV_Handle_t sl_spidrv_eusart_exp_handle; +#endif + +static unsigned int tx_dma_channel; +static unsigned int rx_dma_channel; + +static uint32_t dummy_data; /* Used for DMA - when results don't matter */ +extern void rsi_gpio_irq_cb(uint8_t irqnum); +//#define RS911X_USE_LDMA + +/******************************************************** + * @fn sl_wfx_host_gpio_init(void) + * @brief + * Deal with the PINS that are not associated with SPI - + * Ie. RESET, Wakeup + * @return + * None + **********************************************************/ +void sl_wfx_host_gpio_init(void) +{ + // Enable GPIO clock. + CMU_ClockEnable(cmuClock_GPIO, true); + + GPIO_PinModeSet(WFX_RESET_PIN.port, WFX_RESET_PIN.pin, gpioModePushPull, PINOUT_SET); + GPIO_PinModeSet(WFX_SLEEP_CONFIRM_PIN.port, WFX_SLEEP_CONFIRM_PIN.pin, gpioModePushPull, PINOUT_CLEAR); + + CMU_OscillatorEnable(cmuOsc_LFXO, true, true); + + // Set up interrupt based callback function - trigger on both edges. + GPIOINT_Init(); + GPIO_PinModeSet(WFX_INTERRUPT_PIN.port, WFX_INTERRUPT_PIN.pin, gpioModeInputPull, PINOUT_CLEAR); + GPIO_ExtIntConfig(WFX_INTERRUPT_PIN.port, WFX_INTERRUPT_PIN.pin, SL_WFX_HOST_PINOUT_SPI_IRQ, true, false, true); + GPIOINT_CallbackRegister(SL_WFX_HOST_PINOUT_SPI_IRQ, rsi_gpio_irq_cb); + GPIO_IntDisable(1 << SL_WFX_HOST_PINOUT_SPI_IRQ); /* Will be enabled by RSI */ + + // Change GPIO interrupt priority (FreeRTOS asserts unless this is done here!) + NVIC_SetPriority(GPIO_EVEN_IRQn, WFX_SPI_NVIC_PRIORITY); + NVIC_SetPriority(GPIO_ODD_IRQn, WFX_SPI_NVIC_PRIORITY); +} + +/***************************************************************** + * @fn void sl_wfx_host_reset_chip(void) + * @brief + * To reset the WiFi CHIP + * @return + * None + ****************************************************************/ +void sl_wfx_host_reset_chip(void) +{ + // Pull it low for at least 1 ms to issue a reset sequence + GPIO_PinOutClear(WFX_RESET_PIN.port, WFX_RESET_PIN.pin); + + // Delay for 10ms + vTaskDelay(pdMS_TO_TICKS(10)); + + // Hold pin high to get chip out of reset + GPIO_PinOutSet(WFX_RESET_PIN.port, WFX_RESET_PIN.pin); + + // Delay for 3ms + vTaskDelay(pdMS_TO_TICKS(3)); +} + +/***************************************************************** + * @fn void rsi_hal_board_init(void) + * @brief + * Initialize the board + * @return + * None + ****************************************************************/ +void rsi_hal_board_init(void) +{ + spi_sem = xSemaphoreCreateBinaryStatic(&xEfxSpiIntfSemaBuffer); + xSemaphoreGive(spi_sem); + + /* Assign DMA channel from Handle*/ +#if defined(EFR32MG12) + /* MG12 + rs9116 combination uses USART driver */ + tx_dma_channel = sl_spidrv_exp_handle->txDMACh; + rx_dma_channel = sl_spidrv_exp_handle->rxDMACh; + +#elif defined(EFR32MG24) + /* MG24 + rs9116 combination uses EUSART driver */ + tx_dma_channel = sl_spidrv_eusart_exp_handle->txDMACh; + rx_dma_channel = sl_spidrv_eusart_exp_handle->rxDMACh; +#endif + + /* GPIO INIT of MG12 & MG24 : Reset, Wakeup, Interrupt */ + WFX_RSI_LOG("RSI_HAL: init GPIO"); + sl_wfx_host_gpio_init(); + + /* Reset of Wifi chip */ + WFX_RSI_LOG("RSI_HAL: Reset Wifi"); + sl_wfx_host_reset_chip(); + WFX_RSI_LOG("RSI_HAL: Init done"); +} + +/***************************************************************************** + *@fn static bool rx_dma_complete(unsigned int channel, unsigned int sequenceNo, void *userParam) + * + *@brief + * complete dma + * + * @param[in] channel: + * @param[in] sequenceNO: sequence number + * @param[in] userParam :user parameter + * + * @return + * None + ******************************************************************************/ +static bool rx_dma_complete(unsigned int channel, unsigned int sequenceNo, void * userParam) +{ + BaseType_t xHigherPriorityTaskWoken = pdFALSE; + // uint8_t *buf = (void *)userParam; + + (void) channel; + (void) sequenceNo; + (void) userParam; + + // WFX_RSI_LOG ("SPI: DMA done [%x,%x,%x,%x]", buf [0], buf [1], buf [2], buf [3]); + xSemaphoreGiveFromISR(spi_sem, &xHigherPriorityTaskWoken); + portYIELD_FROM_ISR(xHigherPriorityTaskWoken); + + return true; +} + +/************************************************************* + * @fn static void receiveDMA(uint8_t *rx_buf, uint16_t xlen) + * @brief + * RX buf was specified + * TX buf was not specified by caller - so we + * transmit dummy data (typically 0) + * @param[in] rx_buf: + * @param[in] xlen: + * @return + * None + *******************************************************************/ +static void receiveDMA(uint8_t * rx_buf, uint16_t xlen) +{ + /* + * The caller wants to receive data - + * The xmit can be dummy data (no src increment for tx) + */ + dummy_data = 0; + DMADRV_PeripheralMemory(rx_dma_channel, MY_USART_RX_SIGNAL, (void *) rx_buf, (void *) &(MY_USART->RXDATA), true, xlen, + dmadrvDataSize1, rx_dma_complete, NULL); + + // Start transmit DMA. + DMADRV_MemoryPeripheral(tx_dma_channel, MY_USART_TX_SIGNAL, (void *) &(MY_USART->TXDATA), (void *) &(dummy_data), false, xlen, + dmadrvDataSize1, NULL, NULL); +} + +/***************************************************************************** + *@fn static void transmitDMA(void *rx_buf, void *tx_buf, uint8_t xlen) + *@brief + * we have a tx_buf. There are some instances where + * a rx_buf is not specifed. If one is specified then + * the caller wants results (auto increment src) + * @param[in] rx_buf: + * @param[in] tx_buf: + * @param[in] xlen: + * @return + * None + ******************************************************************************/ +static void transmitDMA(uint8_t * rx_buf, uint8_t * tx_buf, uint16_t xlen) +{ + void * buf; + bool srcinc; + /* + * we have a tx_buf. There are some instances where + * a rx_buf is not specifed. If one is specified then + * the caller wants results (auto increment src) + * TODO - the caller specified 8/32 bit - we should use this + * instead of dmadrvDataSize1 always + */ + if (rx_buf == NULL) + { + buf = &dummy_data; + srcinc = false; + } + else + { + buf = rx_buf; + srcinc = true; + /* DEBUG */ rx_buf[0] = 0xAA; + rx_buf[1] = 0x55; + } + DMADRV_PeripheralMemory(rx_dma_channel, MY_USART_RX_SIGNAL, buf, (void *) &(MY_USART->RXDATA), srcinc, xlen, dmadrvDataSize1, + rx_dma_complete, buf); + // Start transmit DMA. + DMADRV_MemoryPeripheral(tx_dma_channel, MY_USART_TX_SIGNAL, (void *) &(MY_USART->TXDATA), (void *) tx_buf, true, xlen, + dmadrvDataSize1, NULL, NULL); +} + +/********************************************************************* + * @fn int16_t rsi_spi_transfer(uint8_t *tx_buf, uint8_t *rx_buf, uint16_t xlen, uint8_t mode) + * @brief + * Do a SPI transfer - Mode is 8/16 bit - But every 8 bit is aligned + * @param[in] tx_buf: + * @param[in] rx_buf: + * @param[in] xlen: + * @param[in] mode: + * @return + * None + **************************************************************************/ +int16_t rsi_spi_transfer(uint8_t * tx_buf, uint8_t * rx_buf, uint16_t xlen, uint8_t mode) +{ + // WFX_RSI_LOG ("SPI: Xfer: tx=%x,rx=%x,len=%d",(uint32_t)tx_buf, (uint32_t)rx_buf, xlen); + if (xlen > MIN_XLEN) + { + MY_USART->CMD = USART_CMD_CLEARRX | USART_CMD_CLEARTX; + if (xSemaphoreTake(spi_sem, portMAX_DELAY) != pdTRUE) + { + return RSI_FALSE; + } + if (tx_buf == NULL) + { + receiveDMA(rx_buf, xlen); + } + else + { + transmitDMA(rx_buf, tx_buf, xlen); + } + /* + * Wait for the call-back to complete + */ + if (xSemaphoreTake(spi_sem, portMAX_DELAY) == pdTRUE) + { + xSemaphoreGive(spi_sem); + } + } + + return RSI_ERROR_NONE; +} diff --git a/examples/platform/efr32/rs911x/hal/rsi_board_configuration.h b/examples/platform/efr32/rs911x/hal/rsi_board_configuration.h new file mode 100644 index 00000000000000..a67be021de39b7 --- /dev/null +++ b/examples/platform/efr32/rs911x/hal/rsi_board_configuration.h @@ -0,0 +1,42 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef _RSI_BOARD_CONFIGURATION_H_ +#define _RSI_BOARD_CONFIGURATION_H_ + +typedef struct +{ + unsigned char port; + unsigned char pin; +} rsi_pin_t; + +#define PIN(port_id, pin_id) \ + (rsi_pin_t) { .port = gpioPort##port_id, .pin = pin_id } + +#if defined(EFR32MG12_BRD4161A) || defined(BRD4161A) || defined(EFR32MG12_BRD4162A) || defined(BRD4162A) || \ + defined(EFR32MG12_BRD4163A) || defined(BRD4163A) || defined(EFR32MG12_BRD4164A) || defined(BRD4164A) +// BRD4161-63-64 are pin to pin compatible for SPI +#include "brd4161a.h" +#elif defined(EFR32MG24_BRD4186C) || defined(BRD4186C) +#include "brd4186c.h" +#elif defined(EFR32MG24_BRD4187C) || defined(BRD4187C) +#include "brd4187c.h" +#else +#error "Need SPI Pins" +#endif /* EFR32MG12_BRD4161A */ + +#endif /* _RSI_BOARD_CONFIGURATION_H_ */ diff --git a/examples/platform/efr32/rs911x/hal/rsi_hal.h b/examples/platform/efr32/rs911x/hal/rsi_hal.h new file mode 100644 index 00000000000000..8e4e6e25952583 --- /dev/null +++ b/examples/platform/efr32/rs911x/hal/rsi_hal.h @@ -0,0 +1,105 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef _HAL_RSI_HAL_H_ +#define _HAL_RSI_HAL_H_ +#include "rsi_board_configuration.h" + +#define RSI_HAL_NO_COM_PORT /* This will be done by the project */ + +/* Should be enums */ +#define RSI_HAL_RESET_PIN 0 +#define RSI_HAL_MODULE_INTERRUPT 1 +#define RSI_HAL_SLEEP_CONFIRM_PIN 2 +#define RSI_HAL_WAKEUP_INDICATION_PIN 3 +#define RSI_HAL_MODULE_INTERRUPT_PIN 4 + +//! Timer related macros +//! Macro to configure timer type in single shot +#define RSI_HAL_TIMER_TYPE_SINGLE_SHOT 0 + +// Macro to configure timer type in periodic +#define RSI_HAL_TIMER_TYPE_PERIODIC 1 + +// Macro to configure timer in micro seconds mode +#define RSI_HAL_TIMER_MODE_MICRO 0 + +// Macro to configure timer in milli seconds mode +#define RSI_HAL_TIMER_MODE_MILLI 1 + +//! GPIO Pins related Macros +//! Macro to configure GPIO in output mode +#define RSI_HAL_GPIO_OUTPUT_MODE 1 + +// Macro to configure GPIO in input mode +#define RSI_HAL_GPIO_INPUT_MODE 0 + +// Macro to drive low value on GPIO +#define RSI_HAL_GPIO_LOW 0 + +// Macro to drive high value on GPIO +#define RSI_HAL_GPIO_HIGH 1 + +/****************************************************** + * * Function Declarations + * ******************************************************/ + +void rsi_hal_board_init(void); +void rsi_switch_to_high_clk_freq(void); +void rsi_hal_intr_config(void (*rsi_interrupt_handler)(void)); +void rsi_hal_intr_mask(void); +void rsi_hal_intr_unmask(void); +void rsi_hal_intr_clear(void); +uint8_t rsi_hal_intr_pin_status(void); +void rsi_hal_config_gpio(uint8_t gpio_number, uint8_t mode, uint8_t value); +void rsi_hal_set_gpio(uint8_t gpio_number); +uint8_t rsi_hal_get_gpio(uint8_t gpio_number); +void rsi_hal_clear_gpio(uint8_t gpio_number); +int16_t rsi_spi_transfer(uint8_t * tx_buff, uint8_t * rx_buff, uint16_t transfer_length, uint8_t mode); +int16_t rsi_uart_send(uint8_t * ptrBuf, uint16_t bufLen); +int16_t rsi_uart_recv(uint8_t * ptrBuf, uint16_t bufLen); +int16_t rsi_com_port_send(uint8_t * ptrBuf, uint16_t bufLen); +int16_t rsi_com_port_receive(uint8_t * ptrBuf, uint16_t bufLen); +uint32_t rsi_get_random_number(void); +int32_t rsi_timer_start(uint8_t timer_node, uint8_t mode, uint8_t type, uint32_t duration, void (*rsi_timer_expiry_handler)(void)); +int32_t rsi_timer_stop(uint8_t timer_node); +uint32_t rsi_timer_read(uint8_t timer_node); +void rsi_delay_us(uint32_t delay_us); +void rsi_delay_ms(uint32_t delay_ms); +uint32_t rsi_hal_gettickcount(void); +void SysTick_Handler(void); + +void rsi_interrupt_handler(void); +void ABRD(void); + +void Error_Handler(void); + +/* RTC Related API's */ +uint32_t rsi_rtc_get_time(void); +int32_t rsi_rtc_set_time(uint32_t time); +/* End - RTC Related API's */ + +#ifdef LOGGING_STATS +void rsi_hal_log_stats_intr_config(void (*rsi_give_wakeup_indication)()); +#endif /* LOGGING_STATS */ +#ifdef RSI_WITH_OS +void rsi_os_delay_ms(uint32_t delay_ms); +void PORTD_IRQHandler(void); + +#endif /* RSI_WITH_OS */ + +#endif diff --git a/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_interrupt.c b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_interrupt.c new file mode 100644 index 00000000000000..40e4189635d71c --- /dev/null +++ b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_interrupt.c @@ -0,0 +1,161 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include +#include +#include + +#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 "em_usart.h" +#include "gpiointerrupt.h" +#include "sl_device_init_clocks.h" +#include "sl_status.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "wfx_host_events.h" +#include "wfx_rsi.h" + +#include "rsi_board_configuration.h" +#include "rsi_driver.h" + +typedef void (*UserIntCallBack_t)(void); +UserIntCallBack_t call_back, gpio_callback; +#ifdef LOGGING_STATS +uint8_t current_pin_set, prev_pin_set; +#endif /* LOGGING_STATS */ + +/* ARGSUSED */ +void rsi_gpio_irq_cb(uint8_t irqnum) +{ + + // WFX_RSI_LOG ("RSI: Got Int=%d", irqnum) + if (irqnum != SL_WFX_HOST_PINOUT_SPI_IRQ) + return; + GPIO_IntClear(1 << SL_WFX_HOST_PINOUT_SPI_IRQ); + + // WFX_RSI_LOG ("Got SPI intr, cb=%x", (uint32_t)call_back); + if (call_back != NULL) + (*call_back)(); +} + +/*===================================================*/ +/** + * @fn void rsi_hal_intr_config(void (* rsi_interrupt_handler)()) + * @brief Starts and enables the SPI interrupt + * @param[in] rsi_interrupt_handler() ,call back function to handle interrupt + * @param[out] none + * @return none + * @description This HAL API should contain the code to initialize the register/pins + * related to interrupts and enable the interrupts. + */ +void rsi_hal_intr_config(void (*rsi_interrupt_handler)(void)) +{ + call_back = rsi_interrupt_handler; + WFX_RSI_LOG("RSI:Set SPI intr CB to=%x", (uint32_t) call_back); +} + +/*===================================================*/ +/** + * @fn void rsi_hal_log_stats_intr_config(void (* rsi_give_wakeup_indication)()) + * @brief Checks the interrupt and map/set gpio callback function + * @param[in] rsi_give_wakeup_indication() ,gpio call back function to handle interrupt + * @param[out] none + * @return none + * @description This HAL API should contain the code + * related to mapping of gpio callback function. + */ +#ifdef LOGGING_STATS +void rsi_hal_log_stats_intr_config(void (*rsi_give_wakeup_indication)()) +{ + gpio_callback = rsi_give_wakeup_indication; +} +#endif + +/*===================================================*/ +/** + * @fn void rsi_hal_intr_mask(void) + * @brief Disables the SPI Interrupt + * @param[in] none + * @param[out] none + * @return none + * @description This HAL API should contain the code to mask/disable interrupts. + */ +void rsi_hal_intr_mask(void) +{ + // WFX_RSI_LOG ("RSI:Disable IRQ"); + // NVIC_DisableIRQ(GPIO_ODD_IRQn); + GPIO_IntDisable(1 << SL_WFX_HOST_PINOUT_SPI_IRQ); +} + +/*===================================================*/ +/** + * @fn void rsi_hal_intr_unmask(void) + * @brief Enables the SPI interrupt + * @param[in] none + * @param[out] none + * @return none + * @description This HAL API should contain the code to enable interrupts. + */ +void rsi_hal_intr_unmask(void) +{ + // Unmask/Enable the interrupt + NVIC_EnableIRQ(GPIO_ODD_IRQn); + NVIC_EnableIRQ(GPIO_EVEN_IRQn); + GPIO_IntEnable(1 << SL_WFX_HOST_PINOUT_SPI_IRQ); + // WFX_RSI_LOG ("RSI:Enable IRQ (mask=%x)", GPIO_IntGetEnabled ()); +} + +/*===================================================*/ +/** + * @fn void rsi_hal_intr_clear(void) + * @brief Clears the pending interrupt + * @param[in] none + * @param[out] none + * @return none + * @description This HAL API should contain the code to clear the handled interrupts. + */ +void rsi_hal_intr_clear(void) +{ + GPIO_IntClear(1 << SL_WFX_HOST_PINOUT_SPI_IRQ); +} + +/*===================================================*/ +/** + * @fn void rsi_hal_intr_pin_status(void) + * @brief Checks the SPI interrupt at pin level + * @param[in] none + * @param[out] uint8_t, interrupt status + * @return none + * @description This API is used to check interrupt pin status(pin level whether it is high/low). + */ +uint8_t rsi_hal_intr_pin_status(void) +{ + uint32_t mask; + // Return interrupt pin status(high(1) /low (0)) + mask = GPIO_PinInGet(WFX_INTERRUPT_PIN.port, WFX_INTERRUPT_PIN.pin); + + return !!mask; +} diff --git a/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_ioports.c b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_ioports.c new file mode 100644 index 00000000000000..1ff5bc5fedf4f2 --- /dev/null +++ b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_ioports.c @@ -0,0 +1,141 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include +#include +#include + +#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 "em_usart.h" +#include "gpiointerrupt.h" +#include "sl_device_init_clocks.h" +#include "sl_status.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "wfx_host_events.h" +#include "wfx_rsi.h" + +#include "rsi_board_configuration.h" +#include "rsi_driver.h" + +/*===========================================================*/ +/** + * @fn void rsi_hal_config_gpio(uint8_t gpio_number,uint8_t mode,uint8_t value) + * @brief Configures gpio pin in output mode,with a value + * @param[in] uint8_t gpio_number, gpio pin number to be configured + * @param[in] uint8_t mode , input/output mode of the gpio pin to configure + * 0 - input mode + * 1 - output mode + * @param[in] uint8_t value, default value to be driven if gpio is configured in output mode + * 0 - low + * 1 - high + * @param[out] none + * @return none + * @description This API is used to configure host gpio pin in output mode. + */ +void rsi_hal_config_gpio(uint8_t gpio_number, uint8_t mode, uint8_t value) +{ + + CMU_ClockEnable(cmuClock_GPIO, true); + + // WFX_RSI_LOG ("RSI: CFG GPIO: 0x%x", gpio_number); + switch (gpio_number) + { + case RSI_HAL_RESET_PIN: + GPIO_PinModeSet(WFX_RESET_PIN.port, WFX_RESET_PIN.pin, gpioModePushPull, PINOUT_SET); + break; + default: + break; + } +} + +/*===========================================================*/ +/** + * @fn void rsi_hal_set_gpio(uint8_t gpio_number) + * @brief Makes/drives the gpio value high + * @param[in] uint8_t gpio_number, gpio pin number + * @param[out] none + * @return none + * @description This API is used to drives or makes the host gpio value high. + */ +void rsi_hal_set_gpio(uint8_t gpio_number) +{ + // WFX_RSI_LOG ("RSI: SET GPIO: 0x%x", gpio_number); + switch (gpio_number) + { + case RSI_HAL_RESET_PIN: + GPIO_PinModeSet(WFX_RESET_PIN.port, WFX_RESET_PIN.pin, gpioModeWiredOrPullDown, PINOUT_SET); + break; + default: + break; + } +} + +/*===========================================================*/ +/** + * @fn uint8_t rsi_hal_get_gpio(void) + * @brief get the gpio pin value + * @param[in] uint8_t gpio_number, gpio pin number + * @param[out] none + * @return gpio pin value + * @description This API is used to configure get the gpio pin value. + */ +uint8_t rsi_hal_get_gpio(uint8_t gpio_number) +{ + // WFX_RSI_LOG ("RSI: GET GPIO: 0x%x", gpio_number); + switch (gpio_number) + { + case RSI_HAL_RESET_PIN: + return GPIO_PinInGet(WFX_RESET_PIN.port, WFX_RESET_PIN.pin); + case RSI_HAL_MODULE_INTERRUPT_PIN: + return GPIO_PinInGet(WFX_INTERRUPT_PIN.port, WFX_INTERRUPT_PIN.pin); + default: + break; + } + + return 0; +} + +/*===========================================================*/ +/** + * @fn void rsi_hal_set_gpio(uint8_t gpio_number) + * @brief Makes/drives the gpio value to low + * @param[in] uint8_t gpio_number, gpio pin number + * @param[out] none + * @return none + * @description This API is used to drives or makes the host gpio value low. + */ +void rsi_hal_clear_gpio(uint8_t gpio_number) +{ + // WFX_RSI_LOG ("RSI: CLR GPIO: 0x%x", gpio_number); + switch (gpio_number) + { + case RSI_HAL_RESET_PIN: + return GPIO_PinOutClear(WFX_RESET_PIN.port, WFX_RESET_PIN.pin); + default: + break; + } +} diff --git a/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_rtc.c b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_rtc.c new file mode 100644 index 00000000000000..418b2d900dd8d5 --- /dev/null +++ b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_rtc.c @@ -0,0 +1,326 @@ +/* + * + * Copyright (c) 2022 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 "em_cmu.h" +#include "em_core.h" +#include "em_rtcc.h" +#include "sl_sleeptimer_config.h" +#include "sl_status.h" +#include +#include + +#define ZONE0 0 +#define CH_SELECTOR 1u +#define RTC_DEFAULT_COUNTER_VALUE 0u +#define RSI_RTC_FREQ_VALUE 0 +#define TIME_ZONE_OFFSET 0u + +#define SLEEPTIMER_EVENT_OF (0x01) +#define SLEEPTIMER_EVENT_COMP (0x02) +#define SLEEPTIMER_ENUM(name) \ + typedef uint8_t name; \ + enum name##_enum +#define TIME_UNIX_EPOCH (1970u) +#define TIME_NTP_EPOCH (1900u) +#define TIME_ZIGBEE_EPOCH (2000u) +#define TIME_NTP_UNIX_EPOCH_DIFF (TIME_UNIX_EPOCH - TIME_NTP_EPOCH) +#define TIME_ZIGBEE_UNIX_EPOCH_DIFF (TIME_ZIGBEE_EPOCH - TIME_UNIX_EPOCH) +#define TIME_DAY_COUNT_NTP_TO_UNIX_EPOCH (TIME_NTP_UNIX_EPOCH_DIFF * 365u + 17u) ///< 70 years and 17 leap days +#define TIME_DAY_COUNT_ZIGBEE_TO_UNIX_EPOCH (TIME_ZIGBEE_UNIX_EPOCH_DIFF * 365u + 7u) ///< 30 years and 7 leap days +#define TIME_SEC_PER_DAY (60u * 60u * 24u) +#define TIME_NTP_EPOCH_OFFSET_SEC (TIME_DAY_COUNT_NTP_TO_UNIX_EPOCH * TIME_SEC_PER_DAY) +#define TIME_ZIGBEE_EPOCH_OFFSET_SEC (TIME_DAY_COUNT_ZIGBEE_TO_UNIX_EPOCH * TIME_SEC_PER_DAY) +#define TIME_DAY_PER_YEAR (365u) +#define TIME_SEC_PER_YEAR (TIME_SEC_PER_DAY * TIME_DAY_PER_YEAR) +#define TIME_UNIX_TIMESTAMP_MAX (0x7FFFFFFF) + +/// Time zone offset from UTC(second). +typedef int32_t sl_sleeptimer_time_zone_offset_t; +/// Timestamp, wall clock time in seconds. +typedef uint32_t sl_sleeptimer_timestamp_t; +/// @brief Time Format. +SLEEPTIMER_ENUM(sl_sleeptimer_time_format_t){ + TIME_FORMAT_UNIX = 0, ///< Number of seconds since January 1, 1970, 00:00. + ///< Type is signed, so represented on 31 bit. + TIME_FORMAT_NTP = 1, ///< Number of seconds since January 1, 1900, 00:00. + ///< Type is unsigned, so represented on 32 bit. + TIME_FORMAT_ZIGBEE_CLUSTER = 2, ///< Number of seconds since January 1, 2000, 00:00. Type is + ///< unsigned, so represented on 32 bit. +}; + +// Initialization flag. +static bool is_sleeptimer_initialized = false; +// Timer frequency in Hz. +static uint32_t timer_frequency; +#if SL_SLEEPTIMER_WALLCLOCK_CONFIG +// Current time count. +static sl_sleeptimer_timestamp_t second_count; +// Tick rest when the frequency is not a divider of the timer width. +static uint32_t overflow_tick_rest = 0; +#endif + +/******************************************************************************* + * Checks if the time stamp, format and time zone are + * within the supported range. + * + * @param time Time stamp to check. + * @param format Format of the time. + * @param time_zone Time zone offset in second. + * + * @return true if the time is valid. False otherwise. + ******************************************************************************/ +static bool is_valid_time(sl_sleeptimer_timestamp_t time, sl_sleeptimer_time_format_t format, + sl_sleeptimer_time_zone_offset_t time_zone) +{ + bool valid_time = false; + + // Check for overflow. + if ((time_zone < ZONE0 && time > (uint32_t) abs(time_zone)) || (time_zone >= ZONE0 && (time <= UINT32_MAX - time_zone))) + { + valid_time = true; + } + if (format == TIME_FORMAT_UNIX) + { + if (time > TIME_UNIX_TIMESTAMP_MAX) + { // Check if Unix time stamp is an + // unsigned 31 bits. + valid_time = false; + } + } + else + { + if ((format == TIME_FORMAT_NTP) && (time >= TIME_NTP_EPOCH_OFFSET_SEC)) + { + valid_time &= true; + } + else if ((format == TIME_FORMAT_ZIGBEE_CLUSTER) && (time <= TIME_UNIX_TIMESTAMP_MAX - TIME_ZIGBEE_EPOCH_OFFSET_SEC)) + { + valid_time &= true; + } + else + { + valid_time = false; + } + } + return valid_time; +} + +/******************************************************************************* + * Gets RTCC timer frequency. + ******************************************************************************/ +uint32_t rsi_rtc_get_hal_timer_frequency(void) +{ + /* CMU_PrescToLog2 converts prescaler dividend to a logarithmic value. It only works for even + * numbers equal to 2^n. + * An unscaled dividend (dividend = argument + 1). + * So we need to send argument substracted by 1 + */ + return (CMU_ClockFreqGet(cmuClock_RTCC) >> (CMU_PrescToLog2(SL_SLEEPTIMER_FREQ_DIVIDER - 1))); +} + +/****************************************************************************** + * Initializes RTCC sleep timer. + *****************************************************************************/ +void rsi_rtc_init_timer(void) +{ + RTCC_Init_TypeDef rtcc_init = RTCC_INIT_DEFAULT; + RTCC_CCChConf_TypeDef channel = RTCC_CH_INIT_COMPARE_DEFAULT; + + CMU_ClockEnable(cmuClock_RTCC, true); + + rtcc_init.enable = false; + + /* CMU_PrescToLog2 converts prescaler dividend to a logarithmic value. It only works for even + * numbers equal to 2^n. + * An unscaled dividend (dividend = argument + 1). + * So we need to send argument substracted by 1 + */ + rtcc_init.presc = (RTCC_CntPresc_TypeDef)(CMU_PrescToLog2(SL_SLEEPTIMER_FREQ_DIVIDER - 1)); + + RTCC_Init(&rtcc_init); + + // Compare channel starts disabled and is enabled only when compare match + // interrupt is enabled. + channel.chMode = rtccCapComChModeOff; + RTCC_ChannelInit(CH_SELECTOR, &channel); + + RTCC_IntDisable(_RTCC_IEN_MASK); + RTCC_IntClear(_RTCC_IF_MASK); + RTCC_CounterSet(RTC_DEFAULT_COUNTER_VALUE); + + RTCC_Enable(true); + + NVIC_ClearPendingIRQ(RTCC_IRQn); + NVIC_EnableIRQ(RTCC_IRQn); +} + +/****************************************************************************** + * Enables RTCC interrupts. + *****************************************************************************/ +void rsi_rtc_enable_int(uint8_t local_flag) +{ + uint32_t rtcc_ien = 0u; + + if (local_flag & SLEEPTIMER_EVENT_OF) + { + rtcc_ien |= RTCC_IEN_OF; + } + + if (local_flag & SLEEPTIMER_EVENT_COMP) + { + rtcc_ien |= RTCC_IEN_CC1; + } + + RTCC_IntEnable(rtcc_ien); +} + +/******************************************************************************* + * Get timer frequency. + ******************************************************************************/ +uint32_t rsi_rtc_get_timer_frequency(void) +{ + return timer_frequency; +} + +/****************************************************************************** + * Gets RTCC counter value. + *****************************************************************************/ +uint32_t rsi_rtc_get_counter(void) +{ + return RTCC_CounterGet(); +} + +sl_status_t rsi_rtc_init(void) +{ + CORE_DECLARE_IRQ_STATE; + CORE_ENTER_ATOMIC(); + + if (!is_sleeptimer_initialized) + { + rsi_rtc_init_timer(); + rsi_rtc_enable_int(SLEEPTIMER_EVENT_OF); + timer_frequency = rsi_rtc_get_hal_timer_frequency(); + if (timer_frequency == RSI_RTC_FREQ_VALUE) + { + CORE_EXIT_ATOMIC(); + return SL_STATUS_INVALID_PARAMETER; + } + +#if SL_SLEEPTIMER_WALLCLOCK_CONFIG + second_count = 0; +#endif + + is_sleeptimer_initialized = true; + } + CORE_EXIT_ATOMIC(); + + return SL_STATUS_OK; +} + +#if SL_SLEEPTIMER_WALLCLOCK_CONFIG +/******************************************************************************* + * Retrieves current time. + ******************************************************************************/ +uint32_t rsi_rtc_get_time(void) +{ + uint32_t cnt = 0u; + uint32_t freq = 0u; + sl_sleeptimer_timestamp_t time; + CORE_DECLARE_IRQ_STATE; + + cnt = rsi_rtc_get_counter(); + freq = rsi_rtc_get_timer_frequency(); + + CORE_ENTER_ATOMIC(); + time = second_count + cnt / freq; + if (cnt % freq + overflow_tick_rest >= freq) + { + time++; + } + CORE_EXIT_ATOMIC(); + + return time; +} + +/******************************************************************************* + * Sets current time. + ******************************************************************************/ +sl_status_t rsi_rtc_settime(sl_sleeptimer_timestamp_t time) +{ + uint32_t freq = 0u; + uint32_t counter_sec = 0u; + uint32_t cnt = 0; + CORE_DECLARE_IRQ_STATE; + + if (!is_valid_time(time, TIME_FORMAT_UNIX, TIME_ZONE_OFFSET)) + { + return SL_STATUS_INVALID_CONFIGURATION; + } + + freq = rsi_rtc_get_timer_frequency(); + cnt = rsi_rtc_get_counter(); + + CORE_ENTER_ATOMIC(); + second_count = time; + overflow_tick_rest = 0; + counter_sec = cnt / freq; + + if (second_count >= counter_sec) + { + second_count -= counter_sec; + } + else + { + CORE_EXIT_ATOMIC(); + return SL_STATUS_INVALID_CONFIGURATION; + } + + CORE_EXIT_ATOMIC(); + + return SL_STATUS_OK; +} + +/******************************************************************************* + * @fn int32_t rsi_rtc_set_time(uint32_t time) + * @brief + * Init Sleeptimer and Set current time. + * @param[in] time: + * @return + * None + ******************************************************************************/ +int32_t rsi_rtc_set_time(uint32_t time) +{ + sl_status_t ret_val = SL_STATUS_OK; + ret_val = rsi_rtc_init(); + if (ret_val != SL_STATUS_OK) + { + return -1; + } + else + { + ret_val = rsi_rtc_settime(time); + if (ret_val != SL_STATUS_OK) + { + return -1; + } + } + return 0; +} +#endif // SL_SLEEPTIMER_WALLCLOCK_CONFIG diff --git a/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_timer.c b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_timer.c new file mode 100644 index 00000000000000..c6d6381932d3ea --- /dev/null +++ b/examples/platform/efr32/rs911x/hal/rsi_hal_mcu_timer.c @@ -0,0 +1,322 @@ +/* + * + * Copyright (c) 2022 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 "em_cmu.h" +#ifdef RSI_WITH_OS +/* FreeRTOS includes. */ +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" +#include "timers.h" +#if defined(SysTick) +#undef SysTick_Handler +/* FreeRTOS SysTick interrupt handler prototype */ +extern void SysTick_Handler(void); +/* FreeRTOS tick timer interrupt handler prototype */ +extern void xPortSysTickHandler(void); +#endif /* SysTick */ +#endif /* RSI_WITH_OS */ +#include "wfx_host_events.h" + +/* RSI Driver include file */ +#include "rsi_driver.h" +/* RSI WLAN Config include file */ +#include "rsi_bootup_config.h" +#include "rsi_common_apis.h" +#include "rsi_data_types.h" +#include "rsi_error.h" +#include "rsi_nwk.h" +#include "rsi_socket.h" +#include "rsi_utils.h" +#include "rsi_wlan.h" +#include "rsi_wlan_apis.h" +#include "rsi_wlan_config.h" +#include "wfx_rsi.h" + +#ifndef _use_the_rsi_defined_functions + +StaticTimer_t sRsiTimerBuffer; + +/* + * We (Matter port) need a few functions out of this file + * They are at the top + */ +uint32_t rsi_hal_gettickcount(void) +{ + return xTaskGetTickCount(); +} +void rsi_delay_ms(uint32_t delay_ms) +{ +#ifndef RSI_WITH_OS + uint32_t start; +#endif + if (delay_ms == 0) // Check if delay is 0msec + return; + +#ifdef RSI_WITH_OS + vTaskDelay(pdMS_TO_TICKS(delay_ms)); +#else + start = rsi_hal_gettickcount(); + do + { + } while (rsi_hal_gettickcount() - start < delay_ms); +#endif +} +static struct rsi_timer +{ + void (*func)(void); + TimerHandle_t handle; + uint8_t id; + uint8_t name[3]; +} rsi_timer[WFX_RSI_NUM_TIMERS]; +static void timer_cb(TimerHandle_t thandle) +{ + int x; + for (x = 0; x < WFX_RSI_NUM_TIMERS; x++) + { + if (rsi_timer[x].handle == thandle) + { + (*rsi_timer[x].func)(); + break; + } + } +} + +/* + * Run a one-shot/periodic timer + */ +int32_t rsi_timer_start(uint8_t timer_node, uint8_t mode, uint8_t type, uint32_t duration, void (*rsi_timer_cb)(void)) +{ + int x; + struct rsi_timer * tp; + + if (mode == RSI_HAL_TIMER_MODE_MILLI) + return RSI_ERROR_INVALID_OPTION; /* Not supported for now - Fix this later */ + for (x = 0; x < WFX_RSI_NUM_TIMERS; x++) + { + tp = &rsi_timer[x]; + if (tp->handle == NULL) + { + goto found; + } + } + /* No space */ + return RSI_ERROR_INSUFFICIENT_BUFFER; +found: + tp->name[0] = 'r'; + tp->name[1] = timer_node; + tp->name[2] = 0; + tp->func = rsi_timer_cb; + tp->handle = + xTimerCreateStatic((char *) &tp->name[0], pdMS_TO_TICKS(duration), + ((mode == RSI_HAL_TIMER_TYPE_SINGLE_SHOT) ? pdFALSE : pdTRUE), NULL, timer_cb, &sRsiTimerBuffer); + + if (tp->handle == NULL) + { + return RSI_ERROR_INSUFFICIENT_BUFFER; + } + + (void) xTimerStart(tp->handle, TIMER_TICKS_TO_WAIT_0); + + return RSI_ERROR_NONE; +} +#else /* _use_the_rsi_defined_functions */ + +/* Counts 1ms timeTicks */ +volatile uint32_t msTicks = 0; + +/*===================================================*/ +/** + * @fn int32_t rsi_timer_start(uint8_t timer_no, uint8_t mode,uint8_t type,uint32_t duration,void (* + * rsi_timer_expiry_handler)()) + * @brief Starts and configures timer + * @param[in] timer_node, timer node to be configured. + * @param[in] mode , mode of the timer + * 0 - Micro seconds mode + * 1 - Milli seconds mode + * @param[in] type, type of the timer + * 0 - single shot type + * 1 - periodic type + * @param[in] duration, timer duration + * @param[in] rsi_timer_expiry_handler() ,call back function to handle timer interrupt + * @param[out] none + * @return 0 - success + * !0 - Failure + * @description This HAL API should contain the code to initialize the timer and start the timer + * + */ + +int32_t rsi_timer_start(uint8_t timer_node, uint8_t mode, uint8_t type, uint32_t duration, void (*rsi_timer_expiry_handler)(void)) +{ + + // Initialise the timer + + // register the call back + + // Start timer + + return 0; +} + +/*===================================================*/ +/** + * @fn int32_t rsi_timer_stop(uint8_t timer_no) + * @brief Stops timer + * @param[in] timer_node, timer node to stop + * @param[out] none + * @return 0 - success + * !0 - Failure + * @description This HAL API should contain the code to stop the timer + * + */ + +int32_t rsi_timer_stop(uint8_t timer_node) +{ + + // Stop the timer + + return 0; +} + +/*===================================================*/ +/** + * @fn uint32_t rsi_timer_read(uint8_t timer_node) + * @brief read timer + * @param[in] timer_node, timer node to read + * @param[out] none + * @return timer value + * @description This HAL API should contain API to read the timer + * + */ +uint32_t rsi_timer_read(uint8_t timer_node) +{ + + volatile uint32_t timer_val = 0; + + // read the timer and return timer value + + return timer_val; +} + +/*===================================================*/ +/** + * @fn void rsi_delay_us(uint32_t delay) + * @brief create delay in micro seconds + * @param[in] delay_us, timer delay in micro seconds + * @param[out] none + * @return none + * @description This HAL API should contain the code to create delay in micro seconds + * + */ +void rsi_delay_us(uint32_t delay_us) +{ + + // call the API for delay in micro seconds + + return; +} + +#ifdef RSI_M4_INTERFACE + +extern void SysTick_Handler(void); + +void SysTick_Handler(void) +{ + _dwTickCount++; +} + +uint32_t GetTickCount(void) +{ + return _dwTickCount; // gets the tick count from systic ISR +} +#endif + +/*===================================================*/ +/** + * @fn void rsi_delay_ms(uint32_t delay) + * @brief create delay in milli seconds + * @param[in] delay, timer delay in milli seconds + * @param[out] none + * @return none + * @description This HAL API should contain the code to create delay in milli seconds + */ +void rsi_delay_ms(uint32_t delay_ms) +{ +#ifndef RSI_WITH_OS + uint32_t start; +#endif + if (delay_ms == DELAY0) + return; + +#ifdef RSI_WITH_OS + vTaskDelay(delay_ms); +#else + start = rsi_hal_gettickcount(); + do + { + } while (rsi_hal_gettickcount() - start < delay_ms); +#endif +} + +/*===================================================*/ +/** + * @fn uint32_t rsi_hal_gettickcount() + * @brief provides a tick value in milliseconds + * @return tick value + * @description This HAL API should contain the code to read the timer tick count value in milliseconds + * + */ + +#ifndef RSI_HAL_USE_RTOS_SYSTICK +/* + SysTick handler implementation that also clears overflow flag. +*/ +void SysTick_Handler(void) +{ + /* Increment counter necessary in Delay()*/ + msTicks++; +#ifdef RSI_WITH_OS + if (xTaskGetSchedulerState() != taskSCHEDULER_NOT_STARTED) + { + xPortSysTickHandler(); + } +#endif +} + +uint32_t rsi_hal_gettickcount(void) +{ + return msTicks; + +#ifdef LINUX_PLATFORM + // Define your API to get the tick count delay in milli seconds from systic ISR and return the resultant value + struct rsi_timeval tv1; + gettimeofday(&tv1, NULL); + return (tv1.tv_sec * CONVERT_SEC_TO_MSEC + tv1.tv_usec * CONVERT_USEC_TO_MSEC); +#endif +} + +#else +uint32_t rsi_hal_gettickcount(void) +{ + return xTaskGetTickCount(); +} +#endif /* RSI_HAL_USE_RTOS_SYSTICK */ +#endif /* _use_the_rsi_defined_functions */ diff --git a/examples/platform/efr32/rs911x/rs911x.gni b/examples/platform/efr32/rs911x/rs911x.gni new file mode 100644 index 00000000000000..87b30c43a7be33 --- /dev/null +++ b/examples/platform/efr32/rs911x/rs911x.gni @@ -0,0 +1,101 @@ +import("//build_overrides/chip.gni") +import("//build_overrides/efr32_sdk.gni") +import("//build_overrides/pigweed.gni") + +examples_plat_dir = "${chip_root}/examples/platform/efr32" +wifi_sdk_dir = "${chip_root}/src/platform/EFR32/wifi" +wiseconnect_sdk_root = "${chip_root}/third_party/silabs/wiseconnect-wifi-bt-sdk" +rs911x_cflags = [] + +rs911x_src_plat = [ + "${examples_plat_dir}/rs911x/rsi_if.c", + "${examples_plat_dir}/rs911x/wfx_rsi_host.c", + "${wifi_sdk_dir}/wfx_notify.cpp", + "${examples_plat_dir}/rs911x/hal/rsi_hal_mcu_interrupt.c", + "${examples_plat_dir}/rs911x/hal/rsi_hal_mcu_ioports.c", + "${examples_plat_dir}/rs911x/hal/rsi_hal_mcu_timer.c", + "${examples_plat_dir}/rs911x/hal/efx_spi.c", +] +rs911x_plat_incs = [ + "${wifi_sdk_dir}", + "${wifi_sdk_dir}/hal", + "${chip_root}/src/platform/EFR32", +] + +# +# All the stuff from wiseconnect +# +rs911x_src_sapi = [ + "${wiseconnect_sdk_root}/sapi/wlan/rsi_wlan_apis.c", + "${wiseconnect_sdk_root}/sapi/common/rsi_apis_non_rom.c", + "${wiseconnect_sdk_root}/sapi/common/rsi_apis_rom.c", + "${wiseconnect_sdk_root}/sapi/common/rsi_common_apis.c", + "${wiseconnect_sdk_root}/sapi/common/rsi_device_init_apis.c", + "${wiseconnect_sdk_root}/sapi/driver/device_interface/spi/rsi_spi_frame_rd_wr.c", + "${wiseconnect_sdk_root}/sapi/driver/device_interface/spi/rsi_spi_functs.c", + "${wiseconnect_sdk_root}/sapi/driver/device_interface/spi/rsi_spi_iface_init.c", + "${wiseconnect_sdk_root}/sapi/driver/device_interface/spi/rsi_spi_mem_rd_wr.c", + "${wiseconnect_sdk_root}/sapi/driver/device_interface/spi/rsi_spi_reg_rd_wr.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_common.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_device_init.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_driver_event_handlers.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_driver.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_events_rom.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_events.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_iap.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_nwk_rom.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_nwk.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_pkt_mgmt_rom.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_pkt_mgmt.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_queue_rom.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_queue.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_scheduler_rom.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_scheduler.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_setregion_countryinfo.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_timer.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_utils_rom.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_utils.c", + "${wiseconnect_sdk_root}/sapi/driver/rsi_wlan.c", + "${wiseconnect_sdk_root}/sapi/rtos/freertos_wrapper/rsi_os_wrapper.c", +] + +foreach(src_file, rs911x_src_sapi) { + rs911x_cflags += [ "-Wno-empty-body" ] +} + +rs911x_inc_plat = [ + "${wifi_sdk_dir}", + "${examples_plat_dir}/rs911x", + "${examples_plat_dir}/rs911x/hal", + "${wiseconnect_sdk_root}/sapi/include", +] + +# Apparently - the rsi library needs this +rs911x_src_sock = [ + "${wiseconnect_sdk_root}/sapi/network/socket/rsi_socket.c", + "${wiseconnect_sdk_root}/sapi/network/socket/rsi_socket_rom.c", +] +rs911x_sock_inc = [ "${wifi_sdk_dir}/rsi-sockets" ] + +# +# If we use LWIP - not built-in sockets +# +rs911x_src_lwip = [ + "${wifi_sdk_dir}/ethernetif.cpp", + "${wifi_sdk_dir}/dhcp_client.cpp", + "${wifi_sdk_dir}/lwip_netif.cpp", +] +rs911x_defs = [ + "SL_HEAP_SIZE=32768", + "SL_WIFI=1", + "SL_WFX_USE_SPI", + "EFX32_RS911X=1", + "RS911X_WIFI", + "RSI_WLAN_ENABLE", + "RSI_SPI_INTERFACE", + "RSI_WITH_OS", +] +rs911x_sock_defs = [ + "RS911X_SOCKETS", + "RSI_IPV6_ENABLE", +] diff --git a/examples/platform/efr32/rs911x/rsi_if.c b/examples/platform/efr32/rs911x/rsi_if.c new file mode 100644 index 00000000000000..872d82c411269b --- /dev/null +++ b/examples/platform/efr32/rs911x/rsi_if.c @@ -0,0 +1,852 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include +#include +#include + +#include "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" + +#include "sl_status.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "wfx_host_events.h" + +#include "rsi_driver.h" +#include "rsi_wlan_non_rom.h" + +#include "rsi_common_apis.h" +#include "rsi_data_types.h" +#include "rsi_nwk.h" +#include "rsi_socket.h" +#include "rsi_utils.h" +#include "rsi_wlan.h" +#include "rsi_wlan_apis.h" +#include "rsi_wlan_config.h" +//#include "rsi_wlan_non_rom.h" +#include "rsi_bootup_config.h" +#include "rsi_error.h" + +#include "dhcp_client.h" +#include "wfx_host_events.h" +#include "wfx_rsi.h" + +/* Rsi driver Task will use as its stack */ +StackType_t driverRsiTaskStack[WFX_RSI_WLAN_TASK_SZ] = { 0 }; + +/* Structure that will hold the TCB of the wfxRsi Task being created. */ +StaticTask_t driverRsiTaskBuffer; + +/* Declare a variable to hold the data associated with the created event group. */ +StaticEventGroup_t rsiDriverEventGroup; + +bool hasNotifiedIPV6 = false; +#if (CHIP_DEVICE_CONFIG_ENABLE_IPV4) +bool hasNotifiedIPV4 = false; +#endif /* CHIP_DEVICE_CONFIG_ENABLE_IPV4 */ +bool hasNotifiedWifiConnectivity = false; + +/* + * This file implements the interface to the RSI SAPIs + */ +static uint8_t wfx_rsi_drv_buf[WFX_RSI_BUF_SZ]; +wfx_wifi_scan_ext_t * temp_reset; +uint8_t security; + +/****************************************************************** + * @fn int32_t wfx_rsi_get_ap_info(wfx_wifi_scan_result_t *ap) + * @brief + * Getting the AP details + * @param[in] ap: access point + * @return + * status + *********************************************************************/ +int32_t wfx_rsi_get_ap_info(wfx_wifi_scan_result_t * ap) +{ + int32_t status; + uint8_t rssi; + ap->security = security; + ap->chan = wfx_rsi.ap_chan; + memcpy(&ap->bssid[0], &wfx_rsi.ap_mac.octet[0], BSSID_MAX_STR_LEN); + status = rsi_wlan_get(RSI_RSSI, &rssi, sizeof(rssi)); + if (status == RSI_SUCCESS) + { + ap->rssi = (-1) * rssi; + } + return status; +} + +/****************************************************************** + * @fn int32_t wfx_rsi_get_ap_ext(wfx_wifi_scan_ext_t *extra_info) + * @brief + * Getting the AP extra details + * @param[in] extra info: access point extra information + * @return + * status + *********************************************************************/ +int32_t wfx_rsi_get_ap_ext(wfx_wifi_scan_ext_t * extra_info) +{ + int32_t status; + uint8_t buff[RSI_RESPONSE_MAX_SIZE] = { 0 }; + status = rsi_wlan_get(RSI_WLAN_EXT_STATS, buff, sizeof(buff)); + if (status != RSI_SUCCESS) + { + WFX_RSI_LOG("\r\n Failed, Error Code : 0x%lX\r\n", status); + } + else + { + rsi_wlan_ext_stats_t * test = (rsi_wlan_ext_stats_t *) buff; + extra_info->beacon_lost_count = test->beacon_lost_count - temp_reset->beacon_lost_count; + extra_info->beacon_rx_count = test->beacon_rx_count - temp_reset->beacon_rx_count; + extra_info->mcast_rx_count = test->mcast_rx_count - temp_reset->mcast_rx_count; + extra_info->mcast_tx_count = test->mcast_tx_count - temp_reset->mcast_tx_count; + extra_info->ucast_rx_count = test->ucast_rx_count - temp_reset->ucast_rx_count; + extra_info->ucast_tx_count = test->ucast_tx_count - temp_reset->ucast_tx_count; + extra_info->overrun_count = test->overrun_count - temp_reset->overrun_count; + } + return status; +} + +/****************************************************************** + * @fn int32_t wfx_rsi_reset_count() + * @brief + * Getting the driver reset count + * @param[in] None + * @return + * status + *********************************************************************/ +int32_t wfx_rsi_reset_count() +{ + int32_t status; + uint8_t buff[RSI_RESPONSE_MAX_SIZE] = { 0 }; + status = rsi_wlan_get(RSI_WLAN_EXT_STATS, buff, sizeof(buff)); + if (status != RSI_SUCCESS) + { + WFX_RSI_LOG("\r\n Failed, Error Code : 0x%lX\r\n", status); + } + else + { + rsi_wlan_ext_stats_t * test = (rsi_wlan_ext_stats_t *) buff; + temp_reset->beacon_lost_count = test->beacon_lost_count; + temp_reset->beacon_rx_count = test->beacon_rx_count; + temp_reset->mcast_rx_count = test->mcast_rx_count; + temp_reset->mcast_tx_count = test->mcast_tx_count; + temp_reset->ucast_rx_count = test->ucast_rx_count; + temp_reset->ucast_tx_count = test->ucast_tx_count; + temp_reset->overrun_count = test->overrun_count; + } + return status; +} + +/****************************************************************** + * @fn wfx_rsi_disconnect() + * @brief + * Getting the driver disconnect status + * @param[in] None + * @return + * status + *********************************************************************/ +int32_t wfx_rsi_disconnect() +{ + int32_t status = rsi_wlan_disconnect(); + return status; +} + +/****************************************************************** + * @fn wfx_rsi_join_cb(uint16_t status, const uint8_t *buf, const uint16_t len) + * @brief + * called when driver join with cb + * @param[in] status: + * @param[in] buf: + * @param[in] len: + * @return + * None + *********************************************************************/ +static void wfx_rsi_join_cb(uint16_t status, const uint8_t * buf, const uint16_t len) +{ + WFX_RSI_LOG("%s: status: %02x", __func__, status); + wfx_rsi.dev_state &= ~WFX_RSI_ST_STA_CONNECTING; + temp_reset = (wfx_wifi_scan_ext_t *) malloc(sizeof(wfx_wifi_scan_ext_t)); + memset(temp_reset, 0, sizeof(wfx_wifi_scan_ext_t)); + if (status != RSI_SUCCESS) + { + /* + * We should enable retry.. (Need config variable for this) + */ + WFX_RSI_LOG("%s: failed. retry: %d", __func__, wfx_rsi.join_retries); +#if (WFX_RSI_CONFIG_MAX_JOIN != 0) + if (++wfx_rsi.join_retries < WFX_RSI_CONFIG_MAX_JOIN) +#endif + { + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_STA_START_JOIN); + } + } + else + { + /* + * Join was complete - Do the DHCP + */ + WFX_RSI_LOG("%s: join completed.", __func__); +#ifdef RS911X_SOCKETS + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_STA_DO_DHCP); +#else + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_STA_CONN); +#endif + } +} + +/****************************************************************** + * @fn wfx_rsi_join_fail_cb(uint16_t status, uint8_t *buf, uint32_t len) + * @brief + * called when driver fail to join with cb + * @param[in] status: + * @param[in] buf: + * @param[in] len: + * @return + * None + *********************************************************************/ +static void wfx_rsi_join_fail_cb(uint16_t status, uint8_t * buf, uint32_t len) +{ + WFX_RSI_LOG("%s: error: failed status: %02x on try %d", __func__, status, wfx_rsi.join_retries); + wfx_rsi.join_retries += 1; + wfx_rsi.dev_state &= ~WFX_RSI_ST_STA_CONNECTING; + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_STA_START_JOIN); +} +#ifdef RS911X_SOCKETS + +/****************************************************************** + * @fn wfx_rsi_ipchange_cb(uint16_t status, uint8_t *buf, uint32_t len) + * @brief + * DHCP should end up here + * @param[in] status: + * @param[in] buf: + * @param[in] len: + * @return + * None + *********************************************************************/ +static void wfx_rsi_ipchange_cb(uint16_t status, uint8_t * buf, uint32_t len) +{ + WFX_RSI_LOG("%s: status: %02x", __func__, status); + if (status != RSI_SUCCESS) + { + /* Restart DHCP? */ + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_STA_DO_DHCP); + } + else + { + wfx_rsi.dev_state |= WFX_RSI_ST_STA_DHCP_DONE; + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_STA_DHCP_DONE); + } +} + +#else +/************************************************************************************* + * @fn wfx_rsi_wlan_pkt_cb(uint16_t status, uint8_t *buf, uint32_t len) + * @brief + * Got RAW WLAN data pkt + * @param[in] status: + * @param[in] buf: + * @param[in] len: + * @return + * None + *****************************************************************************************/ +static void wfx_rsi_wlan_pkt_cb(uint16_t status, uint8_t * buf, uint32_t len) +{ + // WFX_RSI_LOG("%s: status=%d, len=%d", __func__, status, len); + if (status != RSI_SUCCESS) + { + return; + } + wfx_host_received_sta_frame_cb(buf, len); +} +#endif /* !Socket support */ + +/************************************************************************************* + * @fn static int32_t wfx_rsi_init(void) + * @brief + * driver initialization + * @param[in] None + * @return + * None + *****************************************************************************************/ +static int32_t wfx_rsi_init(void) +{ + int32_t status; + uint8_t buf[RSI_RESPONSE_HOLD_BUFF_SIZE]; + extern void rsi_hal_board_init(void); + + WFX_RSI_LOG("%s: starting(HEAP_SZ = %d)", __func__, SL_HEAP_SIZE); + //! Driver initialization + status = rsi_driver_init(wfx_rsi_drv_buf, WFX_RSI_BUF_SZ); + if ((status < RSI_DRIVER_STATUS) || (status > WFX_RSI_BUF_SZ)) + { + WFX_RSI_LOG("%s: error: RSI drv init failed with status: %02x", __func__, status); + return status; + } + + WFX_RSI_LOG("%s: rsi_device_init", __func__); + /* ! Redpine module intialisation */ + if ((status = rsi_device_init(LOAD_NWP_FW)) != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: error: rsi_device_init failed with status: %02x", __func__, status); + return status; + } + WFX_RSI_LOG("%s: start wireless drv task", __func__); + /* + * Create the driver task + */ + wfx_rsi.drv_task = xTaskCreateStatic((TaskFunction_t) rsi_wireless_driver_task, "rsi_drv", WFX_RSI_WLAN_TASK_SZ, NULL, + WLAN_TASK_PRIORITY, driverRsiTaskStack, &driverRsiTaskBuffer); + if (NULL == wfx_rsi.drv_task) + { + WFX_RSI_LOG("%s: error: rsi_wireless_driver_task failed", __func__); + return RSI_ERROR_INVALID_PARAM; + } + + /* Initialize WiSeConnect or Module features. */ + WFX_RSI_LOG("%s: rsi_wireless_init", __func__); + if ((status = rsi_wireless_init(OPER_MODE_0, COEX_MODE_0)) != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: error: rsi_wireless_init failed with status: %02x", __func__, status); + return status; + } + + WFX_RSI_LOG("%s: get FW version..", __func__); + /* + * Get the MAC and other info to let the user know about it. + */ + if (rsi_wlan_get(RSI_FW_VERSION, buf, sizeof(buf)) != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: error: rsi_wlan_get(RSI_FW_VERSION) failed with status: %02x", __func__, status); + return status; + } + + buf[sizeof(buf) - 1] = 0; + WFX_RSI_LOG("%s: RSI firmware version: %s", __func__, buf); + //! Send feature frame + if ((status = rsi_send_feature_frame()) != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: error: rsi_send_feature_frame failed with status: %02x", __func__, status); + return status; + } + + WFX_RSI_LOG("%s: sent rsi_send_feature_frame", __func__); + /* initializes wlan radio parameters and WLAN supplicant parameters. + */ + (void) rsi_wlan_radio_init(); /* Required so we can get MAC address */ + if ((status = rsi_wlan_get(RSI_MAC_ADDRESS, &wfx_rsi.sta_mac.octet[0], RESP_BUFF_SIZE)) != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: error: rsi_wlan_get failed with status: %02x", __func__, status); + return status; + } + + WFX_RSI_LOG("%s: WLAN: MAC %02x:%02x:%02x %02x:%02x:%02x", __func__, wfx_rsi.sta_mac.octet[0], wfx_rsi.sta_mac.octet[1], + wfx_rsi.sta_mac.octet[2], wfx_rsi.sta_mac.octet[3], wfx_rsi.sta_mac.octet[4], wfx_rsi.sta_mac.octet[5]); + wfx_rsi.events = xEventGroupCreateStatic(&rsiDriverEventGroup); + /* + * Register callbacks - We are only interested in the connectivity CBs + */ + if ((status = rsi_wlan_register_callbacks(RSI_JOIN_FAIL_CB, wfx_rsi_join_fail_cb)) != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: RSI callback register join failed with status: %02x", __func__, status); + return status; + } +#ifdef RS911X_SOCKETS + (void) rsi_wlan_register_callbacks(RSI_IP_CHANGE_NOTIFY_CB, wfx_rsi_ipchange_cb); +#else + if ((status = rsi_wlan_register_callbacks(RSI_WLAN_DATA_RECEIVE_NOTIFY_CB, wfx_rsi_wlan_pkt_cb)) != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: RSI callback register data-notify failed with status: %02x", __func__, status); + return status; + } +#endif + wfx_rsi.dev_state |= WFX_RSI_ST_DEV_READY; + WFX_RSI_LOG("%s: RSI: OK", __func__); + return RSI_SUCCESS; +} + +/************************************************************************************* + * @fn void wfx_show_err(char *msg) + * @brief + * driver shows error message + * @param[in] msg + * @return + * None + *****************************************************************************************/ +void wfx_show_err(char * msg) +{ + WFX_RSI_LOG("%s: message: %d", __func__, msg); +} + +/*************************************************************************************** + * @fn static void wfx_rsi_save_ap_info() + * @brief + * Saving the details of the AP + * @param[in] None + * @return + * None + *******************************************************************************************/ +static void wfx_rsi_save_ap_info() +{ + int32_t status; + rsi_rsp_scan_t rsp; + + status = + rsi_wlan_scan_with_bitmap_options((int8_t *) &wfx_rsi.sec.ssid[0], AP_CHANNEL_NO_0, &rsp, sizeof(rsp), SCAN_BITMAP_OPTN_1); + if (status) + { + /* + * Scan is done - failed + */ + } + else + { + wfx_rsi.sec.security = rsp.scan_info->security_mode; + wfx_rsi.ap_chan = rsp.scan_info->rf_channel; + memcpy(&wfx_rsi.ap_mac.octet[0], &rsp.scan_info->bssid[0], BSSID_MAX_STR_LEN); + } + if ((wfx_rsi.sec.security == RSI_WPA) || (wfx_rsi.sec.security == RSI_WPA2)) + { + // saving the security before changing into mixed mode + security = wfx_rsi.sec.security; + wfx_rsi.sec.security = RSI_WPA_WPA2_MIXED; + } + if (wfx_rsi.sec.security == SME_WPA3) + { + // returning 3 for WPA3 when DGWIFI read security-type is called + security = WPA3_SECURITY; + wfx_rsi.sec.security = RSI_WPA3; + } + WFX_RSI_LOG("%s: WLAN: connecting to %s==%s, sec=%d, status=%02x", __func__, &wfx_rsi.sec.ssid[0], &wfx_rsi.sec.passkey[0], + wfx_rsi.sec.security, status); +} + +/******************************************************************************************** + * @fn static void wfx_rsi_do_join(void) + * @brief + * Start an async Join command + * @return + * None + **********************************************************************************************/ +static void wfx_rsi_do_join(void) +{ + int32_t status; + + if (wfx_rsi.dev_state & (WFX_RSI_ST_STA_CONNECTING | WFX_RSI_ST_STA_CONNECTED)) + { + WFX_RSI_LOG("%s: not joining - already in progress", __func__); + } + else + { + WFX_RSI_LOG("%s: WLAN: connecting to %s==%s, sec=%d", __func__, &wfx_rsi.sec.ssid[0], &wfx_rsi.sec.passkey[0], + wfx_rsi.sec.security); + /* + * Join the network + */ + /* TODO - make the WFX_SECURITY_xxx - same as RSI_xxx + * Right now it's done by hand - we need something better + */ + wfx_rsi.dev_state |= WFX_RSI_ST_STA_CONNECTING; + + /* Try to connect Wifi with given Credentials + * untill there is a success or maximum number of tries allowed + */ + while (++wfx_rsi.join_retries < WFX_RSI_CONFIG_MAX_JOIN) + { + + /* Call rsi connect call with given ssid and password + * And check there is a success + */ + if ((status = rsi_wlan_connect_async((int8_t *) &wfx_rsi.sec.ssid[0], (rsi_security_mode_t) wfx_rsi.sec.security, + &wfx_rsi.sec.passkey[0], wfx_rsi_join_cb)) != RSI_SUCCESS) + { + + wfx_rsi.dev_state &= ~WFX_RSI_ST_STA_CONNECTING; + WFX_RSI_LOG("%s: rsi_wlan_connect_async failed with status: %02x on try %d", __func__, status, + wfx_rsi.join_retries); + vTaskDelay(4000); + /* TODO - Start a timer.. to retry */ + } + else + { + break; // exit while loop + } + } + if (wfx_rsi.join_retries == MAX_JOIN_RETRIES_COUNT) + { + WFX_RSI_LOG("Connect failed after %d tries", wfx_rsi.join_retries); + } + else + { + WFX_RSI_LOG("%s: starting JOIN to %s after %d tries\n", __func__, (char *) &wfx_rsi.sec.ssid[0], wfx_rsi.join_retries); + } + } +} + +/********************************************************************************* + * @fn void wfx_rsi_task(void *arg) + * @brief + * The main WLAN task - started by wfx_wifi_start () that interfaces with RSI. + * The rest of RSI stuff come in call-backs. + * The initialization has been already done. + * @param[in] arg: + * @return + * None + **********************************************************************************/ +/* ARGSUSED */ +void wfx_rsi_task(void * arg) +{ + EventBits_t flags; +#ifndef RS911X_SOCKETS + TickType_t last_dhcp_poll, now; + struct netif * sta_netif; +#endif + (void) arg; + uint32_t rsi_status = wfx_rsi_init(); + if (rsi_status != RSI_SUCCESS) + { + WFX_RSI_LOG("%s: error: wfx_rsi_init with status: %02x", __func__, rsi_status); + return; + } +#ifndef RS911X_SOCKETS + wfx_lwip_start(); + last_dhcp_poll = xTaskGetTickCount(); + sta_netif = wfx_get_netif(SL_WFX_STA_INTERFACE); +#endif + wfx_started_notify(); + + WFX_RSI_LOG("%s: starting event wait", __func__); + for (;;) + { + /* + * This is the main job of this task. + * Wait for commands from the ConnectivityManager + * Make state changes (based on call backs) + */ + flags = xEventGroupWaitBits(wfx_rsi.events, + WFX_EVT_STA_CONN | WFX_EVT_STA_DISCONN | WFX_EVT_STA_START_JOIN +#ifdef RS911X_SOCKETS + | WFX_EVT_STA_DO_DHCP | WFX_EVT_STA_DHCP_DONE +#endif /* RS911X_SOCKETS */ +#ifdef SL_WFX_CONFIG_SOFTAP + | WFX_EVT_AP_START | WFX_EVT_AP_STOP +#endif /* SL_WFX_CONFIG_SOFTAP */ +#ifdef SL_WFX_CONFIG_SCAN + | WFX_EVT_SCAN +#endif /* SL_WFX_CONFIG_SCAN */ + | 0, + pdTRUE, /* Clear the bits */ + pdFALSE, /* Wait for any bit */ + pdMS_TO_TICKS(250)); /* 250 mSec */ + + if (flags) + { + WFX_RSI_LOG("%s: wait event encountered: %x", __func__, flags); + } +#ifdef RS911X_SOCKETS + if (flags & WFX_EVT_STA_DO_DHCP) + { + /* + * Do DHCP - + */ + if ((status = rsi_config_ipaddress(RSI_IP_VERSION_4, RSI_DHCP | RSI_DHCP_UNICAST_OFFER, NULL, NULL, NULL, + &wfx_rsi.ip4_addr[0], IP_CONF_RSP_BUFF_LENGTH_4, STATION)) != RSI_SUCCESS) + { + /* We should try this again.. (perhaps sleep) */ + /* TODO - Figure out what to do here */ + } + } +#else /* !RS911X_SOCKET - using LWIP */ + /* + * Let's handle DHCP polling here + */ + if (wfx_rsi.dev_state & WFX_RSI_ST_STA_CONNECTED) + { + if ((now = xTaskGetTickCount()) > (last_dhcp_poll + pdMS_TO_TICKS(250))) + { +#if (CHIP_DEVICE_CONFIG_ENABLE_IPV4) + uint8_t dhcp_state = dhcpclient_poll(sta_netif); + if (dhcp_state == DHCP_ADDRESS_ASSIGNED && !hasNotifiedIPV4) + { + wfx_dhcp_got_ipv4((uint32_t) sta_netif->ip_addr.u_addr.ip4.addr); + hasNotifiedIPV4 = true; + if (!hasNotifiedWifiConnectivity) + { + wfx_connected_notify(CONNECTION_STATUS_SUCCESS, &wfx_rsi.ap_mac); + hasNotifiedWifiConnectivity = true; + } + } + else if (dhcp_state == DHCP_OFF) + { + wfx_ip_changed_notify(IP_STATUS_FAIL); + hasNotifiedIPV4 = false; + } +#endif /* CHIP_DEVICE_CONFIG_ENABLE_IPV4 */ + /* Checks if the assigned IPv6 address is preferred by evaluating + * the first block of IPv6 address ( block 0) + */ + if ((ip6_addr_ispreferred(netif_ip6_addr_state(sta_netif, 0))) && !hasNotifiedIPV6) + { + wfx_ipv6_notify(GET_IPV6_SUCCESS); + hasNotifiedIPV6 = true; + if (!hasNotifiedWifiConnectivity) + { + wfx_connected_notify(CONNECTION_STATUS_SUCCESS, &wfx_rsi.ap_mac); + hasNotifiedWifiConnectivity = true; + } + } + last_dhcp_poll = now; + } + } +#endif /* RS911X_SOCKETS */ + if (flags & WFX_EVT_STA_START_JOIN) + { + // saving the AP related info + wfx_rsi_save_ap_info(); + // Joining to the network + wfx_rsi_do_join(); + } + if (flags & WFX_EVT_STA_CONN) + { + /* + * Initiate the Join command (assuming we have been provisioned) + */ + WFX_RSI_LOG("%s: starting LwIP STA", __func__); + wfx_rsi.dev_state |= WFX_RSI_ST_STA_CONNECTED; +#ifndef RS911X_SOCKETS + hasNotifiedWifiConnectivity = false; +#if (CHIP_DEVICE_CONFIG_ENABLE_IPV4) + hasNotifiedIPV4 = false; +#endif // CHIP_DEVICE_CONFIG_ENABLE_IPV4 + hasNotifiedIPV6 = false; + wfx_lwip_set_sta_link_up(); +#endif /* !RS911X_SOCKETS */ + /* We need to get AP Mac - TODO */ + // Uncomment once the hook into MATTER is moved to IP connectivty instead + // of AP connectivity. wfx_connected_notify(0, &wfx_rsi.ap_mac); // This + // is independant of IP connectivity. + } + if (flags & WFX_EVT_STA_DISCONN) + { + wfx_rsi.dev_state &= + ~(WFX_RSI_ST_STA_READY | WFX_RSI_ST_STA_CONNECTING | WFX_RSI_ST_STA_CONNECTED | WFX_RSI_ST_STA_DHCP_DONE); + WFX_RSI_LOG("%s: disconnect notify", __func__); + /* TODO: Implement disconnect notify */ +#ifndef RS911X_SOCKETS + wfx_lwip_set_sta_link_down(); // Internally dhcpclient_poll(netif) -> + // wfx_ip_changed_notify(0) for IPV4 +#if (CHIP_DEVICE_CONFIG_ENABLE_IPV4) + wfx_ip_changed_notify(IP_STATUS_FAIL); + hasNotifiedIPV4 = false; +#endif /* CHIP_DEVICE_CONFIG_ENABLE_IPV4 */ + wfx_ipv6_notify(GET_IPV6_FAIL); + hasNotifiedIPV6 = false; + hasNotifiedWifiConnectivity = false; +#endif /* !RS911X_SOCKETS */ + } +#ifdef SL_WFX_CONFIG_SCAN + if (flags & WFX_EVT_SCAN) + { + if (!(wfx_rsi.dev_state & WFX_RSI_ST_SCANSTARTED)) + { + WFX_RSI_LOG("%s: start SSID scan", __func__); + int x; + wfx_wifi_scan_result_t ap; + rsi_scan_info_t * scan; + int32_t status; + uint8_t bgscan_results[BG_SCAN_RES_SIZE] = { 0 }; + status = rsi_wlan_bgscan_profile(1, (rsi_rsp_scan_t *) bgscan_results, BG_SCAN_RES_SIZE); + + WFX_RSI_LOG("%s: status: %02x size = %d", __func__, status, BG_SCAN_RES_SIZE); + rsi_rsp_scan_t * rsp = (rsi_rsp_scan_t *) bgscan_results; + if (status) + { + /* + * Scan is done - failed + */ + } + else + for (x = 0; x < rsp->scan_count[0]; x++) + { + scan = &rsp->scan_info[x]; + strcpy(&ap.ssid[0], (char *) &scan->ssid[0]); + if (wfx_rsi.scan_ssid) + { + WFX_RSI_LOG("Inside scan_ssid"); + WFX_RSI_LOG("SCAN SSID: %s , ap scan: %s", wfx_rsi.scan_ssid, ap.ssid); + if (strcmp(wfx_rsi.scan_ssid, ap.ssid) == CMP_SUCCESS) + { + WFX_RSI_LOG("Inside ap details"); + ap.security = scan->security_mode; + ap.rssi = (-1) * scan->rssi_val; + memcpy(&ap.bssid[0], &scan->bssid[0], BSSID_MAX_STR_LEN); + (*wfx_rsi.scan_cb)(&ap); + } + } + else + { + WFX_RSI_LOG("Inside else"); + ap.security = scan->security_mode; + ap.rssi = (-1) * scan->rssi_val; + memcpy(&ap.bssid[0], &scan->bssid[0], BSSID_MAX_STR_LEN); + (*wfx_rsi.scan_cb)(&ap); + } + } + wfx_rsi.dev_state &= ~WFX_RSI_ST_SCANSTARTED; + /* Terminate with end of scan which is no ap sent back */ + (*wfx_rsi.scan_cb)((wfx_wifi_scan_result_t *) 0); + wfx_rsi.scan_cb = (void (*)(wfx_wifi_scan_result_t *)) 0; + + if (wfx_rsi.scan_ssid) + { + vPortFree(wfx_rsi.scan_ssid); + wfx_rsi.scan_ssid = (char *) 0; + } + } + } +#endif /* SL_WFX_CONFIG_SCAN */ +#ifdef SL_WFX_CONFIG_SOFTAP + /* TODO */ + if (flags & WFX_EVT_AP_START) + { + } + if (flags & WFX_EVT_AP_STOP) + { + } +#endif /* SL_WFX_CONFIG_SOFTAP */ + } +} + +/******************************************************************************************** + * @fn void wfx_dhcp_got_ipv4(uint32_t ip) + * @brief + * Acquire the new ip address + * @param[in] ip: internet protocol + * @return + * None + **********************************************************************************************/ +void wfx_dhcp_got_ipv4(uint32_t ip) +{ + /* + * Acquire the new IP address + */ + wfx_rsi.ip4_addr[0] = (ip) &HEX_VALUE_FF; + wfx_rsi.ip4_addr[1] = (ip >> 8) & HEX_VALUE_FF; + wfx_rsi.ip4_addr[2] = (ip >> 16) & HEX_VALUE_FF; + wfx_rsi.ip4_addr[3] = (ip >> 24) & HEX_VALUE_FF; + WFX_RSI_LOG("%s: DHCP OK: IP=%d.%d.%d.%d", __func__, wfx_rsi.ip4_addr[0], wfx_rsi.ip4_addr[1], wfx_rsi.ip4_addr[2], + wfx_rsi.ip4_addr[3]); + /* Notify the Connectivity Manager - via the app */ + wfx_ip_changed_notify(IP_STATUS_SUCCESS); + wfx_rsi.dev_state |= WFX_RSI_ST_STA_READY; +} + +/* + * WARNING - Taken from RSI and broken up + * This is my own RSI stuff for not copying code and allocating an extra + * level of indirection - when using LWIP buffers + * see also: int32_t rsi_wlan_send_data_xx(uint8_t *buffer, uint32_t length) + */ +/******************************************************************************************** + * @fn void *wfx_rsi_alloc_pkt() + * @brief + * Allocate packet to send data + * @param[in] None + * @return + * None + **********************************************************************************************/ +void * wfx_rsi_alloc_pkt() +{ + rsi_pkt_t * pkt; + + // Allocate packet to send data + if ((pkt = rsi_pkt_alloc(&rsi_driver_cb->wlan_cb->wlan_tx_pool)) == NULL) + { + return (void *) 0; + } + + return (void *) pkt; +} + +/******************************************************************************************** + * @fn void wfx_rsi_pkt_add_data(void *p, uint8_t *buf, uint16_t len, uint16_t off) + * @brief + * add the data into packet + * @param[in] p: + * @param[in] buf: + * @param[in] len: + * @param[in] off: + * @return + * None + **********************************************************************************************/ +void wfx_rsi_pkt_add_data(void * p, uint8_t * buf, uint16_t len, uint16_t off) +{ + rsi_pkt_t * pkt; + + pkt = (rsi_pkt_t *) p; + memcpy(((char *) pkt->data) + off, buf, len); +} + +/******************************************************************************************** + * @fn int32_t wfx_rsi_send_data(void *p, uint16_t len) + * @brief + * Driver send a data + * @param[in] p: + * @param[in] len: + * @return + * None + **********************************************************************************************/ +int32_t wfx_rsi_send_data(void * p, uint16_t len) +{ + int32_t status; + register uint8_t * host_desc; + rsi_pkt_t * pkt; + + pkt = (rsi_pkt_t *) p; + host_desc = pkt->desc; + memset(host_desc, 0, RSI_HOST_DESC_LENGTH); + rsi_uint16_to_2bytes(host_desc, (len & 0xFFF)); + + // Fill packet type + host_desc[1] |= (RSI_WLAN_DATA_Q << 4); + host_desc[2] |= 0x01; + + rsi_enqueue_pkt(&rsi_driver_cb->wlan_tx_q, pkt); + +#ifndef RSI_SEND_SEM_BITMAP + rsi_driver_cb_non_rom->send_wait_bitmap |= BIT(0); +#endif + // Set TX packet pending event + rsi_set_event(RSI_TX_EVENT); + + if (rsi_wait_on_wlan_semaphore(&rsi_driver_cb_non_rom->send_data_sem, RSI_SEND_DATA_RESPONSE_WAIT_TIME) != RSI_ERROR_NONE) + { + return RSI_ERROR_RESPONSE_TIMEOUT; + } + status = rsi_wlan_get_status(); + + return status; +} + +struct wfx_rsi wfx_rsi; diff --git a/examples/platform/efr32/rs911x/rsi_wlan_config.h b/examples/platform/efr32/rs911x/rsi_wlan_config.h new file mode 100644 index 00000000000000..4f31bdc622698c --- /dev/null +++ b/examples/platform/efr32/rs911x/rsi_wlan_config.h @@ -0,0 +1,606 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef RSI_CONFIG_H +#define RSI_CONFIG_H + +#include "rsi_wlan_defines.h" + +//! Enable feature +#define RSI_ENABLE 1 +//! Disable feature +#define RSI_DISABLE 0 + +//! To enable wlan opermode +#define RSI_OPERMODE_WLAN 0 + +//! To enable concurrent mode +#define CONCURRENT_MODE RSI_DISABLE + +//! opermode command paramaters +/*=======================================================================*/ +//! To set wlan feature select bit map +#define RSI_FEATURE_BIT_MAP (FEAT_SECURITY_OPEN) + +//! TCP IP BYPASS feature check +#ifdef RS911X_SOCKETS +#define RSI_TCP_IP_BYPASS RSI_DISABLE + +#define RSI_TCP_IP_FEATURE_BIT_MAP \ + (TCP_IP_FEAT_DHCPV4_CLIENT | /*TCP_IP_FEAT_HTTP_CLIENT | */ \ + TCP_IP_FEAT_EXTENSION_VALID | /*TCP_IP_FEAT_SSL |*/ /*TCP_IP_FEAT_DNS_CLIENT |*/ \ + 0) +//! To set custom feature select bit map +#define RSI_CUSTOM_FEATURE_BIT_MAP FEAT_CUSTOM_FEAT_EXTENTION_VALID + +#else /* Don't use RSI_SOCKETS */ +#define RSI_TCP_IP_BYPASS RSI_ENABLE +#define RSI_TCP_IP_FEATURE_BIT_MAP (TCP_IP_FEAT_BYPASS /*| TCP_IP_FEAT_EXTENSION_VALID*/) +#endif + +//! To set Extended custom feature select bit map +#if WIFI_ENABLE_SECURITY_WPA3 +#ifdef RSI_M4_INTERFACE +#define RSI_EXT_CUSTOM_FEATURE_BIT_MAP (EXT_FEAT_256K_MODE | EXT_FEAT_IEEE_80211W) +#else +#define RSI_EXT_CUSTOM_FEATURE_BIT_MAP (EXT_FEAT_384K_MODE | EXT_FEAT_IEEE_80211W) +#endif +#else +#ifdef RSI_M4_INTERFACE +#define RSI_EXT_CUSTOM_FEATURE_BIT_MAP EXT_FEAT_256K_MODE +#else +#define RSI_EXT_CUSTOM_FEATURE_BIT_MAP EXT_FEAT_384K_MODE +#endif +#endif + +//! To set Extended TCPIP feature select bit map +#define RSI_EXT_TCPIP_FEATURE_BITMAP (/*EXT_FEAT_HTTP_OTAF_SUPPORT |*/ EXT_TCP_IP_SSL_16K_RECORD) +//! Extended custom feature is selected internally +//! CCP -- EXT_FEAT_256K_MODE +//! Wiseconnect -- EXT_FEAT_384K_MODE +/*=======================================================================*/ +//! Feature frame parameters +/*=======================================================================*/ +#define PLL_MODE 0 +#define RF_TYPE 1 //! 0 - External RF 1- Internal RF +#define WIRELESS_MODE 0 +#define ENABLE_PPP 0 +#define AFE_TYPE 1 +#define FEATURE_ENABLES 0 +/*=======================================================================*/ +//! Band command paramters +/*=======================================================================*/ + +//! RSI_BAND_2P4GHZ(2.4GHz) or RSI_BAND_5GHZ(5GHz) or RSI_DUAL_BAND +#define RSI_BAND RSI_BAND_2P4GHZ +/*=======================================================================*/ +//! set region command paramters +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE Set region support +#define RSI_SET_REGION_SUPPORT RSI_DISABLE //@ RSI_ENABLE or RSI_DISABLE set region + +//! If 1:region configurations taken from user ;0:region configurations taken from beacon +#define RSI_SET_REGION_FROM_USER_OR_BEACON 1 + +//! 0-Default Region domain ,1-US, 2-EUROPE, 3-JAPAN +#define RSI_REGION_CODE 1 + +//! 0- Without On Board Antenna , 1- With On Board Antenna +#define RSI_MODULE_TYPE 1 + +/*=======================================================================*/ +//! set region AP command paramters +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE Set region AP support +#define RSI_SET_REGION_AP_SUPPORT RSI_DISABLE + +//! If 1:region configurations taken from user ;0:region configurations taken from firmware +#define RSI_SET_REGION_AP_FROM_USER RSI_DISABLE + +//! "US" or "EU" or "JP" or other region codes +#define RSI_COUNTRY_CODE "US" +/*=======================================================================*/ + +//! Rejoin parameters +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE rejoin params +#define RSI_REJOIN_PARAMS_SUPPORT RSI_ENABLE + +//! Rejoin retry count. If 0 retries infinity times +#define RSI_REJOIN_MAX_RETRY 5 + +//! Periodicity of rejoin attempt +#define RSI_REJOIN_SCAN_INTERVAL 1 + +//! Beacon missed count +#define RSI_REJOIN_BEACON_MISSED_COUNT 40 + +//! RSI_ENABLE or RSI_DISABLE retry for first time join failure +#define RSI_REJOIN_FIRST_TIME_RETRY RSI_DISABLE + +/*=======================================================================*/ + +//! BG scan command parameters +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE BG Scan support +#define RSI_BG_SCAN_SUPPORT RSI_ENABLE + +//! RSI_ENABLE or RSI_DISABLE BG scan +#define RSI_BG_SCAN_ENABLE RSI_ENABLE + +//! RSI_ENABLE or RSI_DISABLE instant BG scan +#define RSI_INSTANT_BG RSI_ENABLE + +//! BG scan threshold value +#define RSI_BG_SCAN_THRESHOLD 63 + +//! RSSI tolerance Threshold +#define RSI_RSSI_TOLERANCE_THRESHOLD 4 + +//! BG scan periodicity +#define RSI_BG_SCAN_PERIODICITY 2 + +//! Active scan duration +#define RSI_ACTIVE_SCAN_DURATION 50 + +//! Passive scan duration +#define RSI_PASSIVE_SCAN_DURATION 50 + +//! Multi probe +#define RSI_MULTIPROBE RSI_ENABLE + +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE to set RTS threshold config +#define RSI_WLAN_CONFIG_ENABLE RSI_ENABLE + +#define CONFIG_RTSTHRESHOLD 1 + +#define RSI_RTS_THRESHOLD 2346 + +/*=======================================================================*/ + +//! Roaming parameters +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE Roaming support +#define RSI_ROAMING_SUPPORT RSI_DISABLE + +//! roaming threshold value +#define RSI_ROAMING_THRESHOLD 67 + +//! roaming hysterisis value +#define RSI_ROAMING_HYSTERISIS 4 + +/*=======================================================================*/ +//! High Throughput Capabilies related information +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE 11n mode in AP mode +#define RSI_MODE_11N_ENABLE RSI_DISABLE + +//! HT caps supported +#define RSI_HT_CAPS_NUM_RX_STBC (1 << 8) +#define RSI_HT_CAPS_SHORT_GI_20MHZ BIT(5) +#define RSI_HT_CAPS_GREENFIELD_EN BIT(4) +#define RSI_HT_CAPS_SUPPORT_CH_WIDTH BIT(1) + +//! HT caps bit map. +#define RSI_HT_CAPS_BIT_MAP \ + (RSI_HT_CAPS_NUM_RX_STBC | RSI_HT_CAPS_SHORT_GI_20MHZ | RSI_HT_CAPS_GREENFIELD_EN | RSI_HT_CAPS_SUPPORT_CH_WIDTH) + +/*=======================================================================*/ +//! Scan command parameters +/*=======================================================================*/ + +//! scan channel bit map in 2.4GHz band,valid if given channel to scan is 0 +#define RSI_SCAN_CHANNEL_BIT_MAP_2_4 0 + +//! scan channle bit map in 5GHz band ,valid if given channel to scan is 0 +#define RSI_SCAN_CHANNEL_BIT_MAP_5 0 + +//! scan_feature_bitmap ,valid only if specific channel to scan and ssid are given +#define RSI_SCAN_FEAT_BITMAP 0 + +/*=======================================================================*/ +//! Enterprise configuration command parameters +/*=======================================================================*/ + +//! Enterprise method ,should be one of among TLS, TTLS, FAST or PEAP +#define RSI_EAP_METHOD "TTLS" +//! This parameter is used to configure the module in Enterprise security mode +#define RSI_EAP_INNER_METHOD "\"auth=MSCHAPV2\"" +//! Private Key Password is required for encrypted private key, format is like "\"12345678\"" +#define RSI_PRIVATE_KEY_PASSWORD "" +/*=======================================================================*/ +//! AP configuration command parameters +/*=======================================================================*/ + +//! This Macro is used to enable AP keep alive functionality +#define RSI_AP_KEEP_ALIVE_ENABLE RSI_ENABLE + +//! This parameter is used to configure keep alive type +#define RSI_AP_KEEP_ALIVE_TYPE RSI_NULL_BASED_KEEP_ALIVE + +//! This parameter is used to configure keep alive period +#define RSI_AP_KEEP_ALIVE_PERIOD 100 + +//! This parameter is used to configure maximum stations supported +#define RSI_MAX_STATIONS_SUPPORT 4 +/*=======================================================================*/ +//! Join command parameters +/*=======================================================================*/ + +//! Tx power level +#define RSI_POWER_LEVEL RSI_POWER_LEVEL_HIGH + +//! RSI_JOIN_FEAT_STA_BG_ONLY_MODE_ENABLE or RSI_JOIN_FEAT_LISTEN_INTERVAL_VALID +#if WIFI_ENABLE_SECURITY_WPA3 +#define RSI_JOIN_FEAT_BIT_MAP RSI_JOIN_FEAT_MFP_CAPABLE_REQUIRED +#else +#define RSI_JOIN_FEAT_BIT_MAP 0 +#endif + +#define RSI_LISTEN_INTERVAL 0 + +//! Transmission data rate. Physical rate at which data has to be transmitted. +#define RSI_DATA_RATE RSI_DATA_RATE_AUTO + +/*=======================================================================*/ +//! Ipconf command parameters +/*=======================================================================*/ + +//! DHCP client host name +#define RSI_DHCP_HOST_NAME "efr_9116" + +//! Transmit test command parameters +/*=======================================================================*/ +//! TX TEST rate flags +#define RSI_TX_TEST_RATE_FLAGS 0 + +//! TX TEST per channel bandwidth +#define RSI_TX_TEST_PER_CH_BW 0 + +//! TX TEST aggregation enable or disable +#define RSI_TX_TEST_AGGR_ENABLE RSI_DISABLE + +//! TX TEST delay +#define RSI_TX_TEST_DELAY 0 + +/*======================================================================*/ +//! ssl parameters +/*=======================================================================*/ +//! ssl version +#define RSI_SSL_VERSION 0 + +//! ssl ciphers +#define RSI_SSL_CIPHERS SSL_ALL_CIPHERS + +//! Enable TCP over SSL with TLS version depends on remote side +#define PROTOCOL_DFLT_VERSION BIT(0) + +//! Enable TCP over SSL with TLS version 1.0 +#define PROTOCOL_TLS_1_0 (BIT(0) | BIT(13)) + +//! Enable TCP over SSL with TLS version 1.1 +#define PROTOCOL_TLS_1_1 (BIT(0) | BIT(14)) + +//! Enable TCP over SSL with TLS version 1.2 +#define PROTOCOL_TLS_1_2 (BIT(0) | BIT(15)) +/*=======================================================================*/ +//! Power save command parameters +/*=======================================================================*/ +//! set handshake type of power mode +#define RSI_HAND_SHAKE_TYPE MSG_BASED + +//! 0 - LP, 1- ULP mode with RAM retention and 2 - ULP with Non RAM retention +#define RSI_SELECT_LP_OR_ULP_MODE RSI_ULP_WITH_RAM_RET + +//! set DTIM aligment required +//! 0 - module wakes up at beacon which is just before or equal to listen_interval +//! 1 - module wakes up at DTIM beacon which is just before or equal to listen_interval +#define RSI_DTIM_ALIGNED_TYPE 0 + +//! Monitor interval for the FAST PSP mode +//! default is 50 ms, and this parameter is valid for FAST PSP only +#define RSI_MONITOR_INTERVAL 50 + +//! Number of DTIMs to skip during powersave +#define RSI_NUM_OF_DTIM_SKIP 0 + +//! WMM PS parameters +//! set wmm enable or disable +#define RSI_WMM_PS_ENABLE RSI_DISABLE + +//! set wmm enable or disable +//! 0- TX BASED 1 - PERIODIC +#define RSI_WMM_PS_TYPE 0 + +//! set wmm wake up interval +#define RSI_WMM_PS_WAKE_INTERVAL 20 + +//! set wmm UAPSD bitmap +#define RSI_WMM_PS_UAPSD_BITMAP 15 + +/*=======================================================================*/ +//! Socket configuration +/*=======================================================================*/ +//! RSI_ENABLE or RSI_DISABLE High performance socket +#define HIGH_PERFORMANCE_ENABLE RSI_ENABLE //@ RSI_ENABLE or RSI_DISABLE High performance socket +#define TOTAL_SOCKETS 10 //@ Total number of sockets. TCP TX + TCP RX + UDP TX + UDP RX +#define TOTAL_TCP_SOCKETS 4 //@ Total TCP sockets. TCP TX + TCP RX +#define TOTAL_UDP_SOCKETS 4 //@ Total UDP sockets. UDP TX + UDP RX +#define TCP_TX_ONLY_SOCKETS 0 //@ Total TCP TX only sockets. TCP TX +#define TCP_RX_ONLY_SOCKETS 0 //@ Total TCP RX only sockets. TCP RX +#define UDP_TX_ONLY_SOCKETS 0 //@ Total UDP TX only sockets. UDP TX +#define UDP_RX_ONLY_SOCKETS 0 //@ Total UDP RX only sockets. UDP RX +#define TCP_RX_HIGH_PERFORMANCE_SOCKETS 1 //@ Total TCP RX High Performance sockets +#define TCP_RX_WINDOW_SIZE_CAP 10 //@ TCP RX Window size +#define TCP_RX_WINDOW_DIV_FACTOR 10 //@ TCP RX Window division factor +/*=======================================================================*/ + +//! Socket Create parameters +/*=======================================================================*/ + +//! Initial timeout for Socket +#define RSI_SOCKET_KEEPALIVE_TIMEOUT 1200 + +//! VAP ID for Concurrent mode +#define RSI_VAP_ID 0 + +//! Timeout for join or scan +/*=======================================================================*/ + +//! RSI_ENABLE or RSI_DISABLE Timeout support +#define RSI_TIMEOUT_SUPPORT RSI_DISABLE + +//! roaming threshold value +#define RSI_TIMEOUT_BIT_MAP 1 + +//! roaming hysterisis value +#define RSI_TIMEOUT_VALUE 1500 + +//! Timeout for ping request +/*=======================================================================*/ + +//! Timeout for PING_REQUEST +#define RSI_PING_REQ_TIMEOUT_MS 1000 + +//! Provide HTTP/HTTPS response status code indication to application e.g 200, 404 etc +/*=======================================================================*/ +//! Enable or Diable feature +#define RSI_HTTP_STATUS_INDICATION_EN RSI_DISABLE +/*=======================================================================*/ + +//! Store Config Profile parameters +/*=======================================================================*/ + +//! Client profile +#define RSI_WLAN_PROFILE_CLIENT 0 +//! P2P profile +#define RSI_WLAN_PROFILE_P2P 1 +//! EAP profile +#define RSI_WLAN_PROFILE_EAP 2 +//! AP profile +#define RSI_WLAN_PROFILE_AP 6 +//! All profiles +#define RSI_WLAN_PROFILE_ALL 0xFF + +//! AP Config Profile Parameters +/*==============================================================================*/ + +//! Transmission data rate. Physical rate at which data has to be transmitted. +#define RSI_CONFIG_AP_DATA_RATE RSI_DATA_RATE_AUTO +//! To set wlan feature select bit map +#define RSI_CONFIG_AP_WLAN_FEAT_BIT_MAP (FEAT_SECURITY_PSK) +//! TCP/IP feature select bitmap for selecting TCP/IP features +#define RSI_CONFIG_AP_TCP_IP_FEAT_BIT_MAP (TCP_IP_FEAT_DHCPV4_SERVER) +//! To set custom feature select bit map +#define RSI_CONFIG_AP_CUSTOM_FEAT_BIT_MAP 0 +//! Tx power level +#define RSI_CONFIG_AP_TX_POWER RSI_POWER_LEVEL_HIGH +//! AP SSID +#define RSI_CONFIG_AP_SSID "SILABS_AP" +//! RSI_BAND_2P4GHZ(2.4GHz) or RSI_BAND_5GHZ(5GHz) or RSI_DUAL_BAND +#define RSI_CONFIG_AP_BAND RSI_BAND_2P4GHZ +//! To configure AP channle number +#define RSI_CONFIG_AP_CHANNEL 6 +//! To configure security type +#define RSI_CONFIG_AP_SECURITY_TYPE RSI_WPA +//! To configure encryption type +#define RSI_CONFIG_AP_ENCRYPTION_TYPE 1 +//! To configure PSK +#define RSI_CONFIG_AP_PSK "1234567890" +//! To configure beacon interval +#define RSI_CONFIG_AP_BEACON_INTERVAL 100 +//! To configure DTIM period +#define RSI_CONFIG_AP_DTIM 2 +//! This parameter is used to configure keep alive type +#define RSI_CONFIG_AP_KEEP_ALIVE_TYPE 0 //! RSI_NULL_BASED_KEEP_ALIVE + +#define RSI_CONFIG_AP_KEEP_ALIVE_COUNTER 0 //! 100 +//! This parameter is used to configure keep alive period +#define RSI_CONFIG_AP_KEEP_ALIVE_PERIOD 100 +//! This parameter is used to configure maximum stations supported +#define RSI_CONFIG_AP_MAX_STATIONS_COUNT 4 +//! P2P Network parameters +//! TCP_STACK_USED BIT(0) - IPv4, BIT(1) -IPv6, (BIT(0) | BIT(1)) - Both IPv4 and IPv6 +#define RSI_CONFIG_AP_TCP_STACK_USED BIT(0) +//! IP address of the module +//! E.g: 0x0A0AA8C0 == 192.168.10.10 +#define RSI_CONFIG_AP_IP_ADDRESS 0x0A0AA8C0 +//! IP address of netmask +//! E.g: 0x00FFFFFF == 255.255.255.0 +#define RSI_CONFIG_AP_SN_MASK_ADDRESS 0x00FFFFFF +//! IP address of Gateway +//! E.g: 0x0A0AA8C0 == 192.168.10.10 +#define RSI_CONFIG_AP_GATEWAY_ADDRESS 0x0A0AA8C0 + +//! Client Profile Parameters +/* ===================================================================================== */ + +//! To configure data rate +#define RSI_CONFIG_CLIENT_DATA_RATE RSI_DATA_RATE_AUTO +//! To configure wlan feature bitmap +#define RSI_CONFIG_CLIENT_WLAN_FEAT_BIT_MAP 0 +//! To configure tcp/ip feature bitmap +#define RSI_CONFIG_CLIENT_TCP_IP_FEAT_BIT_MAP BIT(2) +//! To configure custom feature bit map +#define RSI_CONFIG_CLIENT_CUSTOM_FEAT_BIT_MAP 0 +//! To configure TX power +#define RSI_CONFIG_CLIENT_TX_POWER RSI_POWER_LEVEL_HIGH +//! To configure listen interval +#define RSI_CONFIG_CLIENT_LISTEN_INTERVAL 0 +//! To configure SSID +#define RSI_CONFIG_CLIENT_SSID "Matter_9116" +//! RSI_BAND_2P4GHZ(2.4GHz) or RSI_BAND_5GHZ(5GHz) or RSI_DUAL_BAND +#define RSI_CONFIG_CLIENT_BAND RSI_BAND_2P4GHZ +//! To configure channel number +#define RSI_CONFIG_CLIENT_CHANNEL 0 +//! To configure security type +#define RSI_CONFIG_CLIENT_SECURITY_TYPE 0 // RSI_WPA +//! To configure encryption type +#define RSI_CONFIG_CLIENT_ENCRYPTION_TYPE 0 +//! To configure PSK +#define RSI_CONFIG_CLIENT_PSK "1234567890" +//! To configure PMK +#define RSI_CONFIG_CLIENT_PMK "" +//! Client Network parameters +//! TCP_STACK_USED BIT(0) - IPv4, BIT(1) -IPv6, (BIT(0) | BIT(1)) - Both IPv4 and IPv6 +#define RSI_CONFIG_CLIENT_TCP_STACK_USED BIT(0) +//! DHCP mode 1- Enable 0- Disable +//! If DHCP mode is disabled given IP statically +#define RSI_CONFIG_CLIENT_DHCP_MODE RSI_DHCP +//! IP address of the module +//! E.g: 0x0A0AA8C0 == 192.168.10.10 +#define RSI_CONFIG_CLIENT_IP_ADDRESS 0x0A0AA8C0 +//! IP address of netmask +//! E.g: 0x00FFFFFF == 255.255.255.0 +#define RSI_CONFIG_CLIENT_SN_MASK_ADDRESS 0x00FFFFFF +//! IP address of Gateway +//! E.g: 0x010AA8C0 == 192.168.10.1 +#define RSI_CONFIG_CLIENT_GATEWAY_ADDRESS 0x010AA8C0 +//! scan channel bit map in 2.4GHz band,valid if given channel to scan is 0 +#define RSI_CONFIG_CLIENT_SCAN_FEAT_BITMAP 0 +//! Scan channel magic code +#define RSI_CONFIG_CLIENT_MAGIC_CODE 0x4321 +//! scan channel bit map in 2.4GHz band,valid if given channel to scan is 0 +#define RSI_CONFIG_CLIENT_SCAN_CHAN_BITMAP_2_4_GHZ 0 +//! scan channle bit map in 5GHz band ,valid if given channel to scan is 0 +#define RSI_CONFIG_CLIENT_SCAN_CHAN_BITMAP_5_0_GHZ 0 + +//! EAP Client Profile Parameters +/* =========================================================================== */ + +//! To configure data rate +#define RSI_CONFIG_EAP_DATA_RATE RSI_DATA_RATE_AUTO +//! To configure wlan feature bitmap +#define RSI_CONFIG_EAP_WLAN_FEAT_BIT_MAP 0 +//! To configure tcp/ip feature bitmap +#define RSI_CONFIG_EAP_TCP_IP_FEAT_BIT_MAP BIT(2) +//! To configure custom feature bit map +#define RSI_CONFIG_EAP_CUSTOM_FEAT_BIT_MAP 0 +//! To configure EAP TX power +#define RSI_CONFIG_EAP_TX_POWER RSI_POWER_LEVEL_HIGH +//! To Configure scan channel feature bitmap +#define RSI_CONFIG_EAP_SCAN_FEAT_BITMAP 0 +//! scan channel bit map in 2.4GHz band,valid if given channel to scan is 0 +#define RSI_CONFIG_EAP_CHAN_MAGIC_CODE 0 // 0x4321 +//! scan channel bit map in 2.4GHz band,valid if given channel to scan is 0 +#define RSI_CONFIG_EAP_SCAN_CHAN_BITMAP_2_4_GHZ 0 +//! scan channle bit map in 5GHz band ,valid if given channel to scan is 0 +#define RSI_CONFIG_EAP_SCAN_CHAN_BITMAP_5_0_GHZ 0 +//! To configure SSID +#define RSI_CONFIG_EAP_SSID "SILABS_AP" +//! RSI_BAND_2P4GHZ(2.4GHz) or RSI_BAND_5GHZ(5GHz) or RSI_DUAL_BAND +#define RSI_CONFIG_EAP_BAND RSI_BAND_2P4GHZ +//! To set security type +#define RSI_CONFIG_EAP_SECURITY_TYPE RSI_WPA2_EAP +//! To set encryption type +#define RSI_CONFIG_EAP_ENCRYPTION_TYPE 0 +//! To set channel number +#define RSI_CONFIG_EAP_CHANNEL 0 +//! Enterprise method ,should be one of among TLS, TTLS, FAST or PEAP +#define RSI_CONFIG_EAP_METHOD "TLS" +//! This parameter is used to configure the module in Enterprise security mode +#define RSI_CONFIG_EAP_INNER_METHOD "\"auth=MSCHAPV2\"" +//! To configure EAP user identity +#define RSI_CONFIG_EAP_USER_IDENTITY "\"user1\"" +//! TO configure EAP password +#define RSI_CONFIG_EAP_PASSWORD "\"test123\"" +//! EAP Network parameters +//! TCP_STACK_USED BIT(0) - IPv4, BIT(1) -IPv6, (BIT(0) | BIT(1)) - Both IPv4 and IPv6 +#define RSI_CONFIG_EAP_TCP_STACK_USED BIT(0) +//! DHCP mode 1- Enable 0- Disable +//! If DHCP mode is disabled given IP statically +#define RSI_CONFIG_EAP_DHCP_MODE RSI_DHCP +//! IP address of the module +//! E.g: 0x0A0AA8C0 == 192.168.10.10 +#define RSI_CONFIG_EAP_IP_ADDRESS 0x0A0AA8C0 +//! IP address of netmask +//! E.g: 0x00FFFFFF == 255.255.255.0 +#define RSI_CONFIG_EAP_SN_MASK_ADDRESS 0x00FFFFFF +//! IP address of Gateway +//! E.g: 0x010AA8C0 == 192.168.10.1 +#define RSI_CONFIG_EAP_GATEWAY_ADDRESS 0x010AA8C0 + +//! P2P Profile parameters +/* ================================================================================= */ + +//! To configure data rate +#define RSI_CONFIG_P2P_DATA_RATE RSI_DATA_RATE_AUTO +//! To configure wlan feature bitmap +#define RSI_CONFIG_P2P_WLAN_FEAT_BIT_MAP 0 +//! To configure P2P tcp/ip feature bitmap +#define RSI_CONFIG_P2P_TCP_IP_FEAT_BIT_MAP BIT(2) +//! To configure P2P custom feature bitmap +#define RSI_CONFIG_P2P_CUSTOM_FEAT_BIT_MAP 0 +//! TO configure P2P tx power level +#define RSI_CONFIG_P2P_TX_POWER RSI_POWER_LEVEL_HIGH +//! Set P2P go intent +#define RSI_CONFIG_P2P_GO_INTNET 16 //! Support only Autonomous GO mode +//! Set device name +#define RSI_CONFIG_P2P_DEVICE_NAME "WSC1.1" +//! Set device operating channel +#define RSI_CONFIG_P2P_OPERATING_CHANNEL 11 +//! Set SSID postfix +#define RSI_CONFIG_P2P_SSID_POSTFIX "WSC_1_0_0" +//! Set P2P join SSID +#define RSI_CONFIG_P2P_JOIN_SSID "SILABS_AP" +//! Set psk key +#define RSI_CONFIG_P2P_PSK_KEY "12345678" +//! P2P Network parameters +//! TCP_STACK_USED BIT(0) - IPv4, BIT(1) -IPv6, (BIT(0) | BIT(1)) - Both IPv4 and IPv6 +#define RSI_CONFIG_P2P_TCP_STACK_USED BIT(0) +//! DHCP mode 1- Enable 0- Disable +//! If DHCP mode is disabled given IP statically +#define RSI_CONFIG_P2P_DHCP_MODE 1 +//! IP address of the module +//! E.g: 0x0A0AA8C0 == 192.168.10.10 +#define RSI_CONFIG_P2P_IP_ADDRESS 0x0A0AA8C0 +//! IP address of netmask +//! E.g: 0x00FFFFFF == 255.255.255.0 +#define RSI_CONFIG_P2P_SN_MASK_ADDRESS 0x00FFFFFF +//! IP address of Gateway +//! E.g: 0x010AA8C0 == 192.168.10.1 +#define RSI_CONFIG_P2P_GATEWAY_ADDRESS 0x010AA8C0 + +#endif diff --git a/examples/platform/efr32/rs911x/wfx_rsi.h b/examples/platform/efr32/rs911x/wfx_rsi.h new file mode 100644 index 00000000000000..5899a0c45bc31e --- /dev/null +++ b/examples/platform/efr32/rs911x/wfx_rsi.h @@ -0,0 +1,96 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef _WFX_RSI_H_ +#define _WFX_RSI_H_ +/* + * Interface to RSI Sapis + */ + +#define WFX_RSI_WLAN_TASK_SZ (1024 + 512 + 256) /* Unknown how big this should be */ +#define WFX_RSI_TASK_SZ (1024 + 1024) /* Stack for the WFX/RSI task */ +#define WFX_RSI_BUF_SZ (1024 * 10) /* May need tweak */ +#define WFX_RSI_CONFIG_MAX_JOIN 5 /* Max join retries */ +#define WFX_RSI_NUM_TIMERS 2 /* Number of RSI timers to alloc */ + +/* + * Various events fielded by the wfx_rsi task + * Make sure that we only use 8 bits (otherwise freeRTOS - may need some changes) + */ +#define WFX_EVT_STA_CONN 0x01 +#define WFX_EVT_STA_DISCONN 0x02 +#define WFX_EVT_AP_START 0x04 +#define WFX_EVT_AP_STOP 0x08 +#define WFX_EVT_SCAN 0x10 /* This is used as scan result and start */ +#define WFX_EVT_STA_START_JOIN 0x20 +#define WFX_EVT_STA_DO_DHCP 0x40 +#define WFX_EVT_STA_DHCP_DONE 0x80 + +#define WFX_RSI_ST_DEV_READY 0x01 +#define WFX_RSI_ST_AP_READY 0x02 +#define WFX_RSI_ST_STA_PROVISIONED 0x04 +#define WFX_RSI_ST_STA_CONNECTING 0x08 +#define WFX_RSI_ST_STA_CONNECTED 0x10 +#define WFX_RSI_ST_STA_DHCP_DONE 0x40 /* Requested to do DHCP after conn */ +#define WFX_RSI_ST_STA_MODE 0x80 /* Enable Station Mode */ +#define WFX_RSI_ST_AP_MODE 0x100 /* Enable AP Mode */ +#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 */ + +struct wfx_rsi +{ + EventGroupHandle_t events; + TaskHandle_t drv_task; + TaskHandle_t wlan_task; + uint16_t dev_state; + uint16_t ap_chan; /* The chan our STA is using */ + wfx_wifi_provision_t sec; +#ifdef SL_WFX_CONFIG_SCAN + void (*scan_cb)(wfx_wifi_scan_result_t *); + char * scan_ssid; /* Which one are we scanning for */ +#endif +#ifdef SL_WFX_CONFIG_SOFTAP + sl_wfx_mac_address_t softap_mac; +#endif + sl_wfx_mac_address_t sta_mac; + sl_wfx_mac_address_t ap_mac; /* To which our STA is connected */ + sl_wfx_mac_address_t ap_bssid; /* To which our STA is connected */ + uint16_t join_retries; + uint8_t ip4_addr[4]; /* Not sure if this is enough */ +}; +#define RSI_SCAN_RESP_SZ 54 + +extern struct wfx_rsi wfx_rsi; +#ifdef __cplusplus +extern "C" { +#endif +void wfx_rsidev_init(void); +void wfx_rsi_task(void * arg); +void efr32Log(const char * aFormat, ...); +void wfx_ip_changed_notify(int got_ip); +int32_t wfx_rsi_get_ap_info(wfx_wifi_scan_result_t * ap); +int32_t wfx_rsi_get_ap_ext(wfx_wifi_scan_ext_t * extra_info); +int32_t wfx_rsi_reset_count(); +int32_t wfx_rsi_disconnect(); +#define WFX_RSI_LOG(...) efr32Log(__VA_ARGS__); + +#ifdef __cplusplus +} +#endif + +#endif /* _WFX_RSI_H_ */ diff --git a/examples/platform/efr32/rs911x/wfx_rsi_host.c b/examples/platform/efr32/rs911x/wfx_rsi_host.c new file mode 100644 index 00000000000000..2a502356e6ae66 --- /dev/null +++ b/examples/platform/efr32/rs911x/wfx_rsi_host.c @@ -0,0 +1,439 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include +#include +#include + +#include "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" +#include "sl_status.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "wfx_host_events.h" +#include "wfx_rsi.h" + +/* wfxRsi Task will use as its stack */ +StackType_t wfxRsiTaskStack[WFX_RSI_TASK_SZ] = { 0 }; + +/* Structure that will hold the TCB of the wfxRsi Task being created. */ +StaticTask_t wfxRsiTaskBuffer; + +/********************************************************************* + * @fn sl_status_t wfx_wifi_start(void) + * @brief + * Called from ConnectivityManagerImpl.cpp - to enable the device + * Create the RSI task and let it deal with life. + * @param[in] None + * @return Returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + ***********************************************************************/ +sl_status_t wfx_wifi_start(void) +{ + if (wfx_rsi.dev_state & WFX_RSI_ST_STARTED) + { + WFX_RSI_LOG("%s: already started.", __func__); + return SL_STATUS_OK; + } + wfx_rsi.dev_state |= WFX_RSI_ST_STARTED; + WFX_RSI_LOG("%s: starting..", __func__); + /* + * Create the Wifi driver task + */ + wfx_rsi.wlan_task = xTaskCreateStatic(wfx_rsi_task, "wfx_rsi", WFX_RSI_TASK_SZ, NULL, WLAN_DRIVER_TASK_PRIORITY, + wfxRsiTaskStack, &wfxRsiTaskBuffer); + + if (NULL == wfx_rsi.wlan_task) + { + WFX_RSI_LOG("%s: error: failed to create task.", __func__); + return SL_STATUS_FAIL; + } + return SL_STATUS_OK; +} + +/********************************************************************* + * @fn void wfx_enable_sta_mode(void) + * @brief + * driver enable the STA mode + * @param[in] None + * @return None + ***********************************************************************/ +void wfx_enable_sta_mode(void) +{ + wfx_rsi.dev_state |= WFX_RSI_ST_STA_MODE; +} + +/********************************************************************* + * @fn bool wfx_is_sta_mode_enabled(void) + * @brief + * driver enabled the STA mode + * @param[in] None + * @return mode + ***********************************************************************/ +bool wfx_is_sta_mode_enabled(void) +{ + bool mode; + mode = !!(wfx_rsi.dev_state & WFX_RSI_ST_STA_MODE); + // WFX_RSI_LOG("%s: %d", __func__, (mode ? "yes" : "no")); + return mode; +} + +/********************************************************************* + * @fn sl_wfx_state_t wfx_get_wifi_state(void) + * @brief + * get the wifi state + * @param[in] None + * @return return SL_WFX_NOT_INIT if successful, + * SL_WFX_started otherwise + ***********************************************************************/ +sl_wfx_state_t wfx_get_wifi_state(void) +{ + if (wfx_rsi.dev_state & WFX_RSI_ST_STA_DHCP_DONE) + { + return SL_WFX_STA_INTERFACE_CONNECTED; + } + if (wfx_rsi.dev_state & WFX_RSI_ST_DEV_READY) + { + return SL_WFX_STARTED; + } + return SL_WFX_NOT_INIT; +} + +/********************************************************************* + * @fn sl_wfx_state_t wfx_get_wifi_state(void) + * @brief + * get the wifi mac address + * @param[in] Interface: + * @param[in] addr : address + * @return + * None + ***********************************************************************/ +void wfx_get_wifi_mac_addr(sl_wfx_interface_t interface, sl_wfx_mac_address_t * addr) +{ + sl_wfx_mac_address_t * mac; + +#ifdef SL_WFX_CONFIG_SOFTAP + mac = (interface == SL_WFX_SOFTAP_INTERFACE) ? &wfx_rsi.softap_mac : &wfx_rsi.sta_mac; +#else + mac = &wfx_rsi.sta_mac; +#endif + *addr = *mac; + WFX_RSI_LOG("%s: %02x:%02x:%02x:%02x:%02x:%02x", __func__, mac->octet[0], mac->octet[1], mac->octet[2], mac->octet[3], + mac->octet[4], mac->octet[5]); +} + +/********************************************************************* + * @fn void wfx_set_wifi_provision(wfx_wifi_provision_t *cfg) + * @brief + * Driver set the wifi provision + * @param[in] cfg: wifi configuration + * @return + * None + ***********************************************************************/ +void wfx_set_wifi_provision(wfx_wifi_provision_t * cfg) +{ + WFX_RSI_LOG("%s: SSID: %s", __func__, &wfx_rsi.sec.ssid[0]); + + wfx_rsi.sec = *cfg; + wfx_rsi.dev_state |= WFX_RSI_ST_STA_PROVISIONED; +} + +/********************************************************************* + * @fn bool wfx_get_wifi_provision(wfx_wifi_provision_t *wifiConfig) + * @brief + * Driver get the wifi provision + * @param[in] wifiConfig: wifi configuration + * @return return false if successful, + * true otherwise + ***********************************************************************/ +bool wfx_get_wifi_provision(wfx_wifi_provision_t * wifiConfig) +{ + if (wifiConfig != NULL) + { + if (wfx_rsi.dev_state & WFX_RSI_ST_STA_PROVISIONED) + { + *wifiConfig = wfx_rsi.sec; + return true; + } + } + return false; +} + +/********************************************************************* + * @fn bool wfx_is_sta_provisioned(void) + * @brief + * Driver is STA provisioned + * @param[in] None + * @return None + ***********************************************************************/ +bool wfx_is_sta_provisioned(void) +{ + bool status = (wfx_rsi.dev_state & WFX_RSI_ST_STA_PROVISIONED) ? true : false; + WFX_RSI_LOG("%s: status: SSID -> %s: %s", __func__, &wfx_rsi.sec.ssid[0], (status ? "provisioned" : "not provisioned")); + return status; +} + +/********************************************************************* + * @fn void wfx_clear_wifi_provision(void) + * @brief + * Driver is clear the wifi provision + * @param[in] None + * @return None + ***********************************************************************/ +void wfx_clear_wifi_provision(void) +{ + memset(&wfx_rsi.sec, 0, sizeof(wfx_rsi.sec)); + wfx_rsi.dev_state &= ~WFX_RSI_ST_STA_PROVISIONED; + WFX_RSI_LOG("%s: completed.", __func__); +} + +/************************************************************************* + * @fn sl_status_t wfx_connect_to_ap(void) + * @brief + * Start a JOIN command to the AP - Done by the wfx_rsi task + * @param[in] None + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_INVALID_CONFIGURATION otherwise + ****************************************************************************/ +sl_status_t wfx_connect_to_ap(void) +{ + if (wfx_rsi.dev_state & WFX_RSI_ST_STA_PROVISIONED) + { + WFX_RSI_LOG("%s: connecting to access point -> SSID: %s, PSK:%s", __func__, &wfx_rsi.sec.ssid[0], &wfx_rsi.sec.passkey[0]); + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_STA_START_JOIN); + } + else + { + WFX_RSI_LOG("%s: error: access point not provisioned", __func__); + return SL_STATUS_INVALID_CONFIGURATION; + } + return SL_STATUS_OK; +} + +/********************************************************************* + * @fn void wfx_setup_ip6_link_local(sl_wfx_interface_t whichif) + * @brief + * Implement the ipv6 setup + * @param[in] whichif: + * @return None + ***********************************************************************/ +void wfx_setup_ip6_link_local(sl_wfx_interface_t whichif) +{ + /* + * TODO: Implement IPV6 setup, currently in wfx_rsi_task() + * This is hooked with MATTER code. + */ + WFX_RSI_LOG("%s: warning: not implemented.", __func__); +} + +/********************************************************************* + * @fn bool wfx_is_sta_connected(void) + * @brief + * called fuction when driver is connected to STA + * @param[in] None + * @return returns ture if successful, + * false otherwise + ***********************************************************************/ +bool wfx_is_sta_connected(void) +{ + bool status; + status = (wfx_rsi.dev_state & WFX_RSI_ST_STA_CONNECTED) ? true : false; + WFX_RSI_LOG("%s: status: %s", __func__, (status ? "connected" : "not connected")); + return status; +} + +/********************************************************************* + * @fn wifi_mode_t wfx_get_wifi_mode() + * @brief + * get the wifi mode + * @param[in] None + * @return return WIFI_MODE_NULL if successful, + * WIFI_MODE_STA otherwise + ***********************************************************************/ +wifi_mode_t wfx_get_wifi_mode() +{ + if (wfx_rsi.dev_state & WFX_RSI_ST_DEV_READY) + return WIFI_MODE_STA; + return WIFI_MODE_NULL; +} + +/********************************************************************* + * @fn sl_status_t wfx_sta_discon(void) + * @brief + * called fuction when STA disconnected + * @param[in] None + * @return return SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + ***********************************************************************/ +sl_status_t wfx_sta_discon(void) +{ + WFX_RSI_LOG("%s: started.", __func__); + int32_t status; + status = wfx_rsi_disconnect(); + wfx_rsi.dev_state &= ~WFX_RSI_ST_STA_CONNECTED; + WFX_RSI_LOG("%s: completed.", __func__); + return status; +} + +/********************************************************************* + * @fn bool wfx_have_ipv4_addr(sl_wfx_interface_t which_if) + * @brief + * called fuction when driver have ipv4 address + * @param[in] which_if: + * @return returns ture if successful, + * false otherwise + ***********************************************************************/ +bool wfx_have_ipv4_addr(sl_wfx_interface_t which_if) +{ + bool status = false; + if (which_if == SL_WFX_STA_INTERFACE) + { + status = (wfx_rsi.dev_state & WFX_RSI_ST_STA_DHCP_DONE) ? true : false; + } + else + { + status = false; /* TODO */ + } + WFX_RSI_LOG("%s: status: %d", __func__, status); + return status; +} + +/********************************************************************* + * @fn bool wfx_have_ipv6_addr(sl_wfx_interface_t which_if) + * @brief + * called fuction when driver have ipv6 address + * @param[in] which_if: + * @return returns ture if successful, + * false otherwise + ***********************************************************************/ +bool wfx_have_ipv6_addr(sl_wfx_interface_t which_if) +{ + bool status = false; + if (which_if == SL_WFX_STA_INTERFACE) + { + status = (wfx_rsi.dev_state & WFX_RSI_ST_STA_CONNECTED) ? true : false; + } + else + { + status = false; /* TODO */ + } + WFX_RSI_LOG("%s: status: %d", __func__, status); + return status; +} + +/********************************************************************* + * @fn bool wfx_hw_ready(void) + * @brief + * called fuction when driver ready + * @param[in] None + * @return returns ture if successful, + * false otherwise + ***********************************************************************/ +bool wfx_hw_ready(void) +{ + return (wfx_rsi.dev_state & WFX_RSI_ST_DEV_READY) ? true : false; +} + +/********************************************************************* + * @fn int32_t wfx_get_ap_info(wfx_wifi_scan_result_t *ap) + * @brief + * get the access point information + * @param[in] ap: access point + * @return + * access point information + ***********************************************************************/ +int32_t wfx_get_ap_info(wfx_wifi_scan_result_t * ap) +{ + return wfx_rsi_get_ap_info(ap); +} + +/********************************************************************* + * @fn int32_t wfx_get_ap_ext(wfx_wifi_scan_ext_t *extra_info) + * @brief + * get the access point extra information + * @param[in] extra_info:access point extra information + * @return + * access point extra information + ***********************************************************************/ +int32_t wfx_get_ap_ext(wfx_wifi_scan_ext_t * extra_info) +{ + return wfx_rsi_get_ap_ext(extra_info); +} + +/*************************************************************************** + * @fn int32_t wfx_reset_counts(){ + * @brief + * get the driver reset count + * @param[in] None + * @return + * reset count + *****************************************************************************/ +int32_t wfx_reset_counts() +{ + return wfx_rsi_reset_count(); +} + +#ifdef SL_WFX_CONFIG_SCAN +/******************************************************************************* + * @fn bool wfx_start_scan(char *ssid, void (*callback)(wfx_wifi_scan_result_t *)) + * @brief + * called fuction when driver start scaning + * @param[in] ssid: + * @return returns ture if successful, + * false otherwise + *******************************************************************************/ +bool wfx_start_scan(char * ssid, void (*callback)(wfx_wifi_scan_result_t *)) +{ + int sz; + + if (wfx_rsi.scan_cb) + return false; /* Already in progress */ + if (ssid) + { + sz = strlen(ssid); + if ((wfx_rsi.scan_ssid = (char *) pvPortMalloc(sz + 1)) == (char *) 0) + { + return false; + } + strcpy(wfx_rsi.scan_ssid, ssid); + } + wfx_rsi.scan_cb = callback; + xEventGroupSetBits(wfx_rsi.events, WFX_EVT_SCAN); + + return true; +} + +/*************************************************************************** + * @fn void wfx_cancel_scan(void) + * @brief + * called function when driver cancel scaning + * @param[in] None + * @return + * None + *****************************************************************************/ +void wfx_cancel_scan(void) +{ + /* Not possible */ + WFX_RSI_LOG("%s: cannot cancel scan", __func__); +} +#endif /* SL_WFX_CONFIG_SCAN */ diff --git a/examples/platform/efr32/rs911x/wfx_rsidev.c b/examples/platform/efr32/rs911x/wfx_rsidev.c new file mode 100644 index 00000000000000..2e1b40d41260d5 --- /dev/null +++ b/examples/platform/efr32/rs911x/wfx_rsidev.c @@ -0,0 +1,272 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifdef _WFX_NOT_USED_USING_HAL_INSTEAD_ +#include +#include +#include + +#include "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" +#include "gpiointerrupt.h" + +/* Need Lwip stuff before rsi is included */ +#include "wfx_host_events.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "rsi_common_apis.h" +#include "rsi_data_types.h" +#include "rsi_error.h" +#include "rsi_nwk.h" +#include "rsi_socket.h" +#include "rsi_utils.h" +#include "rsi_wlan.h" +#include "rsi_wlan_apis.h" +#include "rsi_wlan_config.h" +#include "task.h" + +#include "wfx_host_pinout.h" +#include "wfx_rsi.h" + +/* The following stuff comes from hal/rsi_hal_mcu_interrupt.c */ +static void (*rsi_intr_cb)(void); +/********************************************************************* + * @fn void rsi_hal_intr_config(void (*rsi_interrupt_handler)(void)) + * @brief + * get the hal intr configuration + * @param[in] rsi_interrupt_handler: + * @return + * None + ***********************************************************************/ +void rsi_hal_intr_config(void (*rsi_interrupt_handler)(void)) +{ + rsi_intr_cb = rsi_interrupt_handler; +} + +/*********************************************************************** + * @fn static void wfx_spi_wakeup_irq_callback(uint8_t irqNumber) + * @brief + * end of stuff from hal/rsi_hal_mcu_interrupt.c + * @param[in] irqNumber: + * @return None + * **********************************************************************/ +static void wfx_spi_wakeup_irq_callback(uint8_t irqNumber) +{ + BaseType_t bus_task_woken; + uint32_t interrupt_mask; + + if (irqNumber != SL_WFX_HOST_PINOUT_SPI_IRQ) + return; + // Get and clear all pending GPIO interrupts + interrupt_mask = GPIO_IntGet(); + GPIO_IntClear(interrupt_mask); + if (rsi_intr_cb) + (*rsi_intr_cb)(); +} + +/*********************************************************************** + * @fn static void wfx_host_gpio_init(void) + * @brief + * function called when host gpio intialization + * @param[in] None + * @return None + * **********************************************************************/ +static void wfx_host_gpio_init(void) +{ + // Enable GPIO clock. + CMU_ClockEnable(cmuClock_GPIO, true); + + // Configure WF200 reset pin. + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_RESET_PORT, SL_WFX_HOST_PINOUT_RESET_PIN, gpioModePushPull, PINOUT_CLEAR); + // Configure WF200 WUP pin. + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_WUP_PORT, SL_WFX_HOST_PINOUT_WUP_PIN, gpioModePushPull, PINOUT_CLEAR); + + // GPIO used as IRQ. + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_SPI_WIRQ_PORT, SL_WFX_HOST_PINOUT_SPI_WIRQ_PIN, gpioModeInputPull, PINOUT_CLEAR); + CMU_OscillatorEnable(cmuOsc_LFXO, true, true); + + // Set up interrupt based callback function - trigger on both edges. + GPIOINT_Init(); + GPIO_ExtIntConfig(SL_WFX_HOST_PINOUT_SPI_WIRQ_PORT, SL_WFX_HOST_PINOUT_SPI_WIRQ_PIN, SL_WFX_HOST_PINOUT_SPI_IRQ, true, false, + true); + GPIOINT_CallbackRegister(SL_WFX_HOST_PINOUT_SPI_IRQ, wfx_spi_wakeup_irq_callback); + + // Change GPIO interrupt priority (FreeRTOS asserts unless this is done here!) + NVIC_SetPriority(GPIO_EVEN_IRQn, WFX_GPIO_NVIC_PRIORITY); + NVIC_SetPriority(GPIO_ODD_IRQn, WFX_GPIO_NVIC_PRIORITY); +} + +#define USART SL_WFX_HOST_PINOUT_SPI_PERIPHERAL + +/*********************************************************************** + * @fn static int sl_wfx_host_spi_set_config(void *usart) + * @brief + * set the configuration of spi + * @param[in] usart: + * @return returns 0 if sucessful, + * -1 otherwise + * **********************************************************************/ +static int sl_wfx_host_spi_set_config(void * usart) +{ + int ret = -1; + + if (0) + { +#if defined(USART0) + } + else if (usart == USART0) + { + usart_clock = cmuClock_USART0; + usart_tx_signal = dmadrvPeripheralSignal_USART0_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USART0_RXDATAV; + ret = 0; +#endif +#if defined(USART1) + } + else if (usart == USART1) + { + usart_clock = cmuClock_USART1; + usart_tx_signal = dmadrvPeripheralSignal_USART1_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USART1_RXDATAV; + ret = 0; +#endif +#if defined(USART2) + } + else if (usart == USART2) + { + usart_clock = cmuClock_USART2; + usart_tx_signal = dmadrvPeripheralSignal_USART2_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USART2_RXDATAV; + ret = 0; +#endif +#if defined(USART3) + } + else if (usart == USART3) + { + usart_clock = cmuClock_USART3; + usart_tx_signal = dmadrvPeripheralSignal_USART3_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USART3_RXDATAV; + ret = 0; +#endif +#if defined(USART4) + } + else if (usart == USART4) + { + usart_clock = cmuClock_USART4; + usart_tx_signal = dmadrvPeripheralSignal_USART4_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USART4_RXDATAV; + ret = 0; +#endif +#if defined(USART5) + } + else if (usart == USART5) + { + usart_clock = cmuClock_USART5; + usart_tx_signal = dmadrvPeripheralSignal_USART5_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USART5_RXDATAV; + ret = 0; +#endif +#if defined(USARTRF0) + } + else if (usart == USARTRF0) + { + usart_clock = cmuClock_USARTRF0; + usart_tx_signal = dmadrvPeripheralSignal_USARTRF0_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USARTRF0_RXDATAV; + ret = 0; +#endif +#if defined(USARTRF1) + } + else if (usart == USARTRF1) + { + usart_clock = cmuClock_USARTRF1; + usart_tx_signal = dmadrvPeripheralSignal_USARTRF1_TXBL; + usart_rx_signal = dmadrvPeripheralSignal_USARTRF1_RXDATAV; + ret = 0; +#endif + } + + return ret; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_init_bus(void) + * @brief + * Initialize SPI peripheral + * @param[in] None + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_init_bus(void) +{ + int res; + + // Initialize and enable the USART + USART_InitSync_TypeDef usartInit = USART_INITSYNC_DEFAULT; + + res = sl_wfx_host_spi_set_config(USART); + if (res != SPI_CONFIG_SUCESS) + { + return SL_STATUS_FAIL; + } + + spi_enabled = true; + dummy_tx_data = 0; + usartInit.baudrate = 36000000u; + usartInit.msbf = true; + CMU_ClockEnable(cmuClock_HFPER, true); + CMU_ClockEnable(cmuClock_GPIO, true); + CMU_ClockEnable(usart_clock, true); + USART_InitSync(USART, &usartInit); + USART->CTRL |= (1u << _USART_CTRL_SMSDELAY_SHIFT); + USART->ROUTELOC0 = + (USART->ROUTELOC0 & ~(_USART_ROUTELOC0_TXLOC_MASK | _USART_ROUTELOC0_RXLOC_MASK | _USART_ROUTELOC0_CLKLOC_MASK)) | + (SL_WFX_HOST_PINOUT_SPI_TX_LOC << _USART_ROUTELOC0_TXLOC_SHIFT) | + (SL_WFX_HOST_PINOUT_SPI_RX_LOC << _USART_ROUTELOC0_RXLOC_SHIFT) | + (SL_WFX_HOST_PINOUT_SPI_CLK_LOC << _USART_ROUTELOC0_CLKLOC_SHIFT); + + USART->ROUTEPEN = USART_ROUTEPEN_TXPEN | USART_ROUTEPEN_RXPEN | USART_ROUTEPEN_CLKPEN; + GPIO_DriveStrengthSet(SL_WFX_HOST_PINOUT_SPI_CLK_PORT, gpioDriveStrengthStrongAlternateStrong); + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_SPI_TX_PORT, SL_WFX_HOST_PINOUT_SPI_TX_PIN, gpioModePushPull, PINOUT_CLEAR); + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_SPI_RX_PORT, SL_WFX_HOST_PINOUT_SPI_RX_PIN, gpioModeInput, PINOUT_CLEAR); + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_SPI_CLK_PORT, SL_WFX_HOST_PINOUT_SPI_CLK_PIN, gpioModePushPull, PINOUT_CLEAR); + + DMADRV_Init(); + DMADRV_AllocateChannel(&tx_dma_channel, NULL); + DMADRV_AllocateChannel(&rx_dma_channel, NULL); + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_SPI_CS_PORT, SL_WFX_HOST_PINOUT_SPI_CS_PIN, gpioModePushPull, PINOUT_SET); + USART->CMD = USART_CMD_CLEARRX | USART_CMD_CLEARTX; + + return SL_STATUS_OK; +} + +/*********************************************************************** + * @fn void wfx_rsidev_init(void) + * @brief + * function called when driver rsidev intialization + * @param[in] None + * @return None + * **********************************************************************/ +void wfx_rsidev_init(void) +{ + wfx_host_gpio_init(); +} +#endif /* _NOT_USED */ diff --git a/examples/platform/efr32/wf200/efr_spi.c b/examples/platform/efr32/wf200/efr_spi.c new file mode 100644 index 00000000000000..d1d26c5b238bfa --- /dev/null +++ b/examples/platform/efr32/wf200/efr_spi.c @@ -0,0 +1,426 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include "sl_wfx_configuration_defaults.h" + +#include "sl_wfx.h" +#include "sl_wfx_board.h" +#include "sl_wfx_host_api.h" + +#include "dmadrv.h" +#include "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" +#include "spidrv.h" + +#include +#include +#include + +#include "FreeRTOS.h" +#include "semphr.h" +#ifdef SLEEP_ENABLED +#include "sl_power_manager.h" +#endif +#include "AppConfig.h" + +#include "gpiointerrupt.h" + +#include "sl_spidrv_exp_config.h" +#include "sl_wfx_board.h" +#include "sl_wfx_host.h" +#include "sl_wfx_task.h" +#include "wfx_host_events.h" + +extern SPIDRV_Handle_t sl_spidrv_exp_handle; + +#define USART SL_WFX_HOST_PINOUT_SPI_PERIPHERAL + +StaticSemaphore_t xEfrSpiSemaBuffer; +static SemaphoreHandle_t spi_sem; + +static unsigned int tx_dma_channel; +static unsigned int rx_dma_channel; + +static uint32_t dummy_rx_data; +static uint32_t dummy_tx_data; +static bool spi_enabled = false; + +#if defined(EFR32MG12) +uint8_t wirq_irq_nb = SL_WFX_HOST_PINOUT_SPI_IRQ; +#elif defined(EFR32MG24) +uint8_t wirq_irq_nb = SL_WFX_HOST_PINOUT_SPI_WIRQ_PIN; // SL_WFX_HOST_PINOUT_SPI_WIRQ_PIN; +#endif + +#define PIN_OUT_SET 1 +#define PIN_OUT_CLEAR 0 + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_init_bus(void) + * @brief + * Initialize SPI peripheral + * @param[in] None + * @return returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_init_bus(void) +{ + spi_enabled = true; + + /* Assign allocated DMA channel */ + tx_dma_channel = sl_spidrv_exp_handle->txDMACh; + rx_dma_channel = sl_spidrv_exp_handle->rxDMACh; + + /* + * Route EUSART1 MOSI, MISO, and SCLK to the specified pins. CS is + * not controlled by EUSART so there is no write to the corresponding + * EUSARTROUTE register to do this. + */ + MY_USART->CTRL |= (1u << _USART_CTRL_SMSDELAY_SHIFT); + +#if defined(EFR32MG12) + MY_USART->ROUTEPEN = USART_ROUTEPEN_TXPEN | USART_ROUTEPEN_RXPEN | USART_ROUTEPEN_CLKPEN; +#endif + +#if defined(EFR32MG24) + GPIO->USARTROUTE[0].ROUTEEN = GPIO_USART_ROUTEEN_RXPEN | // MISO + GPIO_USART_ROUTEEN_TXPEN | // MOSI + GPIO_USART_ROUTEEN_CLKPEN; +#endif + + spi_sem = xSemaphoreCreateBinaryStatic(&xEfrSpiSemaBuffer); + xSemaphoreGive(spi_sem); + + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_deinit_bus(void) + * @brief + * De-initialize SPI peripheral and DMAs + * @param[in] None + * @return returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_deinit_bus(void) +{ + vSemaphoreDelete(spi_sem); + // Stop DMAs. + DMADRV_StopTransfer(rx_dma_channel); + DMADRV_StopTransfer(tx_dma_channel); + DMADRV_FreeChannel(tx_dma_channel); + DMADRV_FreeChannel(rx_dma_channel); + DMADRV_DeInit(); + USART_Reset(MY_USART); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_spi_cs_assert() + * @brief + * Assert chip select. + * @param[in] None + * @return returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_spi_cs_assert() +{ + GPIO_PinOutClear(SL_SPIDRV_EXP_CS_PORT, SL_SPIDRV_EXP_CS_PIN); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_spi_cs_deassert() + * @brief + * De-Assert chip select. + * @param[in] None + * @return returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_spi_cs_deassert() +{ + GPIO_PinOutSet(SL_SPIDRV_EXP_CS_PORT, SL_SPIDRV_EXP_CS_PIN); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn static bool rx_dma_complete(unsigned int channel, unsigned int sequenceNo, void *userParam) + * @brief + * function called when the DMA complete + * @param[in] channel: + * @param[in] sequenceNo: sequence number + * @param[in] userParam: user parameter + * @return returns true if suucessful, + * false otherwise + *****************************************************************************/ +static bool rx_dma_complete(unsigned int channel, unsigned int sequenceNo, void * userParam) +{ + (void) channel; + (void) sequenceNo; + (void) userParam; + + BaseType_t xHigherPriorityTaskWoken = pdFALSE; + xSemaphoreGiveFromISR(spi_sem, &xHigherPriorityTaskWoken); + portYIELD_FROM_ISR(xHigherPriorityTaskWoken); + + return true; +} + +/**************************************************************************** + * @fn void receiveDMA(uint8_t *buffer, uint16_t buffer_length) + * @brief + * start receive DMA + * @param[in] buffer: + * @param[in] buffer_length: + * @return None + *****************************************************************************/ +void receiveDMA(uint8_t * buffer, uint16_t buffer_length) +{ + // Start receive DMA. + DMADRV_PeripheralMemory(rx_dma_channel, MY_USART_RX_SIGNAL, (void *) buffer, (void *) &(MY_USART->RXDATA), true, buffer_length, + dmadrvDataSize1, rx_dma_complete, NULL); + + // Start transmit DMA. + DMADRV_MemoryPeripheral(tx_dma_channel, MY_USART_TX_SIGNAL, (void *) &(MY_USART->TXDATA), (void *) &(dummy_tx_data), false, + buffer_length, dmadrvDataSize1, NULL, NULL); +} + +/**************************************************************************** + * @fn void transmitDMA(uint8_t *buffer, uint16_t buffer_length) + * @brief + * start transmit DMA + * @param[in] buffer: + * @param[in] buffer_length: + * @return None + *****************************************************************************/ +void transmitDMA(uint8_t * buffer, uint16_t buffer_length) +{ + // Receive DMA runs only to initiate callback + // Start receive DMA. + DMADRV_PeripheralMemory(rx_dma_channel, MY_USART_RX_SIGNAL, &dummy_rx_data, (void *) &(MY_USART->RXDATA), false, buffer_length, + dmadrvDataSize1, rx_dma_complete, NULL); + // Start transmit DMA. + DMADRV_MemoryPeripheral(tx_dma_channel, MY_USART_TX_SIGNAL, (void *) &(MY_USART->TXDATA), (void *) buffer, true, buffer_length, + dmadrvDataSize1, NULL, NULL); +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_spi_transfer_no_cs_assert(sl_wfx_host_bus_transfer_type_t type, + uint8_t *header, + uint16_t header_length, + uint8_t *buffer, + uint16_t buffer_length) + * @brief + * WFX SPI transfer implementation + * @param[in] type: + * @param[in] header: + * @param[in] header_length: + * @param[in] buffer: + * @param[in] buffer_length: + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_spi_transfer_no_cs_assert(sl_wfx_host_bus_transfer_type_t type, uint8_t * header, uint16_t header_length, + uint8_t * buffer, uint16_t buffer_length) +{ + sl_status_t result = SL_STATUS_FAIL; + const bool is_read = (type == SL_WFX_BUS_READ); + + while (!(MY_USART->STATUS & USART_STATUS_TXBL)) + { + } + MY_USART->CMD = USART_CMD_CLEARRX | USART_CMD_CLEARTX; + + /* header length should be greater than 0 */ + if (header_length > 0) + { + for (uint8_t * buffer_ptr = header; header_length > 0; --header_length, ++buffer_ptr) + { + MY_USART->TXDATA = (uint32_t)(*buffer_ptr); + + while (!(MY_USART->STATUS & USART_STATUS_TXC)) + { + } + } + while (!(MY_USART->STATUS & USART_STATUS_TXBL)) + { + } + } + + /* buffer length should be greater than 0 */ + if (buffer_length > 0) + { + MY_USART->CMD = USART_CMD_CLEARRX | USART_CMD_CLEARTX; + if (xSemaphoreTake(spi_sem, portMAX_DELAY) == pdTRUE) + { + if (is_read) + { + receiveDMA(buffer, buffer_length); + result = SL_STATUS_OK; + } + else + { + transmitDMA(buffer, buffer_length); + result = SL_STATUS_OK; + } + + if (xSemaphoreTake(spi_sem, portMAX_DELAY) == pdTRUE) + { + xSemaphoreGive(spi_sem); + } + } + else + { + result = SL_STATUS_TIMEOUT; + } + } + + return result; +} + +/**************************************************************************** + * @fn void sl_wfx_host_start_platform_interrupt(void) + * @brief + * Enable WFX interrupt + * @param[in] none + * @return None + *****************************************************************************/ +void sl_wfx_host_start_platform_interrupt(void) +{ + // Enable (and clear) the bus interrupt + GPIO_ExtIntConfig(SL_WFX_HOST_PINOUT_SPI_WIRQ_PORT, SL_WFX_HOST_PINOUT_SPI_WIRQ_PIN, wirq_irq_nb, true, false, true); +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_disable_platform_interrupt(void) + * @brief + * Disable WFX interrupt + * @param[in] None + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_disable_platform_interrupt(void) +{ + GPIO_IntDisable(1 << wirq_irq_nb); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_enable_platform_interrupt(void) + * @brief + * enable the platform interrupt + * @param[in] None + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_enable_platform_interrupt(void) +{ + GPIO_IntEnable(1 << wirq_irq_nb); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_enable_spi(void) + * @brief + * enable spi + * @param[in] None + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_enable_spi(void) +{ + if (spi_enabled == false) + { +#ifdef SLEEP_ENABLED + // Prevent the host to use lower EM than EM1 + sl_power_manager_add_em_requirement(SL_POWER_MANAGER_EM1); +#endif + spi_enabled = true; + } + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_disable_spi(void) + * @brief + * disable spi + * @param[in] None + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_disable_spi(void) +{ + if (spi_enabled == true) + { + spi_enabled = false; +#ifdef SLEEP_ENABLED + // Allow the host to use the lowest allowed EM + sl_power_manager_remove_em_requirement(SL_POWER_MANAGER_EM1); +#endif + } + return SL_STATUS_OK; +} + +/* + * IRQ for SPI callback + * Clear the Interrupt and wake up the task that + * handles the actions of the interrupt (typically - wfx_bus_task ()) + */ +static void sl_wfx_spi_wakeup_irq_callback(uint8_t irqNumber) +{ + BaseType_t bus_task_woken; + uint32_t interrupt_mask; + + if (irqNumber != wirq_irq_nb) + return; + // Get and clear all pending GPIO interrupts + interrupt_mask = GPIO_IntGet(); + GPIO_IntClear(interrupt_mask); + bus_task_woken = pdFALSE; + xSemaphoreGiveFromISR(wfx_wakeup_sem, &bus_task_woken); + vTaskNotifyGiveFromISR(wfx_bus_task_handle, &bus_task_woken); + portYIELD_FROM_ISR(bus_task_woken); +} + +/**************************************************************************** + * Init some actions pins to the WF-200 expansion board + *****************************************************************************/ +void sl_wfx_host_gpio_init(void) +{ + EFR32_LOG("WIFI: GPIO Init:IRQ=%d", wirq_irq_nb); + // Enable GPIO clock. + CMU_ClockEnable(cmuClock_GPIO, true); + + // Configure WF200 reset pin. + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_RESET_PORT, SL_WFX_HOST_PINOUT_RESET_PIN, gpioModePushPull, 0); + // Configure WF200 WUP pin. + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_WUP_PORT, SL_WFX_HOST_PINOUT_WUP_PIN, gpioModePushPull, 0); + + // GPIO used as IRQ. + GPIO_PinModeSet(SL_WFX_HOST_PINOUT_SPI_WIRQ_PORT, SL_WFX_HOST_PINOUT_SPI_WIRQ_PIN, gpioModeInputPull, 0); + CMU_OscillatorEnable(cmuOsc_LFXO, true, true); + + // Set up interrupt based callback function - trigger on both edges. + GPIOINT_Init(); + GPIO_ExtIntConfig(SL_WFX_HOST_PINOUT_SPI_WIRQ_PORT, SL_WFX_HOST_PINOUT_SPI_WIRQ_PIN, wirq_irq_nb, true, false, + false); /* Don't enable it */ + + GPIOINT_CallbackRegister(wirq_irq_nb, sl_wfx_spi_wakeup_irq_callback); + + // Change GPIO interrupt priority (FreeRTOS asserts unless this is done here!) + NVIC_ClearPendingIRQ(1 << wirq_irq_nb); + NVIC_SetPriority(GPIO_EVEN_IRQn, 5); + NVIC_SetPriority(GPIO_ODD_IRQn, 5); +} diff --git a/examples/platform/efr32/wf200/host_if.cpp b/examples/platform/efr32/wf200/host_if.cpp new file mode 100644 index 00000000000000..58840fc724639c --- /dev/null +++ b/examples/platform/efr32/wf200/host_if.cpp @@ -0,0 +1,1223 @@ +/* + * + * Copyright (c) 2022 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 "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" +#include "gpiointerrupt.h" + +#include "wifi_config.h" + +#include "AppConfig.h" +#include "sl_wfx_board.h" +#include "sl_wfx_host.h" +#include "sl_wfx_task.h" +#include "wfx_host_events.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "dhcp_client.h" +#include "ethernetif.h" +#include + +using namespace ::chip; +using namespace ::chip::DeviceLayer; + +/* wfxRsi Task will use as its stack */ +StackType_t wfxEventTaskStack[1024] = { 0 }; + +/* Structure that will hold the TCB of the wfxRsi Task being created. */ +StaticTask_t wfxEventTaskBuffer; + +/* Declare a variable to hold the data associated with the created event group. */ +StaticEventGroup_t wfxEventGroup; + +EventGroupHandle_t sl_wfx_event_group; +TaskHandle_t wfx_events_task_handle; +static sl_wfx_mac_address_t ap_mac; +static uint32_t sta_ip; + +// Set Scan Parameters +#define ACTIVE_CHANNEL_TIME 110 +#define PASSIVE_CHANNEL_TIME 0 +#define NUM_PROBE_REQUEST 2 + +// wfx_fmac_driver context +sl_wfx_context_t wifiContext; +static uint8_t wifi_extra; + +/***************************************************************************** + * macros + ******************************************************************************/ +#define WE_ST_STARTED 1 +#define WE_ST_STA_CONN 2 +#define WE_ST_HW_STARTED 4 + +#ifdef SL_WFX_CONFIG_SOFTAP +// Connection parameters +char softap_ssid[32] = SOFTAP_SSID_DEFAULT; +char softap_passkey[64] = SOFTAP_PASSKEY_DEFAULT; +sl_wfx_security_mode_t softap_security = SOFTAP_SECURITY_DEFAULT; +uint8_t softap_channel = SOFTAP_CHANNEL_DEFAULT; +#endif + +/* station network interface structures */ +struct netif * sta_netif; +wfx_wifi_provision_t wifi_provision; + +bool hasNotifiedIPV6 = false; +bool hasNotifiedIPV4 = false; +bool hasNotifiedWifiConnectivity = false; +static uint8_t retryJoin = 0; +bool retryInProgress = false; + +#ifdef SL_WFX_CONFIG_SCAN +static struct scan_result_holder +{ + struct scan_result_holder * next; + wfx_wifi_scan_result scan; +} * scan_save; +static uint8_t scan_count = 0; +static void (*scan_cb)(wfx_wifi_scan_result_t *); /* user-callback - when scan is done */ +static char * scan_ssid; /* Which one are we scanning for */ +static void sl_wfx_scan_result_callback(sl_wfx_scan_result_ind_body_t * scan_result); +static void sl_wfx_scan_complete_callback(uint32_t status); +#endif /* SL_WFX_CONFIG_SCAN */ + +static void wfx_events_task(void * p_arg); + +/* WF200 host callbacks */ +static void sl_wfx_connect_callback(uint8_t * mac, uint32_t status); +static void sl_wfx_disconnect_callback(uint8_t * mac, uint16_t reason); +static void sl_wfx_generic_status_callback(sl_wfx_generic_ind_t * frame); + +#ifdef SL_WFX_CONFIG_SOFTAP +static void sl_wfx_start_ap_callback(uint32_t status); +static void sl_wfx_stop_ap_callback(void); +static void sl_wfx_client_connected_callback(uint8_t * mac); +static void sl_wfx_ap_client_disconnected_callback(uint32_t status, uint8_t * mac); +static void sl_wfx_ap_client_rejected_callback(uint32_t status, uint8_t * mac); +#endif + +/*************************************************************************** + * @fn static void wfx_events_task_start() + * @brief + * Creates WFX events processing task. + * @param[in] None + * @return None + ******************************************************************************/ +static void wfx_events_task_start() +{ + /* create an event group to track Wi-Fi events */ + sl_wfx_event_group = xEventGroupCreateStatic(&wfxEventGroup); + + wfx_events_task_handle = xTaskCreateStatic(wfx_events_task, "wfx_events", WLAN_TASK_STACK_SIZE, NULL, WLAN_TASK_PRIORITY, + wfxEventTaskStack, &wfxEventTaskBuffer); + if (NULL == wfx_events_task_handle) + { + EFR32_LOG("Failed to create WFX wfx_events"); + } +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_process_event(sl_wfx_generic_message_t *event_payload) + * @brief + * Called when the driver needs to post an event + * @param[in] event_payload: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_process_event(sl_wfx_generic_message_t * event_payload) +{ + switch (event_payload->header.id) + { + /******** INDICATION ********/ + case SL_WFX_STARTUP_IND_ID: { + EFR32_LOG("WFX Startup Completed\r\n"); + PlatformMgrImpl().HandleWFXSystemEvent(WIFI_EVENT, event_payload); + break; + } + case SL_WFX_CONNECT_IND_ID: { + sl_wfx_connect_ind_t * connect_indication = (sl_wfx_connect_ind_t *) event_payload; + sl_wfx_connect_callback(connect_indication->body.mac, connect_indication->body.status); + break; + } + case SL_WFX_DISCONNECT_IND_ID: { + sl_wfx_disconnect_ind_t * disconnect_indication = (sl_wfx_disconnect_ind_t *) event_payload; + sl_wfx_disconnect_callback(disconnect_indication->body.mac, disconnect_indication->body.reason); + break; + } + case SL_WFX_RECEIVED_IND_ID: { + sl_wfx_received_ind_t * ethernet_frame = (sl_wfx_received_ind_t *) event_payload; + if (ethernet_frame->body.frame_type == ETH_FRAME) + { + sl_wfx_host_received_frame_callback(ethernet_frame); + } + break; + } +#ifdef SL_WFX_CONFIG_SCAN + case SL_WFX_SCAN_RESULT_IND_ID: { + sl_wfx_scan_result_ind_t * scan_result = (sl_wfx_scan_result_ind_t *) event_payload; + sl_wfx_scan_result_callback(&scan_result->body); + break; + } + case SL_WFX_SCAN_COMPLETE_IND_ID: { + sl_wfx_scan_complete_ind_t * scan_complete = (sl_wfx_scan_complete_ind_t *) event_payload; + sl_wfx_scan_complete_callback(scan_complete->body.status); + break; + } +#endif /* SL_WFX_CONFIG_SCAN */ +#ifdef SL_WFX_CONFIG_SOFTAP + case SL_WFX_START_AP_IND_ID: { + sl_wfx_start_ap_ind_t * start_ap_indication = (sl_wfx_start_ap_ind_t *) event_payload; + sl_wfx_start_ap_callback(start_ap_indication->body.status); + break; + } + case SL_WFX_STOP_AP_IND_ID: { + sl_wfx_stop_ap_callback(); + break; + } + case SL_WFX_AP_CLIENT_CONNECTED_IND_ID: { + sl_wfx_ap_client_connected_ind_t * client_connected_indication = (sl_wfx_ap_client_connected_ind_t *) event_payload; + sl_wfx_client_connected_callback(client_connected_indication->body.mac); + break; + } + case SL_WFX_AP_CLIENT_REJECTED_IND_ID: { + sl_wfx_ap_client_rejected_ind_t * ap_client_rejected_indication = (sl_wfx_ap_client_rejected_ind_t *) event_payload; + sl_wfx_ap_client_rejected_callback(ap_client_rejected_indication->body.reason, ap_client_rejected_indication->body.mac); + break; + } + case SL_WFX_AP_CLIENT_DISCONNECTED_IND_ID: { + sl_wfx_ap_client_disconnected_ind_t * ap_client_disconnected_indication = + (sl_wfx_ap_client_disconnected_ind_t *) event_payload; + sl_wfx_ap_client_disconnected_callback(ap_client_disconnected_indication->body.reason, + ap_client_disconnected_indication->body.mac); + break; + } +#endif /* SL_WFX_CONFIG_SOFTAP */ +#ifdef SL_WFX_USE_SECURE_LINK + case SL_WFX_SECURELINK_EXCHANGE_PUB_KEYS_IND_ID: { + if (host_context.waited_event_id != SL_WFX_SECURELINK_EXCHANGE_PUB_KEYS_IND_ID) + { + memcpy((void *) &sl_wfx_context->secure_link_exchange_ind, (void *) event_payload, event_payload->header.length); + } + break; + } +#endif + case SL_WFX_GENERIC_IND_ID: { + sl_wfx_generic_ind_t * generic_status = (sl_wfx_generic_ind_t *) event_payload; + sl_wfx_generic_status_callback(generic_status); + break; + } + case SL_WFX_EXCEPTION_IND_ID: { + sl_wfx_exception_ind_t * firmware_exception = (sl_wfx_exception_ind_t *) event_payload; + uint8_t * exception_tmp = (uint8_t *) firmware_exception; + EFR32_LOG("firmware exception\r\n"); + for (uint16_t i = 0; i < firmware_exception->header.length; i += 16) + { + EFR32_LOG("hif: %.8x:", i); + for (uint8_t j = 0; (j < 16) && ((i + j) < firmware_exception->header.length); j++) + { + EFR32_LOG(" %.2x", *exception_tmp); + exception_tmp++; + } + EFR32_LOG("\r\n"); + } + break; + } + case SL_WFX_ERROR_IND_ID: { + sl_wfx_error_ind_t * firmware_error = (sl_wfx_error_ind_t *) event_payload; + uint8_t * error_tmp = (uint8_t *) firmware_error; + EFR32_LOG("firmware error %lu\r\n", firmware_error->body.type); + for (uint16_t i = 0; i < firmware_error->header.length; i += 16) + { + EFR32_LOG("hif: %.8x:", i); + for (uint8_t j = 0; (j < 16) && ((i + j) < firmware_error->header.length); j++) + { + EFR32_LOG(" %.2x", *error_tmp); + error_tmp++; + } + EFR32_LOG("\r\n"); + } + break; + } + } + + return SL_STATUS_OK; +} + +#ifdef SL_WFX_CONFIG_SCAN +/**************************************************************************** + * @fn static void sl_wfx_scan_result_callback(sl_wfx_scan_result_ind_body_t *scan_result) + * @brief + * Callback for individual scan result + * @param[in] scan_result: + * @return None + *****************************************************************************/ +static void sl_wfx_scan_result_callback(sl_wfx_scan_result_ind_body_t * scan_result) +{ + struct scan_result_holder * ap; + + EFR32_LOG("# %2d %2d %03d %02X:%02X:%02X:%02X:%02X:%02X %s", scan_count, scan_result->channel, + ((int16_t)(scan_result->rcpi - 220) / 2), scan_result->mac[0], scan_result->mac[1], scan_result->mac[2], + scan_result->mac[3], scan_result->mac[4], scan_result->mac[5], scan_result->ssid_def.ssid); + /*Report one AP information*/ + EFR32_LOG("\r\n"); + /* don't save if filter only wants specific ssid */ + if (scan_ssid != (char *) 0) + { + if (strcmp(scan_ssid, (char *) &scan_result->ssid_def.ssid[0]) != CMP_SUCCESS) + return; + } + if ((ap = (struct scan_result_holder *) pvPortMalloc(sizeof(*ap))) == (struct scan_result_holder *) 0) + { + EFR32_LOG("*ERR*Scan: No Mem"); + } + else + { + ap->next = scan_save; + scan_save = ap; + /* Not checking if scan_result->ssid_length is < 33 */ + memcpy(ap->scan.ssid, scan_result->ssid_def.ssid, scan_result->ssid_def.ssid_length); + ap->scan.ssid[scan_result->ssid_def.ssid_length] = 0; /* make sure about null terminate */ + /* We do it in this order WPA3 first */ + /* No EAP supported - Is this required */ + if (scan_result->security_mode.wpa3) + { + ap->scan.security = WFX_SEC_WPA3; + } + else if (scan_result->security_mode.wpa2) + { + ap->scan.security = WFX_SEC_WPA2; + } + else if (scan_result->security_mode.wpa) + { + ap->scan.security = WFX_SEC_WPA; + } + else if (scan_result->security_mode.wep) + { + ap->scan.security = WFX_SEC_WEP; + } + else + { + ap->scan.security = WFX_SEC_NONE; + } + ap->scan.chan = scan_result->channel; + ap->scan.rssi = scan_result->rcpi; + memcpy(&ap->scan.bssid[0], &scan_result->mac[0], BSSID_MAX_STR_LEN); + scan_count++; + } +} + +/**************************************************************************** + * @fn static void sl_wfx_scan_complete_callback(uint32_t status) + * @brief + * Callback for scan complete + * @param[in] status: + * @return None + *****************************************************************************/ +/* ARGSUSED */ +static void sl_wfx_scan_complete_callback(uint32_t status) +{ + (void) (status); + /* Use scan_count value and reset it */ + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_SCAN_COMPLETE); +} +#endif /* SL_WFX_CONFIG_SCAN */ + +/**************************************************************************** + * @fn static void sl_wfx_connect_callback(uint8_t *mac, uint32_t status) + * @brief + * Callback when station connects + * @param[in] mac: + * @param[in] status: + * @return None + *****************************************************************************/ +static void sl_wfx_connect_callback(uint8_t * mac, uint32_t status) +{ + (void) (mac); + switch (status) + { + case WFM_STATUS_SUCCESS: { + EFR32_LOG("STA-Connected\r\n"); + memcpy(&ap_mac.octet[0], mac, MAC_ADDRESS_FIRST_OCTET); + sl_wfx_context->state = + static_cast(static_cast(sl_wfx_context->state) | static_cast(SL_WFX_STA_INTERFACE_CONNECTED)); + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_CONNECT); + break; + } + case WFM_STATUS_NO_MATCHING_AP: { + EFR32_LOG("WFX Connection failed, access point not found\r\n"); + break; + } + case WFM_STATUS_CONNECTION_ABORTED: { + EFR32_LOG("WFX Connection aborted\r\n"); + break; + } + case WFM_STATUS_CONNECTION_TIMEOUT: { + EFR32_LOG("WFX Connection timeout\r\n"); + break; + } + case WFM_STATUS_CONNECTION_REJECTED_BY_AP: { + EFR32_LOG("WFX Connection rejected by the access point\r\n"); + break; + } + case WFM_STATUS_CONNECTION_AUTH_FAILURE: { + EFR32_LOG("WFX Connection authentication failure\r\n"); + break; + } + default: { + EFR32_LOG("WF Connection attempt error\r\n"); + } + } + + if ((status != WFM_STATUS_SUCCESS) && retryJoin < MAX_JOIN_RETRIES_COUNT) + { + retryJoin += 1; + retryInProgress = false; + EFR32_LOG("WFX Retry to connect to network count: %d", retryJoin); + sl_wfx_context->state = + static_cast(static_cast(sl_wfx_context->state) & ~static_cast(SL_WFX_STARTED)); + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_RETRY_CONNECT); + } +} + +/**************************************************************************** + * @fn static void sl_wfx_disconnect_callback(uint8_t *mac, uint16_t reason) + * @brief + * Callback for station disconnect + * @param[in] mac: + * @param[in] reason: + * @return None + *****************************************************************************/ +static void sl_wfx_disconnect_callback(uint8_t * mac, uint16_t reason) +{ + (void) (mac); + EFR32_LOG("WFX Disconnected %d\r\n", reason); + sl_wfx_context->state = + static_cast(static_cast(sl_wfx_context->state) & ~static_cast(SL_WFX_STA_INTERFACE_CONNECTED)); + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_DISCONNECT); +} + +#ifdef SL_WFX_CONFIG_SOFTAP +/**************************************************************************** + * @fn static void sl_wfx_start_ap_callback(uint32_t status) + * @brief + * Callback for AP started + * @param[in] status: + * @return None + *****************************************************************************/ +static void sl_wfx_start_ap_callback(uint32_t status) +{ + if (status == AP_START_SUCCESS) + { + EFR32_LOG("AP started\r\n"); + sl_wfx_context->state = + static_cast(static_cast(sl_wfx_context->state) | static_cast(SL_WFX_AP_INTERFACE_UP)); + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_START_AP); + } + else + { + EFR32_LOG("AP start failed\r\n"); + strcpy(event_log, "AP start failed"); + } +} + +/**************************************************************************** + * @fn static void sl_wfx_stop_ap_callback(void) + * @brief + * Callback for AP stopped + * @param[in] None + * @return None + *****************************************************************************/ +static void sl_wfx_stop_ap_callback(void) +{ + // TODO + // dhcpserver_clear_stored_mac(); + EFR32_LOG("SoftAP stopped\r\n"); + sl_wfx_context->state = + static_cast(static_cast(sl_wfx_context->state) & ~static_cast(SL_WFX_AP_INTERFACE_UP)); + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_STOP_AP); +} + +/**************************************************************************** + * @fn static void sl_wfx_client_connected_callback(uint8_t *mac) + * @brief + * Callback for client connect to AP + * @param[in] mac: + * @return None + *****************************************************************************/ +static void sl_wfx_client_connected_callback(uint8_t * mac) +{ + EFR32_LOG("Client connected, MAC: %02X:%02X:%02X:%02X:%02X:%02X\r\n", mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]); + // TODO + EFR32_LOG("Open a web browser and go to http://%d.%d.%d.%d\r\n", ap_ip_addr0, ap_ip_addr1, ap_ip_addr2, ap_ip_addr3); +} + +/**************************************************************************** + * @fn static void sl_wfx_ap_client_rejected_callback(uint32_t status, uint8_t *mac) + * @brief + * Callback for client rejected from AP + * @param[in] status: + * @param[in] mac: + * @return None + *****************************************************************************/ +static void sl_wfx_ap_client_rejected_callback(uint32_t status, uint8_t * mac) +{ + { + // TODO + EFR32_LOG("Client rejected, reason: %d, MAC: %02X:%02X:%02X:%02X:%02X:%02X\r\n", (int) status, mac[0], mac[1], mac[2], + mac[3], mac[4], mac[5]); + } + + /**************************************************************************** + * @fn static void sl_wfx_ap_client_disconnected_callback(uint32_t status, uint8_t *mac) + * @brief + * Callback for AP client disconnect + * @param[in] status: + * @param[in] mac: + * @return None + *****************************************************************************/ + static void sl_wfx_ap_client_disconnected_callback(uint32_t status, uint8_t * mac) + { + // TODO + EFR32_LOG("Client disconnected, reason: %d, MAC: %02X:%02X:%02X:%02X:%02X:%02X\r\n", (int) status, mac[0], mac[1], mac[2], + mac[3], mac[4], mac[5]); + } +#endif /* SL_WFX_CONFIG_SOFTAP */ + + /**************************************************************************** + * @fn static void sl_wfx_generic_status_callback(sl_wfx_generic_ind_t *frame) + * @brief + * Callback for generic status received + * @param[in] farme: + * @return None + *****************************************************************************/ + static void sl_wfx_generic_status_callback(sl_wfx_generic_ind_t * frame) + { + (void) (frame); + EFR32_LOG("WFX Generic status received\r\n"); + } + + /*************************************************************************** + * @fn static void wfx_events_task(void *p_arg) + * @brief + * WFX events processing task. + * @param[in] p_arg: + * @return None + ******************************************************************************/ + static void wfx_events_task(void * p_arg) + { + TickType_t last_dhcp_poll, now; + EventBits_t flags; + (void) p_arg; + + sta_netif = wfx_get_netif(SL_WFX_STA_INTERFACE); + last_dhcp_poll = xTaskGetTickCount(); + while (true) + { + flags = xEventGroupWaitBits(sl_wfx_event_group, + SL_WFX_CONNECT | SL_WFX_DISCONNECT +#ifdef SL_WFX_CONFIG_SOFTAP + | SL_WFX_START_AP | SL_WFX_STOP_AP +#endif /* SL_WFX_CONFIG_SOFTAP */ +#ifdef SL_WFX_CONFIG_SCAN + | SL_WFX_SCAN_START | SL_WFX_SCAN_COMPLETE +#endif /* SL_WFX_CONFIG_SCAN */ + | BITS_TO_WAIT, + pdTRUE, pdFALSE, pdMS_TO_TICKS(250)); /* 250 msec delay converted to ticks */ + if (flags & SL_WFX_RETRY_CONNECT) + { + if (!retryInProgress) + { + EFR32_LOG("WFX sending the connect command"); + wfx_connect_to_ap(); + retryInProgress = true; + } + } + + if (wifi_extra & WE_ST_STA_CONN) + { + if ((now = xTaskGetTickCount()) > (last_dhcp_poll + pdMS_TO_TICKS(250))) + { +#if (CHIP_DEVICE_CONFIG_ENABLE_IPV4) + uint8_t dhcp_state = dhcpclient_poll(&sta_netif); + + if ((dhcp_state == DHCP_ADDRESS_ASSIGNED) && !hasNotifiedIPV4) + { + wfx_dhcp_got_ipv4((uint32_t) sta_netif->ip_addr.u_addr.ip4.addr); + hasNotifiedIPV4 = true; + if (!hasNotifiedWifiConnectivity) + { + EFR32_LOG("WIFI: Has Notified Wifi Connectivity"); + wfx_connected_notify(CONNECTION_STATUS_SUCCESS, &ap_mac); + hasNotifiedWifiConnectivity = true; + } + } + else if (dhcp_state == DHCP_OFF) + { + wfx_ip_changed_notify(IP_STATUS_FAIL); + hasNotifiedIPV4 = false; + } +#endif // CHIP_DEVICE_CONFIG_ENABLE_IPV4 + if ((ip6_addr_ispreferred(netif_ip6_addr_state(sta_netif, 0))) && !hasNotifiedIPV6) + { + wfx_ipv6_notify(GET_IPV6_SUCCESS); + hasNotifiedIPV6 = true; + if (!hasNotifiedWifiConnectivity) + { + wfx_connected_notify(CONNECTION_STATUS_SUCCESS, &ap_mac); + hasNotifiedWifiConnectivity = true; + } + } + last_dhcp_poll = now; + } + } + + if (flags & SL_WFX_CONNECT) + { +#if (CHIP_DEVICE_CONFIG_ENABLE_IPV4) + wfx_ip_changed_notify(IP_STATUS_FAIL); + hasNotifiedIPV4 = false; +#endif // CHIP_DEVICE_CONFIG_ENABLE_IPV4 + wfx_ipv6_notify(GET_IPV6_FAIL); + hasNotifiedIPV6 = false; + hasNotifiedWifiConnectivity = false; + EFR32_LOG("WIFI: Connected to AP"); + wifi_extra |= WE_ST_STA_CONN; + wfx_lwip_set_sta_link_up(); +#ifdef SLEEP_ENABLED + if (!(wfx_get_wifi_state() & SL_WFX_AP_INTERFACE_UP)) + { + // Enable the power save + sl_wfx_set_power_mode(WFM_PM_MODE_PS, WFM_PM_POLL_UAPSD, BEACON_1); + sl_wfx_enable_device_power_save(); + } +#endif // SLEEP_ENABLED + } + + if (flags & SL_WFX_DISCONNECT) + { + +#if (CHIP_DEVICE_CONFIG_ENABLE_IPV4) + wfx_ip_changed_notify(IP_STATUS_FAIL); + hasNotifiedIPV4 = false; +#endif // CHIP_DEVICE_CONFIG_ENABLE_IPV4 + wfx_ipv6_notify(GET_IPV6_FAIL); + hasNotifiedIPV6 = false; + hasNotifiedWifiConnectivity = false; + wifi_extra &= ~WE_ST_STA_CONN; + wfx_lwip_set_sta_link_down(); + } + +#ifdef SL_WFX_CONFIG_SCAN + if (flags & SL_WFX_SCAN_START) + { + /* + * Start the Scan + */ + sl_wfx_ssid_def_t ssid, *sp; + uint16_t num_ssid, slen; + if (scan_ssid) + { + memset(&ssid, 0, sizeof(ssid)); + slen = strlen(scan_ssid); + memcpy(&ssid.ssid[0], scan_ssid, slen); + ssid.ssid_length = slen; + num_ssid = 1; + sp = &ssid; + } + else + { + num_ssid = 0; + sp = (sl_wfx_ssid_def_t *) 0; + } + + EFR32_LOG("WIFI Scan Paramter set to Active channel time %d, Passive " + "Channel Time: %d, Number of prob: %d", + ACTIVE_CHANNEL_TIME, PASSIVE_CHANNEL_TIME, NUM_PROBE_REQUEST); + (void) sl_wfx_set_scan_parameters(ACTIVE_CHANNEL_TIME, PASSIVE_CHANNEL_TIME, NUM_PROBE_REQUEST); + (void) sl_wfx_send_scan_command(WFM_SCAN_MODE_ACTIVE, CHANNEL_LIST, /* Channel list */ + CHANNEL_COUNT, /* Scan all chans */ + sp, num_ssid, IE_DATA, /* IE we're looking for */ + IE_DATA_LENGTH, BSSID_SCAN); + } + if (flags & SL_WFX_SCAN_COMPLETE) + { + struct scan_result_holder *hp, *next; + + EFR32_LOG("WIFI: Return %d scan results", scan_count); + for (hp = scan_save; hp; hp = next) + { + next = hp->next; + (*scan_cb)(&hp->scan); + vPortFree(hp); + } + (*scan_cb)((wfx_wifi_scan_result *) 0); + scan_save = (struct scan_result_holder *) 0; + scan_count = 0; + if (scan_ssid) + { + vPortFree(scan_ssid); + scan_ssid = (char *) 0; + } + /* Terminate scan */ + scan_cb = 0; + } +#endif /* SL_WFX_CONFIG_SCAN */ + } + } + + /**************************************************************************** + * @fn static sl_status_t wfx_init(void) + * @brief + * Initialize the WF200 used by the two interfaces + * @param[in] None + * @return None + *****************************************************************************/ + static sl_status_t wfx_init(void) + { + /* Initialize the WF200 used by the two interfaces */ + wfx_events_task_start(); + sl_status_t status = sl_wfx_init(&wifiContext); + EFR32_LOG("FMAC Driver version %s", FMAC_DRIVER_VERSION_STRING); + switch (status) + { + case SL_STATUS_OK: + EFR32_LOG("WF200 FW ver:%d.%d.%d [MAC %02x:%02x:%02x-%02x:%02x:%02x]", wifiContext.firmware_major, + wifiContext.firmware_minor, wifiContext.firmware_build, wifiContext.mac_addr_0.octet[0], + wifiContext.mac_addr_0.octet[1], wifiContext.mac_addr_0.octet[2], wifiContext.mac_addr_0.octet[3], + wifiContext.mac_addr_0.octet[4], wifiContext.mac_addr_0.octet[5]); + EFR32_LOG("WF200 Init OK"); + + if (wifiContext.state == SL_WFX_STA_INTERFACE_CONNECTED) + { + sl_wfx_send_disconnect_command(); + } + + break; + case SL_STATUS_WIFI_INVALID_KEY: + EFR32_LOG("*ERR*WF200: F/W keyset invalid"); + break; + case SL_STATUS_WIFI_FIRMWARE_DOWNLOAD_TIMEOUT: + EFR32_LOG("*ERR*WF200: F/W download timo"); + break; + case SL_STATUS_TIMEOUT: + EFR32_LOG("*ERR*WF200: Poll for value timo"); + break; + case SL_STATUS_FAIL: + EFR32_LOG("*ERR*WF200: Error"); + break; + default: + EFR32_LOG("*ERR*WF200: Unknown"); + } + + return status; + } + + /***************************************************************************** + * @fn static void wfx_wifi_hw_start(void) + * @brief + * tcp ip, wfx and lwip stack and start dhcp client. + * + * @param[in] + * not used + * + * @return + * sl_status_t Shows init succes or error. + ******************************************************************************/ + static void wfx_wifi_hw_start(void) + { + sl_status_t status; + + if (wifi_extra & WE_ST_HW_STARTED) + return; + EFR32_LOG("STARTING WF200\n"); + wifi_extra |= WE_ST_HW_STARTED; + + sl_wfx_host_gpio_init(); + if ((status = wfx_init()) == SL_STATUS_OK) + { + /* Initialize the LwIP stack */ + EFR32_LOG("WF200:Start LWIP"); + wfx_lwip_start(); + wifiContext.state = SL_WFX_STARTED; /* Really this is a bit mask */ + EFR32_LOG("WF200:ready.."); + } + else + { + EFR32_LOG("*ERR*WF200:init failed"); + } + } + + /************************************************************************ + * @fn int32_t wfx_get_ap_info(wfx_wifi_scan_result_t *ap) + * @brief + * Get AP info + * @param[in] ap: access point + * @return returns -1 + **************************************************************************/ + int32_t wfx_get_ap_info(wfx_wifi_scan_result_t * ap) + { + /* TODO */ + return -1; + } + + /************************************************************************ + * @fn int32_t wfx_get_ap_ext(wfx_wifi_scan_ext_t *extra_info) + * @brief + * Get AP extra info + * @param[in] extra_info: access point extra information + * @return returns -1 + **************************************************************************/ + int32_t wfx_get_ap_ext(wfx_wifi_scan_ext_t * extra_info) + { + /* TODO */ + return -1; + } + + /************************************************************************ + * @fn int32_t wfx_reset_counts() + * @brief + * reset the count + * @param[in] None + * @return returns -1 + **************************************************************************/ + int32_t wfx_reset_counts() + { + /* TODO */ + return -1; + } + + /************************************************************************* + * @fn sl_status_t wfx_wifi_start(void) + * @brief + * I think that this is getting called before FreeRTOS threads are ready + * @param[in] none + * @return returns SL_STATUS_OK + **************************************************************************/ + sl_status_t wfx_wifi_start(void) + { + if (wifi_extra & WE_ST_STARTED) + { + EFR32_LOG("WIFI: Already started"); + return SL_STATUS_OK; + } + wifi_extra |= WE_ST_STARTED; + wfx_soft_init(); + wfx_wifi_hw_start(); + + return SL_STATUS_OK; + } + + /**************************************************************************** + * @fn sl_wfx_state_t wfx_get_wifi_state(void) + * @brief + * get the wifi state + * @param[in] None + * @return returns wificonetext state + *****************************************************************************/ + sl_wfx_state_t wfx_get_wifi_state(void) { return wifiContext.state; } + + /**************************************************************************** + * @fn struct netif *wfx_GetNetif(sl_wfx_interface_t interface) + * @brief + * getnetif using interface + * @param[in] interface: + * @return returns selectedNetif + *****************************************************************************/ + struct netif * wfx_GetNetif(sl_wfx_interface_t interface) + { + struct netif * SelectedNetif = NULL; + if (interface == SL_WFX_STA_INTERFACE) + { + SelectedNetif = sta_netif; + } +#ifdef SL_WFX_CONFIG_SOFTAP + else if (interface == SL_WFX_SOFTAP_INTERFACE) + { + // no ap currently + } +#endif + return SelectedNetif; + } + + /**************************************************************************** + * @fn sl_wfx_mac_address_t wfx_get_wifi_mac_addr(sl_wfx_interface_t interface) + * @brief + * get the wifi mac address using interface + * @param[in] interface: + * @return returns wificontext.mac_addr_o if successful, + * wificontext.mac_addr_1 otherwise + *****************************************************************************/ + sl_wfx_mac_address_t wfx_get_wifi_mac_addr(sl_wfx_interface_t interface) + { + // return Mac address used by WFX SL_WFX_STA_INTERFACE or SL_WFX_SOFTAP_INTERFACE, + return (interface == SL_WFX_STA_INTERFACE) ? wifiContext.mac_addr_0 : wifiContext.mac_addr_1; + } + + /**************************************************************************** + * @fn void wfx_set_wifi_provision(wfx_wifi_provision_t *wifiConfig) + * @brief + * set the wifi provision + * @param[in] wifiConfig: configuration of wifi + * @return None + *****************************************************************************/ + void wfx_set_wifi_provision(wfx_wifi_provision_t * wifiConfig) + { + memcpy(wifi_provision.ssid, wifiConfig->ssid, sizeof(wifiConfig->ssid)); + memcpy(wifi_provision.passkey, wifiConfig->passkey, sizeof(wifiConfig->passkey)); + EFR32_LOG("WIFI: Provision SSID=%s", &wifi_provision.ssid[0]); + + /* Not very good - To be improved */ + switch (wifiConfig->security) + { + case WFX_SEC_WPA: + wifi_provision.security = static_cast(sl_wfx_security_mode_e::WFM_SECURITY_MODE_WPA2_WPA1_PSK); + break; + case WFX_SEC_WPA3: + wifi_provision.security = WFM_SECURITY_MODE_WPA3_SAE; + break; + case WFX_SEC_WPA2: + wifi_provision.security = static_cast(sl_wfx_security_mode_e::WFM_SECURITY_MODE_WPA2_WPA1_PSK); + break; + case WFX_SEC_WPA_WPA2_MIXED: + wifi_provision.security = static_cast(sl_wfx_security_mode_e::WFM_SECURITY_MODE_WPA2_WPA1_PSK); + break; + default: + wifi_provision.security = WFM_SECURITY_MODE_WPA2_PSK; + break; + } + } + + /**************************************************************************** + * @fn bool wfx_get_wifi_provision(wfx_wifi_provision_t *wifiConfig) + * @brief + * get the wifi provision + * @param[in] wifiConfig: configuration of wifi + * @return returns true if successful, + * false otherwise + *****************************************************************************/ + bool wfx_get_wifi_provision(wfx_wifi_provision_t * wifiConfig) + { + if (wifiConfig == NULL) + { + return false; + } + memcpy(wifiConfig, &wifi_provision, sizeof(wfx_wifi_provision_t)); + + return true; + } + + /**************************************************************************** + * @fn void wfx_clear_wifi_provision(void) + * @brief + * clear the wifi provision + * @param[in] None + * @return returns true if successful, + * false otherwise + *****************************************************************************/ + void wfx_clear_wifi_provision(void) { memset(&wifi_provision, 0, sizeof(wifi_provision)); } + + /**************************************************************************** + * @fn bool wfx_is_sta_provisioned(void) + * @brief + * driver STA provisioned + * @param[in] None + * @return returns true if successful, + * false otherwise + *****************************************************************************/ + bool wfx_is_sta_provisioned(void) { return (wifi_provision.ssid[0]) ? true : false; } + + /**************************************************************************** + * @fn sl_status_t wfx_connect_to_ap(void) + * @brief + * driver connect to ap + * @param[in] None + * @return returns SL_STATUS_NOT_AVAILABLE + *****************************************************************************/ + sl_status_t wfx_connect_to_ap(void) + { + sl_status_t result; + + if (wifi_provision.ssid[0] == 0) + { + return SL_STATUS_NOT_AVAILABLE; + } + EFR32_LOG("WIFI:JOIN to %s", &wifi_provision.ssid[0]); + + EFR32_LOG("WIFI Scan Paramter set to Active channel time %d, Passive Channel " + "Time: %d, Number of prob: %d", + ACTIVE_CHANNEL_TIME, PASSIVE_CHANNEL_TIME, NUM_PROBE_REQUEST); + (void) sl_wfx_set_scan_parameters(ACTIVE_CHANNEL_TIME, PASSIVE_CHANNEL_TIME, NUM_PROBE_REQUEST); + result = sl_wfx_send_join_command((uint8_t *) wifi_provision.ssid, strlen(wifi_provision.ssid), NULL, CHANNEL_0, + static_cast(wifi_provision.security), PREVENT_ROAMING, + DISABLE_PMF_MODE, (uint8_t *) wifi_provision.passkey, strlen(wifi_provision.passkey), + NULL, IE_DATA_LENGTH); + + return result; + } + + /**************************************************************************** + * @fn void wfx_get_wifi_mac_addr(sl_wfx_interface_t interface, sl_wfx_mac_address_t *addr) + * @brief + * get the wifi mac addresss + * @param[in] interface: + * @param[in] addr : address + * @return None + *****************************************************************************/ + void wfx_get_wifi_mac_addr(sl_wfx_interface_t interface, sl_wfx_mac_address_t * addr) + { + sl_wfx_mac_address_t * mac; + +#ifdef SL_WFX_CONFIG_SOFTAP + mac = (interface == SL_WFX_SOFTAP_INTERFACE) ? &wifiContext.mac_addr_1 : &wifiContext.mac_addr_0; +#else + mac = &wifiContext.mac_addr_0; +#endif + *addr = *mac; + EFR32_LOG("WLAN:Get WiFi Mac addr %02x:%02x:%02x:%02x:%02x:%02x", mac->octet[0], mac->octet[1], mac->octet[2], + mac->octet[3], mac->octet[4], mac->octet[5]); + } + + /**************************************************************************** + * @fn bool wfx_have_ipv4_addr(sl_wfx_interface_t which_if) + * @brief + * function called when driver have ipv4 address + * @param[in] which_if: + * @return returns false if sucessful, + * true otherwise + *****************************************************************************/ + bool wfx_have_ipv4_addr(sl_wfx_interface_t which_if) + { + if (which_if == SL_WFX_STA_INTERFACE) + { + return (sta_ip == STA_IP_FAIL) ? false : true; + } + else + { + return false; /* TODO */ + } + } + + /**************************************************************************** + * @fn bool wfx_have_ipv6_addr(sl_wfx_interface_t which_if) + * @brief + * function called when driver have ipv6 address + * @param[in] which_if: + * @return returns false if sucessful, + * true otherwise + *****************************************************************************/ + bool wfx_have_ipv6_addr(sl_wfx_interface_t which_if) + { + EFR32_LOG("%s: started.", __func__); + bool status = false; + if (which_if == SL_WFX_STA_INTERFACE) + { + status = wfx_is_sta_connected(); + } + else + { + status = false; /* TODO */ + } + EFR32_LOG("%s: status: %d", __func__, status); + return status; + } + + /**************************************************************************** + * @fn sl_status_t wfx_sta_discon(void) + * @brief + * Disconnect station mode from connected AP + * @param[in] None + * @returns Returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ + sl_status_t wfx_sta_discon(void) + { + EFR32_LOG("STA-Disconnecting"); + int32_t status = sl_wfx_send_disconnect_command(); + wifi_extra &= ~WE_ST_STA_CONN; + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_RETRY_CONNECT); + return status; + } + + /**************************************************************************** + * @fn bool wfx_is_sta_mode_enabled(void) + * @brief + * enable the STA mode + * @param[in] None + * @return returns true + *****************************************************************************/ + bool wfx_is_sta_mode_enabled(void) { return true; /* It always is */ } + + /**************************************************************************** + * @fn bool wfx_is_sta_connected(void) + * @brief + * fuction called when driver is STA connected + * @param[in] None + * @return returns true if sucessful, + * false otherwise + *****************************************************************************/ + bool wfx_is_sta_connected(void) + { + bool val; + + val = (wifi_extra & WE_ST_STA_CONN) ? true : false; + + EFR32_LOG("WLAN: STA %s connected", (val ? "IS" : "NOT")); + + return val; + } + + /**************************************************************************** + * @fn void wfx_setup_ip6_link_local(sl_wfx_interface_t whichif) + * @brief + * It is automatically done when lwip link up + * @param[in] None + * @return returns true if sucessful, + * false otherwise + *****************************************************************************/ + void wfx_setup_ip6_link_local(sl_wfx_interface_t whichif) + { + EFR32_LOG("Setup-IP6: TODO"); /* It is automatically done when lwip link up */ + } + + /**************************************************************************** + * @fn wifi_mode_t wfx_get_wifi_mode() + * @brief + * get the wifi mode + * @param[in] None + * @return returns WIFI_MODE_NULL if sucessful, + * WIFI_MODE_STA otherwise + *****************************************************************************/ + wifi_mode_t wfx_get_wifi_mode() + { + if (wifiContext.state & SL_WFX_STARTED) + return WIFI_MODE_STA; + return WIFI_MODE_NULL; + } + + /***************************************************************************** + * @fn bool wfx_hw_ready(void) + * @brief + * This is called from the context of AppTask + * For WF200 - Start WIFI here + * @param[in] None + * @return returns true if sucessful, + * false otherwise + ******************************************************************************/ + bool wfx_hw_ready(void) { return (wifiContext.state & SL_WFX_STARTED) ? true : false; } + + /***************************************************************************** + * @fn void wfx_dhcp_got_ipv4(uint32_t ip) + * @brief + * function called when dhcp got ipv4 + * @param[in] ip : internet protocol + *@return None + ******************************************************************************/ + void wfx_dhcp_got_ipv4(uint32_t ip) + { + /* Acquire the new IP address + */ + sta_ip = ip; + wfx_ip_changed_notify(IP_STATUS_SUCCESS); + } + + /***************************************************************************** + * @fn wfx_enable_sta_mode(void) + * @brief + * function called from connectivityManager + * @param[in] + * @return None + ******************************************************************************/ + void wfx_enable_sta_mode(void) + { + /* Nothing to do - default is that it is + place holder */ + } + +/**************************************************************************** + * @fn bool wfx_start_scan(char *ssid, void (*callback)(wfx_wifi_scan_result_t *)) + * @brief + * driver scan start + * @param[in] callback: + * @return returns true if sucessful, + * false otherwise + *****************************************************************************/ +#ifdef SL_WFX_CONFIG_SCAN + bool wfx_start_scan(char * ssid, void (*callback)(wfx_wifi_scan_result_t *)) + { + int sz; + + if (scan_cb) + return false; /* Already in progress */ + if (ssid) + { + sz = strlen(ssid); + if ((scan_ssid = (char *) pvPortMalloc(sz + 1)) == (char *) 0) + { + return false; + } + strcpy(scan_ssid, ssid); + } + scan_cb = callback; + xEventGroupSetBits(sl_wfx_event_group, SL_WFX_SCAN_START); + + return true; + } + + /**************************************************************************** + * @fn void wfx_cancel_scan(void) + * @brief + * driver scan cancelation + * @param[in] None + * @return None + *****************************************************************************/ + void wfx_cancel_scan(void) + { + struct scan_result_holder *hp, *next; + /* Not possible */ + if (!scan_cb) + { + return; + } + sl_wfx_send_stop_scan_command(); + for (hp = scan_save; hp; hp = next) + { + next = hp->next; + vPortFree(hp); + } + scan_save = (struct scan_result_holder *) 0; + scan_count = 0; + if (scan_ssid) + { + vPortFree(scan_ssid); + scan_ssid = (char *) 0; + } + scan_cb = 0; + } +#endif /* SL_WFX_CONFIG_SCAN */ diff --git a/examples/platform/efr32/wf200/sl_wfx_board.h b/examples/platform/efr32/wf200/sl_wfx_board.h new file mode 100644 index 00000000000000..7208b73e2a36cb --- /dev/null +++ b/examples/platform/efr32/wf200/sl_wfx_board.h @@ -0,0 +1,33 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef _SL_WFX_BOARD_H_ +#define _SL_WFX_BOARD_H_ +/* + * Pull in the right board PINS + */ +#if defined(EFR32MG12_BRD4161A) || defined(BRD4161A) || defined(EFR32MG12_BRD4162A) || defined(BRD4162A) || \ + defined(EFR32MG12_BRD4163A) || defined(BRD4163A) || defined(EFR32MG12_BRD4164A) || defined(BRD4164A) +#include "brd4161a.h" +#elif defined(EFR32MG24_BRD4186C) || defined(BRD4186C) || defined(EFR32MG24_BRD4186A) || defined(BRD4186A) +#include "brd4186c.h" +#elif defined(EFR32MG24_BRD4187C) || defined(BRD4187C) || defined(EFR32MG24_BRD4187A) || defined(BRD4187A) +#include "brd4187c.h" +#else +#error "Need SPI Pins" +#endif /* EFR32MG12_BRD4161A */ +#endif /* _SL_WFX_BOARD_H_ */ diff --git a/examples/platform/efr32/wf200/sl_wfx_configuration.h b/examples/platform/efr32/wf200/sl_wfx_configuration.h new file mode 100644 index 00000000000000..deb468d1a6af73 --- /dev/null +++ b/examples/platform/efr32/wf200/sl_wfx_configuration.h @@ -0,0 +1,30 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#pragma once + +// SL_WFX_DEFAULT_REQUEST_TIMEOUT_MS> Timeout period in milliseconds<250-10000> +// Default: 5000 +// Timeout period in milliseconds for requests. +#define SL_WFX_DEFAULT_REQUEST_TIMEOUT_MS (5000) + +// WFx Secure Link configuration + +// SL_WFX_SLK_CURVE25519> Use crypto curves +// Default: 1 +// If this option is enabled ECDH crypto is used, KDF otherwise. +#define SL_WFX_SLK_CURVE25519 (1) diff --git a/examples/platform/efr32/wf200/sl_wfx_crypto.c b/examples/platform/efr32/wf200/sl_wfx_crypto.c new file mode 100644 index 00000000000000..ddad3ec5b95dde --- /dev/null +++ b/examples/platform/efr32/wf200/sl_wfx_crypto.c @@ -0,0 +1,409 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifdef SL_WFX_USE_SECURE_LINK + +/* Includes */ + +#include "sl_wfx.h" +#include + +#include "mbedtls/ccm.h" +#include "mbedtls/ctr_drbg.h" +#include "mbedtls/ecdh.h" +#include "mbedtls/entropy.h" +#include "mbedtls/md.h" +#include "mbedtls/sha256.h" + +#include "FreeRTOS.h" +#include "queue.h" +#include "semphr.h" +#include "task.h" + +// Secure link MAC key location for WGM160P (in DI page in flash) +#ifdef EFM32GG11B820F2048GM64 // WGM160PX22KGA2 +#define SL_WFX_FCCC_BASE_ADDR ((void *) 0x0fe08000ul) +#define SL_WFX_FCCC_DI_OFFSET 0x1B0ul +#define SL_WFX_FCCC_DI_ADDR ((void *) (SL_WFX_FCCC_BASE_ADDR + SL_WFX_FCCC_DI_OFFSET)) +#define SL_WFX_SECURE_LINK_MAC_KEY_LOCATION ((void *) (SL_WFX_FCCC_BASE_ADDR + 0x3D0)) +#endif +/****************************************************** + * Macros + ******************************************************/ +#define MAC_KEY_FAIL_BYTE 0XFF +#define KEY_DIGEST_SIZE 92 +#define MEMCMP_FAIL 0 +#define MPI_SET 1 +#define SUCCESS_STATUS_WIFI_SECURE_LINK_EXCHANGE 0 +#define SHA224_0 0 +#define HMAC_SIZE 92 +#define MEMSET_LEN 1 +#define LABLE_LEN 24 +#define ADDRESS_LENGTH 0 +#define CCM_STATUS_SUCCESS 0 +/****************************************************** + * Constants + ******************************************************/ + +/* Semaphore to signal wfx driver available */ +extern TaskHandle_t wfx_securelink_task; +extern SemaphoreHandle_t wfx_securelink_rx_mutex; + +/****************************************************** + * Enumerations + ******************************************************/ + +/****************************************************** + * Type Definitions + ******************************************************/ + +/****************************************************** + * Structures + ******************************************************/ + +/****************************************************** + * Function Declarations + ******************************************************/ + +static inline void reverse_bytes(uint8_t * src, uint8_t length); + +/****************************************************** + * Variable Definitions + ******************************************************/ + +#if SL_WFX_SLK_CURVE25519 +static mbedtls_ecdh_context mbedtls_host_context; +static mbedtls_ctr_drbg_context host_drbg_context; +#endif +static mbedtls_entropy_context entropy; +uint8_t temp_key_location[SL_WFX_HOST_PUB_KEY_MAC_SIZE]; +#ifdef EFM32GG11B820F2048GM64 // WGM160PX22KGA2 +static const uint8_t * const secure_link_mac_key = (uint8_t *) SL_WFX_SECURE_LINK_MAC_KEY_LOCATION; +#else +static const uint8_t secure_link_mac_key[SL_WFX_SECURE_LINK_MAC_KEY_LENGTH] = { 0x2B, 0x49, 0xFD, 0x66, 0xCB, 0x74, 0x6D, 0x6B, + 0x4F, 0xDC, 0xC3, 0x79, 0x4E, 0xC5, 0x9A, 0x86, + 0xE5, 0x48, 0x2A, 0x41, 0x22, 0x87, 0x8B, 0x12, + 0x1A, 0x7C, 0x3E, 0xEF, 0xB7, 0x04, 0x9E, 0xB3 }; +#endif +/****************************************************** + * Function Definitions + ******************************************************/ +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_get_secure_link_mac_key(uint8_t *sl_mac_key) + * @brief + * Get secure link mac key + * @param[in] sl_mac_key: + * @return returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_get_secure_link_mac_key(uint8_t * sl_mac_key) +{ + sl_status_t result = SL_STATUS_WIFI_SECURE_LINK_MAC_KEY_ERROR; + + memcpy(sl_mac_key, secure_link_mac_key, SL_WFX_SECURE_LINK_MAC_KEY_LENGTH); + + for (uint8_t index = 0; index < SL_WFX_SECURE_LINK_MAC_KEY_LENGTH; ++index) + { + // Assuming 0xFF... when not written + if (sl_mac_key[index] != MAC_KEY_FAIL_BYTE) + { + result = SL_STATUS_OK; + break; + } + } + + return result; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_compute_pub_key(sl_wfx_securelink_exchange_pub_keys_req_body_t *request, + const uint8_t *sl_mac_key) + * @brief + * compute host public key + * @param[in] request : + * @param[in] sl_mac_key : + * @return returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_compute_pub_key(sl_wfx_securelink_exchange_pub_keys_req_body_t * request, const uint8_t * sl_mac_key) +{ + sl_status_t status = SL_STATUS_OK; + +#if SL_WFX_SLK_CURVE25519 + const char identifier[] = "ecdh"; + + mbedtls_ecdh_init(&mbedtls_host_context); + mbedtls_ctr_drbg_init(&host_drbg_context); + mbedtls_entropy_init(&entropy); + status = mbedtls_ctr_drbg_seed(&host_drbg_context, mbedtls_entropy_func, &entropy, (const unsigned char *) identifier, + sizeof(identifier)); + status += mbedtls_ecp_group_load(&mbedtls_host_context.grp, MBEDTLS_ECP_DP_CURVE25519); + status += mbedtls_ecdh_gen_public(&mbedtls_host_context.grp, &mbedtls_host_context.d, &mbedtls_host_context.Q, + mbedtls_ctr_drbg_random, &host_drbg_context); + status += mbedtls_mpi_write_binary(&mbedtls_host_context.Q.X, request->host_pub_key, SL_WFX_HOST_PUB_KEY_SIZE); +#else + mbedtls_entropy_init(&entropy); + status = mbedtls_entropy_func(&entropy, request->host_pub_key, SL_WFX_HOST_PUB_KEY_SIZE); +#endif + reverse_bytes(request->host_pub_key, SL_WFX_HOST_PUB_KEY_SIZE); + SL_WFX_ERROR_CHECK(status); + + // Generate SHA512 digest of public key + status = mbedtls_md_hmac(mbedtls_md_info_from_type(MBEDTLS_MD_SHA512), sl_mac_key, SL_WFX_HOST_PUB_KEY_SIZE, + request->host_pub_key, SL_WFX_HOST_PUB_KEY_SIZE, request->host_pub_key_mac); + SL_WFX_ERROR_CHECK(status); + +error_handler: + if (status != SL_STATUS_OK) + { + return SL_STATUS_WIFI_SECURE_LINK_EXCHANGE_FAILED; + } + return status; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_verify_pub_key(sl_wfx_securelink_exchange_pub_keys_ind_t *response_packet, + const uint8_t *sl_mac_key, + uint8_t *sl_host_pub_key) + * @brief + * verify host public key + * @param[in] response_packet: + * @param[in] sl_mac_key: + * @param[in] sl_host_pub_key: + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_verify_pub_key(sl_wfx_securelink_exchange_pub_keys_ind_t * response_packet, const uint8_t * sl_mac_key, + uint8_t * sl_host_pub_key) +{ + sl_status_t status = SL_STATUS_OK; + uint8_t shared_key_digest[KEY_DIGEST_SIZE]; + + if (xSemaphoreTake(wfx_securelink_rx_mutex, portMAX_DELAY) != pdTRUE) + { + return SL_STATUS_WIFI_SECURE_LINK_EXCHANGE_FAILED; + } + + // Compute the Hash and verify the public key/hashing + status = mbedtls_md_hmac(mbedtls_md_info_from_type(MBEDTLS_MD_SHA512), sl_mac_key, SL_WFX_NCP_PUB_KEY_SIZE, + response_packet->body.ncp_pub_key, SL_WFX_NCP_PUB_KEY_SIZE, temp_key_location); + SL_WFX_ERROR_CHECK(status); + + // Calculate session key if public key/SHA512 digest matches + if (memcmp(temp_key_location, response_packet->body.ncp_pub_key_mac, SL_WFX_HOST_PUB_KEY_MAC_SIZE) != MEMCMP_FAIL) + { + status = SL_STATUS_WIFI_SECURE_LINK_EXCHANGE_FAILED; + goto error_handler; + } + +#if SL_WFX_SLK_CURVE25519 + SL_WFX_UNUSED_PARAMETER(sl_host_pub_key); + + mbedtls_mpi_lset(&mbedtls_host_context.Qp.Z, MPI_SET); + + // Read Ineo public key + reverse_bytes(response_packet->body.ncp_pub_key, SL_WFX_NCP_PUB_KEY_SIZE); + mbedtls_mpi_read_binary(&mbedtls_host_context.Qp.X, response_packet->body.ncp_pub_key, SL_WFX_NCP_PUB_KEY_SIZE); + + // Calculate shared secret + if (mbedtls_ecdh_compute_shared(&mbedtls_host_context.grp, &mbedtls_host_context.z, &mbedtls_host_context.Qp, + &mbedtls_host_context.d, mbedtls_ctr_drbg_random, + &host_drbg_context) != SUCCESS_STATUS_WIFI_SECURE_LINK_EXCHANGE) + { + status = SL_STATUS_WIFI_SECURE_LINK_EXCHANGE_FAILED; + goto error_handler; + } + + // Generate session key + mbedtls_mpi_write_binary(&mbedtls_host_context.z, temp_key_location, SL_WFX_HOST_PUB_KEY_SIZE); + reverse_bytes(temp_key_location, SL_WFX_HOST_PUB_KEY_SIZE); + mbedtls_sha256(temp_key_location, SL_WFX_HOST_PUB_KEY_SIZE, shared_key_digest, SHA224_0); +#else + uint8_t hmac_input[HMAC_SIZE] = { 0 }; + char label[LABLE_LEN] = "SecureLink!KeyDerivation"; + + memset((uint16_t *) &hmac_input[0], (uint16_t) sl_wfx_htole16(1), MEMSET_LEN); + memcpy((uint8_t *) &hmac_input[2], (uint8_t *) label, LABLE_LEN); + memcpy((uint8_t *) &hmac_input[26], sl_host_pub_key, SL_WFX_NCP_PUB_KEY_SIZE); + memcpy((uint8_t *) &hmac_input[58], (uint8_t *) response_packet->body.ncp_pub_key, SL_WFX_NCP_PUB_KEY_SIZE); + memset((uint16_t *) &hmac_input[90], (uint16_t) sl_wfx_htole16(128), 1); + + // Generate SHA256 digest of hmac_input + status = mbedtls_md_hmac(mbedtls_md_info_from_type(MBEDTLS_MD_SHA256), sl_mac_key, SL_WFX_HOST_PUB_KEY_SIZE, + (uint8_t *) hmac_input, HMAC_SIZE, shared_key_digest); +#endif + + memcpy(sl_wfx_context->secure_link_session_key, shared_key_digest, + SL_WFX_SECURE_LINK_SESSION_KEY_LENGTH); // Use the lower 16 bytes of the sha256 + sl_wfx_context->secure_link_nonce.hp_packet_count = 0; + sl_wfx_context->secure_link_nonce.rx_packet_count = 0; + sl_wfx_context->secure_link_nonce.tx_packet_count = 0; + +error_handler: + if (xSemaphoreGive(wfx_securelink_rx_mutex) != pdTRUE) + { + printf("ERROR: sl_wfx_securelink_rx_mutex. unable to post.\n"); + } + return status; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_free_crypto_context(void) + * @brief + * Free host crypto context + * @param[in] None + * @return returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_free_crypto_context(void) +{ +#if SL_WFX_SLK_CURVE25519 + mbedtls_ecdh_free(&mbedtls_host_context); + mbedtls_ctr_drbg_free(&host_drbg_context); +#endif + mbedtls_entropy_free(&entropy); + + return SL_STATUS_OK; +} + +/******************************************************************************** + * @fn sl_status_t sl_wfx_host_decode_secure_link_data(uint8_t *buffer, uint32_t length, uint8_t *session_key) + * @brief + * Decode receive data + * Length excludes size of CCM tag and secure link header + * @param[in] buffer: + * @param[in] length: + * @param[in] session_key: + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + ********************************************************************************/ +sl_status_t sl_wfx_host_decode_secure_link_data(uint8_t * buffer, uint32_t length, uint8_t * session_key) +{ + mbedtls_ccm_context ccm_context; + sl_status_t status = SL_STATUS_SECURITY_DECRYPT_ERROR; + int crypto_status; + sl_wfx_nonce_t nonce = { 0, 0, 0 }; + + if (xSemaphoreTake(wfx_securelink_rx_mutex, portMAX_DELAY) != pdTRUE) + { + return SL_STATUS_FAIL; + } + + // Nonce for decryption should have TX and HP counters 0, only use RX counter + nonce.rx_packet_count = sl_wfx_context->secure_link_nonce.rx_packet_count; + + // Init context + mbedtls_ccm_init(&ccm_context); + + // Set the crypto key + crypto_status = mbedtls_ccm_setkey(&ccm_context, MBEDTLS_CIPHER_ID_AES, session_key, SL_WFX_SECURE_LINK_SESSION_KEY_BIT_COUNT); + SL_WFX_ERROR_CHECK(crypto_status); + + // Decrypt the data + if (!mbedtls_ccm_auth_decrypt(&ccm_context, length, (uint8_t *) &nonce, SL_WFX_SECURE_LINK_NONCE_SIZE_BYTES, NULL, + ADDRESS_LENGTH, (uint8_t *) buffer, (uint8_t *) buffer, (uint8_t *) buffer + length, + SL_WFX_SECURE_LINK_CCM_TAG_SIZE)) + { + status = SL_STATUS_OK; + } + +error_handler: + mbedtls_ccm_free(&ccm_context); + if (xSemaphoreGive(wfx_securelink_rx_mutex) != pdTRUE) + { + printf("ERROR: sl_wfx_securelink_rx_mutex. unable to post.\n"); + } + return status; +} + +/********************************************************************* + * @fn sl_status_t sl_wfx_host_encode_secure_link_data(sl_wfx_generic_message_t *buffer, + uint32_t data_length, + uint8_t *session_key, + uint8_t *nonce) + * @brief + * Encode transmit data + * Length excludes size of CCM tag and secure link header + * @param[in] buffer: + * @param[in] data_length: + * @param[in] session_key: + * @param[in] nonce: + * @return returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise +*************************************************************************/ +sl_status_t sl_wfx_host_encode_secure_link_data(sl_wfx_generic_message_t * buffer, uint32_t data_length, uint8_t * session_key, + uint8_t * nonce) +{ + mbedtls_ccm_context ccm_context; + sl_status_t status = SL_STATUS_FAIL; + + mbedtls_ccm_init(&ccm_context); + if (mbedtls_ccm_setkey(&ccm_context, MBEDTLS_CIPHER_ID_AES, session_key, SL_WFX_SECURE_LINK_SESSION_KEY_BIT_COUNT) == + CCM_STATUS_SUCCESS) + { + mbedtls_ccm_encrypt_and_tag(&ccm_context, data_length, nonce, SL_WFX_SECURE_LINK_NONCE_SIZE_BYTES, NULL, ADDRESS_LENGTH, + (uint8_t *) &buffer->header.id, (uint8_t *) &buffer->header.id, + (uint8_t *) &buffer->header.id + data_length, SL_WFX_SECURE_LINK_CCM_TAG_SIZE); + status = SL_STATUS_OK; + } + + mbedtls_ccm_free(&ccm_context); + + return status; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_schedule_secure_link_renegotiation(void) + * @brief + * Called when the driver needs to schedule secure link renegotiation + * @param[in] None + * @returns Returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_schedule_secure_link_renegotiation(void) +{ + // call sl_wfx_secure_link_renegotiate_session_key() as soon as it makes sense for the host to do so + xTaskNotifyGive(wfx_securelink_task); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn static inline void reverse_bytes(uint8_t *src, uint8_t length) + * @brief + * reverse the bytes + * @param[in] src: source + * @param[in] length: + * @returns None + *****************************************************************************/ +static inline void reverse_bytes(uint8_t * src, uint8_t length) +{ + uint8_t * lo = src; + uint8_t * hi = src + length - 1; + uint8_t swap; + + while (lo < hi) + { + swap = *lo; + *lo++ = *hi; + *hi-- = swap; + } +} + +/******************************************************************************************************** + ******************************************************************************************************** + * DEPENDENCIES & AVAIL CHECK(S) + ******************************************************************************************************** + *******************************************************************************************************/ + +#endif // SL_WFX_USE_SECURE_LINK diff --git a/examples/platform/efr32/wf200/sl_wfx_host.h b/examples/platform/efr32/wf200/sl_wfx_host.h new file mode 100644 index 00000000000000..dc9bcd28524623 --- /dev/null +++ b/examples/platform/efr32/wf200/sl_wfx_host.h @@ -0,0 +1,52 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#pragma once + +#include "FreeRTOS.h" +#include "queue.h" +#include "semphr.h" +#include "sl_wfx.h" +#include "task.h" + +#ifdef __cplusplus +extern "C" { +#endif +uint8_t sl_wfx_host_get_waited_event(void); +sl_status_t wfx_soft_init(void); + +#ifdef SLEEP_ENABLED +sl_status_t sl_wfx_host_switch_to_wirq(void); +#endif +#ifdef __cplusplus +} +#endif + +#define SL_WFX_MAX_STATIONS 8 +#define SL_WFX_MAX_SCAN_RESULTS 50 + +typedef struct __attribute__((__packed__)) scan_result_list_s +{ + sl_wfx_ssid_def_t ssid_def; + uint8_t mac[SL_WFX_MAC_ADDR_SIZE]; + uint16_t channel; + sl_wfx_security_mode_bitmask_t security_mode; + uint16_t rcpi; +} scan_result_list_t; + +void sl_wfx_host_start_platform_interrupt(void); +extern SemaphoreHandle_t wfx_wakeup_sem; diff --git a/examples/platform/efr32/wf200/sl_wfx_securelink_task.c b/examples/platform/efr32/wf200/sl_wfx_securelink_task.c new file mode 100644 index 00000000000000..28ffdda2c3852f --- /dev/null +++ b/examples/platform/efr32/wf200/sl_wfx_securelink_task.c @@ -0,0 +1,85 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifdef SL_WFX_USE_SECURE_LINK +#include "secure_link/sl_wfx_secure_link.h" + +#include "FreeRTOS.h" +#include "queue.h" +#include "semphr.h" +#include "task.h" +#include +#include +#include + +// Securelink Task Configurations +#define WFX_SECURELINK_TASK_PRIO 1u +#define WFX_SECURELINK_TASK_STK_SIZE 512u + +TaskHandle_t secureLinkTaskHandle; +SemaphoreHandle_t s_xSLSemaphore; +StackType_t secureLinkStack[WFX_SECURELINK_TASK_STK_SIZE]; +StaticTask_t secureLinkTaskStruct; + +StaticSemaphore_t xSlMutexBuffer; + +/********************************************************************* + * @fn static void prvSecureLinkTask(void *p_arg) + * @brief + * The task that implements the Secure Link renegotiation with WFX. + * @param[in] p_arg: + * @return None + *************************************************************************/ +static void prvSecureLinkTask(void * p_arg) +{ + sl_status_t result; + (void) p_arg; + + /* Create a mutex used for making Secure Link renegotiations atomic */ + s_xSLSemaphore = xSemaphoreCreateMutexStatic(&xSlMutexBuffer); + + for (;;) + { + /* Wait for a key renegotiation request */ + ulTaskNotifyTake(pdTRUE, portMAX_DELAY); + + result = sl_wfx_secure_link_renegotiate_session_key(); + if (result != SL_STATUS_OK) + { + printf("session key negotiation error %lu\n", result); + } + } +} + +/**************************************************************************** + * @fn void wfx_securelink_task_start(void) + * @brief + * Creates WFX securelink key renegotiation task. + * @param[in] None + * @return None + ******************************************************************************/ +void wfx_securelink_task_start(void) +{ + secureLinkTaskHandle = xTaskCreateStatic(prvSecureLinkTask, "secureLinkTask", WFX_SECURELINK_TASK_STK_SIZE, NULL, + WFX_SECURELINK_TASK_PRIO, secureLinkStack, &secureLinkTaskStruct); + if (secureLinkTaskHandle == NULL) + { + printf("Failed to create WFX secureLinkTask"); + } +} + +#endif diff --git a/examples/platform/efr32/wf200/sl_wfx_task.c b/examples/platform/efr32/wf200/sl_wfx_task.c new file mode 100644 index 00000000000000..baa484772d47a4 --- /dev/null +++ b/examples/platform/efr32/wf200/sl_wfx_task.c @@ -0,0 +1,128 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include +#include +#include + +#include "em_gpio.h" + +#include "sl_wfx.h" +#include "sl_wfx_board.h" +#include "sl_wfx_host.h" +#include "sl_wfx_task.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "AppConfig.h" + +#define CHECK_VAL 0 +#define WFX_BUS_TASK_PRIORITY 2 +#define BUS_TASK_STACK_SIZE 1024 +static StackType_t busStack[BUS_TASK_STACK_SIZE]; +StaticTask_t busTaskStruct; +TaskHandle_t wfx_bus_task_handle; + +wfx_frame_q_item wfx_bus_tx_frame; +SemaphoreHandle_t wfxtask_tx_complete; +SemaphoreHandle_t wfxtask_mutex; + +// Flag to indicate receive frames is currently running. +static bool wfx_bus_rx_in_process = false; + +/*************************************************************************** + * @fn bool wfx_bus_is_receive_processing(void) + * @brief + * Check receive frame status + * @param[in] None + * @return returns wfx_bus_rx_in_process + ******************************************************************************/ +bool wfx_bus_is_receive_processing(void) +{ + return wfx_bus_rx_in_process; +} + +/***************************************************************************** + * @fn static sl_status_t receive_frames() + * @brief + * Receives frames from the WFX. + * @param[in] None + * @return returns result + ******************************************************************************/ +static sl_status_t receive_frames() +{ + sl_status_t result; + uint16_t control_register = 0; + wfx_bus_rx_in_process = true; + do + { + result = sl_wfx_receive_frame(&control_register); + SL_WFX_ERROR_CHECK(result); + } while ((control_register & SL_WFX_CONT_NEXT_LEN_MASK) != CHECK_VAL); + +error_handler: + wfx_bus_rx_in_process = false; + return result; +} + +/******************************************************************************** + * @fn static void wfx_bus_task(void *p_arg) + * @brief + * WFX bus communication task. + * receives frames from the Bus interface + * @param[in] p_arg: + * @return None + */ +static void wfx_bus_task(void * p_arg) +{ + EFR32_LOG("SPI: Bus Task started"); + sl_wfx_host_start_platform_interrupt(); + for (;;) + { + /*Wait for an interrupt from WFX*/ + ulTaskNotifyTake(pdTRUE, portMAX_DELAY); + + /*Disable the interrupt while treating frames received to avoid + *the case where the interrupt is set but there is no frame left to treat.*/ + sl_wfx_host_disable_platform_interrupt(); + + /*Receive the frame(s) pending in WFX*/ + receive_frames(); + + /*Re-enable the interrupt*/ + sl_wfx_host_enable_platform_interrupt(); + } +} + +/*************************************************************************** + * @fn void wfx_bus_start() + * @brief + * Creates WFX bus communication task. + * @param[in] None + * @return None + ******************************************************************************/ +void wfx_bus_start() +{ + wfx_bus_task_handle = + xTaskCreateStatic(wfx_bus_task, "wfxbus", BUS_TASK_STACK_SIZE, NULL, WFX_BUS_TASK_PRIORITY, busStack, &busTaskStruct); + if (wfx_bus_task_handle == NULL) + { + EFR32_LOG("*ERR*WFX BusTask"); + } +} diff --git a/examples/platform/efr32/wf200/sl_wfx_task.h b/examples/platform/efr32/wf200/sl_wfx_task.h new file mode 100644 index 00000000000000..6838b9bac14eb4 --- /dev/null +++ b/examples/platform/efr32/wf200/sl_wfx_task.h @@ -0,0 +1,57 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#pragma once + +#include + +#include "FreeRTOS.h" +#include "sl_wfx_constants.h" +#include "task.h" + +typedef struct +{ + sl_wfx_send_frame_req_t * frame; + uint32_t data_length; + sl_wfx_interface_t interface; + uint8_t priority; +} wfx_frame_q_item; + +extern wfx_frame_q_item wfxtask_tx_frame; +extern TaskHandle_t wfx_bus_task_handle; + +#ifdef __cplusplus +extern "C" { +#endif + +/**************************************************************************** + * @fn void wfx_bus_start(void) + * @brief + * Start wfx bus communication task. + *****************************************************************************/ +void wfx_bus_start(void); + +/**************************************************************************** + * @fn bool wfx_bus_is_receive_processing(void) + * @brief + * Returns status of wfx receive frames. + *****************************************************************************/ +bool wfx_bus_is_receive_processing(void); + +#ifdef __cplusplus +} +#endif diff --git a/examples/platform/efr32/wf200/wf200.gni b/examples/platform/efr32/wf200/wf200.gni new file mode 100644 index 00000000000000..e7236d3004d2c1 --- /dev/null +++ b/examples/platform/efr32/wf200/wf200.gni @@ -0,0 +1,30 @@ +import("//build_overrides/chip.gni") +import("//build_overrides/efr32_sdk.gni") +import("//build_overrides/pigweed.gni") + +examples_plat_dir = "${chip_root}/examples/platform/efr32" +wifi_sdk_dir = "${chip_root}/src/platform/EFR32/wifi" + +wf200_defs = [ + "SL_HEAP_SIZE=24576", + "WF200_WIFI=1", + "SL_WIFI=1", + "SL_WFX_USE_SPI", + "SL_WFX_DEBUG_MASK=0x0003", +] +softap_defs = "SL_WFX_CONFIG_SOFTAP" +wifi_scan_defs = "SL_WFX_CONFIG_SCAN" +wf200_plat_incs = [ + "${wifi_sdk_dir}/", + "${examples_plat_dir}/wf200", +] +wf200_plat_src = [ + "${wifi_sdk_dir}/dhcp_client.cpp", + "${wifi_sdk_dir}/ethernetif.cpp", + "${wifi_sdk_dir}/lwip_netif.cpp", + "${wifi_sdk_dir}/wfx_notify.cpp", + "${examples_plat_dir}/wf200/sl_wfx_task.c", + "${examples_plat_dir}/wf200/wf200_init.c", + "${examples_plat_dir}/wf200/efr_spi.c", + "${examples_plat_dir}/wf200/host_if.cpp", +] diff --git a/examples/platform/efr32/wf200/wf200_init.c b/examples/platform/efr32/wf200/wf200_init.c new file mode 100644 index 00000000000000..bebdaf0f0a5b8c --- /dev/null +++ b/examples/platform/efr32/wf200/wf200_init.c @@ -0,0 +1,543 @@ +/* + * + * Copyright (c) 2022 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 "em_gpio.h" + +#include "sl_wfx.h" +#include "sl_wfx_board.h" + +// File specific to each platform, it must be created for custom boards +#include "sl_wfx_pds.h" + +#include +#include +#include +#include + +/* Firmware include */ +#include "sl_wfx_wf200_C0.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "AppConfig.h" +#include "sl_wfx_host.h" +#include "sl_wfx_task.h" +#include "wfx_host_events.h" + +#include "sl_spidrv_instances.h" +#include "spidrv.h" + +#define SL_WFX_EVENT_MAX_SIZE 512 +#define SL_WFX_EVENT_LIST_SIZE 1 + +StaticSemaphore_t xWfxWakeupSemaBuffer; +uint8_t sWfxEventQueueBuffer[SL_WFX_EVENT_LIST_SIZE * sizeof(uint8_t)]; +StaticQueue_t sWfxEventQueueStruct; +QueueHandle_t wfx_event_Q = NULL; +SemaphoreHandle_t wfx_wakeup_sem = NULL; +SemaphoreHandle_t wfx_mutex = NULL; + +StaticSemaphore_t xWfxMutexBuffer; + +struct +{ + uint32_t wf200_firmware_download_progress; + int wf200_initialized; + uint8_t waited_event_id; + uint8_t posted_event_id; +} host_context; + +#ifdef SL_WFX_USE_SDIO +#ifdef SLEEP_ENABLED +sl_status_t sl_wfx_host_enable_sdio(void); +sl_status_t sl_wfx_host_disable_sdio(void); +#endif +#endif + +#ifdef SL_WFX_USE_SPI +#ifdef SLEEP_ENABLED +sl_status_t sl_wfx_host_enable_spi(void); +sl_status_t sl_wfx_host_disable_spi(void); +#endif +#endif + +/**************************************************************************** + * @fn sl_status_t wfx_soft_init(void) + * @brief + * WFX FMAC driver host interface initialization + * @param[in] None + * @returns Returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t wfx_soft_init(void) +{ + EFR32_LOG("WF200:Soft Init"); + if ((wfx_event_Q = xQueueCreateStatic(SL_WFX_EVENT_LIST_SIZE, sizeof(uint8_t), sWfxEventQueueBuffer, &sWfxEventQueueStruct)) == + NULL) + { + return SL_STATUS_FAIL; + } + + if ((wfx_wakeup_sem = xSemaphoreCreateBinaryStatic(&xWfxWakeupSemaBuffer)) == NULL) + { + return SL_STATUS_FAIL; + } + + if ((wfx_mutex = xSemaphoreCreateMutexStatic(&xWfxMutexBuffer)) == NULL) + { + return SL_STATUS_FAIL; + } + + return SL_STATUS_OK; +} +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_init(void) + * @brief + * Notify driver init function + * @param[in] None + * @returns Returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_init(void) +{ + EFR32_LOG("WFX: Host Init"); + host_context.wf200_firmware_download_progress = 0; + host_context.wf200_initialized = 0; + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_get_firmware_data(const uint8_t **data, uint32_t data_size) + * @brief + * Get firmware data + * @param[in] data: + * @param[in] data_size: + * @returns Returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_get_firmware_data(const uint8_t ** data, uint32_t data_size) +{ + *data = &sl_wfx_firmware[host_context.wf200_firmware_download_progress]; + host_context.wf200_firmware_download_progress += data_size; + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_get_firmware_size(uint32_t *firmware_size) + * @brief + * Get firmware size + * @param[in] firmware_size: + * @returns Returns SL_STATUS_OK if successful, + * SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_get_firmware_size(uint32_t * firmware_size) +{ + *firmware_size = sizeof(sl_wfx_firmware); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_get_pds_data(const char **pds_data, uint16_t index) + * @brief + * Get PDS data + * @param[in] pds_data: + * @param[in] index: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_get_pds_data(const char ** pds_data, uint16_t index) +{ + *pds_data = sl_wfx_pds[index]; + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_get_pds_size(uint16_t *pds_size) + * @brief + * Get PDS size + * @param[in] pds_size: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_get_pds_size(uint16_t * pds_size) +{ + *pds_size = SL_WFX_ARRAY_COUNT(sl_wfx_pds); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_deinit(void) + * @brief + * Deinit host interface + * @param[in] None + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_deinit(void) +{ + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_allocate_buffer(void **buffer, sl_wfx_buffer_type_t type, uint32_t buffer_size) + * @brief + * Allocate buffer (Should allocate either Ethernet - from LWIP or Control) - TODO + * @param[in] buffer: + * @param[in] type: + * @param[in] buffer_size: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_allocate_buffer(void ** buffer, sl_wfx_buffer_type_t type, uint32_t buffer_size) +{ + if ((*buffer = pvPortMalloc(buffer_size)) == (void *) 0) + { + return SL_STATUS_FAIL; + } + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_free_buffer(void *buffer, sl_wfx_buffer_type_t type) + * @brief + * Free host buffer (CHECK LWIP buffer) + * @param[in] buffer: + * @param[in] type: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_free_buffer(void * buffer, sl_wfx_buffer_type_t type) +{ + vPortFree(buffer); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_hold_in_reset(void) + * @brief + * Set reset pin low + * @param[in] None + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_hold_in_reset(void) +{ + GPIO_PinOutClear(SL_WFX_HOST_PINOUT_RESET_PORT, SL_WFX_HOST_PINOUT_RESET_PIN); + host_context.wf200_initialized = 0; + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_set_wake_up_pin(uint8_t state) + * @brief + * Set wakeup pin status + * @param[in] state: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_set_wake_up_pin(uint8_t state) +{ + CORE_DECLARE_IRQ_STATE; + + CORE_ENTER_ATOMIC(); + if (state > PINOUT_CLEAR_STATUS) + { +#ifdef SLEEP_ENABLED +#ifdef SL_WFX_USE_SDIO + sl_wfx_host_enable_sdio(); +#endif +#ifdef SL_WFX_USE_SPI + sl_wfx_host_enable_spi(); +#endif +#endif + GPIO_PinOutSet(SL_WFX_HOST_PINOUT_WUP_PORT, SL_WFX_HOST_PINOUT_WUP_PIN); + } + else + { + GPIO_PinOutClear(SL_WFX_HOST_PINOUT_WUP_PORT, SL_WFX_HOST_PINOUT_WUP_PIN); +#ifdef SLEEP_ENABLED +#ifdef SL_WFX_USE_SDIO + sl_wfx_host_disable_sdio(); +#endif +#ifdef SL_WFX_USE_SPI + sl_wfx_host_disable_spi(); +#endif +#endif + } + CORE_EXIT_ATOMIC(); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_reset_chip(void) + * @brief + * reset the host chip + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_reset_chip(void) +{ + // Pull it low for at least 1 ms to issue a reset sequence + GPIO_PinOutClear(SL_WFX_HOST_PINOUT_RESET_PORT, SL_WFX_HOST_PINOUT_RESET_PIN); + + // Delay for 10ms + vTaskDelay(pdMS_TO_TICKS(10)); + + // Hold pin high to get chip out of reset + GPIO_PinOutSet(SL_WFX_HOST_PINOUT_RESET_PORT, SL_WFX_HOST_PINOUT_RESET_PIN); + + // Delay for 3ms + vTaskDelay(pdMS_TO_TICKS(3)); + + host_context.wf200_initialized = 0; + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_wait_for_wake_up(void) + * @brief + * wait for the host wake up + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_wait_for_wake_up(void) +{ + xSemaphoreTake(wfx_wakeup_sem, TICKS_TO_WAIT_0); + xSemaphoreTake(wfx_wakeup_sem, TICKS_TO_WAIT_3 / portTICK_PERIOD_MS); + + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_wait(uint32_t wait_time) + * @brief + * wait for the host + * @param[in] wait_time: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ + +sl_status_t sl_wfx_host_wait(uint32_t wait_time) +{ + uint32_t ticks = pdMS_TO_TICKS(wait_time); + vTaskDelay(ticks ? ticks : 10); + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_setup_waited_event(uint8_t event_id) + * @brief + * Called when the driver needs to setup the waited event + * @param[in] event_id: + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_FAIL otherwise + *****************************************************************************/ + +sl_status_t sl_wfx_host_setup_waited_event(uint8_t event_id) +{ + host_context.waited_event_id = event_id; + host_context.posted_event_id = 0; + + return SL_STATUS_OK; +} + +/**************************************************************************** + * @fn uint8_t sl_wfx_host_get_waited_event(void) + * @brief + * Called when the driver get waited event + * @returns returns host_context.waited_event_id + *****************************************************************************/ + +uint8_t sl_wfx_host_get_waited_event(void) +{ + return host_context.waited_event_id; +} + +/****************************************************************************** + * @fn sl_status_t sl_wfx_host_wait_for_confirmation(uint8_t confirmation_id, uint32_t timeout, void **event_payload_out) + * @brief + * wait for the host confirmation + * @param[in] confirmation_id: + * @param[in] timeout: + * @param[in] event_payload_out: + * @returns Returns SL_STATUS_OK if successful, + * Timeout, SL_STATUS_TIMEOUT otherwise + *****************************************************************************/ + +sl_status_t sl_wfx_host_wait_for_confirmation(uint8_t confirmation_id, uint32_t timeout, void ** event_payload_out) +{ + uint8_t posted_event_id; + for (uint32_t i = 0; i < timeout; i++) + { + /* Wait for an event posted by the function sl_wfx_host_post_event() */ + if (xQueueReceive(wfx_event_Q, &posted_event_id, TICKS_TO_WAIT_1) == pdTRUE) + { + /* Once a message is received, check if it is the expected ID */ + if (confirmation_id == posted_event_id) + { + /* Pass the confirmation reply and return*/ + if (event_payload_out != NULL) + { + *event_payload_out = sl_wfx_context->event_payload_buffer; + } + return SL_STATUS_OK; + } + } + } + /* The wait for the confirmation timed out, return */ + return SL_STATUS_TIMEOUT; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_lock(void) + * @brief + * Called when the driver needs to lock its access + * @returns Returns SL_STATUS_OK if successful, + *SL_STATUS_TIMEOUT otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_lock(void) +{ + + sl_status_t status = SL_STATUS_OK; + + if (xSemaphoreTake(wfx_mutex, TICKS_TO_WAIT_500) != pdTRUE) + { + EFR32_LOG("*ERR*Wi-Fi driver mutex timo"); + status = SL_STATUS_TIMEOUT; + } + + return status; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_unlock(void) + * @brief + * Called when the driver needs to unlock its access + * @returns Returns SL_STATUS_OK + *****************************************************************************/ +sl_status_t sl_wfx_host_unlock(void) +{ + xSemaphoreGive(wfx_mutex); + + return SL_STATUS_OK; +} + +/****************************************************************************** + * @fn sl_status_t sl_wfx_host_post_event(sl_wfx_generic_message_t *event_payload) + * @brief + * Called when the driver needs to post an event + * @param[in] event_payload: + * @returns Returns status + *****************************************************************************/ +sl_status_t sl_wfx_host_post_event(sl_wfx_generic_message_t * event_payload) +{ + sl_status_t status; + + /* Forward the message to the application */ + status = sl_wfx_host_process_event(event_payload); + + if (host_context.waited_event_id == event_payload->header.id) + { + if (event_payload->header.length < SL_WFX_EVENT_MAX_SIZE) + { + /* Post the event in the queue */ + memcpy(sl_wfx_context->event_payload_buffer, (void *) event_payload, event_payload->header.length); + host_context.posted_event_id = event_payload->header.id; + xQueueOverwrite(wfx_event_Q, (void *) &event_payload->header.id); + } + } + + return status; +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_transmit_frame(void *frame, uint32_t frame_len) + * @brief + * Called when the driver needs to transmit a frame + * @param[in] frame: + * @param[in] frame_len: + * @returns returns sl_wfx_data_write(frame, frame_len) + *****************************************************************************/ +sl_status_t sl_wfx_host_transmit_frame(void * frame, uint32_t frame_len) +{ + return sl_wfx_data_write(frame, frame_len); +} + +/**************************************************************************** + * @fn sl_status_t sl_wfx_host_sleep_grant(sl_wfx_host_bus_transfer_type_t type, + sl_wfx_register_address_t address, + uint32_t length) + * @brief + * Called when the driver is considering putting the + * WFx in sleep mode + * @param[in] type: + * @param[in] address: + * @param[in] length: + * @returns SL_WIFI_SLEEP_GRANTED to let the WFx go to + *sleep, SL_WIFI_SLEEP_NOT_GRANTED otherwise + *****************************************************************************/ +sl_status_t sl_wfx_host_sleep_grant(sl_wfx_host_bus_transfer_type_t type, sl_wfx_register_address_t address, uint32_t length) +{ + (void) (type); + (void) (address); + (void) (length); + + return SL_STATUS_WIFI_SLEEP_GRANTED; +} + +#if SL_WFX_DEBUG_MASK +/**************************************************************************** + * @fn void sl_wfx_host_log(const char *str, ...) + * @brief + * Host debug output + * @param[in] str: string + * @return None + *****************************************************************************/ +void sl_wfx_host_log(const char * str, ...) +{ + va_list args; + va_start(args, str); + vprintf(str, args); + va_end(args); +} +#endif +#ifndef PW_RPC_ENABLED +/* Place holder - This is just to handle UART interrupts + * The "otThread tasks handles it. WiFi does not need it yet + * I don't care for it. I should really have the thread + * shut it off + */ +#if !CHIP_ENABLE_OPENTHREAD +/**************************************************************************** + * @fn void otSysEventSignalPending(void) + * @brief + * system event signal pending + * @param[in] None + * @return None + *****************************************************************************/ +void otSysEventSignalPending(void) +{ + // BaseType_t yieldRequired = ThreadStackMgrImpl().SignalThreadActivityPendingFromISR(); + EFR32_LOG("*ERR*UART intr - NOT Handled"); + portYIELD_FROM_ISR(pdFALSE); +} +#endif /* !CHIP_ENABLE_OPENTHREAD */ +#endif /* PW_RPC_ENABLED */ diff --git a/examples/thermostat/efr32/BUILD.gn b/examples/thermostat/efr32/BUILD.gn index 3c4190218c68c6..27b9bee06ee343 100644 --- a/examples/thermostat/efr32/BUILD.gn +++ b/examples/thermostat/efr32/BUILD.gn @@ -91,7 +91,7 @@ if (silabs_board == "BRD4166A" || silabs_board == "BRD2601B" || # WiFi settings if (chip_enable_wifi) { - wifi_sdk_dir = "${chip_root}/third_party/silabs/matter_support/matter/wifi" + wifi_sdk_dir = "${chip_root}/src/platform/EFR32/wifi" efr32_lwip_defs = [ "LWIP_NETIF_API=1" ] efr32_lwip_defs += [ "LWIP_IPV4=1", @@ -105,9 +105,9 @@ if (chip_enable_wifi) { if (use_rs911x) { wiseconnect_sdk_root = "${chip_root}/third_party/silabs/wiseconnect-wifi-bt-sdk" - import("${wifi_sdk_dir}/rs911x/rs911x.gni") + import("${examples_plat_dir}/rs911x/rs911x.gni") } else { - import("${wifi_sdk_dir}/wf200/wf200.gni") + import("${examples_plat_dir}/wf200/wf200.gni") } } diff --git a/examples/window-app/efr32/BUILD.gn b/examples/window-app/efr32/BUILD.gn index 5b781828462497..36e429efffffd0 100644 --- a/examples/window-app/efr32/BUILD.gn +++ b/examples/window-app/efr32/BUILD.gn @@ -95,7 +95,7 @@ if (chip_enable_wifi) { show_qr_code = false disable_lcd = true } - wifi_sdk_dir = "${chip_root}/third_party/silabs/matter_support/matter/wifi" + wifi_sdk_dir = "${chip_root}/src/platform/EFR32/wifi" efr32_lwip_defs = [ "LWIP_NETIF_API=1" ] efr32_lwip_defs += [ "LWIP_IPV4=1", @@ -109,9 +109,9 @@ if (chip_enable_wifi) { if (use_rs911x) { wiseconnect_sdk_root = "${chip_root}/third_party/silabs/wiseconnect-wifi-bt-sdk" - import("${wifi_sdk_dir}/rs911x/rs911x.gni") + import("${examples_plat_dir}/rs911x/rs911x.gni") } else { - import("${wifi_sdk_dir}/wf200/wf200.gni") + import("${examples_plat_dir}/wf200/wf200.gni") } } diff --git a/src/platform/EFR32/wifi/dhcp_client.cpp b/src/platform/EFR32/wifi/dhcp_client.cpp new file mode 100644 index 00000000000000..b78e21f84411f2 --- /dev/null +++ b/src/platform/EFR32/wifi/dhcp_client.cpp @@ -0,0 +1,145 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include +#include +#include + +#include "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" + +#include "dhcp_client.h" +#include "lwip/dhcp.h" +#include "wfx_host_events.h" +#include "wifi_config.h" + +#include "AppConfig.h" +#include "FreeRTOS.h" +#include "event_groups.h" + +#define MAX_DHCP_TRIES 4 +#define NETIF_IPV4_ADDRESS(X, Y) (((X) >> (8 * Y)) & 0xFF) + +/* Station IP address */ +uint8_t sta_ip_addr0 = STA_IP_ADDR0_DEFAULT; +uint8_t sta_ip_addr1 = STA_IP_ADDR1_DEFAULT; +uint8_t sta_ip_addr2 = STA_IP_ADDR2_DEFAULT; +uint8_t sta_ip_addr3 = STA_IP_ADDR3_DEFAULT; +uint8_t sta_netmask_addr0 = STA_NETMASK_ADDR0_DEFAULT; +uint8_t sta_netmask_addr1 = STA_NETMASK_ADDR1_DEFAULT; +uint8_t sta_netmask_addr2 = STA_NETMASK_ADDR2_DEFAULT; +uint8_t sta_netmask_addr3 = STA_NETMASK_ADDR3_DEFAULT; +uint8_t sta_gw_addr0 = STA_GW_ADDR0_DEFAULT; +uint8_t sta_gw_addr1 = STA_GW_ADDR1_DEFAULT; +uint8_t sta_gw_addr2 = STA_GW_ADDR2_DEFAULT; +uint8_t sta_gw_addr3 = STA_GW_ADDR3_DEFAULT; + +/// Current DHCP state machine state. +static volatile uint8_t dhcp_state = DHCP_OFF; + +/***************************************************************************** + * @fn void dhcpclient_set_link_state(int link_up) + * @brief + * Notify DHCP client task about the wifi status + * @param link_up link status + * @return None + ******************************************************************************/ +void dhcpclient_set_link_state(int link_up) +{ + if (link_up) + { + dhcp_state = DHCP_START; + EFR32_LOG("DHCP: Starting"); + } + else + { + /* Update DHCP state machine */ + dhcp_state = DHCP_LINK_DOWN; + } +} + +/********************************************************************************** + * @fn uint8_t dhcpclient_poll(void *arg) + * @brief + * Don't need a task here. We get polled every 250ms + * @return None + ************************************************************************************/ +uint8_t dhcpclient_poll(void * arg) +{ + struct netif * netif = (struct netif *) arg; + ip_addr_t ipaddr; + ip_addr_t netmask; + ip_addr_t gw; + struct dhcp * dhcp; + + switch (dhcp_state) + { + case DHCP_START: + EFR32_LOG("DHCP: Wait addr"); + ip_addr_set_zero_ip4(&netif->ip_addr); + ip_addr_set_zero_ip4(&netif->netmask); + ip_addr_set_zero_ip4(&netif->gw); + dhcp_start(netif); + dhcp_state = DHCP_WAIT_ADDRESS; + break; + + case DHCP_WAIT_ADDRESS: + if (dhcp_supplied_address(netif)) + { + dhcp_state = DHCP_ADDRESS_ASSIGNED; + + uint64_t addr = netif->ip_addr.u_addr.ip4.addr; + EFR32_LOG("DHCP IP: %d.%d.%d.%d", NETIF_IPV4_ADDRESS(addr, 0), NETIF_IPV4_ADDRESS(addr, 1), NETIF_IPV4_ADDRESS(addr, 2), + NETIF_IPV4_ADDRESS(addr, 3)); + } + else + { + dhcp = (struct dhcp *) netif_get_client_data(netif, LWIP_NETIF_CLIENT_DATA_INDEX_DHCP); + + /* DHCP timeout */ + if (dhcp->tries > MAX_DHCP_TRIES) + { + dhcp_state = DHCP_TIMEOUT; + + EFR32_LOG("*ERR*DHCP: Failed"); + /* Stop DHCP */ + dhcp_stop(netif); + + /* TODO - I am not sure that this is best */ + /* Static address used */ + IP_ADDR4(&ipaddr, sta_ip_addr0, sta_ip_addr1, sta_ip_addr2, sta_ip_addr3); + IP_ADDR4(&netmask, sta_netmask_addr0, sta_netmask_addr1, sta_netmask_addr2, sta_netmask_addr3); + IP_ADDR4(&gw, sta_gw_addr0, sta_gw_addr1, sta_gw_addr2, sta_gw_addr3); + netif_set_addr(netif, ip_2_ip4(&ipaddr), ip_2_ip4(&netmask), ip_2_ip4(&gw)); + } + } + break; + + case DHCP_LINK_DOWN: + /* Stop DHCP */ + EFR32_LOG("*ERR*DHCP Link down"); + dhcp_stop(netif); + dhcp_state = DHCP_OFF; + break; + default: + break; + } + return dhcp_state; +} diff --git a/src/platform/EFR32/wifi/dhcp_client.h b/src/platform/EFR32/wifi/dhcp_client.h new file mode 100644 index 00000000000000..5937f6a29d86d3 --- /dev/null +++ b/src/platform/EFR32/wifi/dhcp_client.h @@ -0,0 +1,41 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#pragma once +#ifdef __cplusplus +extern "C" { +#endif + +// DHCP client states +#define DHCP_OFF (uint8_t) 0 +#define DHCP_START (uint8_t) 1 +#define DHCP_WAIT_ADDRESS (uint8_t) 2 +#define DHCP_ADDRESS_ASSIGNED (uint8_t) 3 +#define DHCP_TIMEOUT (uint8_t) 4 +#define DHCP_LINK_DOWN (uint8_t) 5 + +/***************************************************************************** + * @fn void dhcpclient_set_link_state(int link_up) + * @brief + * Notify DHCP client task about the wifi status + * @param link_up link status + ******************************************************************************/ +void dhcpclient_set_link_state(int link_up); +uint8_t dhcpclient_poll(void * arg); +#ifdef __cplusplus +} +#endif diff --git a/src/platform/EFR32/wifi/ethernetif.cpp b/src/platform/EFR32/wifi/ethernetif.cpp new file mode 100644 index 00000000000000..318f8a272ece1b --- /dev/null +++ b/src/platform/EFR32/wifi/ethernetif.cpp @@ -0,0 +1,417 @@ +/* + * + * Copyright (c) 2022 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 "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" + +#ifndef WF200_WIFI +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" +#endif + +#include "wfx_host_events.h" +#include "wifi_config.h" +#ifdef WF200_WIFI +#include "sl_wfx.h" +#endif +/* LwIP includes. */ +#include "ethernetif.h" +#include "lwip/ethip6.h" +#include "lwip/timeouts.h" +#include "netif/etharp.h" + +#ifndef EFR32_LOG +extern "C" { +void efr32Log(const char * aFormat, ...); +#define EFR32_LOG(...) efr32Log(__VA_ARGS__); +} +#endif + +StaticSemaphore_t xEthernetIfSemaBuffer; + +/***************************************************************************** + * Defines + ******************************************************************************/ +#define STATION_NETIF0 's' +#define STATION_NETIF1 't' + +#define LWIP_FRAME_ALIGNMENT 60 + +/***************************************************************************** + * Variables + ******************************************************************************/ + +/***************************************************************************** + * @fn static void low_level_init(struct netif *netif) + * @brief + * Initializes the hardware parameters. Called from ethernetif_init(). + * + * @param[in] netif: the already initialized lwip network interface structure + * + * @return + * None + ******************************************************************************/ +static void low_level_init(struct netif * netif) +{ + /* set netif MAC hardware address length */ + netif->hwaddr_len = ETH_HWADDR_LEN; + + /* Set netif MAC hardware address */ + sl_wfx_mac_address_t mac_addr; + + wfx_get_wifi_mac_addr(SL_WFX_STA_INTERFACE, &mac_addr); + + netif->hwaddr[0] = mac_addr.octet[0]; + netif->hwaddr[1] = mac_addr.octet[1]; + netif->hwaddr[2] = mac_addr.octet[2]; + netif->hwaddr[3] = mac_addr.octet[3]; + netif->hwaddr[4] = mac_addr.octet[4]; + netif->hwaddr[5] = mac_addr.octet[5]; + + /* Set netif maximum transfer unit */ + netif->mtu = 1500; + + /* Accept broadcast address and ARP traffic */ + netif->flags |= NETIF_FLAG_BROADCAST | NETIF_FLAG_ETHARP | NETIF_FLAG_IGMP; +} + +/******************************************************************************** + * @fn static void low_level_input(struct netif *netif, uint8_t *b, uint16_t len) + * @brief + * Make PBUF out of a linear buffer - that can be fed into lwip + * @param[in] netif: the already initialized lwip network interface structure + * @param[in] len: length + * @return + * None + ************************************************************************************/ +static void low_level_input(struct netif * netif, uint8_t * b, uint16_t len) +{ + struct pbuf *p, *q; + uint32_t bufferoffset; + + if (len <= 0) + { + return; + } + if (len < 60) + { /* 60 : LWIP frame alignment */ + len = 60; + } + /* We allocate a pbuf chain of pbufs from the Lwip buffer pool + * and copy the data to the pbuf chain + */ + if ((p = pbuf_alloc(PBUF_RAW, len, PBUF_POOL)) != STRUCT_PBUF) + { + for (q = p, bufferoffset = 0; q != NULL; q = q->next) + { + memcpy((uint8_t *) q->payload, (uint8_t *) b + bufferoffset, q->len); + bufferoffset += q->len; + } + +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("EN:IN %d,[%02x:%02x:%02x:%02x:%02x%02x][%02x:%02x:%02x:%02x:%02x:%02x]type=%02x%02x", bufferoffset, b[0], b[1], + b[2], b[3], b[4], b[5], b[6], b[7], b[8], b[9], b[10], b[11], b[12], b[13]); +#endif + + if (netif->input(p, netif) != ERR_OK) + { + pbuf_free(p); + } + } +} + +/***************************************************************************** + * @fn static err_t low_level_output(struct netif *netif, struct pbuf *p) + * @brief + * This function should does the actual transmission of the packet(s). + * The packet is contained in the pbuf that is passed to the function. + * This pbuf might be chained. + * + * @param[in] netif: the lwip network interface structure + * + * @param[in] p: the packet to send + * + * @return + * ERR_OK if successful + ******************************************************************************/ +#ifdef WF200_WIFI +static err_t low_level_output(struct netif * netif, struct pbuf * p) +{ + struct pbuf * q; + sl_wfx_send_frame_req_t * tx_buffer; + uint8_t * buffer; + uint32_t framelength, asize; + uint32_t bufferoffset; + uint32_t padding; + sl_status_t result; + + for (q = p, framelength = 0; q != NULL; q = q->next) + { + framelength += q->len; + } + if (framelength < LWIP_FRAME_ALIGNMENT) + { /* 60 : Frame alignment for LWIP */ + padding = LWIP_FRAME_ALIGNMENT - framelength; + } + else + { + padding = 0; + } + + /* choose padding of 64 */ + asize = SL_WFX_ROUND_UP(framelength + padding, 64) + sizeof(sl_wfx_send_frame_req_t); + // 12 is size of other data in buffer struct, user shouldn't have to care about this? + if (sl_wfx_host_allocate_buffer((void **) &tx_buffer, SL_WFX_TX_FRAME_BUFFER, asize) != SL_STATUS_OK) + { + EFR32_LOG("*ERR*EN-Out: No mem frame len=%d", framelength); + return ERR_MEM; + } + buffer = tx_buffer->body.packet_data; + /* copy frame from pbufs to driver buffers */ + for (q = p, bufferoffset = 0; q != NULL; q = q->next) + { + /* Get bytes in current lwIP buffer */ + memcpy((uint8_t *) ((uint8_t *) buffer + bufferoffset), (uint8_t *) ((uint8_t *) q->payload), q->len); + bufferoffset += q->len; + } + /* No requirement to do this - but we should for security */ + if (padding) + { + memset(buffer + bufferoffset, 0, padding); + framelength += padding; + } + /* transmit */ + int i = 0; + result = SL_STATUS_FAIL; + +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("WF200: Out %d", (int) framelength); +#endif + + /* send the generated frame over Wifi network */ + while ((result != SL_STATUS_OK) && (i++ < 10)) + { + result = sl_wfx_send_ethernet_frame(tx_buffer, framelength, SL_WFX_STA_INTERFACE, PRIORITY_0); + } + sl_wfx_host_free_buffer(tx_buffer, SL_WFX_TX_FRAME_BUFFER); + + if (result != SL_STATUS_OK) + { + EFR32_LOG("*ERR*Send enet %d", (int) framelength); + return ERR_IF; + } + return ERR_OK; +} + +/***************************************************************************** + * @fn void sl_wfx_host_received_frame_callback(sl_wfx_received_ind_t *rx_buffer) + * @brief + * This function implements the wf200 received frame callback. + * Called from the context of the bus_task (not ISR) + * + * @param[in] rx_buffer: the ethernet frame received by the wf200 + * + * @return + * None + ******************************************************************************/ +void sl_wfx_host_received_frame_callback(sl_wfx_received_ind_t * rx_buffer) +{ + struct netif * netif; + + /* Check packet interface to send to AP or STA interface */ + if ((rx_buffer->header.info & SL_WFX_MSG_INFO_INTERFACE_MASK) == (SL_WFX_STA_INTERFACE << SL_WFX_MSG_INFO_INTERFACE_OFFSET)) + { + + /* Send received frame to station interface */ + if ((netif = wfx_get_netif(SL_WFX_STA_INTERFACE)) != NULL) + { + uint8_t * buffer; + uint16_t len; + + len = rx_buffer->body.frame_length; + buffer = (uint8_t *) &(rx_buffer->body.frame[rx_buffer->body.frame_padding]); + +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("WF200: In %d", (int) len); +#endif + + low_level_input(netif, buffer, len); + } + else + { +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("WF200: NO-INTF"); +#endif + } + } + else + { +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("WF200: Invalid frame IN"); +#endif + } +} + +#else /* For RS911x - using LWIP */ +static SemaphoreHandle_t ethout_sem; +/***************************************************************************** + * @fn static err_t low_level_output(struct netif *netif, struct pbuf *p) + * @brief + * This function is called from LWIP task when LWIP stack + * has some data to be forwarded over WiFi Network + * + * @param[in] netif: lwip network interface + * + * @param[in] p: the packet to send + * + * @return + * ERR_OK if successful + ******************************************************************************/ +static err_t low_level_output(struct netif * netif, struct pbuf * p) +{ + void * rsipkt; + struct pbuf * q; + uint16_t framelength; + + if (xSemaphoreTake(ethout_sem, portMAX_DELAY) != pdTRUE) + { + return ERR_IF; + } +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("EN-RSI: Output"); +#endif + if ((netif->flags & (NETIF_FLAG_LINK_UP | NETIF_FLAG_UP)) != (NETIF_FLAG_LINK_UP | NETIF_FLAG_UP)) + { + EFR32_LOG("EN-RSI:NOT UP"); + xSemaphoreGive(ethout_sem); + return ERR_IF; + } + /* Confirm if packet is allocated */ + rsipkt = wfx_rsi_alloc_pkt(); + if (!rsipkt) + { + EFR32_LOG("EN-RSI:No buf"); + xSemaphoreGive(ethout_sem); + return ERR_IF; + } + +#ifdef WIFI_DEBUG_ENABLED + uint8_t * b = (uint8_t *) p->payload; + EFR32_LOG("EN-RSI: Out [%02x:%02x:%02x:%02x:%02x:%02x][%02x:%02x:%02x:%02x:%02x:%02x]type=%02x%02x", b[0], b[1], b[2], b[3], + b[4], b[5], b[6], b[7], b[8], b[9], b[10], b[11], b[12], b[13]); +#endif + /* Generate the packet */ + for (q = p, framelength = 0; q != NULL; q = q->next) + { + wfx_rsi_pkt_add_data(rsipkt, (uint8_t *) (q->payload), (uint16_t) q->len, framelength); + framelength += q->len; + } + if (framelength < LWIP_FRAME_ALIGNMENT) + { + /* Add junk data to the end for frame alignment if framelength is less than 60 */ + wfx_rsi_pkt_add_data(rsipkt, (uint8_t *) (p->payload), LWIP_FRAME_ALIGNMENT - framelength, framelength); + } +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("EN-RSI: Sending %d", framelength); +#endif + + /* forward the generated packet to RSI to + * send the data over wifi network + */ + if (wfx_rsi_send_data(rsipkt, framelength)) + { + EFR32_LOG("*ERR*EN-RSI:Send fail"); + xSemaphoreGive(ethout_sem); + return ERR_IF; + } + +#ifdef WIFI_DEBUG_ENABLED + EFR32_LOG("EN-RSI:Xmit %d", framelength); +#endif + xSemaphoreGive(ethout_sem); + + return ERR_OK; +} + +/***************************************************************************** + * @fn void wfx_host_received_sta_frame_cb(uint8_t *buf, int len) + * @brief + * host received frame cb + * + * @param[in] buf: buffer + * + * @param[in] len: length + * + * @return + * None + ******************************************************************************/ +void wfx_host_received_sta_frame_cb(uint8_t * buf, int len) +{ + struct netif * ifp; + + /* get the network interface for STATION interface, + * and forward the received frame buffer to LWIP + */ + if ((ifp = wfx_get_netif(SL_WFX_STA_INTERFACE)) != (struct netif *) 0) + { + low_level_input(ifp, buf, len); + } +} + +#endif /* RS911x - with LWIP */ + +/***************************************************************************** + * @fn err_t sta_ethernetif_init(struct netif *netif) + * @brief + * sta ethernet if initialization + * + * @param[in] netif: the lwip network interface structure + * + * @return + * ERR_OK if successful + ******************************************************************************/ +err_t sta_ethernetif_init(struct netif * netif) +{ + LWIP_ASSERT("netif != NULL", (netif != NULL)); + + /* Set the netif name to identify the interface */ + netif->name[0] = STATION_NETIF0; + netif->name[1] = STATION_NETIF1; + + netif->output = etharp_output; + netif->output_ip6 = ethip6_output; + netif->linkoutput = low_level_output; + + /* initialize the hardware */ + low_level_init(netif); +#ifndef WF200_WIFI + /* Need single output only */ + ethout_sem = xSemaphoreCreateBinaryStatic(&xEthernetIfSemaBuffer); + xSemaphoreGive(ethout_sem); +#endif + return ERR_OK; +} diff --git a/src/platform/EFR32/wifi/ethernetif.h b/src/platform/EFR32/wifi/ethernetif.h new file mode 100644 index 00000000000000..dfea1ea6ad3540 --- /dev/null +++ b/src/platform/EFR32/wifi/ethernetif.h @@ -0,0 +1,52 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#pragma once + +#include "lwip/err.h" +#include "lwip/netif.h" +#ifdef __cplusplus +extern "C" { +#endif +/*************************************************************************** + * @fn err_t sta_ethernetif_init(struct netif *netif) + * @brief + * Sets up the station network interface. + * + * @param netif the lwip network interface structure + * @returns ERR_OK if successful + ******************************************************************************/ +err_t sta_ethernetif_init(struct netif * netif); + +/*************************************************************************** + * @fn err_t ap_ethernetif_init(struct netif *netif + * @brief + * Sets up the AP network interface. + * + * @param netif the lwip network interface structure + * @returns ERR_OK if successful + ******************************************************************************/ +err_t ap_ethernetif_init(struct netif * netif); + +#ifdef WF200_WIFI +void sl_wfx_host_received_frame_callback(sl_wfx_received_ind_t * rx_buffer); +#else +void wfx_host_received_sta_frame_cb(uint8_t * buf, int len); +#endif /* WF200_WIFI */ +#ifdef __cplusplus +} +#endif diff --git a/src/platform/EFR32/wifi/lwip_netif.cpp b/src/platform/EFR32/wifi/lwip_netif.cpp new file mode 100644 index 00000000000000..a13a9c35abcc25 --- /dev/null +++ b/src/platform/EFR32/wifi/lwip_netif.cpp @@ -0,0 +1,146 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef RS911X_SOCKETS +#include +#include +#include + +#include "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" + +#include "wfx_host_events.h" +#include "wifi_config.h" + +#include "AppConfig.h" +#include "dhcp_client.h" +#include "ethernetif.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include +using namespace ::chip; +using namespace ::chip::DeviceLayer; +static struct netif sta_netif; + +#ifdef SL_WFX_CONFIG_SOFTAP +static struct netif ap_netif; +#endif + +/**************************************************************************** + * @fn static void netif_config(struct netif *sta_if, struct netif *ap_if) + * @brief + * netif configuration + * @param[in] sta_if: + * @param[in] ap_if: + * @return None + *****************************************************************************/ +static void netif_config(struct netif * sta_if, struct netif * ap_if) +{ + if (sta_if != NULL) + { + ip_addr_t sta_ipaddr; + ip_addr_t sta_netmask; + ip_addr_t sta_gw; + + /* Initialize the Station information */ + ip_addr_set_zero_ip4(&sta_ipaddr); + ip_addr_set_zero_ip4(&sta_netmask); + ip_addr_set_zero_ip4(&sta_gw); + + /* Add station interfaces */ + netif_add(sta_if, (const ip4_addr_t *) &sta_ipaddr, (const ip4_addr_t *) &sta_netmask, (const ip4_addr_t *) &sta_gw, NULL, + &sta_ethernetif_init, &tcpip_input); + + /* Registers the default network interface */ + netif_set_default(sta_if); + } +} + +/**************************************************************************** + * @fn void wfx_lwip_set_sta_link_up(void) + * @brief + * Set station link status to up. + * @param[in] None + * @return None + *****************************************************************************/ +void wfx_lwip_set_sta_link_up(void) +{ + netifapi_netif_set_up(&sta_netif); + netifapi_netif_set_link_up(&sta_netif); + dhcpclient_set_link_state(LINK_UP); + /* + * Enable IPV6 + */ + netif_create_ip6_linklocal_address(&sta_netif, MAC_48_BIT_SET); +} + +/*************************************************************************** + * @fn void wfx_lwip_set_sta_link_down(void) + * @brief + * Set station link status to down. + * @param[in] None + * @return None + *****************************************************************************/ +void wfx_lwip_set_sta_link_down(void) +{ + dhcpclient_set_link_state(LINK_DOWN); + netifapi_netif_set_link_down(&sta_netif); + netifapi_netif_set_down(&sta_netif); +} + +/*************************************************************************** + * @fn void wfx_lwip_start(void) + * @brief + * Initialize the LwIP stack + * @param[in] None + * @return None + *****************************************************************************/ +void wfx_lwip_start(void) +{ + /* Initialize the LwIP stack */ + netif_config(&sta_netif, NULL); +} + +/*************************************************************************** + * @fn struct netif *wfx_get_netif(sl_wfx_interface_t interface) + * @brief + * get the netif + * @param[in] interface: + * @return None + *****************************************************************************/ +struct netif * wfx_get_netif(sl_wfx_interface_t interface) +{ + if (interface == SL_WFX_STA_INTERFACE) + { + return &sta_netif; + } +#ifdef SL_WFX_CONFIG_SOFTAP + else if (interface == SL_WFX_SOFTAP_INTERFACE) + { + return &ap_netif; + } +#endif + return (struct netif *) 0; +} + +#endif /* RS911X_SOCKETS */ diff --git a/src/platform/EFR32/wifi/wfx_host_events.h b/src/platform/EFR32/wifi/wfx_host_events.h new file mode 100644 index 00000000000000..6a1e367d29cad0 --- /dev/null +++ b/src/platform/EFR32/wifi/wfx_host_events.h @@ -0,0 +1,298 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#pragma once + +#ifdef WF200_WIFI +#include "FreeRTOS.h" +#include "event_groups.h" +#include "semphr.h" +#include "task.h" +#include "timers.h" + +#include "sl_wfx_cmd_api.h" +#include "sl_wfx_constants.h" +#else /* RS911x */ +#include "wfx_msgs.h" + +/* Wi-Fi events*/ +#define SL_WFX_STARTUP_IND_ID 1 +#define SL_WFX_CONNECT_IND_ID 2 +#define SL_WFX_DISCONNECT_IND_ID 3 +#define SL_WFX_SCAN_COMPLETE_ID 4 +#define WFX_RSI_SSID_SIZE 64 + +#endif /* WF200 */ + +#ifndef RS911X_SOCKETS +/* LwIP includes. */ +#include "lwip/apps/httpd.h" +#include "lwip/ip_addr.h" +#include "lwip/netif.h" +#include "lwip/netifapi.h" +#include "lwip/tcpip.h" + +/* Wi-Fi bitmask events - for the task */ +#define SL_WFX_CONNECT (1 << 1) +#define SL_WFX_DISCONNECT (1 << 2) +#define SL_WFX_START_AP (1 << 3) +#define SL_WFX_STOP_AP (1 << 4) +#define SL_WFX_SCAN_START (1 << 5) +#define SL_WFX_SCAN_COMPLETE (1 << 6) +#define SL_WFX_RETRY_CONNECT (1 << 7) + +#endif /* RS911X_SOCKETS */ + +#include "sl_status.h" + +#ifdef RS911X_WIFI +#define WLAN_TASK_STACK_SIZE 1024 +#define WLAN_TASK_PRIORITY 1 +#define WLAN_DRIVER_TASK_PRIORITY 1 +#define MAX_JOIN_RETRIES_COUNT 5 + +#else /* WF200 */ +#define WLAN_TASK_STACK_SIZE 1024 +#define WLAN_TASK_PRIORITY 1 +#define MAX_JOIN_RETRIES_COUNT 5 +#endif + +// WLAN related Macros +#define ETH_FRAME 0 +#define CMP_SUCCESS 0 +#define BSSID_MAX_STR_LEN 6 +#define MAC_ADDRESS_FIRST_OCTET 6 +#define AP_START_SUCCESS 0 +#define BITS_TO_WAIT 0 +#define CONNECTION_STATUS_SUCCESS 1 +#define IP_STATUS_FAIL 0 +#define GET_IPV6_SUCCESS 1 +#define GET_IPV6_FAIL 0 +#define BEACON_1 0 +#define CHANNEL_LIST (const uint8_t *) 0 +#define CHANNEL_COUNT 0 +#define IE_DATA (const uint8_t *) 0 +#define IE_DATA_LENGTH 0 +#define BSSID_SCAN (const uint8_t *) 0 +#define CHANNEL_0 0 +#define PREVENT_ROAMING 1 +#define DISABLE_PMF_MODE 0 +#define STA_IP_FAIL 0 +#define IP_STATUS_SUCCESS 1 +#define ACTIVE_CHANNEL_TIME_100 100 +#define PASSIVE_CHANNEL_TIME_0 0 +#define PROBE_NUM_REQ_1 1 + +#define PINOUT_CLEAR_STATUS 0 +#define TICKS_TO_WAIT_0 0 +#define TICKS_TO_WAIT_3 3 +#define TICKS_TO_WAIT_1 1 +#define TICKS_TO_WAIT_500 500 + +// TASK and Interrupt Macros +#define SUCCESS_STATUS 1 +#define LINK_UP 1 +#define LINK_DOWN 0 +#define MAC_48_BIT_SET 1 +#define STRUCT_PBUF (struct pbuf *) 0 +#define PRIORITY_0 0 +#define HEX_VALUE_FF 0XFF + +// Timer Delay +#define MAX_XLEN 16 +#define MIN_XLEN 0 +#define PINOUT_CLEAR 0 +#define PINOUT_SET 1 +#define WFX_SPI_NVIC_PRIORITY 5 +#define WFX_GPIO_NVIC_PRIORITY 5 +#define CB_VALUE (DMADRV_Callback_t) 0 + +/* TIMER_TICKS_TO_WAIT Specifies the time, in ticks, that the calling task should + * be held in the Blocked state to wait for the start command to be successfully + * sent to the timer command queue. + */ +#define TIMER_TICKS_TO_WAIT_0 0 + +#define CONVERT_SEC_TO_MSEC 1000 +#define CONVERT_USEC_TO_MSEC (1 / 1000) + +#define RSI_RESPONSE_MAX_SIZE 28 +#define RSI_RESPONSE_HOLD_BUFF_SIZE 128 +#define RSI_DRIVER_STATUS 0 +#define OPER_MODE_0 0 +#define COEX_MODE_0 0 +#define RESP_BUFF_SIZE 6 +#define AP_CHANNEL_NO_0 0 +#define SCAN_BITMAP_OPTN_1 1 +#define IP_CONF_RSP_BUFF_LENGTH_4 4 +#define STATION 0 +#define BG_SCAN_RES_SIZE 500 + +#define SPI_CONFIG_SUCESS 0 +#define WPA3_SECURITY 3 + +typedef enum +{ + WIFI_EVENT, + IP_EVENT, +} wfx_event_base_t; + +typedef enum +{ + IP_EVENT_STA_GOT_IP, + IP_EVENT_GOT_IP6, + IP_EVENT_STA_LOST_IP, +} ip_event_id_t; + +/* Note that these are same as RSI_security */ +typedef enum +{ + WFX_SEC_NONE = 0, + WFX_SEC_WPA = 1, + WFX_SEC_WPA2 = 2, + WFX_SEC_WEP = 3, + WFX_SEC_WPA_EAP = 4, + WFX_SEC_WPA2_EAP = 5, + WFX_SEC_WPA_WPA2_MIXED = 6, + WFX_SEC_WPA_PMK = 7, + WFX_SEC_WPA2_PMK = 8, + WFX_SEC_WPS_PIN = 9, + WFX_SEC_GEN_WPS_PIN = 10, + WFX_SEC_PUSH_BTN = 11, + WFX_SEC_WPA3 = 11, +} wfx_sec_t; + +#define WPA3_SECURITY 3 + +typedef struct +{ + char ssid[32 + 1]; + char passkey[64 + 1]; + uint8_t security; +} wfx_wifi_provision_t; + +typedef enum +{ + WIFI_MODE_NULL = 0, + WIFI_MODE_STA, + WIFI_MODE_AP, + WIFI_MODE_APSTA, + WIFI_MODE_MAX, +} wifi_mode_t; + +typedef struct wfx_wifi_scan_result +{ + char ssid[32 + 1]; + uint8_t security; + uint8_t bssid[6]; + uint8_t chan; + int16_t rssi; /* I suspect this is in dBm - so signed */ +} wfx_wifi_scan_result_t; + +typedef struct wfx_wifi_scan_ext +{ + uint32_t beacon_lost_count; + uint32_t beacon_rx_count; + uint32_t mcast_rx_count; + uint32_t mcast_tx_count; + uint32_t ucast_rx_count; + uint32_t ucast_tx_count; + uint32_t overrun_count; +} wfx_wifi_scan_ext_t; + +#ifdef RS911X_WIFI +/* + * This Sh%t is here to support WFXUtils - and the Matter stuff that uses it + * We took it from the SDK (for WF200) + */ +typedef enum +{ + SL_WFX_NOT_INIT = 0, + SL_WFX_STARTED = 1, + SL_WFX_STA_INTERFACE_CONNECTED = 2, + SL_WFX_AP_INTERFACE_UP = 3, + SL_WFX_SLEEPING = 4, + SL_WFX_POWER_SAVE_ACTIVE = 5, +} sl_wfx_state_t; + +typedef enum +{ + SL_WFX_STA_INTERFACE = 0, ///< Interface 0, linked to the station + SL_WFX_SOFTAP_INTERFACE = 1, ///< Interface 1, linked to the softap +} sl_wfx_interface_t; + +#endif /* RS911X_WIFI */ +#ifdef __cplusplus +extern "C" { +#endif + +void sl_wfx_host_gpio_init(void); +sl_status_t wfx_wifi_start(void); +void wfx_enable_sta_mode(void); +sl_wfx_state_t wfx_get_wifi_state(void); +void wfx_get_wifi_mac_addr(sl_wfx_interface_t interface, sl_wfx_mac_address_t * addr); +void wfx_set_wifi_provision(wfx_wifi_provision_t * wifiConfig); +bool wfx_get_wifi_provision(wfx_wifi_provision_t * wifiConfig); +bool wfx_is_sta_provisioned(void); +bool wfx_is_sta_mode_enabled(void); +int32_t wfx_get_ap_info(wfx_wifi_scan_result_t * ap); +int32_t wfx_get_ap_ext(wfx_wifi_scan_ext_t * extra_info); +int32_t wfx_reset_counts(); + +void wfx_clear_wifi_provision(void); +sl_status_t wfx_connect_to_ap(void); +void wfx_setup_ip6_link_local(sl_wfx_interface_t); +bool wfx_is_sta_connected(void); +sl_status_t wfx_sta_discon(void); +bool wfx_have_ipv4_addr(sl_wfx_interface_t); +bool wfx_have_ipv6_addr(sl_wfx_interface_t); +wifi_mode_t wfx_get_wifi_mode(void); +bool wfx_start_scan(char * ssid, void (*scan_cb)(wfx_wifi_scan_result_t *)); /* true returned if successfuly started */ +void wfx_cancel_scan(void); + +/* + * Call backs into the Matter Platform code + */ +void wfx_started_notify(void); +void wfx_connected_notify(int32_t status, sl_wfx_mac_address_t * ap); +void wfx_disconnected_notify(int32_t status); +/* Implemented for LWIP */ +void wfx_host_received_sta_frame_cb(uint8_t * buf, int len); +void wfx_lwip_set_sta_link_up(void); +void wfx_lwip_set_sta_link_down(void); +void wfx_lwip_start(void); +struct netif * wfx_get_netif(sl_wfx_interface_t interface); +void wfx_dhcp_got_ipv4(uint32_t); +bool wfx_hw_ready(void); +void wfx_ip_changed_notify(int got_ip); +void wfx_ipv6_notify(int got_ip); + +#ifdef RS911X_WIFI +/* RSI for LWIP */ +void * wfx_rsi_alloc_pkt(void); +void wfx_rsi_pkt_add_data(void * p, uint8_t * buf, uint16_t len, uint16_t off); +int32_t wfx_rsi_send_data(void * p, uint16_t len); +#endif /* RS911X_WIFI */ + +#ifdef WF200_WIFI +void wfx_bus_start(void); +void sl_wfx_host_gpio_init(void); +sl_status_t sl_wfx_host_process_event(sl_wfx_generic_message_t * event_payload); +#endif +#ifdef __cplusplus +} +#endif diff --git a/src/platform/EFR32/wifi/wfx_msgs.h b/src/platform/EFR32/wifi/wfx_msgs.h new file mode 100644 index 00000000000000..edf0aec5828fa7 --- /dev/null +++ b/src/platform/EFR32/wifi/wfx_msgs.h @@ -0,0 +1,182 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef _WFX_MSGS_H_ +#define _WFX_MSGS_H_ +/* + * Taken from sl_wfx firmware - so I can re-use. + * I need to do a better job than to use this stuff + * in the CPP files of Matter + */ +typedef struct +{ + uint8_t octet[6]; ///< Table to store a MAC address +} sl_wfx_mac_address_t; +/** + * @brief General Message header structure + * + */ +typedef struct __attribute__((__packed__)) sl_wfx_header_s +{ + uint16_t length; ///< Message length in bytes including this uint16_t. + ///< Maximum value is 8188 but maximum Request size is FW dependent and reported in the + ///< ::sl_wfx_startup_ind_body_t::size_inp_ch_buf. + uint8_t id; ///< Contains the message Id indexed by sl_wfx_general_commands_ids_t or sl_wfx_message_ids_t. + uint8_t info; ///< TODO comment missing +} sl_wfx_header_t; + +/** + * @brief Generic message structure for all requests, confirmations and indications + * + */ +typedef struct __attribute__((__packed__)) sl_wfx_generic_message_s +{ + sl_wfx_header_t header; ///< 4 bytes header + uint8_t body[]; ///< variable size payload of the message +} sl_wfx_generic_message_t; +#define SL_WFX_OPN_SIZE 14 +#define SL_WFX_UID_SIZE 8 +#define SL_WFX_DISABLED_CHANNEL_LIST_SIZE 2 +#define SL_WFX_FIRMWARE_LABEL_SIZE 128 +/** + * @brief Startup Indication message. + * This is the first message sent to the host to confirm boot success. + * It gives detailed information on the HW and FW versions and capabilities + */ +typedef struct __attribute__((__packed__)) sl_wfx_startup_ind_body_s +{ + uint32_t + status; ///< Initialization status. A value of zero indicates the boot is completed successfully (see enum sl_wfx_status_t) + uint16_t hardware_id; ///<=RO misc_read_reg7 register value +#if 0 /* Not used in RS911x for now - use stuff here for the port */ + uint8_t opn[SL_WFX_OPN_SIZE]; ///<=OTP part_OPN + uint8_t uid[SL_WFX_UID_SIZE]; ///<=OTP UID + uint16_t num_inp_ch_bufs; ///WFM_STATUS_SUCCESS: the connection request was completed successfully. + *
any other value: the connection request failed. + *
See sl_wfx_fmac_status_t for enumeration values. + */ + uint32_t status; + /** + * @brief MAC address of the connected access point. + */ + uint8_t mac[6]; + /** + * @brief Channel of the connected access point. + * @details 1 - 13: Channel number. + */ + uint16_t channel; + /** + * @brief Beacon Interval of the connected access point. + */ + uint8_t beacon_interval; + /** + * @brief DTIM period of the connected access point. + * @details 1 - 255: DTIM period. + */ + uint8_t dtim_period; + /** + * @brief Maximum PHY data rate supported by the connection. + * @details See sl_wfx_rate_index_t for enumeration values. + */ + uint16_t max_phy_rate; +} sl_wfx_connect_ind_body_t; + +/** + * @brief Indication message used to signal the completion of a connection operation. + * @details The device will send this indication to signal the connection request initiated + * with sl_wfx_connect_req_t has been completed. The indication is also sent when + * the device autonomously roams to another access point. + * @ingroup WFM_GROUP_MODE_IDLE + */ +typedef struct __attribute__((__packed__)) sl_wfx_connect_ind_s +{ + /** Common message header. */ + sl_wfx_header_t header; + /** Indication message body. */ + sl_wfx_connect_ind_body_t body; +} sl_wfx_connect_ind_t; +/** + * @brief Indication message body for sl_wfx_disconnect_ind_t. + */ +typedef struct __attribute__((__packed__)) sl_wfx_disconnect_ind_body_s +{ + /** + * @brief MAC address of the access point. + */ + uint8_t mac[6]; + /** + * @brief Reason for disconnection. + * @details WFM_DISCONNECTED_REASON_UNSPECIFIED: The device disconnected because of an internal error. + *
WFM_DISCONNECTED_REASON_AP_LOST: The device lost the AP beacons for too long. + *
WFM_DISCONNECTED_REASON_REJECTED: The device was disconnected by the AP. + *
WFM_DISCONNECTED_REASON_LEAVING_BSS: Disconnection was requested through the device API. + *
WFM_DISCONNECTED_REASON_WPA_COUNTERMEASURES: WPA countermeasures triggered a disconnection + *
See sl_wfx_disconnected_reason_t for enumeration values. + */ + uint16_t reason; +} sl_wfx_disconnect_ind_body_t; + +/** + * @brief Indication message used to signal the completion of a disconnection operation. + * @details The device will send this indication to signal the disconnection request initiated + * with sl_wfx_disconnect_req_t has been completed. The indication is also sent when + * the device has lost the connection to an access point and has been unable to regain it. + * @ingroup WFM_GROUP_MODE_STA + */ +typedef struct __attribute__((__packed__)) sl_wfx_disconnect_ind_s +{ + /** Common message header. */ + sl_wfx_header_t header; + /** Indication message body. */ + sl_wfx_disconnect_ind_body_t body; +} sl_wfx_disconnect_ind_t; + +#endif /* _WFX_MSGS_H_ */ diff --git a/src/platform/EFR32/wifi/wfx_notify.cpp b/src/platform/EFR32/wifi/wfx_notify.cpp new file mode 100644 index 00000000000000..7e975f93416b41 --- /dev/null +++ b/src/platform/EFR32/wifi/wfx_notify.cpp @@ -0,0 +1,189 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#include +#include +#include + +#include "em_bus.h" +#include "em_cmu.h" +#include "em_gpio.h" +#include "em_ldma.h" +#include "em_usart.h" +#include "gpiointerrupt.h" + +#include "AppConfig.h" + +#include "FreeRTOS.h" +#include "event_groups.h" +#include "task.h" + +#include "wfx_host_events.h" + +#ifdef RS911X_WIFI +#include "wfx_rsi.h" +#endif + +#include +//#include +#include +#include + +using namespace ::chip; +using namespace ::chip::DeviceLayer; + +/* + * Notifications to the upper-layer + * All done in the context of the RSI/WiFi task (rsi_if.c) + */ + +/*********************************************************************************** + * @fn wfx_started_notify() + * @brief + * Wifi device started notification + * @param[in]: None + * @return None + *************************************************************************************/ +void wfx_started_notify() +{ + sl_wfx_startup_ind_t evt; + sl_wfx_mac_address_t mac; + + EFR32_LOG("%s: started.", __func__); + + memset(&evt, 0, sizeof(evt)); + evt.header.id = SL_WFX_STARTUP_IND_ID; + evt.header.length = sizeof evt; + evt.body.status = 0; + wfx_get_wifi_mac_addr(SL_WFX_STA_INTERFACE, &mac); + memcpy(&evt.body.mac_addr[0], &mac.octet[0], MAC_ADDRESS_FIRST_OCTET); + + PlatformMgrImpl().HandleWFXSystemEvent(WIFI_EVENT, (sl_wfx_generic_message_t *) &evt); +} + +/*********************************************************************************** + * @fn void wfx_connected_notify(int32_t status, sl_wfx_mac_address_t *ap) + * @brief + * For now we are not notifying anything other than AP Mac - + * Other stuff such as DTIM etc. may be required for later + * @param[in] status: + * @param[in] ap: access point + * @return None + *************************************************************************************/ +void wfx_connected_notify(int32_t status, sl_wfx_mac_address_t * ap) +{ + sl_wfx_connect_ind_t evt; + + EFR32_LOG("%s: started.", __func__); + + if (status != SUCCESS_STATUS) + { + EFR32_LOG("%s: error: failed status: %d.", __func__, status); + return; + } + + EFR32_LOG("%s: connected.", __func__); + + memset(&evt, 0, sizeof(evt)); + evt.header.id = SL_WFX_CONNECT_IND_ID; + evt.header.length = sizeof evt; + +#ifdef RS911X_WIFI + evt.body.channel = wfx_rsi.ap_chan; +#endif + memcpy(&evt.body.mac[0], &ap->octet[0], MAC_ADDRESS_FIRST_OCTET); + + PlatformMgrImpl().HandleWFXSystemEvent(WIFI_EVENT, (sl_wfx_generic_message_t *) &evt); +} + +/************************************************************************************** + * @fn void wfx_disconnected_notify(int32_t status) + * @brief + * notification of disconnection + * @param[in] status: + * @return None + ********************************************************************************************/ +void wfx_disconnected_notify(int32_t status) +{ + sl_wfx_disconnect_ind_t evt; + + EFR32_LOG("%s: started.", __func__); + + memset(&evt, 0, sizeof(evt)); + evt.header.id = SL_WFX_DISCONNECT_IND_ID; + evt.header.length = sizeof evt; + evt.body.reason = status; + PlatformMgrImpl().HandleWFXSystemEvent(WIFI_EVENT, (sl_wfx_generic_message_t *) &evt); +} + +/************************************************************************************** + * @fn void wfx_ipv6_notify(int got_ip) + * @brief + * notification of ipv6 + * @param[in] got_ip: + * @return None + ********************************************************************************************/ +void wfx_ipv6_notify(int got_ip) +{ + sl_wfx_generic_message_t eventData; + + EFR32_LOG("%s: started.", __func__); + + memset(&eventData, 0, sizeof(eventData)); + eventData.header.id = got_ip ? IP_EVENT_GOT_IP6 : IP_EVENT_STA_LOST_IP; + eventData.header.length = sizeof(eventData.header); + PlatformMgrImpl().HandleWFXSystemEvent(IP_EVENT, &eventData); + + /* So the other threads can run and have the connectivity OK */ + if (got_ip) + { + /* Should remember this */ + vTaskDelay(1); + chip::DeviceLayer::PlatformMgr().LockChipStack(); + chip::app::DnssdServer::Instance().StartServer(/*Dnssd::CommissioningMode::kEnabledBasic*/); + chip::DeviceLayer::PlatformMgr().UnlockChipStack(); + } +} + +/************************************************************************************** + * @fn void wfx_ip_changed_notify(int got_ip) + * @brief + * notification of ip change + * @param[in] got_ip: + * @return None + ********************************************************************************************/ +void wfx_ip_changed_notify(int got_ip) +{ + sl_wfx_generic_message_t eventData; + + EFR32_LOG("%s: started.", __func__); + + memset(&eventData, 0, sizeof(eventData)); + eventData.header.id = got_ip ? IP_EVENT_STA_GOT_IP : IP_EVENT_STA_LOST_IP; + eventData.header.length = sizeof(eventData.header); + PlatformMgrImpl().HandleWFXSystemEvent(IP_EVENT, &eventData); + + /* So the other threads can run and have the connectivity OK */ + if (got_ip) + { + /* Should remember this */ + vTaskDelay(1); + chip::DeviceLayer::PlatformMgr().LockChipStack(); + chip::app::DnssdServer::Instance().StartServer(/*Dnssd::CommissioningMode::kEnabledBasic*/); + chip::DeviceLayer::PlatformMgr().UnlockChipStack(); + } +} diff --git a/src/platform/EFR32/wifi/wifi_config.h b/src/platform/EFR32/wifi/wifi_config.h new file mode 100644 index 00000000000000..88ad34b5741649 --- /dev/null +++ b/src/platform/EFR32/wifi/wifi_config.h @@ -0,0 +1,71 @@ +/* + * + * Copyright (c) 2022 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. + */ + +#ifndef DEMO_CONFIG_H +#define DEMO_CONFIG_H + +#define USE_DHCP_CLIENT_DEFAULT 1 ///< If defined, DHCP is enabled, otherwise static address below is used + +/************************** Station Static Default ****************************/ +#define STA_IP_ADDR0_DEFAULT (uint8_t) 192 ///< Static IP: IP address value 0 +#define STA_IP_ADDR1_DEFAULT (uint8_t) 168 ///< Static IP: IP address value 1 +#define STA_IP_ADDR2_DEFAULT (uint8_t) 0 ///< Static IP: IP address value 2 +#define STA_IP_ADDR3_DEFAULT (uint8_t) 1 ///< Static IP: IP address value 3 + +/*NETMASK*/ +#define STA_NETMASK_ADDR0_DEFAULT (uint8_t) 255 ///< Static IP: Netmask value 0 +#define STA_NETMASK_ADDR1_DEFAULT (uint8_t) 255 ///< Static IP: Netmask value 1 +#define STA_NETMASK_ADDR2_DEFAULT (uint8_t) 255 ///< Static IP: Netmask value 2 +#define STA_NETMASK_ADDR3_DEFAULT (uint8_t) 0 ///< Static IP: Netmask value 3 + +/*Gateway Address*/ +#define STA_GW_ADDR0_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 0 +#define STA_GW_ADDR1_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 1 +#define STA_GW_ADDR2_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 2 +#define STA_GW_ADDR3_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 3 + +/************************** Access Point Static Default ****************************/ +// #define AP_IP_ADDR0_DEFAULT (uint8_t) 10 ///< Static IP: IP address value 0 +// #define AP_IP_ADDR1_DEFAULT (uint8_t) 10 ///< Static IP: IP address value 1 +// #define AP_IP_ADDR2_DEFAULT (uint8_t) 0 ///< Static IP: IP address value 2 +// #define AP_IP_ADDR3_DEFAULT (uint8_t) 1 ///< Static IP: IP address value 3 + +/*NETMASK*/ +// #define AP_NETMASK_ADDR0_DEFAULT (uint8_t) 255 ///< Static IP: Netmask value 0 +// #define AP_NETMASK_ADDR1_DEFAULT (uint8_t) 255 ///< Static IP: Netmask value 1 +// #define AP_NETMASK_ADDR2_DEFAULT (uint8_t) 255 ///< Static IP: Netmask value 2 +// #define AP_NETMASK_ADDR3_DEFAULT (uint8_t) 0 ///< Static IP: Netmask value 3 + +/*Gateway Address*/ +// #define AP_GW_ADDR0_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 0 +// #define AP_GW_ADDR1_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 1 +// #define AP_GW_ADDR2_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 2 +// #define AP_GW_ADDR3_DEFAULT (uint8_t) 0 ///< Static IP: Gateway value 3 + +#define WLAN_SSID_DEFAULT "AP_name" ///< wifi ssid for client mode +#define WLAN_PASSKEY_DEFAULT "passkey" ///< wifi password for client mode +#define WLAN_SECURITY_DEFAULT WFM_SECURITY_MODE_WPA2_PSK ///< wifi security mode for client mode: +///< WFM_SECURITY_MODE_OPEN/WFM_SECURITY_MODE_WEP/WFM_SECURITY_MODE_WPA2_WPA1_PSK + +#define SOFTAP_SSID_DEFAULT "silabs_softap" ///< wifi ssid for soft ap mode +#define SOFTAP_PASSKEY_DEFAULT "changeme" ///< wifi password for soft ap mode +#define SOFTAP_SECURITY_DEFAULT WFM_SECURITY_MODE_WPA2_PSK ///< wifi security for soft ap mode: +///< WFM_SECURITY_MODE_OPEN/WFM_SECURITY_MODE_WEP/WFM_SECURITY_MODE_WPA2_WPA1_PSK + +#define SOFTAP_CHANNEL_DEFAULT 6 ///< wifi channel for soft ap + +#endif // DEMO_CONFIG_H diff --git a/third_party/silabs/efr32_sdk.gni b/third_party/silabs/efr32_sdk.gni index bd7876d48ebb2c..9d118640b5ca1e 100644 --- a/third_party/silabs/efr32_sdk.gni +++ b/third_party/silabs/efr32_sdk.gni @@ -224,7 +224,7 @@ template("efr32_sdk") { # USART include files if ((defined(invoker.chip_enable_pw_rpc) && invoker.chip_enable_pw_rpc) || chip_build_libshell || enable_openthread_cli || - (defined(invoker.use_wf200) && invoker.use_wf200) || + (defined(invoker.chip_enable_wifi) && invoker.chip_enable_wifi) || (defined(invoker.show_qr_code) && invoker.show_qr_code) || (defined(invoker.disable_lcd) && !invoker.disable_lcd) || (defined(invoker.use_external_flash) && use_external_flash)) { @@ -250,6 +250,7 @@ template("efr32_sdk") { "${efr32_sdk_root}/util/third_party/freertos/kernel/portable/GCC/ARM_CM4F", "${efr32_sdk_root}/platform/radio/rail_lib/plugin/pa-conversions/efr32xg1x/config", "${efr32_sdk_root}/platform/service/device_init/config/s1/", + "${efr32_sdk_root}/platform/emdrv/spidrv/inc", ] libs += [ @@ -289,6 +290,7 @@ template("efr32_sdk") { "${efr32_sdk_root}/platform/radio/rail_lib/plugin/pa-conversions/efr32xg24", "${efr32_sdk_root}/platform/radio/rail_lib/plugin/pa-conversions/efr32xg24/config", "${efr32_sdk_root}/platform/service/device_init/config/s2/", + "${efr32_sdk_root}/platform/emdrv/spidrv/inc", ] libs += [ @@ -575,6 +577,14 @@ template("efr32_sdk") { ] } + # SPI is only used for Wifi + if (defined(invoker.chip_enable_wifi) && invoker.chip_enable_wifi) { + sources += [ + "${efr32_sdk_root}/platform/emdrv/spidrv/src/spidrv.c", + "${sdk_support_root}/matter/efr32/${silabs_family}/${silabs_board}/autogen/sl_spidrv_init.c", + ] + } + if (defined(invoker.enable_sleepy_device)) { if (invoker.enable_sleepy_device) { sources += [ "${efr32_sdk_root}/util/third_party/freertos/kernel/portable/SiliconLabs/tick_power_manager.c" ] @@ -590,7 +600,7 @@ template("efr32_sdk") { # USART sources files if ((defined(invoker.chip_enable_pw_rpc) && invoker.chip_enable_pw_rpc) || chip_build_libshell || enable_openthread_cli || - (defined(invoker.use_wf200) && invoker.use_wf200) || + (defined(invoker.chip_enable_wifi) && invoker.chip_enable_wifi) || (defined(invoker.show_qr_code) && invoker.show_qr_code) || (defined(invoker.disable_lcd) && !invoker.disable_lcd) || (defined(invoker.use_external_flash) && use_external_flash)) { diff --git a/third_party/silabs/matter_support b/third_party/silabs/matter_support index d9f3fb767d7b4a..58b1a4fd07291a 160000 --- a/third_party/silabs/matter_support +++ b/third_party/silabs/matter_support @@ -1 +1 @@ -Subproject commit d9f3fb767d7b4a79d664b0c635ffe6d777a812f2 +Subproject commit 58b1a4fd07291aecf710b5de268d34682c3768c2