mirror of
https://github.com/0xFEEDC0DE64/arduino-esp32.git
synced 2025-06-30 12:30:59 +02:00
Update IDF
This commit is contained in:
@ -38,6 +38,16 @@
|
||||
*/
|
||||
void heap_alloc_caps_init();
|
||||
|
||||
/**
|
||||
* @brief Enable the memory region where the startup stacks are located for allocation
|
||||
*
|
||||
* On startup, the pro/app CPUs have a certain memory region they use as stack, so we
|
||||
* cannot do allocations in the regions these stack frames are. When FreeRTOS is
|
||||
* completely started, they do not use that memory anymore and allocation there can
|
||||
* be re-enabled.
|
||||
*/
|
||||
void heap_alloc_enable_nonos_stack_tag();
|
||||
|
||||
/**
|
||||
* @brief Allocate a chunk of memory which has the given capabilities
|
||||
*
|
||||
@ -75,4 +85,6 @@ size_t xPortGetFreeHeapSizeCaps( uint32_t caps );
|
||||
*/
|
||||
size_t xPortGetMinimumEverFreeHeapSizeCaps( uint32_t caps );
|
||||
|
||||
|
||||
|
||||
#endif
|
@ -232,12 +232,11 @@ esp_err_t esp_phy_store_cal_data_to_nvs(const esp_phy_calibration_data_t* cal_da
|
||||
* function.
|
||||
* @param mode Calibration mode (Full, partial, or no calibration)
|
||||
* @param[inout] calibration_data
|
||||
* @param is_sleep WiFi wakes up from sleep or not
|
||||
* @return ESP_OK on success.
|
||||
* @return ESP_FAIL on fail.
|
||||
*/
|
||||
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, bool is_sleep);
|
||||
esp_phy_calibration_mode_t mode, esp_phy_calibration_data_t* calibration_data);
|
||||
|
||||
/**
|
||||
* @brief De-initialize PHY and RF module
|
||||
|
@ -97,6 +97,8 @@ typedef struct {
|
||||
system_event_handler_t event_handler; /**< WiFi event handler */
|
||||
int static_rx_buf_num; /**< WiFi static RX buffer number */
|
||||
int dynamic_rx_buf_num; /**< WiFi dynamic RX buffer number */
|
||||
int tx_buf_type; /**< WiFi TX buffer type */
|
||||
int static_tx_buf_num; /**< WiFi static TX buffer number */
|
||||
int dynamic_tx_buf_num; /**< WiFi dynamic TX buffer number */
|
||||
int ampdu_enable; /**< WiFi AMPDU feature enable flag */
|
||||
int nvs_enable; /**< WiFi NVS flash enable flag */
|
||||
@ -104,6 +106,18 @@ typedef struct {
|
||||
int magic; /**< WiFi init magic number, it should be the last field */
|
||||
} wifi_init_config_t;
|
||||
|
||||
#ifdef CONFIG_ESP32_WIFI_STATIC_TX_BUFFER_NUM
|
||||
#define WIFI_STATIC_TX_BUFFER_NUM CONFIG_ESP32_WIFI_STATIC_TX_BUFFER_NUM
|
||||
#else
|
||||
#define WIFI_STATIC_TX_BUFFER_NUM 0
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM
|
||||
#define WIFI_DYNAMIC_TX_BUFFER_NUM CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM
|
||||
#else
|
||||
#define WIFI_DYNAMIC_TX_BUFFER_NUM 0
|
||||
#endif
|
||||
|
||||
#if CONFIG_ESP32_WIFI_AMPDU_ENABLED
|
||||
#define WIFI_AMPDU_ENABLED 1
|
||||
#else
|
||||
@ -128,14 +142,16 @@ typedef struct {
|
||||
.event_handler = &esp_event_send, \
|
||||
.static_rx_buf_num = CONFIG_ESP32_WIFI_STATIC_RX_BUFFER_NUM,\
|
||||
.dynamic_rx_buf_num = CONFIG_ESP32_WIFI_DYNAMIC_RX_BUFFER_NUM,\
|
||||
.dynamic_tx_buf_num = CONFIG_ESP32_WIFI_DYNAMIC_TX_BUFFER_NUM,\
|
||||
.tx_buf_type = CONFIG_ESP32_WIFI_TX_BUFFER_TYPE,\
|
||||
.static_tx_buf_num = WIFI_STATIC_TX_BUFFER_NUM,\
|
||||
.dynamic_tx_buf_num = WIFI_DYNAMIC_TX_BUFFER_NUM,\
|
||||
.ampdu_enable = WIFI_AMPDU_ENABLED,\
|
||||
.nvs_enable = WIFI_NVS_ENABLED,\
|
||||
.nano_enable = WIFI_NANO_FORMAT_ENABLED,\
|
||||
.magic = WIFI_INIT_CONFIG_MAGIC\
|
||||
};
|
||||
#else
|
||||
#define WIFI_INIT_CONFIG_DEFAULT #error Wifi is disabled in config, WIFI_INIT_CONFIG_DEFAULT will not work
|
||||
#define WIFI_INIT_CONFIG_DEFAULT() {0}; _Static_assert(0, "please enable wifi in menuconfig to use esp_wifi.h");
|
||||
#endif
|
||||
|
||||
/**
|
||||
@ -164,7 +180,6 @@ esp_err_t esp_wifi_init(wifi_init_config_t *config);
|
||||
* Free all resource allocated in esp_wifi_init and stop WiFi task
|
||||
*
|
||||
* @attention 1. This API should be called if you want to remove WiFi driver from the system
|
||||
* @attention 2. This API can not be called yet and will be done in the future.
|
||||
*
|
||||
* @return ESP_OK: succeed
|
||||
*/
|
||||
@ -297,6 +312,8 @@ esp_err_t esp_wifi_deauth_sta(uint16_t aid);
|
||||
* @attention If this API is called, the found APs are stored in WiFi driver dynamic allocated memory and the
|
||||
* will be freed in esp_wifi_get_ap_list, so generally, call esp_wifi_get_ap_list to cause
|
||||
* the memory to be freed once the scan is done
|
||||
* @attention The values of maximum active scan time and passive scan time per channel are limited to 1500 milliseconds.
|
||||
* Values above 1500ms may cause station to disconnect from AP and are not recommended.
|
||||
*
|
||||
* @param config configuration of scanning
|
||||
* @param block if block is true, this API will block the caller until the scan is done, otherwise
|
||||
|
@ -49,11 +49,12 @@ typedef enum {
|
||||
} wifi_country_t;
|
||||
|
||||
typedef enum {
|
||||
WIFI_AUTH_OPEN = 0, /**< authenticate mode : open */
|
||||
WIFI_AUTH_WEP, /**< authenticate mode : WEP */
|
||||
WIFI_AUTH_WPA_PSK, /**< authenticate mode : WPA_PSK */
|
||||
WIFI_AUTH_WPA2_PSK, /**< authenticate mode : WPA2_PSK */
|
||||
WIFI_AUTH_WPA_WPA2_PSK, /**< authenticate mode : WPA_WPA2_PSK */
|
||||
WIFI_AUTH_OPEN = 0, /**< authenticate mode : open */
|
||||
WIFI_AUTH_WEP, /**< authenticate mode : WEP */
|
||||
WIFI_AUTH_WPA_PSK, /**< authenticate mode : WPA_PSK */
|
||||
WIFI_AUTH_WPA2_PSK, /**< authenticate mode : WPA2_PSK */
|
||||
WIFI_AUTH_WPA_WPA2_PSK, /**< authenticate mode : WPA_WPA2_PSK */
|
||||
WIFI_AUTH_WPA2_ENTERPRISE, /**< authenticate mode : WPA2_ENTERPRISE */
|
||||
WIFI_AUTH_MAX
|
||||
} wifi_auth_mode_t;
|
||||
|
||||
@ -95,11 +96,30 @@ typedef enum {
|
||||
WIFI_SECOND_CHAN_BELOW, /**< the channel width is HT40 and the second channel is below the primary channel */
|
||||
} wifi_second_chan_t;
|
||||
|
||||
typedef enum {
|
||||
WIFI_SCAN_TYPE_ACTIVE = 0, /**< active scan */
|
||||
WIFI_SCAN_TYPE_PASSIVE, /**< passive scan */
|
||||
} wifi_scan_type_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t *ssid; /**< SSID of AP */
|
||||
uint8_t *bssid; /**< MAC address of AP */
|
||||
uint8_t channel; /**< channel, scan the specific channel */
|
||||
bool show_hidden; /**< enable to scan AP whose SSID is hidden */
|
||||
uint32_t min; /**< minimum active scan time per channel, units: millisecond */
|
||||
uint32_t max; /**< maximum active scan time per channel, units: millisecond, values above 1500ms may
|
||||
cause station to disconnect from AP and are not recommended. */
|
||||
} wifi_active_scan_time_t;
|
||||
|
||||
typedef union {
|
||||
wifi_active_scan_time_t active; /**< active scan time per channel */
|
||||
uint32_t passive; /**< passive scan time per channel, units: millisecond, values above 1500ms may
|
||||
cause station to disconnect from AP and are not recommended. */
|
||||
} wifi_scan_time_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t *ssid; /**< SSID of AP */
|
||||
uint8_t *bssid; /**< MAC address of AP */
|
||||
uint8_t channel; /**< channel, scan the specific channel */
|
||||
bool show_hidden; /**< enable to scan AP whose SSID is hidden */
|
||||
wifi_scan_type_t scan_type; /**< scan type, active or passive */
|
||||
wifi_scan_time_t scan_time; /**< scan time per channel */
|
||||
} wifi_scan_config_t;
|
||||
|
||||
typedef struct {
|
||||
|
@ -1,34 +1,3 @@
|
||||
// Copyright 2015-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 HEAP_ALLOC_CAPS_H
|
||||
#define HEAP_ALLOC_CAPS_H
|
||||
|
||||
#define MALLOC_CAP_EXEC (1<<0) //Memory must be able to run executable code
|
||||
#define MALLOC_CAP_32BIT (1<<1) //Memory must allow for aligned 32-bit data accesses
|
||||
#define MALLOC_CAP_8BIT (1<<2) //Memory must allow for 8/16/...-bit data accesses
|
||||
#define MALLOC_CAP_DMA (1<<3) //Memory must be able to accessed by DMA
|
||||
#define MALLOC_CAP_PID2 (1<<4) //Memory must be mapped to PID2 memory space
|
||||
#define MALLOC_CAP_PID3 (1<<5) //Memory must be mapped to PID3 memory space
|
||||
#define MALLOC_CAP_PID4 (1<<6) //Memory must be mapped to PID4 memory space
|
||||
#define MALLOC_CAP_PID5 (1<<7) //Memory must be mapped to PID5 memory space
|
||||
#define MALLOC_CAP_PID6 (1<<8) //Memory must be mapped to PID6 memory space
|
||||
#define MALLOC_CAP_PID7 (1<<9) //Memory must be mapped to PID7 memory space
|
||||
#define MALLOC_CAP_SPISRAM (1<<10) //Memory must be in SPI SRAM
|
||||
#define MALLOC_CAP_INVALID (1<<31) //Memory can't be used / list end marker
|
||||
|
||||
|
||||
void heap_alloc_caps_init();
|
||||
void *pvPortMallocCaps(size_t xWantedSize, uint32_t caps);
|
||||
|
||||
#endif
|
||||
#pragma once
|
||||
#warning heap_alloc_caps.h has been renamed to esp_heap_alloc_caps.h. The old header file is deprecated and will be removed in v3.0.
|
||||
#include "esp_heap_alloc_caps.h"
|
||||
|
@ -21,7 +21,8 @@ typedef volatile struct {
|
||||
uint32_t timer_sel: 2; /*There are four high speed timers the two bits are used to select one of them for high speed channel. 2'b00: seletc hstimer0. 2'b01: select hstimer1. 2'b10: select hstimer2. 2'b11: select hstimer3.*/
|
||||
uint32_t sig_out_en: 1; /*This is the output enable control bit for high speed channel*/
|
||||
uint32_t idle_lv: 1; /*This bit is used to control the output value when high speed channel is off.*/
|
||||
uint32_t reserved4: 27;
|
||||
uint32_t low_speed_update: 1; /*This bit is only useful for low speed timer channels, reserved for high speed timers*/
|
||||
uint32_t reserved4: 26;
|
||||
uint32_t clk_en: 1; /*This bit is clock gating control signal. when software configure LED_PWM internal registers it controls the register clock.*/
|
||||
};
|
||||
uint32_t val;
|
||||
@ -204,9 +205,13 @@ typedef volatile struct {
|
||||
} int_clr;
|
||||
union {
|
||||
struct {
|
||||
uint32_t apb_clk_sel: 1; /*This bit is used to set the frequency of slow_clk. 1'b1:80mhz 1'b0:8mhz*/
|
||||
uint32_t apb_clk_sel: 1; /*This bit decides the slow clock for LEDC low speed channels, so we want to replace the field name with slow_clk_sel*/
|
||||
uint32_t reserved1: 31;
|
||||
};
|
||||
struct {
|
||||
uint32_t slow_clk_sel: 1; /*This bit is used to set the frequency of slow_clk. 1'b1:80mhz 1'b0:8mhz, (only used by LEDC low speed channels/timers)*/
|
||||
uint32_t reserved: 31;
|
||||
};
|
||||
uint32_t val;
|
||||
} conf;
|
||||
uint32_t reserved_194;
|
||||
|
@ -15,7 +15,9 @@
|
||||
#ifndef _ESP32_SOC_H_
|
||||
#define _ESP32_SOC_H_
|
||||
|
||||
#ifndef __ASSEMBLER__
|
||||
#include <stdint.h>
|
||||
#endif
|
||||
|
||||
//Register Bits{{
|
||||
#define BIT31 0x80000000
|
||||
@ -59,7 +61,11 @@
|
||||
#define ETS_UNCACHED_ADDR(addr) (addr)
|
||||
#define ETS_CACHED_ADDR(addr) (addr)
|
||||
|
||||
#ifndef __ASSEMBLER__
|
||||
#define BIT(nr) (1UL << (nr))
|
||||
#else
|
||||
#define BIT(nr) (1 << (nr))
|
||||
#endif //__ASSEMBLER__
|
||||
|
||||
//write value to register
|
||||
#define REG_WRITE(_r, _v) (*(volatile uint32_t *)(_r)) = (_v)
|
||||
|
46
tools/sdk/include/esp32/soc/soc_ulp.h
Normal file
46
tools/sdk/include/esp32/soc/soc_ulp.h
Normal file
@ -0,0 +1,46 @@
|
||||
// Copyright 2010-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.
|
||||
#pragma once
|
||||
|
||||
// This file contains various convenience macros to be used in ULP programs.
|
||||
|
||||
// Helper macros to calculate bit field width from mask, using the preprocessor.
|
||||
// Used later in READ_RTC_FIELD and WRITE_RTC_FIELD.
|
||||
#define IS_BIT_SET(m, i) (((m) >> (i)) & 1)
|
||||
#define MASK_TO_WIDTH_HELPER1(m, i) IS_BIT_SET(m, i)
|
||||
#define MASK_TO_WIDTH_HELPER2(m, i) (MASK_TO_WIDTH_HELPER1(m, i) + MASK_TO_WIDTH_HELPER1(m, i + 1))
|
||||
#define MASK_TO_WIDTH_HELPER4(m, i) (MASK_TO_WIDTH_HELPER2(m, i) + MASK_TO_WIDTH_HELPER2(m, i + 2))
|
||||
#define MASK_TO_WIDTH_HELPER8(m, i) (MASK_TO_WIDTH_HELPER4(m, i) + MASK_TO_WIDTH_HELPER4(m, i + 4))
|
||||
#define MASK_TO_WIDTH_HELPER16(m, i) (MASK_TO_WIDTH_HELPER8(m, i) + MASK_TO_WIDTH_HELPER8(m, i + 8))
|
||||
#define MASK_TO_WIDTH_HELPER32(m, i) (MASK_TO_WIDTH_HELPER16(m, i) + MASK_TO_WIDTH_HELPER16(m, i + 16))
|
||||
|
||||
// Peripheral register access macros, build around REG_RD and REG_WR instructions.
|
||||
// Registers defined in rtc_cntl_reg.h, rtc_io_reg.h, and sens_reg.h are usable with these macros.
|
||||
|
||||
// Read from rtc_reg[low_bit + bit_width - 1 : low_bit] into R0, bit_width <= 16
|
||||
#define READ_RTC_REG(rtc_reg, low_bit, bit_width) \
|
||||
REG_RD (((rtc_reg) - DR_REG_RTCCNTL_BASE) / 4), ((low_bit) + (bit_width) - 1), (low_bit)
|
||||
|
||||
// Write immediate value into rtc_reg[low_bit + bit_width - 1 : low_bit], bit_width <= 8
|
||||
#define WRITE_RTC_REG(rtc_reg, low_bit, bit_width, value) \
|
||||
REG_WR (((rtc_reg) - DR_REG_RTCCNTL_BASE) / 4), ((low_bit) + (bit_width) - 1), (low_bit), ((value) & 0xff)
|
||||
|
||||
// Read from a field in rtc_reg into R0, up to 16 bits
|
||||
#define READ_RTC_FIELD(rtc_reg, field) \
|
||||
READ_RTC_REG(rtc_reg, field ## _S, MASK_TO_WIDTH_HELPER16(field ## _V, 0))
|
||||
|
||||
// Write immediate value into a field in rtc_reg, up to 8 bits
|
||||
#define WRITE_RTC_FIELD(rtc_reg, field, value) \
|
||||
WRITE_RTC_REG(rtc_reg, field ## _S, MASK_TO_WIDTH_HELPER8(field ## _V, 0), ((value) & field ## _V))
|
||||
|
Reference in New Issue
Block a user