diff --git a/.gitmodules b/.gitmodules index 9ec2545274..f146c1f5b9 100644 --- a/.gitmodules +++ b/.gitmodules @@ -65,3 +65,6 @@ [submodule "components/esp_wifi/lib_esp32"] path = components/esp_wifi/lib_esp32 url = https://github.com/espressif/esp32-wifi-lib.git +[submodule "components/esp_wifi/lib_esp32s2beta"] + path = components/esp_wifi/lib_esp32s2beta + url = ssh://git@gitlab.espressif.cn:27227/idf/esp32-wifi-lib.git diff --git a/components/driver/periph_ctrl.c b/components/driver/periph_ctrl.c index 2ef8c965a3..d448a914bf 100644 --- a/components/driver/periph_ctrl.c +++ b/components/driver/periph_ctrl.c @@ -130,7 +130,11 @@ static uint32_t get_clk_en_mask(periph_module_t periph) case PERIPH_RNG_MODULE: return DPORT_WIFI_CLK_RNG_EN; case PERIPH_WIFI_MODULE: +#if CONFIG_IDF_TARGET_ESP32 return DPORT_WIFI_CLK_WIFI_EN_M; +#elif CONFIG_IDF_TARGET_ESP32S2BETA + return 0; +#endif case PERIPH_BT_MODULE: return DPORT_WIFI_CLK_BT_EN_M; case PERIPH_WIFI_BT_COMMON_MODULE: diff --git a/components/driver/uart.c b/components/driver/uart.c index f557f4f4e0..37925e54df 100644 --- a/components/driver/uart.c +++ b/components/driver/uart.c @@ -308,9 +308,8 @@ static esp_err_t uart_reset_rx_fifo(uart_port_t uart_num) READ_PERI_REG(UART_FIFO_REG(uart_num)); } #elif CONFIG_IDF_TARGET_ESP32S2BETA - while(UART[uart_num]->status.rxfifo_cnt != 0 || (UART[uart_num]->mem_rx_status.rx_waddr != UART[uart_num]->mem_rx_status.apb_rx_raddr)) { - READ_PERI_REG(UART_FIFO_AHB_REG(uart_num)); - } + UART[uart_num]->conf0.rxfifo_rst = 1; + UART[uart_num]->conf0.rxfifo_rst = 0; #endif return ESP_OK; } diff --git a/components/esp32/Kconfig b/components/esp32/Kconfig index 405718ae08..e5b5dee5b3 100644 --- a/components/esp32/Kconfig +++ b/components/esp32/Kconfig @@ -658,6 +658,10 @@ menu "ESP32-specific" endmenu # ESP32-Specific menu "Power Management" + # TODO: this component simply shouldn't be included + # in the build at the CMake level, but this is currently + # not working so we just hide all items here + visible if IDF_TARGET_ESP32 config PM_ENABLE bool "Support for power management" diff --git a/components/esp32/Makefile.projbuild b/components/esp32/Makefile.projbuild index b99415538e..0ae77a69d2 100644 --- a/components/esp32/Makefile.projbuild +++ b/components/esp32/Makefile.projbuild @@ -1,44 +1,10 @@ -ifdef CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION - -PHY_INIT_DATA_OBJ = $(BUILD_DIR_BASE)/phy_init_data.o -PHY_INIT_DATA_BIN = $(BUILD_DIR_BASE)/phy_init_data.bin - -# Command to flash PHY init data partition -PHY_INIT_DATA_FLASH_CMD = $(ESPTOOLPY_SERIAL) write_flash $(PHY_DATA_OFFSET) $(PHY_INIT_DATA_BIN) -ESPTOOL_ALL_FLASH_ARGS += $(PHY_DATA_OFFSET) $(PHY_INIT_DATA_BIN) - -ESP32_COMPONENT_PATH := $(COMPONENT_PATH) - -$(PHY_INIT_DATA_OBJ): $(ESP32_COMPONENT_PATH)/phy_init_data.h $(BUILD_DIR_BASE)/include/sdkconfig.h - $(summary) CC $(notdir $@) - printf "#include \"phy_init_data.h\"\n" | $(CC) -I $(BUILD_DIR_BASE)/include -I $(ESP32_COMPONENT_PATH) -I $(ESP32_COMPONENT_PATH)/include -c -o $@ -xc - - -$(PHY_INIT_DATA_BIN): $(PHY_INIT_DATA_OBJ) - $(summary) BIN $(notdir $@) - $(OBJCOPY) -O binary $< $@ - -phy_init_data: $(PHY_INIT_DATA_BIN) - -phy_init_data-flash: $(BUILD_DIR_BASE)/phy_init_data.bin - @echo "Flashing PHY init data..." - $(PHY_INIT_DATA_FLASH_CMD) - -phy_init_data-clean: - rm -f $(PHY_INIT_DATA_BIN) $(PHY_INIT_DATA_OBJ) - -all: phy_init_data -flash: phy_init_data - -endif # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION - - # Enable psram cache bug workaround in compiler if selected ifdef CONFIG_SPIRAM_CACHE_WORKAROUND CFLAGS+=-mfix-esp32-psram-cache-issue CXXFLAGS+=-mfix-esp32-psram-cache-issue endif -# Enable dynamic esp_timer overflow value if building unit tests +# Enable dynamic esp_timer overflow value if building unit tests ifneq ("$(filter esp32,$(TEST_COMPONENTS_LIST))","") CPPFLAGS += -DESP_TIMER_DYNAMIC_OVERFLOW_VAL endif diff --git a/components/esp32s2beta/CMakeLists.txt b/components/esp32s2beta/CMakeLists.txt index ca521cfcec..dcd86321f4 100644 --- a/components/esp32s2beta/CMakeLists.txt +++ b/components/esp32s2beta/CMakeLists.txt @@ -17,6 +17,7 @@ elseif(CONFIG_IDF_TARGET_ESP32S2BETA) "crosscore_int.c" "dport_access.c" "dport_panic_highint_hdl.S" + "esp_adapter.c" "esp_timer_esp32s2beta.c" "gdbstub.c" "hw_random.c" diff --git a/components/esp32s2beta/Kconfig b/components/esp32s2beta/Kconfig index c69adb2ab9..66aa4b1ebb 100644 --- a/components/esp32s2beta/Kconfig +++ b/components/esp32s2beta/Kconfig @@ -508,6 +508,10 @@ menu "ESP32S2-specific" endmenu # ESP32S2-Specific menu "Power Management" + # TODO: this component simply shouldn't be included + # in the build at the CMake level, but this is currently + # not working so we just hide all items here + visible if IDF_TARGET_ESP32S2BETA config PM_ENABLE bool "Support for power management" diff --git a/components/esp32s2beta/clk.c b/components/esp32s2beta/clk.c index 975d7de6d7..fb078195d0 100644 --- a/components/esp32s2beta/clk.c +++ b/components/esp32s2beta/clk.c @@ -292,6 +292,9 @@ void esp_perip_clk_init(void) /* Disable WiFi/BT/SDIO clocks. */ DPORT_CLEAR_PERI_REG_MASK(DPORT_WIFI_CLK_EN_REG, wifi_bt_sdio_clk); + /* Enable WiFi MAC and POWER clocks */ + DPORT_SET_PERI_REG_MASK(DPORT_WIFI_CLK_EN_REG, DPORT_WIFI_CLK_WIFI_EN); + /* Enable RNG clock. */ periph_module_enable(PERIPH_RNG_MODULE); } diff --git a/components/esp32s2beta/esp_adapter.c b/components/esp32s2beta/esp_adapter.c new file mode 100644 index 0000000000..f27ad94b31 --- /dev/null +++ b/components/esp32s2beta/esp_adapter.c @@ -0,0 +1,629 @@ +// Copyright 2015-2018 Espressif Systems (Shanghai) PTE LTD +// +// 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 +#include +#include + +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "freertos/queue.h" +#include "freertos/semphr.h" +#include "freertos/event_groups.h" +#include "freertos/xtensa_api.h" +#include "freertos/portmacro.h" +#include "freertos/xtensa_api.h" +#include "esp_types.h" +#include "esp_system.h" +#include "esp_task.h" +#include "esp_intr_alloc.h" +#include "esp_attr.h" +#include "esp_log.h" +#include "esp_heap_caps.h" +#include "esp_private/wifi_os_adapter.h" +#include "esp_private/wifi.h" +#include "esp_phy_init.h" +#include "crypto/md5.h" +#include "crypto/sha1.h" +#include "crypto/crypto.h" +#include "crypto/aes.h" +#include "crypto/dh_group5.h" +#include "driver/periph_ctrl.h" +#include "nvs.h" +#include "os.h" +#include "esp_smartconfig.h" +#include "smartconfig_ack.h" +#include "esp_coexist_internal.h" +#include "esp_coexist_adapter.h" +#if CONFIG_IDF_TARGET_ESP32S2BETA +#include "esp32s2beta/clk.h" +#endif + + +extern void esp_dport_access_stall_other_cpu_start_wrap(void); +extern void esp_dport_access_stall_other_cpu_end_wrap(void); + +#define TAG "esp_adapter" + +/* + If CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP is enabled. Prefer to allocate a chunk of memory in SPIRAM firstly. + If failed, try to allocate it in internal memory then. + */ +IRAM_ATTR void *wifi_malloc( size_t size ) +{ +#if CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP + return heap_caps_malloc_prefer(size, 2, MALLOC_CAP_DEFAULT|MALLOC_CAP_SPIRAM, MALLOC_CAP_DEFAULT|MALLOC_CAP_INTERNAL); +#else + return malloc(size); +#endif +} + +/* + If CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP is enabled. Prefer to allocate a chunk of memory in SPIRAM firstly. + If failed, try to allocate it in internal memory then. + */ +IRAM_ATTR void *wifi_realloc( void *ptr, size_t size ) +{ +#if CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP + return heap_caps_realloc_prefer(ptr, size, 2, MALLOC_CAP_DEFAULT|MALLOC_CAP_SPIRAM, MALLOC_CAP_DEFAULT|MALLOC_CAP_INTERNAL); +#else + return realloc(ptr, size); +#endif +} + +/* + If CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP is enabled. Prefer to allocate a chunk of memory in SPIRAM firstly. + If failed, try to allocate it in internal memory then. + */ +IRAM_ATTR void *wifi_calloc( size_t n, size_t size ) +{ +#if CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP + return heap_caps_calloc_prefer(n, size, 2, MALLOC_CAP_DEFAULT|MALLOC_CAP_SPIRAM, MALLOC_CAP_DEFAULT|MALLOC_CAP_INTERNAL); +#else + return calloc(n, size); +#endif +} + +static void * IRAM_ATTR wifi_zalloc_wrapper(size_t size) +{ + void *ptr = wifi_calloc(1, size); + if (ptr) { + memset(ptr, 0, size); + } + return ptr; +} + +wifi_static_queue_t* wifi_create_queue( int queue_len, int item_size) +{ + wifi_static_queue_t *queue = NULL; + + queue = (wifi_static_queue_t*)heap_caps_malloc(sizeof(wifi_static_queue_t), MALLOC_CAP_INTERNAL|MALLOC_CAP_8BIT); + if (!queue) { + return NULL; + } + +#if CONFIG_SPIRAM_USE_MALLOC + + queue->storage = heap_caps_calloc(1, sizeof(StaticQueue_t) + (queue_len*item_size), MALLOC_CAP_INTERNAL|MALLOC_CAP_8BIT); + if (!queue->storage) { + goto _error; + } + + queue->handle = xQueueCreateStatic( queue_len, item_size, ((uint8_t*)(queue->storage)) + sizeof(StaticQueue_t), (StaticQueue_t*)(queue->storage)); + + if (!queue->handle) { + goto _error; + } + + return queue; + +_error: + if (queue) { + if (queue->storage) { + free(queue->storage); + } + + free(queue); + } + + return NULL; +#else + queue->handle = xQueueCreate( queue_len, item_size); + return queue; +#endif +} + +void wifi_delete_queue(wifi_static_queue_t *queue) +{ + if (queue) { + vQueueDelete(queue->handle); + +#if CONFIG_SPIRAM_USE_MALLOC + if (queue->storage) { + free(queue->storage); + } +#endif + + free(queue); + } +} + +static void * wifi_create_queue_wrapper(int queue_len, int item_size) +{ + return wifi_create_queue(queue_len, item_size); +} + +static void wifi_delete_queue_wrapper(void *queue) +{ + wifi_delete_queue(queue); +} + +static void set_isr_wrapper(int32_t n, void *f, void *arg) +{ + xt_set_interrupt_handler(n, (xt_handler)f, arg); +} + +static void * spin_lock_create_wrapper(void) +{ + portMUX_TYPE tmp = portMUX_INITIALIZER_UNLOCKED; + void *mux = malloc(sizeof(portMUX_TYPE)); + + if (mux) { + memcpy(mux,&tmp,sizeof(portMUX_TYPE)); + return mux; + } + return NULL; +} + +static uint32_t IRAM_ATTR wifi_int_disable_wrapper(void *wifi_int_mux) +{ + if (xPortInIsrContext()) { + portENTER_CRITICAL_ISR(wifi_int_mux); + } else { + portENTER_CRITICAL(wifi_int_mux); + } + + return 0; +} + +static void IRAM_ATTR wifi_int_restore_wrapper(void *wifi_int_mux, uint32_t tmp) +{ + if (xPortInIsrContext()) { + portEXIT_CRITICAL_ISR(wifi_int_mux); + } else { + portEXIT_CRITICAL(wifi_int_mux); + } +} + +static void IRAM_ATTR task_yield_from_isr_wrapper(void) +{ + portYIELD_FROM_ISR(); +} + +static void * semphr_create_wrapper(uint32_t max, uint32_t init) +{ + return (void *)xSemaphoreCreateCounting(max, init); +} + +static void semphr_delete_wrapper(void *semphr) +{ + vSemaphoreDelete(semphr); +} + +static void wifi_thread_semphr_free(void* data) +{ + xSemaphoreHandle *sem = (xSemaphoreHandle*)(data); + + if (sem) { + vSemaphoreDelete(sem); + } +} + +static void * wifi_thread_semphr_get_wrapper(void) +{ + static bool s_wifi_thread_sem_key_init = false; + static pthread_key_t s_wifi_thread_sem_key; + xSemaphoreHandle sem = NULL; + + if (s_wifi_thread_sem_key_init == false) { + if (0 != pthread_key_create(&s_wifi_thread_sem_key, wifi_thread_semphr_free)) { + return NULL; + } + s_wifi_thread_sem_key_init = true; + } + + sem = pthread_getspecific(s_wifi_thread_sem_key); + if (!sem) { + sem = xSemaphoreCreateCounting(1, 0); + if (sem) { + pthread_setspecific(s_wifi_thread_sem_key, sem); + ESP_LOGV(TAG, "thread sem create: sem=%p", sem); + } + } + + ESP_LOGV(TAG, "thread sem get: sem=%p", sem); + return (void*)sem; +} + +static int32_t IRAM_ATTR semphr_take_from_isr_wrapper(void *semphr, void *hptw) +{ + return (int32_t)xSemaphoreTakeFromISR(semphr, hptw); +} + +static int32_t IRAM_ATTR semphr_give_from_isr_wrapper(void *semphr, void *hptw) +{ + return (int32_t)xSemaphoreGiveFromISR(semphr, hptw); +} + +static int32_t semphr_take_wrapper(void *semphr, uint32_t block_time_tick) +{ + if (block_time_tick == OSI_FUNCS_TIME_BLOCKING) { + return (int32_t)xSemaphoreTake(semphr, portMAX_DELAY); + } else { + return (int32_t)xSemaphoreTake(semphr, block_time_tick); + } +} + +static int32_t semphr_give_wrapper(void *semphr) +{ + return (int32_t)xSemaphoreGive(semphr); +} + +static void * recursive_mutex_create_wrapper(void) +{ + return (void *)xSemaphoreCreateRecursiveMutex(); +} + +static void * mutex_create_wrapper(void) +{ + return (void *)xSemaphoreCreateMutex(); +} + +static void mutex_delete_wrapper(void *mutex) +{ + vSemaphoreDelete(mutex); +} + +static int32_t IRAM_ATTR mutex_lock_wrapper(void *mutex) +{ + return (int32_t)xSemaphoreTakeRecursive(mutex, portMAX_DELAY); +} + +static int32_t IRAM_ATTR mutex_unlock_wrapper(void *mutex) +{ + return (int32_t)xSemaphoreGiveRecursive(mutex); +} + +static void * queue_create_wrapper(uint32_t queue_len, uint32_t item_size) +{ + return (void *)xQueueCreate(queue_len, item_size); +} + +static int32_t queue_send_wrapper(void *queue, void *item, uint32_t block_time_tick) +{ + if (block_time_tick == OSI_FUNCS_TIME_BLOCKING) { + return (int32_t)xQueueSend(queue, item, portMAX_DELAY); + } else { + return (int32_t)xQueueSend(queue, item, block_time_tick); + } +} + +static int32_t IRAM_ATTR queue_send_from_isr_wrapper(void *queue, void *item, void *hptw) +{ + return (int32_t)xQueueSendFromISR(queue, item, hptw); +} + +static int32_t queue_send_to_back_wrapper(void *queue, void *item, uint32_t block_time_tick) +{ + return (int32_t)xQueueGenericSend(queue, item, block_time_tick, queueSEND_TO_BACK); +} + +static int32_t queue_send_to_front_wrapper(void *queue, void *item, uint32_t block_time_tick) +{ + return (int32_t)xQueueGenericSend(queue, item, block_time_tick, queueSEND_TO_FRONT); +} + +static int32_t queue_recv_wrapper(void *queue, void *item, uint32_t block_time_tick) +{ + if (block_time_tick == OSI_FUNCS_TIME_BLOCKING) { + return (int32_t)xQueueReceive(queue, item, portMAX_DELAY); + } else { + return (int32_t)xQueueReceive(queue, item, block_time_tick); + } +} + +static uint32_t event_group_wait_bits_wrapper(void *event, uint32_t bits_to_wait_for, int clear_on_exit, int wait_for_all_bits, uint32_t block_time_tick) +{ + if (block_time_tick == OSI_FUNCS_TIME_BLOCKING) { + return (uint32_t)xEventGroupWaitBits(event, bits_to_wait_for, clear_on_exit, wait_for_all_bits, portMAX_DELAY); + } else { + return (uint32_t)xEventGroupWaitBits(event, bits_to_wait_for, clear_on_exit, wait_for_all_bits, block_time_tick); + } +} + +static int32_t task_create_pinned_to_core_wrapper(void *task_func, const char *name, uint32_t stack_depth, void *param, uint32_t prio, void *task_handle, uint32_t core_id) +{ + return (uint32_t)xTaskCreatePinnedToCore(task_func, name, stack_depth, param, prio, task_handle, (core_id < portNUM_PROCESSORS ? core_id : tskNO_AFFINITY)); +} + +static int32_t task_create_wrapper(void *task_func, const char *name, uint32_t stack_depth, void *param, uint32_t prio, void *task_handle) +{ + return (uint32_t)xTaskCreate(task_func, name, stack_depth, param, prio, task_handle); +} + +static int32_t IRAM_ATTR task_ms_to_tick_wrapper(uint32_t ms) +{ + return (int32_t)(ms / portTICK_PERIOD_MS); +} + + +static int32_t task_get_max_priority_wrapper(void) +{ + return (int32_t)(configMAX_PRIORITIES); +} + +static void IRAM_ATTR timer_arm_wrapper(void *timer, uint32_t tmout, bool repeat) +{ + ets_timer_arm(timer, tmout, repeat); +} + +static void IRAM_ATTR timer_disarm_wrapper(void *timer) +{ + ets_timer_disarm(timer); +} + +static void timer_done_wrapper(void *ptimer) +{ + ets_timer_done(ptimer); +} + +static void timer_setfn_wrapper(void *ptimer, void *pfunction, void *parg) +{ + ets_timer_setfn(ptimer, pfunction, parg); +} + +static void IRAM_ATTR timer_arm_us_wrapper(void *ptimer, uint32_t us, bool repeat) +{ + ets_timer_arm_us(ptimer, us, repeat); +} + +static int get_time_wrapper(void *t) +{ + return os_get_time(t); +} + +static void * IRAM_ATTR malloc_internal_wrapper(size_t size) +{ + return heap_caps_malloc(size, MALLOC_CAP_DEFAULT|MALLOC_CAP_INTERNAL); +} + +static void * IRAM_ATTR realloc_internal_wrapper(void *ptr, size_t size) +{ + return heap_caps_realloc(ptr, size, MALLOC_CAP_DEFAULT|MALLOC_CAP_INTERNAL); +} + +static void * IRAM_ATTR calloc_internal_wrapper(size_t n, size_t size) +{ + return heap_caps_calloc(n, size, MALLOC_CAP_DEFAULT|MALLOC_CAP_INTERNAL); +} + +static void * IRAM_ATTR zalloc_internal_wrapper(size_t size) +{ + void *ptr = heap_caps_calloc(1, size, MALLOC_CAP_DEFAULT|MALLOC_CAP_INTERNAL); + if (ptr) { + memset(ptr, 0, size); + } + return ptr; +} + +static void sc_ack_send_wrapper(void *param) +{ + return sc_ack_send((sc_ack_t *)param); +} + +static uint32_t coex_status_get_wrapper(void) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + return coex_status_get(); +#else + return 0; +#endif +} + +static int coex_wifi_request_wrapper(uint32_t event, uint32_t latency, uint32_t duration) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + return coex_wifi_request(event, latency, duration); +#else + return 0; +#endif +} + +static int coex_wifi_release_wrapper(uint32_t event) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + return coex_wifi_release(event); +#else + return 0; +#endif +} + +int IRAM_ATTR coex_bt_request_wrapper(uint32_t event, uint32_t latency, uint32_t duration) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + return coex_bt_request(event, latency, duration); +#else + return 0; +#endif +} + +int IRAM_ATTR coex_bt_release_wrapper(uint32_t event) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + return coex_bt_release(event); +#else + return 0; +#endif +} + +int coex_register_bt_cb_wrapper(coex_func_cb_t cb) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + return coex_register_bt_cb(cb); +#else + return 0; +#endif +} + +uint32_t IRAM_ATTR coex_bb_reset_lock_wrapper(void) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + return coex_bb_reset_lock(); +#else + return 0; +#endif +} + +void IRAM_ATTR coex_bb_reset_unlock_wrapper(uint32_t restore) +{ +#if CONFIG_ESP32_WIFI_SW_COEXIST_ENABLE + coex_bb_reset_unlock(restore); +#endif +} + +wifi_osi_funcs_t g_wifi_osi_funcs = { + ._version = ESP_WIFI_OS_ADAPTER_VERSION, + ._set_isr = set_isr_wrapper, + ._ints_on = xt_ints_on, + ._ints_off = xt_ints_off, + ._spin_lock_create = spin_lock_create_wrapper, + ._spin_lock_delete = free, + ._wifi_int_disable = wifi_int_disable_wrapper, + ._wifi_int_restore = wifi_int_restore_wrapper, + ._task_yield_from_isr = task_yield_from_isr_wrapper, + ._semphr_create = semphr_create_wrapper, + ._semphr_delete = semphr_delete_wrapper, + ._semphr_take = semphr_take_wrapper, + ._semphr_give = semphr_give_wrapper, + ._wifi_thread_semphr_get = wifi_thread_semphr_get_wrapper, + ._mutex_create = mutex_create_wrapper, + ._recursive_mutex_create = recursive_mutex_create_wrapper, + ._mutex_delete = mutex_delete_wrapper, + ._mutex_lock = mutex_lock_wrapper, + ._mutex_unlock = mutex_unlock_wrapper, + ._queue_create = queue_create_wrapper, + ._queue_delete = vQueueDelete, + ._queue_send = queue_send_wrapper, + ._queue_send_from_isr = queue_send_from_isr_wrapper, + ._queue_send_to_back = queue_send_to_back_wrapper, + ._queue_send_to_front = queue_send_to_front_wrapper, + ._queue_recv = queue_recv_wrapper, + ._queue_msg_waiting = uxQueueMessagesWaiting, + ._event_group_create = xEventGroupCreate, + ._event_group_delete = vEventGroupDelete, + ._event_group_set_bits = xEventGroupSetBits, + ._event_group_clear_bits = xEventGroupClearBits, + ._event_group_wait_bits = event_group_wait_bits_wrapper, + ._task_create_pinned_to_core = task_create_pinned_to_core_wrapper, + ._task_create = task_create_wrapper, + ._task_delete = vTaskDelete, + ._task_delay = vTaskDelay, + ._task_ms_to_tick = task_ms_to_tick_wrapper, + ._task_get_current_task = xTaskGetCurrentTaskHandle, + ._task_get_max_priority = task_get_max_priority_wrapper, + ._malloc = malloc, + ._free = free, + ._get_free_heap_size = esp_get_free_heap_size, + ._rand = esp_random, + ._dport_access_stall_other_cpu_start_wrap = esp_dport_access_stall_other_cpu_start_wrap, + ._dport_access_stall_other_cpu_end_wrap = esp_dport_access_stall_other_cpu_end_wrap, + ._phy_rf_deinit = esp_phy_rf_deinit, + ._phy_load_cal_and_init = esp_phy_load_cal_and_init, + ._read_mac = esp_read_mac, + ._timer_arm = timer_arm_wrapper, + ._timer_disarm = timer_disarm_wrapper, + ._timer_done = timer_done_wrapper, + ._timer_setfn = timer_setfn_wrapper, + ._timer_arm_us = timer_arm_us_wrapper, + ._periph_module_enable = periph_module_enable, + ._periph_module_disable = periph_module_disable, + ._esp_timer_get_time = esp_timer_get_time, + ._nvs_set_i8 = nvs_set_i8, + ._nvs_get_i8 = nvs_get_i8, + ._nvs_set_u8 = nvs_set_u8, + ._nvs_get_u8 = nvs_get_u8, + ._nvs_set_u16 = nvs_set_u16, + ._nvs_get_u16 = nvs_get_u16, + ._nvs_open = nvs_open, + ._nvs_close = nvs_close, + ._nvs_commit = nvs_commit, + ._nvs_set_blob = nvs_set_blob, + ._nvs_get_blob = nvs_get_blob, + ._nvs_erase_key = nvs_erase_key, + ._get_random = os_get_random, + ._get_time = get_time_wrapper, + ._random = os_random, +#if CONFIG_IDF_TARGET_ESP32S2BETA + ._slowclk_cal_get = esp_clk_slowclk_cal_get, +#endif + ._log_write = esp_log_write, + ._log_timestamp = esp_log_timestamp, + ._malloc_internal = malloc_internal_wrapper, + ._realloc_internal = realloc_internal_wrapper, + ._calloc_internal = calloc_internal_wrapper, + ._zalloc_internal = zalloc_internal_wrapper, + ._wifi_malloc = wifi_malloc, + ._wifi_realloc = wifi_realloc, + ._wifi_calloc = wifi_calloc, + ._wifi_zalloc = wifi_zalloc_wrapper, + ._wifi_create_queue = wifi_create_queue_wrapper, + ._wifi_delete_queue = wifi_delete_queue_wrapper, + ._modem_sleep_enter = esp_modem_sleep_enter, + ._modem_sleep_exit = esp_modem_sleep_exit, + ._modem_sleep_register = esp_modem_sleep_register, + ._modem_sleep_deregister = esp_modem_sleep_deregister, + ._sc_ack_send = sc_ack_send_wrapper, + ._sc_ack_send_stop = sc_ack_send_stop, + ._coex_status_get = coex_status_get_wrapper, + ._coex_wifi_request = coex_wifi_request_wrapper, + ._coex_wifi_release = coex_wifi_release_wrapper, + ._magic = ESP_WIFI_OS_ADAPTER_MAGIC, +}; + +coex_adapter_funcs_t g_coex_adapter_funcs = { + ._version = COEX_ADAPTER_VERSION, + ._spin_lock_create = spin_lock_create_wrapper, + ._spin_lock_delete = free, + ._int_disable = wifi_int_disable_wrapper, + ._int_enable = wifi_int_restore_wrapper, + ._task_yield_from_isr = task_yield_from_isr_wrapper, + ._semphr_create = semphr_create_wrapper, + ._semphr_delete = semphr_delete_wrapper, + ._semphr_take_from_isr = semphr_take_from_isr_wrapper, + ._semphr_give_from_isr = semphr_give_from_isr_wrapper, + ._semphr_take = semphr_take_wrapper, + ._semphr_give = semphr_give_wrapper, + ._is_in_isr = xPortInIsrContext, + ._malloc_internal = malloc_internal_wrapper, + ._free = free, + ._timer_disarm = timer_disarm_wrapper, + ._timer_done = timer_done_wrapper, + ._timer_setfn = timer_setfn_wrapper, + ._timer_arm_us = timer_arm_us_wrapper, + ._esp_timer_get_time = esp_timer_get_time, + ._magic = COEX_ADAPTER_MAGIC, +}; diff --git a/components/esp32s2beta/system_api.c b/components/esp32s2beta/system_api.c index 85a063d9b6..e038d56a50 100644 --- a/components/esp32s2beta/system_api.c +++ b/components/esp32s2beta/system_api.c @@ -216,6 +216,17 @@ esp_err_t esp_register_shutdown_handler(shutdown_handler_t handler) return ESP_FAIL; } +esp_err_t esp_unregister_shutdown_handler(shutdown_handler_t handler) +{ + for (int i = 0; i < SHUTDOWN_HANDLERS_NO; i++) { + if (shutdown_handlers[i] == handler) { + shutdown_handlers[i] = NULL; + return ESP_OK; + } + } + return ESP_ERR_INVALID_STATE; +} + void esp_restart_noos() __attribute__ ((noreturn)); void IRAM_ATTR esp_restart(void) diff --git a/components/esp_wifi/CMakeLists.txt b/components/esp_wifi/CMakeLists.txt index df144b9984..70f9b78279 100644 --- a/components/esp_wifi/CMakeLists.txt +++ b/components/esp_wifi/CMakeLists.txt @@ -1,3 +1,6 @@ +idf_build_get_property(idf_target IDF_TARGET) +idf_build_get_property(build_dir BUILD_DIR) + set(COMPONENT_SRCS "src/coexist.c" "src/fast_crypto_ops.c" @@ -6,7 +9,7 @@ set(COMPONENT_SRCS "src/phy_init.c" "src/restore.c" "src/wifi_init.c") -set(COMPONENT_ADD_INCLUDEDIRS "include") +set(COMPONENT_ADD_INCLUDEDIRS "include" "${idf_target}/include") set(COMPONENT_PRIV_INCLUDEDIRS) set(COMPONENT_REQUIRES wpa_supplicant smartconfig_ack) set(COMPONENT_PRIV_REQUIRES "nvs_flash") @@ -16,26 +19,19 @@ if (CONFIG_ESP32_NO_BLOBS OR CONFIG_ESP32S2_NO_BLOBS) set(link_binary_libs 0) endif() -if (CONFIG_IDF_TARGET_ESP32S2BETA) - message(WARNING "No Wi-Fi libraries yet for esp32s2beta") - set(link_binary_libs 0) -endif() - if(link_binary_libs) set(COMPONENT_ADD_LDFRAGMENTS "linker.lf") endif() register_component() -target_link_libraries(${COMPONENT_LIB} "-L ${CMAKE_CURRENT_SOURCE_DIR}/lib_${IDF_TARGET}") +target_link_libraries(${COMPONENT_LIB} PUBLIC "-L ${CMAKE_CURRENT_SOURCE_DIR}/lib_${idf_target}") if(link_binary_libs) set(blobs coexist core espnow mesh net80211 phy pp rtc smartconfig wpa2 wpa wps) foreach(blob ${blobs}) add_library(${blob} STATIC IMPORTED) - # set_property(TARGET ${blob} PROPERTY IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/lib_${IDF_TARGET}/lib${blob}.a) - # ToDo: add lib_esp32s2beta in esp_wifi component - set_property(TARGET ${blob} PROPERTY IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/lib_esp32/lib${blob}.a) - target_link_libraries(${COMPONENT_LIB} ${blob}) + set_property(TARGET ${blob} PROPERTY IMPORTED_LOCATION ${CMAKE_CURRENT_SOURCE_DIR}/lib_${idf_target}/lib${blob}.a) + target_link_libraries(${COMPONENT_LIB} PUBLIC ${blob}) foreach(_blob ${blobs}) if(NOT _blob STREQUAL ${blob}) @@ -48,7 +44,7 @@ if(link_binary_libs) endif() if(CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION) - idf_build_get_property(build_dir BUILD_DIR) + idf_component_get_property(esp_common_dir esp_common COMPONENT_DIR) partition_table_get_partition_info(phy_partition_offset "--partition-type data --partition-subtype phy" "offset") set(phy_init_data_bin "${build_dir}/phy_init_data.bin") @@ -56,11 +52,11 @@ if(CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION) # the object file to a raw binary add_custom_command( OUTPUT ${phy_init_data_bin} - DEPENDS ${CMAKE_CURRENT_LIST_DIR}/phy_init_data.h + DEPENDS ${CMAKE_CURRENT_LIST_DIR}/${idf_target}/include/phy_init_data.h COMMAND ${CMAKE_C_COMPILER} -x c -c - -I ${CMAKE_CURRENT_LIST_DIR} -I ${CMAKE_CURRENT_LIST_DIR}/include -I ${build_dir} + -I ${esp_common_dir}/include -I ${CMAKE_CURRENT_LIST_DIR}/include -I ${build_dir}/config -o phy_init_data.obj - ${CMAKE_CURRENT_LIST_DIR}/phy_init_data.h + ${CMAKE_CURRENT_LIST_DIR}/${idf_target}/include/phy_init_data.h COMMAND ${CMAKE_OBJCOPY} -O binary phy_init_data.obj ${phy_init_data_bin} ) add_custom_target(phy_init_data ALL DEPENDS ${phy_init_data_bin}) diff --git a/components/esp_wifi/Kconfig b/components/esp_wifi/Kconfig index 4d007271bf..eff3f7c1fa 100644 --- a/components/esp_wifi/Kconfig +++ b/components/esp_wifi/Kconfig @@ -321,6 +321,8 @@ endmenu # Wi-Fi menu PHY config ESP32_PHY_CALIBRATION_AND_DATA_STORAGE + # ToDo: remove once NVS and PHY partial calibration are supported + depends on IDF_TARGET_ESP32 bool "Store phy calibration data in NVS" default y help diff --git a/components/esp_wifi/Makefile.projbuild b/components/esp_wifi/Makefile.projbuild new file mode 100644 index 0000000000..3cc445ce08 --- /dev/null +++ b/components/esp_wifi/Makefile.projbuild @@ -0,0 +1,32 @@ +ifdef CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION + +PHY_INIT_DATA_OBJ = $(BUILD_DIR_BASE)/phy_init_data.o +PHY_INIT_DATA_BIN = $(BUILD_DIR_BASE)/phy_init_data.bin + +# Command to flash PHY init data partition +PHY_INIT_DATA_FLASH_CMD = $(ESPTOOLPY_SERIAL) write_flash $(PHY_DATA_OFFSET) $(PHY_INIT_DATA_BIN) +ESPTOOL_ALL_FLASH_ARGS += $(PHY_DATA_OFFSET) $(PHY_INIT_DATA_BIN) + +ESP_WIFI_COMPONENT_PATH := $(COMPONENT_PATH) + +$(PHY_INIT_DATA_OBJ): $(ESP_WIFI_COMPONENT_PATH)/$(IDF_TARGET)/include/phy_init_data.h $(BUILD_DIR_BASE)/include/sdkconfig.h + $(summary) CC $(notdir $@) + printf "#include \"phy_init_data.h\"\n" | $(CC) -I $(BUILD_DIR_BASE)/include -I $(ESP_WIFI_COMPONENT_PATH)/../esp_common/include -I $(ESP_WIFI_COMPONENT_PATH)/include -I $(ESP_WIFI_COMPONENT_PATH)/$(IDF_TARGET)/include -c -o $@ -xc - + +$(PHY_INIT_DATA_BIN): $(PHY_INIT_DATA_OBJ) + $(summary) BIN $(notdir $@) + $(OBJCOPY) -O binary $< $@ + +phy_init_data: $(PHY_INIT_DATA_BIN) + +phy_init_data-flash: $(BUILD_DIR_BASE)/phy_init_data.bin + @echo "Flashing PHY init data..." + $(PHY_INIT_DATA_FLASH_CMD) + +phy_init_data-clean: + rm -f $(PHY_INIT_DATA_BIN) $(PHY_INIT_DATA_OBJ) + +all: phy_init_data +flash: phy_init_data + +endif # CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION diff --git a/components/esp_wifi/component.mk b/components/esp_wifi/component.mk index a72ad1ccd5..866a1fdd11 100644 --- a/components/esp_wifi/component.mk +++ b/components/esp_wifi/component.mk @@ -2,7 +2,7 @@ # Component Makefile # -COMPONENT_ADD_INCLUDEDIRS := include +COMPONENT_ADD_INCLUDEDIRS := include $(IDF_TARGET)/include COMPONENT_SRCDIRS := src ifndef CONFIG_ESP32_NO_BLOBS diff --git a/components/esp_wifi/include/phy_init_data.h b/components/esp_wifi/esp32/include/phy_init_data.h similarity index 100% rename from components/esp_wifi/include/phy_init_data.h rename to components/esp_wifi/esp32/include/phy_init_data.h diff --git a/components/esp_wifi/esp32s2beta/include/phy_init_data.h b/components/esp_wifi/esp32s2beta/include/phy_init_data.h new file mode 100644 index 0000000000..57ea2faa2d --- /dev/null +++ b/components/esp_wifi/esp32s2beta/include/phy_init_data.h @@ -0,0 +1,148 @@ +// Copyright 2016 Espressif Systems (Shanghai) PTE LTD +// +// 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 PHY_INIT_DATA_H +#define PHY_INIT_DATA_H /* don't use #pragma once here, we compile this file sometimes */ +#include "esp_phy_init.h" +#include "sdkconfig.h" + +// constrain a value between 'low' and 'high', inclusive +#define LIMIT(val, low, high) ((val < low) ? low : (val > high) ? high : val) + +#define PHY_INIT_MAGIC "PHYINIT" + +// define the lowest tx power as LOWEST_PHY_TX_POWER +#define PHY_TX_POWER_LOWEST LIMIT(CONFIG_ESP32_PHY_MAX_TX_POWER * 4, 0, 52) +#define PHY_TX_POWER_OFFSET 44 +#define PHY_TX_POWER_NUM 5 + +static const char phy_init_magic_pre[] = PHY_INIT_MAGIC; + +/** + * @brief Structure containing default recommended PHY initialization parameters. + */ +static const esp_phy_init_data_t phy_init_data= { { + 3, + 0, + 0x04, + 0x05, + 0x04, + 0x05, + 0x05, + 0x04, + 0x06, + 0x06, + 0x06, + 0x05, + 0x06, + 0x00, + 0x00, + 0x00, + 0x00, + 0x05, + 0x09, + 0x06, + 0x05, + 0x03, + 0x06, + 0x05, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0xf4, + 0xf8, + 0xf8, + 0xf0, + 0xf0, + 0xf0, + 0xe0, + 0xe0, + 0xe0, + 0x18, + 0x18, + 0x18, + LIMIT(CONFIG_ESP32_PHY_MAX_TX_POWER * 4, 0, 78), + LIMIT(CONFIG_ESP32_PHY_MAX_TX_POWER * 4, 0, 72), + LIMIT(CONFIG_ESP32_PHY_MAX_TX_POWER * 4, 0, 66), + LIMIT(CONFIG_ESP32_PHY_MAX_TX_POWER * 4, 0, 60), + LIMIT(CONFIG_ESP32_PHY_MAX_TX_POWER * 4, 0, 56), + LIMIT(CONFIG_ESP32_PHY_MAX_TX_POWER * 4, 0, 52), + 0, + 1, + 1, + 2, + 2, + 3, + 4, + 5, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, +} }; + +static const char phy_init_magic_post[] = PHY_INIT_MAGIC; + +#endif /* PHY_INIT_DATA_H */ + diff --git a/components/esp_wifi/include/esp_private/wifi_os_adapter.h b/components/esp_wifi/include/esp_private/wifi_os_adapter.h index 165caa6edc..d339ce0789 100644 --- a/components/esp_wifi/include/esp_private/wifi_os_adapter.h +++ b/components/esp_wifi/include/esp_private/wifi_os_adapter.h @@ -102,6 +102,9 @@ typedef struct { int32_t (* _get_random)(uint8_t *buf, size_t len); int32_t (* _get_time)(void *t); unsigned long (* _random)(void); +#if CONFIG_IDF_TARGET_ESP32S2BETA + uint32_t (* _slowclk_cal_get)(void); +#endif void (* _log_write)(uint32_t level, const char* tag, const char* format, ...); uint32_t (* _log_timestamp)(void); void * (* _malloc_internal)(size_t size); diff --git a/components/esp_wifi/include/esp_wifi_types.h b/components/esp_wifi/include/esp_wifi_types.h index 8e930c555d..714b88bc6c 100644 --- a/components/esp_wifi/include/esp_wifi_types.h +++ b/components/esp_wifi/include/esp_wifi_types.h @@ -323,7 +323,11 @@ typedef struct { unsigned stbc:2; /**< Space Time Block Code(STBC). 0: non STBC packet; 1: STBC packet */ unsigned fec_coding:1; /**< Flag is set for 11n packets which are LDPC */ unsigned sgi:1; /**< Short Guide Interval(SGI). 0: Long GI; 1: Short GI */ +#if CONFIG_IDF_TARGET_ESP32 signed noise_floor:8; /**< noise floor of Radio Frequency Module(RF). unit: 0.25dBm*/ +#elif CONFIG_IDF_TARGET_ESP32S2BETA + unsigned :8; +#endif unsigned ampdu_cnt:8; /**< ampdu cnt */ unsigned channel:4; /**< primary channel on which this packet is received */ unsigned secondary_channel:4; /**< secondary channel on which this packet is received. 0: none; 1: above; 2: below */ @@ -332,6 +336,10 @@ typedef struct { unsigned :32; /**< reserve */ unsigned :31; /**< reserve */ unsigned ant:1; /**< antenna number from which this packet is received. 0: WiFi antenna 0; 1: WiFi antenna 1 */ +#if CONFIG_IDF_TARGET_ESP32S2BETA + signed noise_floor:8; /**< noise floor of Radio Frequency Module(RF). unit: 0.25dBm*/ + unsigned :24; +#endif unsigned sig_len:12; /**< length of packet including Frame Check Sequence(FCS) */ unsigned :12; /**< reserve */ unsigned rx_state:8; /**< state of the packet. 0: no error; others: error numbers which are not public */ diff --git a/components/esp_wifi/lib_esp32s2beta b/components/esp_wifi/lib_esp32s2beta new file mode 160000 index 0000000000..f3442ab1f8 --- /dev/null +++ b/components/esp_wifi/lib_esp32s2beta @@ -0,0 +1 @@ +Subproject commit f3442ab1f881dd72cbe23ca76c7e318e26342191 diff --git a/components/esp_wifi/src/fast_crypto_ops.c b/components/esp_wifi/src/fast_crypto_ops.c index 7e05a7b8c9..5226a720b5 100644 --- a/components/esp_wifi/src/fast_crypto_ops.c +++ b/components/esp_wifi/src/fast_crypto_ops.c @@ -28,6 +28,11 @@ #include "wpa2/eap_peer/eap_i.h" #include "wpa2/eap_peer/eap_common.h" #include "esp_wifi_crypto_types.h" + +#if CONFIG_IDF_TARGET_ESP32S2BETA +#warning "TODO: fix hardware crypto support for esp32s2beta" +#endif + /* * The parameters is used to set the cyrpto callback function for station connect when in security mode, * every callback function can register as fast_xxx or normal one, i.e, fast_aes_wrap or aes_wrap, the @@ -38,10 +43,17 @@ const wpa_crypto_funcs_t g_wifi_default_wpa_crypto_funcs = { .size = sizeof(wpa_crypto_funcs_t), .version = ESP_WIFI_CRYPTO_VERSION, +#if CONFIG_IDF_TARGET_ESP32 .aes_wrap = (esp_aes_wrap_t)fast_aes_wrap, .aes_unwrap = (esp_aes_unwrap_t)fast_aes_unwrap, .hmac_sha256_vector = (esp_hmac_sha256_vector_t)fast_hmac_sha256_vector, .sha256_prf = (esp_sha256_prf_t)fast_sha256_prf, +#elif CONFIG_IDF_TARGET_ESP32S2BETA + .aes_wrap = (esp_aes_wrap_t)aes_wrap, + .aes_unwrap = (esp_aes_unwrap_t)aes_unwrap, + .hmac_sha256_vector = (esp_hmac_sha256_vector_t)hmac_sha256_vector, + .sha256_prf = (esp_sha256_prf_t)sha256_prf, +#endif .hmac_md5 = (esp_hmac_md5_t)hmac_md5, .hamc_md5_vector = (esp_hmac_md5_vector_t)hmac_md5_vector, .hmac_sha1 = (esp_hmac_sha1_t)hmac_sha1, @@ -62,12 +74,21 @@ const wpa_crypto_funcs_t g_wifi_default_wpa_crypto_funcs = { const wps_crypto_funcs_t g_wifi_default_wps_crypto_funcs = { .size = sizeof(wps_crypto_funcs_t), .version = ESP_WIFI_CRYPTO_VERSION, +#if CONFIG_IDF_TARGET_ESP32 .aes_128_encrypt = (esp_aes_128_encrypt_t)fast_aes_128_cbc_encrypt, .aes_128_decrypt = (esp_aes_128_decrypt_t)fast_aes_128_cbc_decrypt, .crypto_mod_exp = (esp_crypto_mod_exp_t)fast_crypto_mod_exp, .hmac_sha256 = (esp_hmac_sha256_t)fast_hmac_sha256, .hmac_sha256_vector = (esp_hmac_sha256_vector_t)fast_hmac_sha256_vector, .sha256_vector = (esp_sha256_vector_t)fast_sha256_vector, +#elif CONFIG_IDF_TARGET_ESP32S2BETA + .aes_128_encrypt = (esp_aes_128_encrypt_t)aes_128_cbc_encrypt, + .aes_128_decrypt = (esp_aes_128_decrypt_t)aes_128_cbc_decrypt, + .crypto_mod_exp = (esp_crypto_mod_exp_t)crypto_mod_exp, + .hmac_sha256 = (esp_hmac_sha256_t)hmac_sha256, + .hmac_sha256_vector = (esp_hmac_sha256_vector_t)hmac_sha256_vector, + .sha256_vector = (esp_sha256_vector_t)fast_sha256_vector, +#endif .uuid_gen_mac_addr = (esp_uuid_gen_mac_addr_t)uuid_gen_mac_addr, .dh5_free = (esp_dh5_free_t)dh5_free, .wps_build_assoc_req_ie = (esp_wps_build_assoc_req_ie_t)wps_build_assoc_req_ie, @@ -91,6 +112,7 @@ const wps_crypto_funcs_t g_wifi_default_wps_crypto_funcs = { const wpa2_crypto_funcs_t g_wifi_default_wpa2_crypto_funcs = { .size = sizeof(wpa2_crypto_funcs_t), .version = ESP_WIFI_CRYPTO_VERSION, +#if CONFIG_IDF_TARGET_ESP32 .crypto_hash_init = (esp_crypto_hash_init_t)fast_crypto_hash_init, .crypto_hash_update = (esp_crypto_hash_update_t)fast_crypto_hash_update, .crypto_hash_finish = (esp_crypto_hash_finish_t)fast_crypto_hash_finish, @@ -100,6 +122,17 @@ const wpa2_crypto_funcs_t g_wifi_default_wpa2_crypto_funcs = { .crypto_cipher_deinit = (esp_crypto_cipher_deinit_t)fast_crypto_cipher_deinit, .crypto_mod_exp = (esp_crypto_mod_exp_t)crypto_mod_exp, .sha256_vector = (esp_sha256_vector_t)fast_sha256_vector, +#elif CONFIG_IDF_TARGET_ESP32S2BETA + .crypto_hash_init = (esp_crypto_hash_init_t)crypto_hash_init, + .crypto_hash_update = (esp_crypto_hash_update_t)crypto_hash_update, + .crypto_hash_finish = (esp_crypto_hash_finish_t)crypto_hash_finish, + .crypto_cipher_init = (esp_crypto_cipher_init_t)crypto_cipher_init, + .crypto_cipher_encrypt = (esp_crypto_cipher_encrypt_t)crypto_cipher_encrypt, + .crypto_cipher_decrypt = (esp_crypto_cipher_decrypt_t)crypto_cipher_decrypt, + .crypto_cipher_deinit = (esp_crypto_cipher_deinit_t)crypto_cipher_deinit, + .crypto_mod_exp = (esp_crypto_mod_exp_t)crypto_mod_exp, + .sha256_vector = (esp_sha256_vector_t)sha256_vector, +#endif .tls_init = (esp_tls_init_t)tls_init, .tls_deinit = (esp_tls_deinit_t)tls_deinit, .eap_peer_blob_init = (esp_eap_peer_blob_init_t)eap_peer_blob_init, @@ -117,6 +150,11 @@ const wpa2_crypto_funcs_t g_wifi_default_wpa2_crypto_funcs = { }; const mesh_crypto_funcs_t g_wifi_default_mesh_crypto_funcs = { +#if CONFIG_IDF_TARGET_ESP32 .aes_128_encrypt = (esp_aes_128_encrypt_t)fast_aes_128_cbc_encrypt, .aes_128_decrypt = (esp_aes_128_decrypt_t)fast_aes_128_cbc_decrypt, +#elif CONFIG_IDF_TARGET_ESP32S2BETA + .aes_128_encrypt = (esp_aes_128_encrypt_t)aes_128_cbc_encrypt, + .aes_128_decrypt = (esp_aes_128_decrypt_t)aes_128_cbc_decrypt, +#endif }; diff --git a/components/esp_wifi/src/phy_init.c b/components/esp_wifi/src/phy_init.c index bd990c8fcd..c5abe2da57 100644 --- a/components/esp_wifi/src/phy_init.c +++ b/components/esp_wifi/src/phy_init.c @@ -43,7 +43,9 @@ #include "esp32s2beta/rom/rtc.h" #endif +#if CONFIG_IDF_TARGET_ESP32 extern wifi_mac_time_update_cb_t s_wifi_mac_time_update_cb; +#endif static const char* TAG = "phy_init"; @@ -68,8 +70,10 @@ static volatile bool s_is_modem_sleep_en = false; static _lock_t s_modem_sleep_lock; +#if CONFIG_IDF_TARGET_ESP32 /* time stamp updated when the PHY/RF is turned on */ static int64_t s_phy_rf_en_ts = 0; +#endif uint32_t IRAM_ATTR phy_enter_critical(void) { @@ -81,6 +85,7 @@ void IRAM_ATTR phy_exit_critical(uint32_t level) portEXIT_CRITICAL_NESTED(level); } +#if CONFIG_IDF_TARGET_ESP32 int64_t esp_phy_rf_get_on_ts(void) { return s_phy_rf_en_ts; @@ -103,6 +108,7 @@ static inline void phy_update_wifi_mac_time(bool en_clock_stopped, int64_t now) } } } +#endif esp_err_t esp_phy_rf_init(const esp_phy_init_data_t* init_data, esp_phy_calibration_mode_t mode, esp_phy_calibration_data_t* calibration_data, phy_rf_module_t module) @@ -147,10 +153,12 @@ esp_err_t esp_phy_rf_init(const esp_phy_init_data_t* init_data, esp_phy_calibrat } } if (s_is_phy_rf_en == true){ +#if CONFIG_IDF_TARGET_ESP32 // Update time stamp s_phy_rf_en_ts = esp_timer_get_time(); // Update WiFi MAC time before WiFi/BT common clock is enabled phy_update_wifi_mac_time(false, s_phy_rf_en_ts); +#endif // Enable WiFi/BT common peripheral clock periph_module_enable(PERIPH_WIFI_BT_COMMON_MODULE); phy_set_wifi_mode_only(0); @@ -234,8 +242,10 @@ esp_err_t esp_phy_rf_deinit(phy_rf_module_t module) if (s_is_phy_rf_en == false) { // Disable PHY and RF. phy_close_rf(); +#if CONFIG_IDF_TARGET_ESP32 // Update WiFi MAC time before disalbe WiFi/BT common peripheral clock phy_update_wifi_mac_time(true, esp_timer_get_time()); +#endif // Disable WiFi/BT common peripheral clock. Do not disable clock for hardware RNG periph_module_disable(PERIPH_WIFI_BT_COMMON_MODULE); } @@ -620,9 +630,12 @@ void esp_phy_load_cal_and_init(phy_rf_module_t module) } memcpy(init_data, phy_init_data, sizeof(esp_phy_init_data_t)); +#if CONFIG_IDF_TARGET_ESP32 + // ToDo: remove once esp_reset_reason is supported on esp32s2 if (esp_reset_reason() == ESP_RST_BROWNOUT) { esp_phy_reduce_tx_power(init_data); } +#endif #else const esp_phy_init_data_t* init_data = esp_phy_get_init_data(); if (init_data == NULL) { diff --git a/components/esp_wifi/src/wifi_init.c b/components/esp_wifi/src/wifi_init.c index 2091e1b509..a4b4d00531 100644 --- a/components/esp_wifi/src/wifi_init.c +++ b/components/esp_wifi/src/wifi_init.c @@ -25,8 +25,10 @@ ESP_EVENT_DEFINE_BASE(WIFI_EVENT); static esp_pm_lock_handle_t s_wifi_modem_sleep_lock; #endif +#if CONFIG_IDF_TARGET_ESP32 /* Callback function to update WiFi MAC time */ wifi_mac_time_update_cb_t s_wifi_mac_time_update_cb = NULL; +#endif static const char* TAG = "wifi_init"; @@ -105,7 +107,9 @@ esp_err_t esp_wifi_init(const wifi_init_config_t *config) esp_err_t result = esp_wifi_init_internal(config); if (result == ESP_OK) { esp_wifi_set_debug_log(); +#if CONFIG_IDF_TARGET_ESP32 s_wifi_mac_time_update_cb = esp_wifi_internal_update_mac_time; +#endif } return result; diff --git a/components/mbedtls/Kconfig b/components/mbedtls/Kconfig index 91b5c506ea..44fa4649bf 100644 --- a/components/mbedtls/Kconfig +++ b/components/mbedtls/Kconfig @@ -118,6 +118,8 @@ menu "mbedTLS" config MBEDTLS_HARDWARE_AES bool "Enable hardware AES acceleration" + depends on IDF_TARGET_ESP32 + # ToDo: remove once hardware AES acceleration is supported on esp32s2 default y help Enable hardware accelerated AES encryption & decryption. diff --git a/components/soc/esp32s2beta/i2c_apll.h b/components/soc/esp32s2beta/i2c_apll.h index 935810afab..909326f64e 100644 --- a/components/soc/esp32s2beta/i2c_apll.h +++ b/components/soc/esp32s2beta/i2c_apll.h @@ -24,7 +24,7 @@ */ #define I2C_APLL 0X6D -#define I2C_APLL_HOSTID 3 +#define I2C_APLL_HOSTID 1 #define I2C_APLL_IR_CAL_DELAY 0 #define I2C_APLL_IR_CAL_DELAY_MSB 3 diff --git a/components/soc/esp32s2beta/include/soc/rtc.h b/components/soc/esp32s2beta/include/soc/rtc.h index eef0962608..5f1d6f226a 100644 --- a/components/soc/esp32s2beta/include/soc/rtc.h +++ b/components/soc/esp32s2beta/include/soc/rtc.h @@ -598,6 +598,7 @@ typedef struct { uint32_t rtc_dboost_fpd : 1; //!< Force power down RTC_DBOOST uint32_t xtal_fpu : 1; uint32_t bbpll_fpu : 1; + uint32_t cpu_waiti_clk_gate : 1; } rtc_config_t; /** @@ -614,7 +615,8 @@ typedef struct { .pwrctl_init = 1, \ .rtc_dboost_fpd = 1, \ .xtal_fpu = 0, \ - .bbpll_fpu = 0 \ + .bbpll_fpu = 0, \ + .cpu_waiti_clk_gate = 1\ } /** diff --git a/components/soc/esp32s2beta/include/soc/rtc_cntl_reg.h b/components/soc/esp32s2beta/include/soc/rtc_cntl_reg.h index 9eacfc6b42..54bf7764e3 100644 --- a/components/soc/esp32s2beta/include/soc/rtc_cntl_reg.h +++ b/components/soc/esp32s2beta/include/soc/rtc_cntl_reg.h @@ -329,7 +329,7 @@ extern "C" { #define RTC_CNTL_PLL_BUF_WAIT_M ((RTC_CNTL_PLL_BUF_WAIT_V)<<(RTC_CNTL_PLL_BUF_WAIT_S)) #define RTC_CNTL_PLL_BUF_WAIT_V 0xFF #define RTC_CNTL_PLL_BUF_WAIT_S 24 -#define RTC_CNTL_PLL_BUF_WAIT_DEFAULT 20 +#define RTC_CNTL_PLL_BUF_WAIT_DEFAULT 100 /* RTC_CNTL_XTL_BUF_WAIT : R/W ;bitpos:[23:14] ;default: 10'd80 ; */ /*description: XTAL wait cycles in slow_clk_rtc*/ #define RTC_CNTL_XTL_BUF_WAIT 0x000003FF diff --git a/components/soc/esp32s2beta/include/soc/syscon_reg.h b/components/soc/esp32s2beta/include/soc/syscon_reg.h index 3aa039748d..efa9a0ba78 100644 --- a/components/soc/esp32s2beta/include/soc/syscon_reg.h +++ b/components/soc/esp32s2beta/include/soc/syscon_reg.h @@ -793,9 +793,9 @@ extern "C" { /* Mask for all Wifi clock bits - 0, 1, 2, 3, 6, 7, 8, 9, 10, 15, 19, 20, 21 Bit15 not included here because of the bit now can't be cleared */ -#define DPORT_WIFI_CLK_WIFI_EN 0x003807cf +#define DPORT_WIFI_CLK_WIFI_EN 0x00008040 #define DPORT_WIFI_CLK_WIFI_EN_M ((DPORT_WIFI_CLK_WIFI_EN_V)<<(DPORT_WIFI_CLK_WIFI_EN_S)) -#define DPORT_WIFI_CLK_WIFI_EN_V 0x7cf +#define DPORT_WIFI_CLK_WIFI_EN_V 0x0804 #define DPORT_WIFI_CLK_WIFI_EN_S 0 /* Mask for all Bluetooth clock bits - 11, 16, 17 */ #define DPORT_WIFI_CLK_BT_EN 0x61 @@ -803,7 +803,7 @@ extern "C" { #define DPORT_WIFI_CLK_BT_EN_V 0x61 #define DPORT_WIFI_CLK_BT_EN_S 11 /* Mask for clock bits used by both WIFI and Bluetooth, bit 0, 3, 6, 7, 8, 9 */ -#define DPORT_WIFI_CLK_WIFI_BT_COMMON_M 0x000003c9 +#define DPORT_WIFI_CLK_WIFI_BT_COMMON_M 0x0038078f /* Digital team to check */ //bluetooth baseband bit11 diff --git a/components/soc/esp32s2beta/include/soc/wdev_reg.h b/components/soc/esp32s2beta/include/soc/wdev_reg.h index f258088a24..093989f067 100644 --- a/components/soc/esp32s2beta/include/soc/wdev_reg.h +++ b/components/soc/esp32s2beta/include/soc/wdev_reg.h @@ -17,5 +17,5 @@ #include "soc.h" /* Hardware random number generator register */ -#define WDEV_RND_REG 0x60035100 +#define WDEV_RND_REG 0x6003510C diff --git a/components/soc/esp32s2beta/rtc_clk.c b/components/soc/esp32s2beta/rtc_clk.c index f1bcdd0e9e..1d7e0a6fb1 100644 --- a/components/soc/esp32s2beta/rtc_clk.c +++ b/components/soc/esp32s2beta/rtc_clk.c @@ -416,6 +416,20 @@ void rtc_clk_bbpll_set(rtc_xtal_freq_t xtal_freq, rtc_pll_t pll_freq) I2C_WRITEREG_MASK_RTC(I2C_BBPLL, I2C_BBPLL_OC_DR3, dr3); I2C_WRITEREG_RTC(I2C_BBPLL, I2C_BBPLL_OC_DCUR, i2c_bbpll_dcur); + // Enable calibration by software + I2C_WRITEREG_MASK_RTC(I2C_BBPLL, I2C_BBPLL_IR_CAL_ENX_CAP, 1); + for (int ext_cap = 0; ext_cap < 16; ext_cap++) { + uint8_t cal_result; + I2C_WRITEREG_MASK_RTC(I2C_BBPLL, I2C_BBPLL_IR_CAL_EXT_CAP, ext_cap); + cal_result = I2C_READREG_MASK_RTC(I2C_BBPLL, I2C_BBPLL_OR_CAL_CAP); + if (cal_result == 0) { + break; + } + if(ext_cap == 15) { + SOC_LOGE(TAG, "BBPLL SOFTWARE CAL FAIL"); + } + } + /* this delay is replaced by polling Pll calibration end flag * uint32_t delay_pll_en = (rtc_clk_slow_freq_get() == RTC_SLOW_FREQ_RTC) ? * DELAY_PLL_ENABLE_WITH_150K : DELAY_PLL_ENABLE_WITH_32K; @@ -427,7 +441,6 @@ void rtc_clk_bbpll_set(rtc_xtal_freq_t xtal_freq, rtc_pll_t pll_freq) ets_delay_us(1); } */ - ets_delay_us(50000); } /** diff --git a/components/soc/esp32s2beta/rtc_init.c b/components/soc/esp32s2beta/rtc_init.c index b241edca6f..c42b98f0f2 100644 --- a/components/soc/esp32s2beta/rtc_init.c +++ b/components/soc/esp32s2beta/rtc_init.c @@ -162,10 +162,13 @@ void rtc_init(rtc_config_t cfg) // CLEAR_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_CPU_ROM_RAM_FORCE_NOISO); CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FORCE_NOISO); //cancel digital PADS force no iso - //wangqiang ++ - rom_i2c_writeReg_Mask(0x6a,1,0,1,0,2); - - rom_i2c_writeReg_Mask(0x6a,1,2,5,4,2); + if (cfg.cpu_waiti_clk_gate){ + CLEAR_PERI_REG_MASK(DPORT_CPU_PER_CONF_REG, DPORT_CPU_WAIT_MODE_FORCE_ON); + } + else{ + SET_PERI_REG_MASK(DPORT_CPU_PER_CONF_REG, DPORT_CPU_WAIT_MODE_FORCE_ON); + } + /*if DPORT_CPU_WAIT_MODE_FORCE_ON == 0 , the cpu clk will be closed when cpu enter WAITI mode*/ #ifdef CONFIG_CHIP_IS_ESP32 CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_PAD_FORCE_UNHOLD); diff --git a/components/soc/esp32s2beta/rtc_sleep.c b/components/soc/esp32s2beta/rtc_sleep.c index ff8dff1c29..892cb45ff6 100644 --- a/components/soc/esp32s2beta/rtc_sleep.c +++ b/components/soc/esp32s2beta/rtc_sleep.c @@ -84,14 +84,22 @@ void rtc_sleep_init(rtc_sleep_config_t cfg) if (cfg.rtc_fastmem_pd_en) { SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_PD_EN); + CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_FASTMEM_FORCE_PU); + CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_FASTMEM_FORCE_NOISO); } else { CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_FASTMEM_PD_EN); + SET_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_FASTMEM_FORCE_PU); + SET_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_FASTMEM_FORCE_NOISO); } if (cfg.rtc_slowmem_pd_en) { SET_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_PD_EN); + CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_SLOWMEM_FORCE_PU); + CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_SLOWMEM_FORCE_NOISO); } else { CLEAR_PERI_REG_MASK(RTC_CNTL_PWC_REG, RTC_CNTL_SLOWMEM_PD_EN); + SET_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_SLOWMEM_FORCE_PU); + SET_PERI_REG_MASK(RTC_CNTL_PWC_REG,RTC_CNTL_SLOWMEM_FORCE_NOISO); } if (cfg.rtc_peri_pd_en) { diff --git a/docs/en/api-guides/RF_calibration.rst b/docs/en/api-guides/RF_calibration.rst index 6b8aec0bd7..696cc53239 100644 --- a/docs/en/api-guides/RF_calibration.rst +++ b/docs/en/api-guides/RF_calibration.rst @@ -48,7 +48,7 @@ PHY initialization data The PHY initialization data is used for RF calibration. There are two ways to get the PHY initialization data. -One is the default initialization data which is located in the header file :idf_file:`components/esp32/phy_init_data.h`. +One is the default initialization data which is located in the header file :idf_file:`components/esp_wifi/esp32/include/phy_init_data.h`. It is embedded into the application binary after compiling and then stored into read-only memory (DROM). To use the default initialization data, please go to ``menuconfig`` and disable :ref:`CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION`. diff --git a/examples/common_components/protocol_examples_common/Kconfig.projbuild b/examples/common_components/protocol_examples_common/Kconfig.projbuild index 4a370b5634..36f2161168 100644 --- a/examples/common_components/protocol_examples_common/Kconfig.projbuild +++ b/examples/common_components/protocol_examples_common/Kconfig.projbuild @@ -145,6 +145,8 @@ menu "Example Connection Configuration" config EXAMPLE_CONNECT_IPV6 bool "Obtain IPv6 link-local address" + depends on IDF_TARGET_ESP32 + # ToDo: remove once IPV6 is supported on esp32s2 default y help By default, examples will wait until IPv4 and IPv6 addresses are obtained. diff --git a/examples/common_components/protocol_examples_common/connect.c b/examples/common_components/protocol_examples_common/connect.c index 718d498f71..e3f42d1b88 100644 --- a/examples/common_components/protocol_examples_common/connect.c +++ b/examples/common_components/protocol_examples_common/connect.c @@ -12,7 +12,9 @@ #include "sdkconfig.h" #include "esp_event.h" #include "esp_wifi.h" +#if CONFIG_EXAMPLE_CONNECT_ETHERNET #include "esp_eth.h" +#endif #include "esp_log.h" #include "tcpip_adapter.h" #include "freertos/FreeRTOS.h" diff --git a/tools/ci/test_build_system.sh b/tools/ci/test_build_system.sh index 9ffea7042c..667691de06 100755 --- a/tools/ci/test_build_system.sh +++ b/tools/ci/test_build_system.sh @@ -57,6 +57,7 @@ function run_tests() BOOTLOADER_BINS="bootloader/bootloader.elf bootloader/bootloader.bin" APP_BINS="app-template.elf app-template.bin" + PHY_INIT_BIN="phy_init_data.bin" print_status "Initial clean build" # if make fails here, everything fails @@ -283,6 +284,18 @@ function run_tests() rm sdkconfig sdkconfig.defaults make defconfig + print_status "can build with phy_init_data" + make clean > /dev/null + rm -f sdkconfig.defaults + rm -f sdkconfig + echo "CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION=y" >> sdkconfig.defaults + make defconfig > /dev/null + make || failure "Failed to build with PHY_INIT_DATA" + assert_built ${APP_BINS} ${BOOTLOADER_BINS} ${PHY_INIT_BIN} + rm sdkconfig + rm sdkconfig.defaults + make defconfig + print_status "Empty directory not treated as a component" mkdir -p components/esp32 make || failure "Failed to build with empty esp32 directory in components" diff --git a/tools/ci/test_build_system_cmake.sh b/tools/ci/test_build_system_cmake.sh index 3e35eaf9b8..80686322c7 100755 --- a/tools/ci/test_build_system_cmake.sh +++ b/tools/ci/test_build_system_cmake.sh @@ -58,6 +58,7 @@ function run_tests() BOOTLOADER_BINS="bootloader/bootloader.elf bootloader/bootloader.bin" APP_BINS="app-template.elf app-template.bin" PARTITION_BIN="partition_table/partition-table.bin" + PHY_INIT_BIN="phy_init_data.bin" BUILD_ARTIFACTS="project_description.json flasher_args.json config/kconfig_menus.json config/sdkconfig.json" IDF_COMPONENT_PREFIX="__idf" @@ -342,6 +343,18 @@ function run_tests() rm sdkconfig; rm sdkconfig.defaults; + print_status "can build with phy_init_data" + idf.py clean > /dev/null; + idf.py fullclean > /dev/null; + rm -f sdkconfig.defaults; + rm -f sdkconfig; + echo "CONFIG_ESP32_PHY_INIT_DATA_IN_PARTITION=y" >> sdkconfig.defaults; + idf.py reconfigure > /dev/null; + idf.py build || failure "Failed to build with PHY_INIT_DATA" + assert_built ${APP_BINS} ${BOOTLOADER_BINS} ${PARTITION_BIN} ${PHY_INIT_BIN} + rm sdkconfig; + rm sdkconfig.defaults; + print_status "Building a project with CMake library imported and PSRAM workaround, all files compile with workaround" # Test for libraries compiled within ESP-IDF rm -rf build @@ -440,7 +453,7 @@ endmenu\n" >> ${IDF_PATH}/Kconfig; print_status "If a component directory is added to COMPONENT_DIRS, its sibling directories are not added" clean_build_dir - mkdir -p mycomponents/mycomponent + mkdir -p mycomponents/mycomponent echo "idf_component_register()" > mycomponents/mycomponent/CMakeLists.txt # first test by adding single component directory to EXTRA_COMPONENT_DIRS mkdir -p mycomponents/esp32